mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-20 06:45:16 +03:00
STM32F4: Library update
This commit is contained in:
parent
5d385d0019
commit
bca73007d6
179 changed files with 5024 additions and 32738 deletions
|
@ -2,8 +2,8 @@
|
|||
******************************************************************************
|
||||
* @file misc.c
|
||||
* @author MCD Application Team
|
||||
* @version V1.6.1
|
||||
* @date 21-October-2015
|
||||
* @version V1.7.1
|
||||
* @date 20-May-2016
|
||||
* @brief This file provides all the miscellaneous firmware functions (add-on
|
||||
* to CMSIS functions).
|
||||
*
|
||||
|
@ -55,7 +55,7 @@
|
|||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2015 STMicroelectronics</center></h2>
|
||||
* <h2><center>© COPYRIGHT 2016 STMicroelectronics</center></h2>
|
||||
*
|
||||
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
|
||||
* You may not use this file except in compliance with the License.
|
||||
|
|
|
@ -2,8 +2,8 @@
|
|||
******************************************************************************
|
||||
* @file stm32f4xx_adc.c
|
||||
* @author MCD Application Team
|
||||
* @version V1.6.1
|
||||
* @date 21-October-2015
|
||||
* @version V1.7.1
|
||||
* @date 20-May-2016
|
||||
* @brief This file provides firmware functions to manage the following
|
||||
* functionalities of the Analog to Digital Convertor (ADC) peripheral:
|
||||
* + Initialization and Configuration (in addition to ADC multi mode
|
||||
|
@ -85,7 +85,7 @@
|
|||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2015 STMicroelectronics</center></h2>
|
||||
* <h2><center>© COPYRIGHT 2016 STMicroelectronics</center></h2>
|
||||
*
|
||||
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
|
||||
* You may not use this file except in compliance with the License.
|
||||
|
|
|
@ -2,8 +2,8 @@
|
|||
******************************************************************************
|
||||
* @file stm32f4xx_can.c
|
||||
* @author MCD Application Team
|
||||
* @version V1.6.1
|
||||
* @date 21-October-2015
|
||||
* @version V1.7.1
|
||||
* @date 20-May-2016
|
||||
* @brief This file provides firmware functions to manage the following
|
||||
* functionalities of the Controller area network (CAN) peripheral:
|
||||
* + Initialization and Configuration
|
||||
|
@ -63,7 +63,7 @@
|
|||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2015 STMicroelectronics</center></h2>
|
||||
* <h2><center>© COPYRIGHT 2016 STMicroelectronics</center></h2>
|
||||
*
|
||||
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
|
||||
* You may not use this file except in compliance with the License.
|
||||
|
|
|
@ -2,8 +2,8 @@
|
|||
******************************************************************************
|
||||
* @file stm32f4xx_cec.c
|
||||
* @author MCD Application Team
|
||||
* @version V1.6.1
|
||||
* @date 21-October-2015
|
||||
* @version V1.7.1
|
||||
* @date 20-May-2016
|
||||
* @brief This file provides firmware functions to manage the following
|
||||
* functionalities of the Consumer Electronics Control (CEC) peripheral
|
||||
* applicable only on STM32F446xx devices:
|
||||
|
@ -72,7 +72,7 @@
|
|||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2015 STMicroelectronics</center></h2>
|
||||
* <h2><center>© COPYRIGHT 2016 STMicroelectronics</center></h2>
|
||||
*
|
||||
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
|
||||
* You may not use this file except in compliance with the License.
|
||||
|
|
|
@ -2,13 +2,13 @@
|
|||
******************************************************************************
|
||||
* @file stm32f4xx_crc.c
|
||||
* @author MCD Application Team
|
||||
* @version V1.6.1
|
||||
* @date 21-October-2015
|
||||
* @version V1.7.1
|
||||
* @date 20-May-2016
|
||||
* @brief This file provides all the CRC firmware functions.
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2015 STMicroelectronics</center></h2>
|
||||
* <h2><center>© COPYRIGHT 2016 STMicroelectronics</center></h2>
|
||||
*
|
||||
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
|
||||
* You may not use this file except in compliance with the License.
|
||||
|
|
|
@ -2,8 +2,8 @@
|
|||
******************************************************************************
|
||||
* @file stm32f4xx_cryp.c
|
||||
* @author MCD Application Team
|
||||
* @version V1.6.1
|
||||
* @date 21-October-2015
|
||||
* @version V1.7.1
|
||||
* @date 20-May-2016
|
||||
* @brief This file provides firmware functions to manage the following
|
||||
* functionalities of the Cryptographic processor (CRYP) peripheral:
|
||||
* + Initialization and Configuration functions
|
||||
|
@ -143,7 +143,7 @@
|
|||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2015 STMicroelectronics</center></h2>
|
||||
* <h2><center>© COPYRIGHT 2016 STMicroelectronics</center></h2>
|
||||
*
|
||||
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
|
||||
* You may not use this file except in compliance with the License.
|
||||
|
|
|
@ -2,8 +2,8 @@
|
|||
******************************************************************************
|
||||
* @file stm32f4xx_cryp_aes.c
|
||||
* @author MCD Application Team
|
||||
* @version V1.6.1
|
||||
* @date 21-October-2015
|
||||
* @version V1.7.1
|
||||
* @date 20-May-2016
|
||||
* @brief This file provides high level functions to encrypt and decrypt an
|
||||
* input message using AES in ECB/CBC/CTR/GCM/CCM modes.
|
||||
* It uses the stm32f4xx_cryp.c/.h drivers to access the STM32F4xx CRYP
|
||||
|
@ -34,7 +34,7 @@
|
|||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2015 STMicroelectronics</center></h2>
|
||||
* <h2><center>© COPYRIGHT 2016 STMicroelectronics</center></h2>
|
||||
*
|
||||
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
|
||||
* You may not use this file except in compliance with the License.
|
||||
|
|
|
@ -2,8 +2,8 @@
|
|||
******************************************************************************
|
||||
* @file stm32f4xx_cryp_des.c
|
||||
* @author MCD Application Team
|
||||
* @version V1.6.1
|
||||
* @date 21-October-2015
|
||||
* @version V1.7.1
|
||||
* @date 20-May-2016
|
||||
* @brief This file provides high level functions to encrypt and decrypt an
|
||||
* input message using DES in ECB/CBC modes.
|
||||
* It uses the stm32f4xx_cryp.c/.h drivers to access the STM32F4xx CRYP
|
||||
|
@ -27,7 +27,7 @@
|
|||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2015 STMicroelectronics</center></h2>
|
||||
* <h2><center>© COPYRIGHT 2016 STMicroelectronics</center></h2>
|
||||
*
|
||||
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
|
||||
* You may not use this file except in compliance with the License.
|
||||
|
|
|
@ -2,8 +2,8 @@
|
|||
******************************************************************************
|
||||
* @file stm32f4xx_cryp_tdes.c
|
||||
* @author MCD Application Team
|
||||
* @version V1.6.1
|
||||
* @date 21-October-2015
|
||||
* @version V1.7.1
|
||||
* @date 20-May-2016
|
||||
* @brief This file provides high level functions to encrypt and decrypt an
|
||||
* input message using TDES in ECB/CBC modes .
|
||||
* It uses the stm32f4xx_cryp.c/.h drivers to access the STM32F4xx CRYP
|
||||
|
@ -27,7 +27,7 @@
|
|||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2015 STMicroelectronics</center></h2>
|
||||
* <h2><center>© COPYRIGHT 2016 STMicroelectronics</center></h2>
|
||||
*
|
||||
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
|
||||
* You may not use this file except in compliance with the License.
|
||||
|
|
|
@ -2,8 +2,8 @@
|
|||
******************************************************************************
|
||||
* @file stm32f4xx_dac.c
|
||||
* @author MCD Application Team
|
||||
* @version V1.6.1
|
||||
* @date 21-October-2015
|
||||
* @version V1.7.1
|
||||
* @date 20-May-2016
|
||||
* @brief This file provides firmware functions to manage the following
|
||||
* functionalities of the Digital-to-Analog Converter (DAC) peripheral:
|
||||
* + DAC channels configuration: trigger, output buffer, data format
|
||||
|
@ -109,7 +109,7 @@
|
|||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2015 STMicroelectronics</center></h2>
|
||||
* <h2><center>© COPYRIGHT 2016 STMicroelectronics</center></h2>
|
||||
*
|
||||
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
|
||||
* You may not use this file except in compliance with the License.
|
||||
|
|
|
@ -2,13 +2,13 @@
|
|||
******************************************************************************
|
||||
* @file stm32f4xx_dbgmcu.c
|
||||
* @author MCD Application Team
|
||||
* @version V1.6.1
|
||||
* @date 21-October-2015
|
||||
* @version V1.7.1
|
||||
* @date 20-May-2016
|
||||
* @brief This file provides all the DBGMCU firmware functions.
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2015 STMicroelectronics</center></h2>
|
||||
* <h2><center>© COPYRIGHT 2016 STMicroelectronics</center></h2>
|
||||
*
|
||||
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
|
||||
* You may not use this file except in compliance with the License.
|
||||
|
|
|
@ -2,8 +2,8 @@
|
|||
******************************************************************************
|
||||
* @file stm32f4xx_dcmi.c
|
||||
* @author MCD Application Team
|
||||
* @version V1.6.1
|
||||
* @date 21-October-2015
|
||||
* @version V1.7.1
|
||||
* @date 20-May-2016
|
||||
* @brief This file provides firmware functions to manage the following
|
||||
* functionalities of the DCMI peripheral:
|
||||
* + Initialization and Configuration
|
||||
|
@ -65,7 +65,7 @@
|
|||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2015 STMicroelectronics</center></h2>
|
||||
* <h2><center>© COPYRIGHT 2016 STMicroelectronics</center></h2>
|
||||
*
|
||||
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
|
||||
* You may not use this file except in compliance with the License.
|
||||
|
|
1441
lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_dfsdm.c
Normal file
1441
lib/main/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_dfsdm.c
Normal file
File diff suppressed because it is too large
Load diff
|
@ -2,8 +2,8 @@
|
|||
******************************************************************************
|
||||
* @file stm32f4xx_dma.c
|
||||
* @author MCD Application Team
|
||||
* @version V1.6.1
|
||||
* @date 21-October-2015
|
||||
* @version V1.7.1
|
||||
* @date 20-May-2016
|
||||
* @brief This file provides firmware functions to manage the following
|
||||
* functionalities of the Direct Memory Access controller (DMA):
|
||||
* + Initialization and Configuration
|
||||
|
@ -103,7 +103,7 @@
|
|||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2015 STMicroelectronics</center></h2>
|
||||
* <h2><center>© COPYRIGHT 2016 STMicroelectronics</center></h2>
|
||||
*
|
||||
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
|
||||
* You may not use this file except in compliance with the License.
|
||||
|
|
|
@ -2,8 +2,8 @@
|
|||
******************************************************************************
|
||||
* @file stm32f4xx_dma2d.c
|
||||
* @author MCD Application Team
|
||||
* @version V1.6.1
|
||||
* @date 21-October-2015
|
||||
* @version V1.7.1
|
||||
* @date 20-May-2016
|
||||
* @brief This file provides firmware functions to manage the following
|
||||
* functionalities of the DMA2D controller (DMA2D) peripheral:
|
||||
* + Initialization and configuration
|
||||
|
@ -37,7 +37,7 @@
|
|||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2015 STMicroelectronics</center></h2>
|
||||
* <h2><center>© COPYRIGHT 2016 STMicroelectronics</center></h2>
|
||||
*
|
||||
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
|
||||
* You may not use this file except in compliance with the License.
|
||||
|
|
|
@ -2,8 +2,8 @@
|
|||
******************************************************************************
|
||||
* @file stm32f4xx_dsi.c
|
||||
* @author MCD Application Team
|
||||
* @version V1.6.1
|
||||
* @date 21-October-2015
|
||||
* @version V1.7.1
|
||||
* @date 20-May-2016
|
||||
* @brief This file provides firmware functions to manage the following
|
||||
* functionalities of the Display Serial Interface (DSI):
|
||||
* + Initialization and Configuration
|
||||
|
@ -23,7 +23,7 @@
|
|||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2015 STMicroelectronics</center></h2>
|
||||
* <h2><center>© COPYRIGHT 2016 STMicroelectronics</center></h2>
|
||||
*
|
||||
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
|
||||
* You may not use this file except in compliance with the License.
|
||||
|
|
|
@ -2,8 +2,8 @@
|
|||
******************************************************************************
|
||||
* @file stm32f4xx_exti.c
|
||||
* @author MCD Application Team
|
||||
* @version V1.6.1
|
||||
* @date 21-October-2015
|
||||
* @version V1.7.1
|
||||
* @date 20-May-2016
|
||||
* @brief This file provides firmware functions to manage the following
|
||||
* functionalities of the EXTI peripheral:
|
||||
* + Initialization and Configuration
|
||||
|
@ -47,7 +47,7 @@
|
|||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2015 STMicroelectronics</center></h2>
|
||||
* <h2><center>© COPYRIGHT 2016 STMicroelectronics</center></h2>
|
||||
*
|
||||
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
|
||||
* You may not use this file except in compliance with the License.
|
||||
|
|
|
@ -2,8 +2,8 @@
|
|||
******************************************************************************
|
||||
* @file stm32f4xx_flash.c
|
||||
* @author MCD Application Team
|
||||
* @version V1.6.1
|
||||
* @date 21-October-2015
|
||||
* @version V1.7.1
|
||||
* @date 20-May-2016
|
||||
* @brief This file provides firmware functions to manage the following
|
||||
* functionalities of the FLASH peripheral:
|
||||
* + FLASH Interface configuration
|
||||
|
@ -51,7 +51,7 @@
|
|||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2015 STMicroelectronics</center></h2>
|
||||
* <h2><center>© COPYRIGHT 2016 STMicroelectronics</center></h2>
|
||||
*
|
||||
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
|
||||
* You may not use this file except in compliance with the License.
|
||||
|
@ -266,8 +266,8 @@
|
|||
* @arg FLASH_Latency_14: FLASH Fourteen Latency cycles
|
||||
* @arg FLASH_Latency_15: FLASH Fifteen Latency cycles
|
||||
*
|
||||
* @note For STM32F405xx/407xx, STM32F415xx/417xx and STM32F401xx/411xE devices this parameter
|
||||
* can be a value between FLASH_Latency_0 and FLASH_Latency_7.
|
||||
* @note For STM32F405xx/407xx, STM32F415xx/417xx, STM32F401xx/411xE and STM32F412xG devices
|
||||
* this parameter can be a value between FLASH_Latency_0 and FLASH_Latency_7.
|
||||
*
|
||||
* @note For STM32F42xxx/43xxx devices this parameter can be a value between
|
||||
* FLASH_Latency_0 and FLASH_Latency_15.
|
||||
|
@ -449,7 +449,7 @@ void FLASH_Lock(void)
|
|||
* For STM32F401xx devices this parameter can be a value between
|
||||
* FLASH_Sector_0 and FLASH_Sector_5.
|
||||
*
|
||||
* For STM32F411xE devices this parameter can be a value between
|
||||
* For STM32F411xE and STM32F412xG devices this parameter can be a value between
|
||||
* FLASH_Sector_0 and FLASH_Sector_7.
|
||||
*
|
||||
* For STM32F410xx devices this parameter can be a value between
|
||||
|
@ -565,7 +565,7 @@ FLASH_Status FLASH_EraseAllSectors(uint8_t VoltageRange)
|
|||
if(status == FLASH_COMPLETE)
|
||||
{
|
||||
/* if the previous operation is completed, proceed to erase all sectors */
|
||||
#if defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F469_479xx)
|
||||
#if defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F469_479xx)
|
||||
FLASH->CR &= CR_PSIZE_MASK;
|
||||
FLASH->CR |= tmp_psize;
|
||||
FLASH->CR |= (FLASH_CR_MER1 | FLASH_CR_MER2);
|
||||
|
@ -578,7 +578,7 @@ FLASH_Status FLASH_EraseAllSectors(uint8_t VoltageRange)
|
|||
FLASH->CR &= ~(FLASH_CR_MER1 | FLASH_CR_MER2);
|
||||
#endif /* STM32F427_437xx || STM32F429_439xx || STM32F469_479xx */
|
||||
|
||||
#if defined(STM32F40_41xxx) || defined(STM32F401xx) || defined(STM32F410xx) || defined(STM32F411xE) || defined(STM32F446xx)
|
||||
#if defined(STM32F40_41xxx) || defined(STM32F401xx) || defined(STM32F410xx) || defined(STM32F411xE) || defined(STM32F412xG) || defined(STM32F446xx)
|
||||
FLASH->CR &= CR_PSIZE_MASK;
|
||||
FLASH->CR |= tmp_psize;
|
||||
FLASH->CR |= FLASH_CR_MER;
|
||||
|
@ -589,7 +589,7 @@ FLASH_Status FLASH_EraseAllSectors(uint8_t VoltageRange)
|
|||
|
||||
/* if the erase operation is completed, disable the MER Bit */
|
||||
FLASH->CR &= (~FLASH_CR_MER);
|
||||
#endif /* STM32F40_41xxx || STM32F401xx || STM32F410xx || STM32F411xE || STM32F446xx */
|
||||
#endif /* STM32F40_41xxx || STM32F401xx || STM32F410xx || STM32F411xE || STM32F412xG || STM32F446xx */
|
||||
|
||||
}
|
||||
/* Return the Erase Status */
|
||||
|
@ -1116,7 +1116,8 @@ void FLASH_OB_PCROPSelectionConfig(uint8_t OB_PcROP)
|
|||
* @brief Enables or disables the read/write protection (PCROP) of the desired
|
||||
* sectors, for the first 1 MB of the Flash.
|
||||
*
|
||||
* @note This function can be used only for STM32F42xxx/43xxx and STM32F401xx/411xE devices.
|
||||
* @note This function can be used only for STM32F42xxx/43xxx , STM32F401xx/411xE
|
||||
* and STM32F412xG devices.
|
||||
*
|
||||
* @param OB_PCROP: specifies the sector(s) to be read/write protected or unprotected.
|
||||
* This parameter can be one of the following values:
|
||||
|
|
|
@ -2,8 +2,8 @@
|
|||
******************************************************************************
|
||||
* @file stm32f4xx_flash_ramfunc.c
|
||||
* @author MCD Application Team
|
||||
* @version V1.6.1
|
||||
* @date 21-October-2015
|
||||
* @version V1.7.1
|
||||
* @date 20-May-2016
|
||||
* @brief FLASH RAMFUNC module driver.
|
||||
* This file provides a FLASH firmware functions which should be
|
||||
* executed from internal SRAM
|
||||
|
@ -37,7 +37,7 @@
|
|||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2015 STMicroelectronics</center></h2>
|
||||
* <h2><center>© COPYRIGHT 2016 STMicroelectronics</center></h2>
|
||||
*
|
||||
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
|
||||
* You may not use this file except in compliance with the License.
|
||||
|
|
|
@ -2,8 +2,8 @@
|
|||
******************************************************************************
|
||||
* @file stm32f4xx_fmc.c
|
||||
* @author MCD Application Team
|
||||
* @version V1.6.1
|
||||
* @date 21-October-2015
|
||||
* @version V1.7.1
|
||||
* @date 20-May-2016
|
||||
* @brief This file provides firmware functions to manage the following
|
||||
* functionalities of the FMC peripheral:
|
||||
* + Interface with SRAM, PSRAM, NOR and OneNAND memories
|
||||
|
@ -15,7 +15,7 @@
|
|||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2015 STMicroelectronics</center></h2>
|
||||
* <h2><center>© COPYRIGHT 2016 STMicroelectronics</center></h2>
|
||||
*
|
||||
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
|
||||
* You may not use this file except in compliance with the License.
|
||||
|
@ -232,13 +232,13 @@ void FMC_NORSRAMInit(FMC_NORSRAMInitTypeDef* FMC_NORSRAMInitStruct)
|
|||
|
||||
/* NOR/SRAM Bank timing register configuration */
|
||||
FMC_Bank1->BTCR[FMC_NORSRAMInitStruct->FMC_Bank+1] =
|
||||
(uint32_t)(FMC_NORSRAMInitStruct->FMC_ReadWriteTimingStruct->FMC_AddressSetupTime |
|
||||
(uint32_t)FMC_NORSRAMInitStruct->FMC_ReadWriteTimingStruct->FMC_AddressSetupTime |
|
||||
(FMC_NORSRAMInitStruct->FMC_ReadWriteTimingStruct->FMC_AddressHoldTime << 4) |
|
||||
(FMC_NORSRAMInitStruct->FMC_ReadWriteTimingStruct->FMC_DataSetupTime << 8) |
|
||||
(FMC_NORSRAMInitStruct->FMC_ReadWriteTimingStruct->FMC_BusTurnAroundDuration << 16) |
|
||||
(FMC_NORSRAMInitStruct->FMC_ReadWriteTimingStruct->FMC_CLKDivision << 20) |
|
||||
(FMC_NORSRAMInitStruct->FMC_ReadWriteTimingStruct->FMC_DataLatency << 24) |
|
||||
FMC_NORSRAMInitStruct->FMC_ReadWriteTimingStruct->FMC_AccessMode);
|
||||
FMC_NORSRAMInitStruct->FMC_ReadWriteTimingStruct->FMC_AccessMode;
|
||||
|
||||
/* NOR/SRAM Bank timing register for write configuration, if extended mode is used */
|
||||
if(FMC_NORSRAMInitStruct->FMC_ExtendedMode == FMC_ExtendedMode_Enable)
|
||||
|
@ -248,7 +248,7 @@ void FMC_NORSRAMInit(FMC_NORSRAMInitTypeDef* FMC_NORSRAMInitStruct)
|
|||
assert_param(IS_FMC_DATASETUP_TIME(FMC_NORSRAMInitStruct->FMC_WriteTimingStruct->FMC_DataSetupTime));
|
||||
assert_param(IS_FMC_TURNAROUND_TIME(FMC_NORSRAMInitStruct->FMC_WriteTimingStruct->FMC_BusTurnAroundDuration));
|
||||
assert_param(IS_FMC_ACCESS_MODE(FMC_NORSRAMInitStruct->FMC_WriteTimingStruct->FMC_AccessMode));
|
||||
|
||||
|
||||
/* Get the BWTR register value */
|
||||
tmpbwr = FMC_Bank1E->BWTR[FMC_NORSRAMInitStruct->FMC_Bank];
|
||||
|
||||
|
|
|
@ -2,8 +2,8 @@
|
|||
******************************************************************************
|
||||
* @file stm32f4xx_fmpi2c.c
|
||||
* @author MCD Application Team
|
||||
* @version V1.6.1
|
||||
* @date 21-October-2015
|
||||
* @version V1.7.1
|
||||
* @date 20-May-2016
|
||||
* @brief This file provides firmware functions to manage the following
|
||||
* functionalities of the Inter-Integrated circuit Fast Mode Plus (FMPI2C):
|
||||
* + Initialization and Configuration
|
||||
|
@ -58,7 +58,7 @@
|
|||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2015 STMicroelectronics</center></h2>
|
||||
* <h2><center>© COPYRIGHT 2016 STMicroelectronics</center></h2>
|
||||
*
|
||||
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
|
||||
* You may not use this file except in compliance with the License.
|
||||
|
@ -79,15 +79,15 @@
|
|||
#include "stm32f4xx_fmpi2c.h"
|
||||
#include "stm32f4xx_rcc.h"
|
||||
|
||||
/** @addtogroup STM32F40x_StdPeriph_Driver
|
||||
/** @addtogroup STM32F4xx_StdPeriph_Driver
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @defgroup FMPI2C
|
||||
/** @defgroup FMPI2C FMPI2C
|
||||
* @brief FMPI2C driver modules
|
||||
* @{
|
||||
*/
|
||||
#if defined(STM32F410xx) || defined(STM32F446xx)
|
||||
#if defined(STM32F410xx) || defined(STM32F412xG) || defined(STM32F446xx)
|
||||
/* Private typedef -----------------------------------------------------------*/
|
||||
/* Private define ------------------------------------------------------------*/
|
||||
|
||||
|
@ -368,31 +368,6 @@ void FMPI2C_StretchClockCmd(FMPI2C_TypeDef* FMPI2Cx, FunctionalState NewState)
|
|||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Enables or disables FMPI2Cp from stop mode.
|
||||
* @param FMPI2Cx: where x can be 1 to select the FMPI2C peripheral.
|
||||
* @param NewState: new state of the FMPI2Cx stop mode.
|
||||
* This parameter can be: ENABLE or DISABLE.
|
||||
* @retval None
|
||||
*/
|
||||
void FMPI2C_StopModeCmd(FMPI2C_TypeDef* FMPI2Cx, FunctionalState NewState)
|
||||
{
|
||||
/* Check the parameters */
|
||||
assert_param(IS_FMPI2C_ALL_PERIPH(FMPI2Cx));
|
||||
assert_param(IS_FUNCTIONAL_STATE(NewState));
|
||||
|
||||
if (NewState != DISABLE)
|
||||
{
|
||||
/* Enable wakeup from stop mode */
|
||||
FMPI2Cx->CR1 |= FMPI2C_CR1_WUPEN;
|
||||
}
|
||||
else
|
||||
{
|
||||
/* Disable wakeup from stop mode */
|
||||
FMPI2Cx->CR1 &= (uint32_t)~((uint32_t)FMPI2C_CR1_WUPEN);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Enables or disables the FMPI2C own address 2.
|
||||
* @param FMPI2Cx: where x can be 1 to select the FMPI2C peripheral.
|
||||
|
@ -1566,7 +1541,7 @@ void FMPI2C_ClearITPendingBit(FMPI2C_TypeDef* FMPI2Cx, uint32_t FMPI2C_IT)
|
|||
/**
|
||||
* @}
|
||||
*/
|
||||
#endif /* STM32F410xx || STM32F446xx */
|
||||
#endif /* STM32F410xx || STM32F412xG || STM32F446xx */
|
||||
|
||||
/**
|
||||
* @}
|
||||
|
|
|
@ -2,8 +2,8 @@
|
|||
******************************************************************************
|
||||
* @file stm32f4xx_fsmc.c
|
||||
* @author MCD Application Team
|
||||
* @version V1.6.1
|
||||
* @date 21-October-2015
|
||||
* @version V1.7.1
|
||||
* @date 20-May-2016
|
||||
* @brief This file provides firmware functions to manage the following
|
||||
* functionalities of the FSMC peripheral:
|
||||
* + Interface with SRAM, PSRAM, NOR and OneNAND memories
|
||||
|
@ -14,7 +14,7 @@
|
|||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2015 STMicroelectronics</center></h2>
|
||||
* <h2><center>© COPYRIGHT 2016 STMicroelectronics</center></h2>
|
||||
*
|
||||
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
|
||||
* You may not use this file except in compliance with the License.
|
||||
|
|
|
@ -2,8 +2,8 @@
|
|||
******************************************************************************
|
||||
* @file stm32f4xx_gpio.c
|
||||
* @author MCD Application Team
|
||||
* @version V1.6.1
|
||||
* @date 21-October-2015
|
||||
* @version V1.7.1
|
||||
* @date 20-May-2016
|
||||
* @brief This file provides firmware functions to manage the following
|
||||
* functionalities of the GPIO peripheral:
|
||||
* + Initialization and Configuration
|
||||
|
@ -63,7 +63,7 @@
|
|||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2015 STMicroelectronics</center></h2>
|
||||
* <h2><center>© COPYRIGHT 2016 STMicroelectronics</center></h2>
|
||||
*
|
||||
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
|
||||
* You may not use this file except in compliance with the License.
|
||||
|
|
|
@ -2,8 +2,8 @@
|
|||
******************************************************************************
|
||||
* @file stm32f4xx_hash.c
|
||||
* @author MCD Application Team
|
||||
* @version V1.6.1
|
||||
* @date 21-October-2015
|
||||
* @version V1.7.1
|
||||
* @date 20-May-2016
|
||||
* @brief This file provides firmware functions to manage the following
|
||||
* functionalities of the HASH / HMAC Processor (HASH) peripheral:
|
||||
* - Initialization and Configuration functions
|
||||
|
@ -102,7 +102,7 @@
|
|||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2015 STMicroelectronics</center></h2>
|
||||
* <h2><center>© COPYRIGHT 2016 STMicroelectronics</center></h2>
|
||||
*
|
||||
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
|
||||
* You may not use this file except in compliance with the License.
|
||||
|
|
|
@ -2,8 +2,8 @@
|
|||
******************************************************************************
|
||||
* @file stm32f4xx_hash_md5.c
|
||||
* @author MCD Application Team
|
||||
* @version V1.6.1
|
||||
* @date 21-October-2015
|
||||
* @version V1.7.1
|
||||
* @date 20-May-2016
|
||||
* @brief This file provides high level functions to compute the HASH MD5 and
|
||||
* HMAC MD5 Digest of an input message.
|
||||
* It uses the stm32f4xx_hash.c/.h drivers to access the STM32F4xx HASH
|
||||
|
@ -26,7 +26,7 @@
|
|||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2015 STMicroelectronics</center></h2>
|
||||
* <h2><center>© COPYRIGHT 2016 STMicroelectronics</center></h2>
|
||||
*
|
||||
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
|
||||
* You may not use this file except in compliance with the License.
|
||||
|
|
|
@ -2,8 +2,8 @@
|
|||
******************************************************************************
|
||||
* @file stm32f4xx_hash_sha1.c
|
||||
* @author MCD Application Team
|
||||
* @version V1.6.1
|
||||
* @date 21-October-2015
|
||||
* @version V1.7.1
|
||||
* @date 20-May-2016
|
||||
* @brief This file provides high level functions to compute the HASH SHA1 and
|
||||
* HMAC SHA1 Digest of an input message.
|
||||
* It uses the stm32f4xx_hash.c/.h drivers to access the STM32F4xx HASH
|
||||
|
@ -26,7 +26,7 @@
|
|||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2015 STMicroelectronics</center></h2>
|
||||
* <h2><center>© COPYRIGHT 2016 STMicroelectronics</center></h2>
|
||||
*
|
||||
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
|
||||
* You may not use this file except in compliance with the License.
|
||||
|
|
|
@ -2,8 +2,8 @@
|
|||
******************************************************************************
|
||||
* @file stm32f4xx_i2c.c
|
||||
* @author MCD Application Team
|
||||
* @version V1.6.1
|
||||
* @date 21-October-2015
|
||||
* @version V1.7.1
|
||||
* @date 20-May-2016
|
||||
* @brief This file provides firmware functions to manage the following
|
||||
* functionalities of the Inter-integrated circuit (I2C)
|
||||
* + Initialization and Configuration
|
||||
|
@ -71,7 +71,7 @@
|
|||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2015 STMicroelectronics</center></h2>
|
||||
* <h2><center>© COPYRIGHT 2016 STMicroelectronics</center></h2>
|
||||
*
|
||||
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
|
||||
* You may not use this file except in compliance with the License.
|
||||
|
|
|
@ -2,8 +2,8 @@
|
|||
******************************************************************************
|
||||
* @file stm32f4xx_iwdg.c
|
||||
* @author MCD Application Team
|
||||
* @version V1.6.1
|
||||
* @date 21-October-2015
|
||||
* @version V1.7.1
|
||||
* @date 20-May-2016
|
||||
* @brief This file provides firmware functions to manage the following
|
||||
* functionalities of the Independent watchdog (IWDG) peripheral:
|
||||
* + Prescaler and Counter configuration
|
||||
|
@ -64,7 +64,7 @@
|
|||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2015 STMicroelectronics</center></h2>
|
||||
* <h2><center>© COPYRIGHT 2016 STMicroelectronics</center></h2>
|
||||
*
|
||||
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
|
||||
* You may not use this file except in compliance with the License.
|
||||
|
|
|
@ -2,8 +2,8 @@
|
|||
******************************************************************************
|
||||
* @file stm32f4xx_lptim.c
|
||||
* @author MCD Application Team
|
||||
* @version V1.6.1
|
||||
* @date 21-October-2015
|
||||
* @version V1.7.1
|
||||
* @date 20-May-2016
|
||||
* @brief This file provides firmware functions to manage the following
|
||||
* functionalities of the Low Power Timer (LPT) peripheral:
|
||||
* + Initialization functions.
|
||||
|
@ -75,7 +75,7 @@
|
|||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2015 STMicroelectronics</center></h2>
|
||||
* <h2><center>© COPYRIGHT 2016 STMicroelectronics</center></h2>
|
||||
*
|
||||
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
|
||||
* You may not use this file except in compliance with the License.
|
||||
|
|
|
@ -2,8 +2,8 @@
|
|||
******************************************************************************
|
||||
* @file stm32f4xx_ltdc.c
|
||||
* @author MCD Application Team
|
||||
* @version V1.6.1
|
||||
* @date 21-October-2015
|
||||
* @version V1.7.1
|
||||
* @date 20-May-2016
|
||||
* @brief This file provides firmware functions to manage the following
|
||||
* functionalities of the LTDC controller (LTDC) peripheral:
|
||||
* + Initialization and configuration
|
||||
|
@ -55,7 +55,7 @@
|
|||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2015 STMicroelectronics</center></h2>
|
||||
* <h2><center>© COPYRIGHT 2016 STMicroelectronics</center></h2>
|
||||
*
|
||||
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
|
||||
* You may not use this file except in compliance with the License.
|
||||
|
|
|
@ -2,8 +2,8 @@
|
|||
******************************************************************************
|
||||
* @file stm32f4xx_pwr.c
|
||||
* @author MCD Application Team
|
||||
* @version V1.6.1
|
||||
* @date 21-October-2015
|
||||
* @version V1.7.1
|
||||
* @date 20-May-2016
|
||||
* @brief This file provides firmware functions to manage the following
|
||||
* functionalities of the Power Controller (PWR) peripheral:
|
||||
* + Backup Domain Access
|
||||
|
@ -17,7 +17,7 @@
|
|||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2015 STMicroelectronics</center></h2>
|
||||
* <h2><center>© COPYRIGHT 2016 STMicroelectronics</center></h2>
|
||||
*
|
||||
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
|
||||
* You may not use this file except in compliance with the License.
|
||||
|
@ -89,7 +89,7 @@
|
|||
#define CR_LPUDS_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (LPUDS_BitNumber * 4))
|
||||
#endif /* STM32F427_437xx || STM32F429_439xx || STM32F446xx */
|
||||
|
||||
#if defined(STM32F401xx) || defined(STM32F410xx) || defined(STM32F411xE)
|
||||
#if defined(STM32F401xx) || defined(STM32F410xx) || defined(STM32F411xE) || defined(STM32F412xG)
|
||||
/* Alias word address of MRLVDS bit */
|
||||
#define MRLVDS_BitNumber 0x0B
|
||||
#define CR_MRLVDS_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (MRLVDS_BitNumber * 4))
|
||||
|
@ -97,7 +97,7 @@
|
|||
/* Alias word address of LPLVDS bit */
|
||||
#define LPLVDS_BitNumber 0x0A
|
||||
#define CR_LPLVDS_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (LPLVDS_BitNumber * 4))
|
||||
#endif /* STM32F401xx || STM32F410xx || STM32F411xE */
|
||||
#endif /* STM32F401xx || STM32F410xx || STM32F411xE || STM32F412xG */
|
||||
|
||||
/* --- CSR Register ---*/
|
||||
#if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F401xx) || defined(STM32F410xx) || defined(STM32F411xE) || defined(STM32F469_479xx)
|
||||
|
@ -107,18 +107,18 @@
|
|||
#define CSR_EWUP_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (EWUP_BitNumber * 4))
|
||||
#endif /* STM32F40_41xxx || STM32F427_437xx || STM32F429_439xx || STM32F401xx || STM32F410xx || STM32F411xE || STM32F469_479xx */
|
||||
|
||||
#if defined(STM32F410xx) || defined(STM32F446xx)
|
||||
#if defined(STM32F410xx) || defined(STM32F412xG) || defined(STM32F446xx)
|
||||
/* Alias word address of EWUP2 bit */
|
||||
#define CSR_OFFSET (PWR_OFFSET + 0x04)
|
||||
#define EWUP1_BitNumber 0x08
|
||||
#define CSR_EWUP1_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (EWUP1_BitNumber * 4))
|
||||
#define EWUP2_BitNumber 0x07
|
||||
#define CSR_EWUP2_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (EWUP2_BitNumber * 4))
|
||||
#if defined(STM32F410xx)
|
||||
#if defined(STM32F410xx) || defined(STM32F412xG)
|
||||
#define EWUP3_BitNumber 0x06
|
||||
#define CSR_EWUP3_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (EWUP2_BitNumber * 4))
|
||||
#endif /* STM32F410xx */
|
||||
#endif /* STM32F410xx || STM32F446xx */
|
||||
#endif /* STM32F410xx || STM32F412xG */
|
||||
#endif /* STM32F410xx || STM32F412xG || STM32F446xx */
|
||||
|
||||
/* Alias word address of BRE bit */
|
||||
#define BRE_BitNumber 0x09
|
||||
|
@ -297,14 +297,14 @@ void PWR_WakeUpPinCmd(FunctionalState NewState)
|
|||
}
|
||||
#endif /* STM32F40_41xxx || STM32F427_437xx || STM32F429_439xx || STM32F401xx || STM32F411xE */
|
||||
|
||||
#if defined(STM32F410xx) || defined(STM32F446xx)
|
||||
#if defined(STM32F410xx) || defined(STM32F412xG) || defined(STM32F446xx)
|
||||
/**
|
||||
* @brief Enables or disables the WakeUp Pin functionality.
|
||||
* @param PWR_WakeUpPinx: specifies the WakeUp Pin.
|
||||
* This parameter can be one of the following values:
|
||||
* @arg PWR_WakeUp_Pin1: WKUP1 pin is used for wakeup from Standby mode.
|
||||
* @arg PWR_WakeUp_Pin2: WKUP2 pin is used for wakeup from Standby mode.
|
||||
* @arg PWR_WakeUp_Pin3: WKUP3 pin is used for wakeup from Standby mode.(only for STM32F410xx)
|
||||
* @arg PWR_WakeUp_Pin3: WKUP3 pin is used for wakeup from Standby mode.(only for STM32F410xx and STM32F412xG Devices)
|
||||
* @param NewState: new state of the WakeUp Pin functionality.
|
||||
* This parameter can be: ENABLE or DISABLE.
|
||||
* @retval None
|
||||
|
@ -318,7 +318,7 @@ void PWR_WakeUpPinCmd(uint32_t PWR_WakeUpPinx, FunctionalState NewState)
|
|||
{
|
||||
*(__IO uint32_t *) CSR_EWUP1_BB = (uint32_t)NewState;
|
||||
}
|
||||
#if defined(STM32F410xx)
|
||||
#if defined(STM32F410xx)|| defined(STM32F412xG)
|
||||
else if(PWR_WakeUpPinx == PWR_WakeUp_Pin3) /* PWR_WakeUp_Pin3 */
|
||||
{
|
||||
*(__IO uint32_t *) CSR_EWUP3_BB = (uint32_t)NewState;
|
||||
|
@ -329,7 +329,7 @@ void PWR_WakeUpPinCmd(uint32_t PWR_WakeUpPinx, FunctionalState NewState)
|
|||
*(__IO uint32_t *) CSR_EWUP2_BB = (uint32_t)NewState;
|
||||
}
|
||||
}
|
||||
#endif /* STM32F410xx || STM32F446xx */
|
||||
#endif /* STM32F410xx || STM32F412xG || STM32F446xx */
|
||||
|
||||
/**
|
||||
* @}
|
||||
|
@ -589,11 +589,11 @@ void PWR_LowRegulatorUnderDriveCmd(FunctionalState NewState)
|
|||
}
|
||||
#endif /* STM32F427_437xx || STM32F429_439xx || STM32F446xx */
|
||||
|
||||
#if defined(STM32F401xx) || defined(STM32F410xx) || defined(STM32F411xE)
|
||||
#if defined(STM32F401xx) || defined(STM32F410xx) || defined(STM32F411xE) || defined(STM32F412xG)
|
||||
/**
|
||||
* @brief Enables or disables the Main Regulator low voltage mode.
|
||||
*
|
||||
* @note This mode is only available for STM32F401xx/STM32F410xx/STM32F411xx devices.
|
||||
* @note This mode is only available for STM32F401xx/STM32F410xx/STM32F411xx/STM32F412xG devices.
|
||||
*
|
||||
* @param NewState: new state of the Main Regulator Low Voltage mode.
|
||||
* This parameter can be: ENABLE or DISABLE.
|
||||
|
@ -617,7 +617,7 @@ void PWR_MainRegulatorLowVoltageCmd(FunctionalState NewState)
|
|||
/**
|
||||
* @brief Enables or disables the Low Power Regulator low voltage mode.
|
||||
*
|
||||
* @note This mode is only available for STM32F401xx/STM32F410xx/STM32F411xx devices.
|
||||
* @note This mode is only available for STM32F401xx/STM32F410xx/STM32F411xx/STM32F412xG devices.
|
||||
*
|
||||
* @param NewState: new state of the Low Power Regulator Low Voltage mode.
|
||||
* This parameter can be: ENABLE or DISABLE.
|
||||
|
@ -637,7 +637,7 @@ void PWR_LowRegulatorLowVoltageCmd(FunctionalState NewState)
|
|||
*(__IO uint32_t *) CR_LPLVDS_BB = (uint32_t)DISABLE;
|
||||
}
|
||||
}
|
||||
#endif /* STM32F401xx || STM32F410xx || STM32F411xE */
|
||||
#endif /* STM32F401xx || STM32F410xx || STM32F411xE || STM32F412xG */
|
||||
|
||||
/**
|
||||
* @}
|
||||
|
@ -1029,9 +1029,9 @@ void PWR_ClearFlag(uint32_t PWR_FLAG)
|
|||
}
|
||||
#endif /* STM32F427_437xx || STM32F429_439xx */
|
||||
|
||||
#if defined (STM32F40_41xxx) || defined (STM32F401xx) || defined (STM32F410xx) || defined (STM32F411xE)
|
||||
#if defined (STM32F40_41xxx) || defined (STM32F401xx) || defined (STM32F410xx) || defined (STM32F411xE) || defined(STM32F412xG)
|
||||
PWR->CR |= PWR_FLAG << 2;
|
||||
#endif /* STM32F40_41xxx || STM32F401xx || STM32F410xx || STM32F411xE */
|
||||
#endif /* STM32F40_41xxx || STM32F401xx || STM32F410xx || STM32F411xE || STM32F412xG */
|
||||
}
|
||||
|
||||
/**
|
||||
|
|
|
@ -2,8 +2,8 @@
|
|||
******************************************************************************
|
||||
* @file stm32f4xx_qspi.c
|
||||
* @author MCD Application Team
|
||||
* @version V1.6.1
|
||||
* @date 21-October-2015
|
||||
* @version V1.7.1
|
||||
* @date 20-May-2016
|
||||
* @brief This file provides firmware functions to manage the following
|
||||
* functionalities of the Serial peripheral interface (QSPI):
|
||||
* + Initialization and Configuration
|
||||
|
@ -61,7 +61,7 @@
|
|||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2015 STMicroelectronics</center></h2>
|
||||
* <h2><center>© COPYRIGHT 2016 STMicroelectronics</center></h2>
|
||||
*
|
||||
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
|
||||
* You may not use this file except in compliance with the License.
|
||||
|
@ -89,7 +89,7 @@
|
|||
* @brief QSPI driver modules
|
||||
* @{
|
||||
*/
|
||||
#if defined(STM32F446xx) || defined(STM32F469_479xx)
|
||||
#if defined(STM32F412xG) || defined(STM32F446xx) || defined(STM32F469_479xx)
|
||||
/* Private typedef -----------------------------------------------------------*/
|
||||
/* Private define ------------------------------------------------------------*/
|
||||
#define QSPI_CR_CLEAR_MASK 0x00FFFFCF
|
||||
|
@ -898,7 +898,7 @@ void QSPI_DualFlashMode_Cmd(FunctionalState NewState)
|
|||
/**
|
||||
* @}
|
||||
*/
|
||||
#endif /* STM32F446xx || STM32F469_479xx */
|
||||
#endif /* STM32F412xG || STM32F446xx || STM32F469_479xx */
|
||||
|
||||
/**
|
||||
* @}
|
||||
|
|
|
@ -2,8 +2,8 @@
|
|||
******************************************************************************
|
||||
* @file stm32f4xx_rcc.c
|
||||
* @author MCD Application Team
|
||||
* @version V1.6.1
|
||||
* @date 21-October-2015
|
||||
* @version V1.7.1
|
||||
* @date 20-May-2016
|
||||
* @brief This file provides firmware functions to manage the following
|
||||
* functionalities of the Reset and clock control (RCC) peripheral:
|
||||
* + Internal/external clocks, PLL, CSS and MCO configuration
|
||||
|
@ -38,7 +38,7 @@
|
|||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2015 STMicroelectronics</center></h2>
|
||||
* <h2><center>© COPYRIGHT 2016 STMicroelectronics</center></h2>
|
||||
*
|
||||
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
|
||||
* You may not use this file except in compliance with the License.
|
||||
|
@ -445,7 +445,7 @@ void RCC_LSICmd(FunctionalState NewState)
|
|||
*(__IO uint32_t *) CSR_LSION_BB = (uint32_t)NewState;
|
||||
}
|
||||
|
||||
#if defined(STM32F410xx) || defined(STM32F446xx) || defined(STM32F469_479xx)
|
||||
#if defined(STM32F410xx) || defined(STM32F412xG) || defined(STM32F446xx) || defined(STM32F469_479xx)
|
||||
/**
|
||||
* @brief Configures the main PLL clock source, multiplication and division factors.
|
||||
* @note This function must be used only when the main PLL is disabled.
|
||||
|
@ -498,7 +498,7 @@ void RCC_PLLConfig(uint32_t RCC_PLLSource, uint32_t PLLM, uint32_t PLLN, uint32_
|
|||
RCC->PLLCFGR = PLLM | (PLLN << 6) | (((PLLP >> 1) -1) << 16) | (RCC_PLLSource) |
|
||||
(PLLQ << 24) | (PLLR << 28);
|
||||
}
|
||||
#endif /* STM32F410xx || STM32F446xx || STM32F469_479xx */
|
||||
#endif /* STM32F410xx || STM32F412xG || STM32F446xx || STM32F469_479xx */
|
||||
|
||||
#if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F401xx) || defined(STM32F411xE)
|
||||
/**
|
||||
|
@ -675,7 +675,7 @@ void RCC_PLLI2SConfig(uint32_t PLLI2SN, uint32_t PLLI2SQ, uint32_t PLLI2SR)
|
|||
}
|
||||
#endif /* STM32F427_437xx || STM32F429_439xx || STM32F469_479xx */
|
||||
|
||||
#if defined(STM32F446xx)
|
||||
#if defined(STM32F412xG ) || defined(STM32F446xx)
|
||||
/**
|
||||
* @brief Configures the PLLI2S clock multiplication and division factors.
|
||||
*
|
||||
|
@ -721,7 +721,7 @@ void RCC_PLLI2SConfig(uint32_t PLLI2SM, uint32_t PLLI2SN, uint32_t PLLI2SP, uint
|
|||
|
||||
RCC->PLLI2SCFGR = PLLI2SM | (PLLI2SN << 6) | (((PLLI2SP >> 1) -1) << 16) | (PLLI2SQ << 24) | (PLLI2SR << 28);
|
||||
}
|
||||
#endif /* STM32F446xx */
|
||||
#endif /* STM32F412xG || STM32F446xx */
|
||||
|
||||
/**
|
||||
* @brief Enables or disables the PLLI2S.
|
||||
|
@ -770,7 +770,7 @@ void RCC_PLLSAIConfig(uint32_t PLLSAIN, uint32_t PLLSAIP, uint32_t PLLSAIQ, uint
|
|||
assert_param(IS_RCC_PLLSAIQ_VALUE(PLLSAIQ));
|
||||
assert_param(IS_RCC_PLLSAIR_VALUE(PLLSAIR));
|
||||
|
||||
RCC->PLLSAICFGR = (PLLSAIN << 6) | (PLLSAIP << 16) | (PLLSAIQ << 24) | (PLLSAIR << 28);
|
||||
RCC->PLLSAICFGR = (PLLSAIN << 6) | (((PLLSAIP >> 1) -1) << 16) | (PLLSAIQ << 24) | (PLLSAIR << 28);
|
||||
}
|
||||
#endif /* STM32F469_479xx */
|
||||
|
||||
|
@ -1143,7 +1143,7 @@ void RCC_MCO2Config(uint32_t RCC_MCO2Source, uint32_t RCC_MCO2Div)
|
|||
* @arg RCC_SYSCLKSource_HSI: HSI selected as system clock source
|
||||
* @arg RCC_SYSCLKSource_HSE: HSE selected as system clock source
|
||||
* @arg RCC_SYSCLKSource_PLLCLK: PLL selected as system clock source (RCC_SYSCLKSource_PLLPCLK for STM32F446xx devices)
|
||||
* @arg RCC_SYSCLKSource_PLLRCLK: PLL R selected as system clock source only for STM32F446xx devices
|
||||
* @arg RCC_SYSCLKSource_PLLRCLK: PLL R selected as system clock source only for STM32F412xG and STM32F446xx devices
|
||||
* @retval None
|
||||
*/
|
||||
void RCC_SYSCLKConfig(uint32_t RCC_SYSCLKSource)
|
||||
|
@ -1173,7 +1173,7 @@ void RCC_SYSCLKConfig(uint32_t RCC_SYSCLKSource)
|
|||
* - 0x00: HSI used as system clock
|
||||
* - 0x04: HSE used as system clock
|
||||
* - 0x08: PLL used as system clock (PLL P for STM32F446xx devices)
|
||||
* - 0x0C: PLL R used as system clock (only for STM32F446xx devices)
|
||||
* - 0x0C: PLL R used as system clock (only for STM32F412xG and STM32F446xx devices)
|
||||
*/
|
||||
uint8_t RCC_GetSYSCLKSource(void)
|
||||
{
|
||||
|
@ -1317,9 +1317,9 @@ void RCC_PCLK2Config(uint32_t RCC_HCLK)
|
|||
void RCC_GetClocksFreq(RCC_ClocksTypeDef* RCC_Clocks)
|
||||
{
|
||||
uint32_t tmp = 0, presc = 0, pllvco = 0, pllp = 2, pllsource = 0, pllm = 2;
|
||||
#if defined(STM32F446xx)
|
||||
#if defined(STM32F412xG) || defined(STM32F446xx)
|
||||
uint32_t pllr = 2;
|
||||
#endif /* STM32F446xx */
|
||||
#endif /* STM32F412xG || STM32F446xx */
|
||||
|
||||
/* Get SYSCLK source -------------------------------------------------------*/
|
||||
tmp = RCC->CFGR & RCC_CFGR_SWS;
|
||||
|
@ -1348,14 +1348,14 @@ void RCC_GetClocksFreq(RCC_ClocksTypeDef* RCC_Clocks)
|
|||
else
|
||||
{
|
||||
/* HSI used as PLL clock source */
|
||||
pllvco = (HSI_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6);
|
||||
pllvco = (HSI_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6);
|
||||
}
|
||||
|
||||
pllp = (((RCC->PLLCFGR & RCC_PLLCFGR_PLLP) >>16) + 1 ) *2;
|
||||
RCC_Clocks->SYSCLK_Frequency = pllvco/pllp;
|
||||
break;
|
||||
|
||||
#if defined(STM32F446xx)
|
||||
#if defined(STM32F412xG) || defined(STM32F446xx)
|
||||
case 0x0C: /* PLL R used as system clock source */
|
||||
/* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLLM) * PLLN
|
||||
SYSCLK = PLL_VCO / PLLR
|
||||
|
@ -1371,13 +1371,13 @@ void RCC_GetClocksFreq(RCC_ClocksTypeDef* RCC_Clocks)
|
|||
else
|
||||
{
|
||||
/* HSI used as PLL clock source */
|
||||
pllvco = (HSI_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6);
|
||||
pllvco = (HSI_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6);
|
||||
}
|
||||
|
||||
pllr = (((RCC->PLLCFGR & RCC_PLLCFGR_PLLR) >>28) + 1 ) *2;
|
||||
RCC_Clocks->SYSCLK_Frequency = pllvco/pllr;
|
||||
break;
|
||||
#endif /* STM32F446xx */
|
||||
#endif /* STM32F412xG || STM32F446xx */
|
||||
|
||||
default:
|
||||
RCC_Clocks->SYSCLK_Frequency = HSI_VALUE;
|
||||
|
@ -1523,7 +1523,7 @@ void RCC_BackupResetCmd(FunctionalState NewState)
|
|||
*(__IO uint32_t *) BDCR_BDRST_BB = (uint32_t)NewState;
|
||||
}
|
||||
|
||||
#if defined(STM32F446xx)
|
||||
#if defined (STM32F412xG) || defined(STM32F446xx)
|
||||
/**
|
||||
* @brief Configures the I2S clock source (I2SCLK).
|
||||
* @note This function must be called before enabling the I2S APB clock.
|
||||
|
@ -1563,7 +1563,7 @@ void RCC_I2SCLKConfig(uint32_t RCC_I2SAPBx, uint32_t RCC_I2SCLKSource)
|
|||
RCC->DCKCFGR |= (RCC_I2SCLKSource << 2);
|
||||
}
|
||||
}
|
||||
|
||||
#if defined(STM32F446xx)
|
||||
/**
|
||||
* @brief Configures the SAIx clock source (SAIxCLK).
|
||||
* @note This function must be called before enabling the SAIx APB clock.
|
||||
|
@ -1603,6 +1603,7 @@ void RCC_SAICLKConfig(uint32_t RCC_SAIInstance, uint32_t RCC_SAICLKSource)
|
|||
}
|
||||
}
|
||||
#endif /* STM32F446xx */
|
||||
#endif /* STM32F412xG || STM32F446xx */
|
||||
|
||||
#if defined(STM32F410xx)
|
||||
/**
|
||||
|
@ -1822,6 +1823,66 @@ void RCC_LTDCCLKDivConfig(uint32_t RCC_PLLSAIDivR)
|
|||
RCC->DCKCFGR = tmpreg;
|
||||
}
|
||||
|
||||
#if defined(STM32F412xG)
|
||||
/**
|
||||
* @brief Configures the DFSDM clock source (DFSDMCLK).
|
||||
* @note This function must be called before enabling the DFSDM APB clock.
|
||||
* @param RCC_DFSDMCLKSource: specifies the DFSDM clock source.
|
||||
* This parameter can be one of the following values:
|
||||
* @arg RCC_DFSDM1CLKSource_APB: APB clock used as DFSDM clock source.
|
||||
* @arg RCC_DFSDM1CLKSource_SYS: System clock used as DFSDM clock source.
|
||||
*
|
||||
* @retval None
|
||||
*/
|
||||
void RCC_DFSDM1CLKConfig(uint32_t RCC_DFSDM1CLKSource)
|
||||
{
|
||||
uint32_t tmpreg = 0;
|
||||
|
||||
/* Check the parameters */
|
||||
assert_param(IS_RCC_DFSDM1CLK_SOURCE(RCC_DFSDM1CLKSource));
|
||||
|
||||
tmpreg = RCC->DCKCFGR;
|
||||
|
||||
/* Clear CKDFSDM-SEL bit */
|
||||
tmpreg &= ~RCC_DCKCFGR_CKDFSDM1SEL;
|
||||
|
||||
/* Set CKDFSDM-SEL bit according to RCC_DFSDMCLKSource value */
|
||||
tmpreg |= (RCC_DFSDM1CLKSource << 31) ;
|
||||
|
||||
/* Store the new value */
|
||||
RCC->DCKCFGR = tmpreg;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Configures the DFSDM Audio clock source (DFSDMACLK).
|
||||
* @note This function must be called before enabling the DFSDM APB clock.
|
||||
* @param RCC_DFSDMACLKSource: specifies the DFSDM clock source.
|
||||
* This parameter can be one of the following values:
|
||||
* @arg RCC_DFSDM1AUDIOCLKSOURCE_I2SAPB1: APB clock used as DFSDM clock source.
|
||||
* @arg RCC_DFSDM1AUDIOCLKSOURCE_I2SAPB2: System clock used as DFSDM clock source.
|
||||
*
|
||||
* @retval None
|
||||
*/
|
||||
void RCC_DFSDM1ACLKConfig(uint32_t RCC_DFSDMACLKSource)
|
||||
{
|
||||
uint32_t tmpreg = 0;
|
||||
|
||||
/* Check the parameters */
|
||||
assert_param(IS_RCC_DFSDMACLK_SOURCE(RCC_DFSDMACLKSource));
|
||||
|
||||
tmpreg = RCC->DCKCFGR;
|
||||
|
||||
/* Clear CKDFSDMA SEL bit */
|
||||
tmpreg &= ~RCC_DCKCFGR_CKDFSDM1ASEL;
|
||||
|
||||
/* Set CKDFSDM-SEL bt according to RCC_DFSDMCLKSource value */
|
||||
tmpreg |= RCC_DFSDMACLKSource;
|
||||
|
||||
/* Store the new value */
|
||||
RCC->DCKCFGR = tmpreg;
|
||||
}
|
||||
#endif /* STM32F412xG */
|
||||
|
||||
/**
|
||||
* @brief Configures the Timers clocks prescalers selection.
|
||||
*
|
||||
|
@ -1930,7 +1991,7 @@ void RCC_AHB2PeriphClockCmd(uint32_t RCC_AHB2Periph, FunctionalState NewState)
|
|||
}
|
||||
}
|
||||
|
||||
#if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx)
|
||||
#if defined(STM32F40_41xxx) || defined(STM32F412xG) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx)
|
||||
/**
|
||||
* @brief Enables or disables the AHB3 peripheral clock.
|
||||
* @note After reset, the peripheral clock (used for registers read/write access)
|
||||
|
@ -1938,8 +1999,8 @@ void RCC_AHB2PeriphClockCmd(uint32_t RCC_AHB2Periph, FunctionalState NewState)
|
|||
* using it.
|
||||
* @param RCC_AHBPeriph: specifies the AHB3 peripheral to gates its clock.
|
||||
* This parameter must be:
|
||||
* - RCC_AHB3Periph_FSMC or RCC_AHB3Periph_FMC (STM32F429x/439x devices)
|
||||
* - RCC_AHB3Periph_QSPI (STM32F446xx/STM32F469_479xx devices)
|
||||
* - RCC_AHB3Periph_FSMC or RCC_AHB3Periph_FMC (STM32F412xG/STM32F429x/439x devices)
|
||||
* - RCC_AHB3Periph_QSPI (STM32F412xG/STM32F446xx/STM32F469_479xx devices)
|
||||
* @param NewState: new state of the specified peripheral clock.
|
||||
* This parameter can be: ENABLE or DISABLE.
|
||||
* @retval None
|
||||
|
@ -1959,7 +2020,7 @@ void RCC_AHB3PeriphClockCmd(uint32_t RCC_AHB3Periph, FunctionalState NewState)
|
|||
RCC->AHB3ENR &= ~RCC_AHB3Periph;
|
||||
}
|
||||
}
|
||||
#endif /* STM32F40_41xxx || STM32F427_437xx || STM32F429_439xx || STM32F446xx || STM32F469_479xx */
|
||||
#endif /* STM32F40_41xxx || STM32F412xG || STM32F427_437xx || STM32F429_439xx || STM32F446xx || STM32F469_479xx */
|
||||
|
||||
/**
|
||||
* @brief Enables or disables the Low Speed APB (APB1) peripheral clock.
|
||||
|
@ -2043,7 +2104,8 @@ void RCC_APB1PeriphClockCmd(uint32_t RCC_APB1Periph, FunctionalState NewState)
|
|||
* @arg RCC_APB2Periph_SAI1: SAI1 clock (STM32F42xxx/43xxx/446xx/469xx/479xx devices)
|
||||
* @arg RCC_APB2Periph_SAI2: SAI2 clock (STM32F446xx devices)
|
||||
* @arg RCC_APB2Periph_LTDC: LTDC clock (STM32F429xx/439xx devices)
|
||||
* @arg RCC_APB2Periph_DSI: DSI clock (STM32F469_479xx devices)
|
||||
* @arg RCC_APB2Periph_DSI: DSI clock (STM32F469_479xx devices)
|
||||
* @arg RCC_APB2Periph_DFSDM: DFSDM Clock (STM32F412xG Devices)
|
||||
* @param NewState: new state of the specified peripheral clock.
|
||||
* This parameter can be: ENABLE or DISABLE.
|
||||
* @retval None
|
||||
|
@ -2114,7 +2176,7 @@ void RCC_AHB1PeriphResetCmd(uint32_t RCC_AHB1Periph, FunctionalState NewState)
|
|||
* @arg RCC_AHB2Periph_DCMI: DCMI clock
|
||||
* @arg RCC_AHB2Periph_CRYP: CRYP clock
|
||||
* @arg RCC_AHB2Periph_HASH: HASH clock
|
||||
* @arg RCC_AHB2Periph_RNG: RNG clock for STM32F40_41xxx/STM32F427_437xx/STM32F429_439xx/STM32F469_479xx devices
|
||||
* @arg RCC_AHB2Periph_RNG: RNG clock for STM32F40_41xxx/STM32F412xG/STM32F427_437xx/STM32F429_439xx/STM32F469_479xx devices
|
||||
* @arg RCC_AHB2Periph_OTG_FS: USB OTG FS clock
|
||||
* @param NewState: new state of the specified peripheral reset.
|
||||
* This parameter can be: ENABLE or DISABLE.
|
||||
|
@ -2136,13 +2198,13 @@ void RCC_AHB2PeriphResetCmd(uint32_t RCC_AHB2Periph, FunctionalState NewState)
|
|||
}
|
||||
}
|
||||
|
||||
#if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx)
|
||||
#if defined(STM32F40_41xxx) || defined(STM32F412xG) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx)
|
||||
/**
|
||||
* @brief Forces or releases AHB3 peripheral reset.
|
||||
* @param RCC_AHB3Periph: specifies the AHB3 peripheral to reset.
|
||||
* This parameter must be:
|
||||
* - RCC_AHB3Periph_FSMC or RCC_AHB3Periph_FMC (STM32F429x/439x devices)
|
||||
* - RCC_AHB3Periph_QSPI (STM32F446xx/STM32F469_479xx devices)
|
||||
* - RCC_AHB3Periph_FSMC or RCC_AHB3Periph_FMC (STM32F412xG and STM32F429x/439x devices)
|
||||
* - RCC_AHB3Periph_QSPI (STM32F412xG/STM32F446xx/STM32F469_479xx devices)
|
||||
* @param NewState: new state of the specified peripheral reset.
|
||||
* This parameter can be: ENABLE or DISABLE.
|
||||
* @retval None
|
||||
|
@ -2162,7 +2224,7 @@ void RCC_AHB3PeriphResetCmd(uint32_t RCC_AHB3Periph, FunctionalState NewState)
|
|||
RCC->AHB3RSTR &= ~RCC_AHB3Periph;
|
||||
}
|
||||
}
|
||||
#endif /* STM32F40_41xxx || STM32F427_437xx || STM32F429_439xx || STM32F446xx || STM32F469_479xx */
|
||||
#endif /* STM32F40_41xxx || STM32F412xG || STM32F427_437xx || STM32F429_439xx || STM32F446xx || STM32F469_479xx */
|
||||
|
||||
/**
|
||||
* @brief Forces or releases Low Speed APB (APB1) peripheral reset.
|
||||
|
@ -2340,7 +2402,7 @@ void RCC_AHB2PeriphClockLPModeCmd(uint32_t RCC_AHB2Periph, FunctionalState NewSt
|
|||
}
|
||||
}
|
||||
|
||||
#if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx)
|
||||
#if defined(STM32F40_41xxx) || defined(STM32F412xG) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx)
|
||||
/**
|
||||
* @brief Enables or disables the AHB3 peripheral clock during Low Power (Sleep) mode.
|
||||
* @note Peripheral clock gating in SLEEP mode can be used to further reduce
|
||||
|
@ -2349,8 +2411,8 @@ void RCC_AHB2PeriphClockLPModeCmd(uint32_t RCC_AHB2Periph, FunctionalState NewSt
|
|||
* @note By default, all peripheral clocks are enabled during SLEEP mode.
|
||||
* @param RCC_AHBPeriph: specifies the AHB3 peripheral to gates its clock.
|
||||
* This parameter must be:
|
||||
* - RCC_AHB3Periph_FSMC or RCC_AHB3Periph_FMC (STM32F429x/439x devices)
|
||||
* - RCC_AHB3Periph_QSPI (STM32F446xx/STM32F469_479xx devices)
|
||||
* - RCC_AHB3Periph_FSMC or RCC_AHB3Periph_FMC (STM32F412xG/STM32F429x/439x devices)
|
||||
* - RCC_AHB3Periph_QSPI (STM32F412xG/STM32F446xx/STM32F469_479xx devices)
|
||||
* @param NewState: new state of the specified peripheral clock.
|
||||
* This parameter can be: ENABLE or DISABLE.
|
||||
* @retval None
|
||||
|
@ -2369,7 +2431,7 @@ void RCC_AHB3PeriphClockLPModeCmd(uint32_t RCC_AHB3Periph, FunctionalState NewSt
|
|||
RCC->AHB3LPENR &= ~RCC_AHB3Periph;
|
||||
}
|
||||
}
|
||||
#endif /* STM32F40_41xxx || STM32F427_437xx || STM32F429_439xx || STM32F446xx || STM32F469_479xx */
|
||||
#endif /* STM32F40_41xxx || STM32F412xG || STM32F427_437xx || STM32F429_439xx || STM32F446xx || STM32F469_479xx */
|
||||
|
||||
/**
|
||||
* @brief Enables or disables the APB1 peripheral clock during Low Power (Sleep) mode.
|
||||
|
@ -2548,7 +2610,7 @@ void RCC_DSIClockSourceConfig(uint8_t RCC_ClockSource)
|
|||
}
|
||||
#endif /* STM32F469_479xx */
|
||||
|
||||
#if defined(STM32F446xx) || defined(STM32F469_479xx)
|
||||
#if defined(STM32F412xG) || defined(STM32F446xx) || defined(STM32F469_479xx)
|
||||
/**
|
||||
* @brief Configures the 48MHz clock Source.
|
||||
* @note This feature is only available for STM32F446xx/STM32F469_479xx devices.
|
||||
|
@ -2556,6 +2618,7 @@ void RCC_DSIClockSourceConfig(uint8_t RCC_ClockSource)
|
|||
* This parameter can be one of the following values:
|
||||
* @arg RCC_48MHZCLKSource_PLL: 48MHz from PLL selected.
|
||||
* @arg RCC_48MHZCLKSource_PLLSAI: 48MHz from PLLSAI selected.
|
||||
* @arg RCC_CK48CLKSOURCE_PLLI2SQ : 48MHz from PLLI2SQ
|
||||
* @retval None
|
||||
*/
|
||||
void RCC_48MHzClockSourceConfig(uint8_t RCC_ClockSource)
|
||||
|
@ -2571,7 +2634,7 @@ void RCC_48MHzClockSourceConfig(uint8_t RCC_ClockSource)
|
|||
{
|
||||
CLEAR_BIT(RCC->DCKCFGR, RCC_DCKCFGR_CK48MSEL);
|
||||
}
|
||||
#elif defined(STM32F446xx)
|
||||
#elif defined(STM32F446xx)
|
||||
if(RCC_ClockSource == RCC_48MHZCLKSource_PLLSAI)
|
||||
{
|
||||
SET_BIT(RCC->DCKCFGR2, RCC_DCKCFGR2_CK48MSEL);
|
||||
|
@ -2580,6 +2643,15 @@ void RCC_48MHzClockSourceConfig(uint8_t RCC_ClockSource)
|
|||
{
|
||||
CLEAR_BIT(RCC->DCKCFGR2, RCC_DCKCFGR2_CK48MSEL);
|
||||
}
|
||||
#elif defined(STM32F412xG)
|
||||
if(RCC_ClockSource == RCC_CK48CLKSOURCE_PLLI2SQ)
|
||||
{
|
||||
SET_BIT(RCC->DCKCFGR2, RCC_DCKCFGR2_CK48MSEL);
|
||||
}
|
||||
else
|
||||
{
|
||||
CLEAR_BIT(RCC->DCKCFGR2, RCC_DCKCFGR2_CK48MSEL);
|
||||
}
|
||||
#else
|
||||
#endif /* STM32F469_479xx */
|
||||
}
|
||||
|
@ -2606,7 +2678,7 @@ void RCC_SDIOClockSourceConfig(uint8_t RCC_ClockSource)
|
|||
{
|
||||
CLEAR_BIT(RCC->DCKCFGR, RCC_DCKCFGR_SDIOSEL);
|
||||
}
|
||||
#elif defined(STM32F446xx)
|
||||
#elif defined(STM32F412xG) || defined(STM32F446xx)
|
||||
if(RCC_ClockSource == RCC_SDIOCLKSource_SYSCLK)
|
||||
{
|
||||
SET_BIT(RCC->DCKCFGR2, RCC_DCKCFGR2_SDIOSEL);
|
||||
|
@ -2618,7 +2690,7 @@ void RCC_SDIOClockSourceConfig(uint8_t RCC_ClockSource)
|
|||
#else
|
||||
#endif /* STM32F469_479xx */
|
||||
}
|
||||
#endif /* STM32F446xx || STM32F469_479xx */
|
||||
#endif /* STM32F412xG || STM32F446xx || STM32F469_479xx */
|
||||
|
||||
#if defined(STM32F446xx)
|
||||
/**
|
||||
|
@ -2702,7 +2774,7 @@ void RCC_CECClockSourceConfig(uint8_t RCC_ClockSource)
|
|||
}
|
||||
#endif /* STM32F446xx */
|
||||
|
||||
#if defined(STM32F410xx) || defined(STM32F446xx)
|
||||
#if defined(STM32F410xx) || defined(STM32F412xG) || defined(STM32F446xx)
|
||||
/**
|
||||
* @brief Configures the FMPI2C1 clock Source.
|
||||
* @note This feature is only available for STM32F446xx devices.
|
||||
|
@ -2723,7 +2795,7 @@ void RCC_FMPI2C1ClockSourceConfig(uint32_t RCC_ClockSource)
|
|||
/* Set new FMPI2C1 clock source */
|
||||
RCC->DCKCFGR2 |= RCC_ClockSource;
|
||||
}
|
||||
#endif /* STM32F410xx || STM32F446xx */
|
||||
#endif /* STM32F410xx || STM32F412xG || STM32F446xx */
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
|
|
@ -2,8 +2,8 @@
|
|||
******************************************************************************
|
||||
* @file stm32f4xx_rng.c
|
||||
* @author MCD Application Team
|
||||
* @version V1.6.1
|
||||
* @date 21-October-2015
|
||||
* @version V1.7.1
|
||||
* @date 20-May-2016
|
||||
* @brief This file provides firmware functions to manage the following
|
||||
* functionalities of the Random Number Generator (RNG) peripheral:
|
||||
* + Initialization and Configuration
|
||||
|
@ -35,7 +35,7 @@
|
|||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2015 STMicroelectronics</center></h2>
|
||||
* <h2><center>© COPYRIGHT 2016 STMicroelectronics</center></h2>
|
||||
*
|
||||
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
|
||||
* You may not use this file except in compliance with the License.
|
||||
|
@ -64,7 +64,7 @@
|
|||
* @brief RNG driver modules
|
||||
* @{
|
||||
*/
|
||||
#if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F410xx) || defined(STM32F429_439xx) || defined(STM32F469_479xx)
|
||||
#if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F410xx) || defined(STM32F412xG) || defined(STM32F429_439xx) || defined(STM32F469_479xx)
|
||||
/* Private typedef -----------------------------------------------------------*/
|
||||
/* Private define ------------------------------------------------------------*/
|
||||
/* Private macro -------------------------------------------------------------*/
|
||||
|
@ -393,7 +393,7 @@ void RNG_ClearITPendingBit(uint8_t RNG_IT)
|
|||
/**
|
||||
* @}
|
||||
*/
|
||||
#endif /* STM32F40_41xxx || STM32F427_437xx || STM32F410xx || STM32F429_439xx || STM32F469_479xx */
|
||||
#endif /* STM32F40_41xxx || STM32F427_437xx || STM32F410xx || STM32F412xG || STM32F429_439xx || STM32F469_479xx */
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
|
|
@ -2,8 +2,8 @@
|
|||
******************************************************************************
|
||||
* @file stm32f4xx_rtc.c
|
||||
* @author MCD Application Team
|
||||
* @version V1.6.1
|
||||
* @date 21-October-2015
|
||||
* @version V1.7.1
|
||||
* @date 20-May-2016
|
||||
* @brief This file provides firmware functions to manage the following
|
||||
* functionalities of the Real-Time Clock (RTC) peripheral:
|
||||
* + Initialization
|
||||
|
@ -264,7 +264,7 @@
|
|||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2015 STMicroelectronics</center></h2>
|
||||
* <h2><center>© COPYRIGHT 2016 STMicroelectronics</center></h2>
|
||||
*
|
||||
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
|
||||
* You may not use this file except in compliance with the License.
|
||||
|
@ -305,7 +305,7 @@
|
|||
RTC_FLAG_ALRBF | RTC_FLAG_ALRAF | RTC_FLAG_INITF | \
|
||||
RTC_FLAG_RSF | RTC_FLAG_INITS | RTC_FLAG_WUTWF | \
|
||||
RTC_FLAG_ALRBWF | RTC_FLAG_ALRAWF | RTC_FLAG_TAMP1F | \
|
||||
RTC_FLAG_RECALPF | RTC_FLAG_SHPF))
|
||||
RTC_FLAG_TAMP2F | RTC_FLAG_RECALPF | RTC_FLAG_SHPF))
|
||||
|
||||
#define INITMODE_TIMEOUT ((uint32_t) 0x00010000)
|
||||
#define SYNCHRO_TIMEOUT ((uint32_t) 0x00020000)
|
||||
|
@ -2092,7 +2092,7 @@ uint32_t RTC_GetTimeStampSubSecond(void)
|
|||
/**
|
||||
* @brief Configures the select Tamper pin edge.
|
||||
* @param RTC_Tamper: Selected tamper pin.
|
||||
* This parameter can be RTC_Tamper_1.
|
||||
* This parameter can be RTC_Tamper_1 or RTC_Tamper 2
|
||||
* @param RTC_TamperTrigger: Specifies the trigger on the tamper pin that
|
||||
* stimulates tamper event.
|
||||
* This parameter can be one of the following values:
|
||||
|
@ -2123,7 +2123,7 @@ void RTC_TamperTriggerConfig(uint32_t RTC_Tamper, uint32_t RTC_TamperTrigger)
|
|||
/**
|
||||
* @brief Enables or Disables the Tamper detection.
|
||||
* @param RTC_Tamper: Selected tamper pin.
|
||||
* This parameter can be RTC_Tamper_1.
|
||||
* This parameter can be RTC_Tamper_1 or RTC_Tamper_2
|
||||
* @param NewState: new state of the tamper pin.
|
||||
* This parameter can be: ENABLE or DISABLE.
|
||||
* @retval None
|
||||
|
@ -2356,8 +2356,8 @@ uint32_t RTC_ReadBackupRegister(uint32_t RTC_BKP_DR)
|
|||
* @brief Selects the RTC Tamper Pin.
|
||||
* @param RTC_TamperPin: specifies the RTC Tamper Pin.
|
||||
* This parameter can be one of the following values:
|
||||
* @arg RTC_TamperPin_PC13: PC13 is selected as RTC Tamper Pin.
|
||||
* @arg RTC_TamperPin_PI8: PI8 is selected as RTC Tamper Pin.
|
||||
* @arg RTC_TamperPin_Default: RTC_AF1 is used as RTC Tamper Pin.
|
||||
* @arg RTC_TamperPin_Pos1: RTC_AF2 is selected as RTC Tamper Pin.
|
||||
* @retval None
|
||||
*/
|
||||
void RTC_TamperPinSelection(uint32_t RTC_TamperPin)
|
||||
|
@ -2588,6 +2588,7 @@ void RTC_ITConfig(uint32_t RTC_IT, FunctionalState NewState)
|
|||
* This parameter can be one of the following values:
|
||||
* @arg RTC_FLAG_RECALPF: RECALPF event flag.
|
||||
* @arg RTC_FLAG_TAMP1F: Tamper 1 event flag
|
||||
* @arg RTC_FLAG_TAMP2F: Tamper 2 event flag
|
||||
* @arg RTC_FLAG_TSOVF: Time Stamp OverFlow flag
|
||||
* @arg RTC_FLAG_TSF: Time Stamp event flag
|
||||
* @arg RTC_FLAG_WUTF: WakeUp Timer flag
|
||||
|
@ -2630,6 +2631,7 @@ FlagStatus RTC_GetFlagStatus(uint32_t RTC_FLAG)
|
|||
* @param RTC_FLAG: specifies the RTC flag to clear.
|
||||
* This parameter can be any combination of the following values:
|
||||
* @arg RTC_FLAG_TAMP1F: Tamper 1 event flag
|
||||
* @arg RTC_FLAG_TAMP2F: Tamper 2 event flag
|
||||
* @arg RTC_FLAG_TSOVF: Time Stamp Overflow flag
|
||||
* @arg RTC_FLAG_TSF: Time Stamp event flag
|
||||
* @arg RTC_FLAG_WUTF: WakeUp Timer flag
|
||||
|
@ -2655,7 +2657,8 @@ void RTC_ClearFlag(uint32_t RTC_FLAG)
|
|||
* @arg RTC_IT_WUT: WakeUp Timer interrupt
|
||||
* @arg RTC_IT_ALRB: Alarm B interrupt
|
||||
* @arg RTC_IT_ALRA: Alarm A interrupt
|
||||
* @arg RTC_IT_TAMP1: Tamper 1 event interrupt
|
||||
* @arg RTC_IT_TAMP1: Tamper 1 event interrupt
|
||||
* @arg RTC_IT_TAMP2: Tamper 2 event interrupt
|
||||
* @retval The new state of RTC_IT (SET or RESET).
|
||||
*/
|
||||
ITStatus RTC_GetITStatus(uint32_t RTC_IT)
|
||||
|
@ -2670,7 +2673,7 @@ ITStatus RTC_GetITStatus(uint32_t RTC_IT)
|
|||
tmpreg = (uint32_t)(RTC->TAFCR & (RTC_TAFCR_TAMPIE));
|
||||
|
||||
/* Get the Interrupt enable Status */
|
||||
enablestatus = (uint32_t)((RTC->CR & RTC_IT) | (tmpreg & (RTC_IT >> 15)));
|
||||
enablestatus = (uint32_t)((RTC->CR & RTC_IT) | (tmpreg & (RTC_IT >> 15)) | (tmpreg & (RTC_IT >> 16)));
|
||||
|
||||
/* Get the Interrupt pending bit */
|
||||
tmpreg = (uint32_t)((RTC->ISR & (uint32_t)(RTC_IT >> 4)));
|
||||
|
@ -2695,7 +2698,8 @@ ITStatus RTC_GetITStatus(uint32_t RTC_IT)
|
|||
* @arg RTC_IT_WUT: WakeUp Timer interrupt
|
||||
* @arg RTC_IT_ALRB: Alarm B interrupt
|
||||
* @arg RTC_IT_ALRA: Alarm A interrupt
|
||||
* @arg RTC_IT_TAMP1: Tamper 1 event interrupt
|
||||
* @arg RTC_IT_TAMP1: Tamper 1 event interrupt
|
||||
* @arg RTC_IT_TAMP2: Tamper 2 event interrupt
|
||||
* @retval None
|
||||
*/
|
||||
void RTC_ClearITPendingBit(uint32_t RTC_IT)
|
||||
|
|
|
@ -2,8 +2,8 @@
|
|||
******************************************************************************
|
||||
* @file stm32f4xx_sai.c
|
||||
* @author MCD Application Team
|
||||
* @version V1.6.1
|
||||
* @date 21-October-2015
|
||||
* @version V1.7.1
|
||||
* @date 20-May-2016
|
||||
* @brief This file provides firmware functions to manage the following
|
||||
* functionalities of the Serial Audio Interface (SAI):
|
||||
* + Initialization and Configuration
|
||||
|
@ -105,7 +105,7 @@
|
|||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2015 STMicroelectronics</center></h2>
|
||||
* <h2><center>© COPYRIGHT 2016 STMicroelectronics</center></h2>
|
||||
*
|
||||
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
|
||||
* You may not use this file except in compliance with the License.
|
||||
|
|
|
@ -2,8 +2,8 @@
|
|||
******************************************************************************
|
||||
* @file stm32f4xx_sdio.c
|
||||
* @author MCD Application Team
|
||||
* @version V1.6.1
|
||||
* @date 21-October-2015
|
||||
* @version V1.7.1
|
||||
* @date 20-May-2016
|
||||
* @brief This file provides firmware functions to manage the following
|
||||
* functionalities of the Secure digital input/output interface (SDIO)
|
||||
* peripheral:
|
||||
|
@ -135,7 +135,7 @@
|
|||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2015 STMicroelectronics</center></h2>
|
||||
* <h2><center>© COPYRIGHT 2016 STMicroelectronics</center></h2>
|
||||
*
|
||||
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
|
||||
* You may not use this file except in compliance with the License.
|
||||
|
|
|
@ -2,8 +2,8 @@
|
|||
******************************************************************************
|
||||
* @file stm32f4xx_spdifrx.c
|
||||
* @author MCD Application Team
|
||||
* @version V1.6.1
|
||||
* @date 21-October-2015
|
||||
* @version V1.7.1
|
||||
* @date 20-May-2016
|
||||
* @brief This file provides firmware functions to manage the following
|
||||
* functionalities of the Serial Audio Interface (SPDIFRX):
|
||||
* + Initialization and Configuration
|
||||
|
@ -13,7 +13,7 @@
|
|||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2015 STMicroelectronics</center></h2>
|
||||
* <h2><center>© COPYRIGHT 2016 STMicroelectronics</center></h2>
|
||||
*
|
||||
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
|
||||
* You may not use this file except in compliance with the License.
|
||||
|
|
|
@ -2,8 +2,8 @@
|
|||
******************************************************************************
|
||||
* @file stm32f4xx_spi.c
|
||||
* @author MCD Application Team
|
||||
* @version V1.6.1
|
||||
* @date 21-October-2015
|
||||
* @version V1.7.1
|
||||
* @date 20-May-2016
|
||||
* @brief This file provides firmware functions to manage the following
|
||||
* functionalities of the Serial peripheral interface (SPI):
|
||||
* + Initialization and Configuration
|
||||
|
@ -138,7 +138,7 @@
|
|||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2015 STMicroelectronics</center></h2>
|
||||
* <h2><center>© COPYRIGHT 2016 STMicroelectronics</center></h2>
|
||||
*
|
||||
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
|
||||
* You may not use this file except in compliance with the License.
|
||||
|
|
|
@ -2,8 +2,8 @@
|
|||
******************************************************************************
|
||||
* @file stm32f4xx_syscfg.c
|
||||
* @author MCD Application Team
|
||||
* @version V1.6.1
|
||||
* @date 21-October-2015
|
||||
* @version V1.7.1
|
||||
* @date 20-May-2016
|
||||
* @brief This file provides firmware functions to manage the SYSCFG peripheral.
|
||||
*
|
||||
@verbatim
|
||||
|
@ -29,7 +29,7 @@
|
|||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2015 STMicroelectronics</center></h2>
|
||||
* <h2><center>© COPYRIGHT 2016 STMicroelectronics</center></h2>
|
||||
*
|
||||
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
|
||||
* You may not use this file except in compliance with the License.
|
||||
|
@ -225,7 +225,7 @@ FlagStatus SYSCFG_GetCompensationCellStatus(void)
|
|||
return bitstatus;
|
||||
}
|
||||
|
||||
#if defined(STM32F410xx)
|
||||
#if defined(STM32F410xx) || defined(STM32F412xG)
|
||||
/**
|
||||
* @brief Connects the selected parameter to the break input of TIM1.
|
||||
* @note The selected configuration is locked and can be unlocked by system reset
|
||||
|
@ -243,7 +243,7 @@ void SYSCFG_BreakConfig(uint32_t SYSCFG_Break)
|
|||
|
||||
SYSCFG->CFGR2 |= (uint32_t) SYSCFG_Break;
|
||||
}
|
||||
#endif /* STM32F410xx */
|
||||
#endif /* STM32F410xx || STM32F412xG */
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
|
|
@ -2,8 +2,8 @@
|
|||
******************************************************************************
|
||||
* @file stm32f4xx_tim.c
|
||||
* @author MCD Application Team
|
||||
* @version V1.6.1
|
||||
* @date 21-October-2015
|
||||
* @version V1.7.1
|
||||
* @date 20-May-2016
|
||||
* @brief This file provides firmware functions to manage the following
|
||||
* functionalities of the TIM peripheral:
|
||||
* + TimeBase management
|
||||
|
@ -98,7 +98,7 @@
|
|||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2015 STMicroelectronics</center></h2>
|
||||
* <h2><center>© COPYRIGHT 2016 STMicroelectronics</center></h2>
|
||||
*
|
||||
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
|
||||
* You may not use this file except in compliance with the License.
|
||||
|
|
|
@ -2,8 +2,8 @@
|
|||
******************************************************************************
|
||||
* @file stm32f4xx_usart.c
|
||||
* @author MCD Application Team
|
||||
* @version V1.6.1
|
||||
* @date 21-October-2015
|
||||
* @version V1.7.1
|
||||
* @date 20-May-2016
|
||||
* @brief This file provides firmware functions to manage the following
|
||||
* functionalities of the Universal synchronous asynchronous receiver
|
||||
* transmitter (USART):
|
||||
|
@ -71,7 +71,7 @@
|
|||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2015 STMicroelectronics</center></h2>
|
||||
* <h2><center>© COPYRIGHT 2016 STMicroelectronics</center></h2>
|
||||
*
|
||||
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
|
||||
* You may not use this file except in compliance with the License.
|
||||
|
|
|
@ -2,8 +2,8 @@
|
|||
******************************************************************************
|
||||
* @file stm32f4xx_wwdg.c
|
||||
* @author MCD Application Team
|
||||
* @version V1.6.1
|
||||
* @date 21-October-2015
|
||||
* @version V1.7.1
|
||||
* @date 20-May-2016
|
||||
* @brief This file provides firmware functions to manage the following
|
||||
* functionalities of the Window watchdog (WWDG) peripheral:
|
||||
* + Prescaler, Refresh window and Counter configuration
|
||||
|
@ -63,7 +63,7 @@
|
|||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2015 STMicroelectronics</center></h2>
|
||||
* <h2><center>© COPYRIGHT 2016 STMicroelectronics</center></h2>
|
||||
*
|
||||
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
|
||||
* You may not use this file except in compliance with the License.
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue