The STM32 UART is finally running.
authortravisutk <travisutk@12e2690d-a6be-4b82-a7b7-67c4a43b65c8>
Mon, 7 May 2012 17:06:53 +0000 (17:06 +0000)
committertravisutk <travisutk@12e2690d-a6be-4b82-a7b7-67c4a43b65c8>
Mon, 7 May 2012 17:06:53 +0000 (17:06 +0000)
Problem was that .data wasn't being initialized by the custom linker script.

git-svn-id: https://svn.code.sf.net/p/goodfet/code/trunk@1164 12e2690d-a6be-4b82-a7b7-67c4a43b65c8

firmware/config.mk
firmware/include/stm32f4xx.h
firmware/lib/stm32f407.c
firmware/lib/stm32f4xx_rcc.c [new file with mode: 0644]
firmware/lib/system_stm32f4xx.c

index 20562c9..0adba78 100644 (file)
@@ -64,7 +64,7 @@ config = monitor
 
 # This is a pain.
 #usblibs =  $(usbsrc)/usbd_core.o $(usbsrc)/usbd_req.o $(usbsrc)/usbd_ioreq.o $(usbsrc)/usbd_core.o $(otgsrc)/usb_dcd.o $(otgsrc)/usb_dcd_int.o $(otgsrc)/usb_hcd.o $(otgsrc)/usb_hcd_int.o $(otgsrc)/usb_otg.o
-extralibs = lib/cortexm3.o lib/system_stm32f4xx.o $(psrc)/stm32f4xx_rcc.o $(psrc)/stm32f4xx_gpio.o $(psrc)/stm32f4xx_usart.o $(usblibs) 
+extralibs = lib/cortexm3.o lib/system_stm32f4xx.o lib/stm32f4xx_rcc.o $(psrc)/stm32f4xx_gpio.o $(psrc)/stm32f4xx_usart.o $(usblibs) 
 
 endif
 
index e7b49be..63306ba 100644 (file)
         can define the HSE value in your toolchain compiler preprocessor.\r
   */           \r
 \r
-#if !defined  (HSE_VALUE) \r
-  #define HSE_VALUE    ((uint32_t)25000000) /*!< Value of the External oscillator in Hz */\r
-#endif /* HSE_VALUE */\r
+//#if !defined  (HSE_VALUE) \r
+#undef HSE_VALUE\r
+#define HSE_VALUE    ((uint32_t)8000000) /*!< Value of the External oscillator in Hz */\r
+//#endif /* HSE_VALUE */\r
 \r
 /**\r
  * @brief In the following line adjust the External High Speed oscillator (HSE) Startup \r
index b781e49..fa23289 100644 (file)
@@ -22,8 +22,8 @@ void ioinit(){
   GPIO_InitStructure.GPIO_Pin = GPIO_Pin_12 | GPIO_Pin_13| GPIO_Pin_14| GPIO_Pin_15;
   GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT;
   GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
-  GPIO_InitStructure.GPIO_Speed = GPIO_Speed_2MHz;
-  GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
+  GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+  GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP;
   GPIO_Init(GPIOD, &GPIO_InitStructure);
 }
 
@@ -84,20 +84,24 @@ uint32_t strlen(const char *s){
 }
 
 
-//! Initialize the USART
-void usartinit(){
-  GPIO_InitTypeDef GPIO_InitStructure;
-  USART_InitTypeDef USART_InitStructure;
-  
+/**************************************************************************************/
+void Repair_Data();
+void RCC_Configuration(void)
+{
   /* --------------------------- System Clocks Configuration -----------------*/
   /* USART1 clock enable */
   RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1, ENABLE);
  
   /* GPIOB clock enable */
   RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOB, ENABLE);
-  
-  
-  
+}
+/**************************************************************************************/
+void GPIO_Configuration(void)
+{
+  GPIO_InitTypeDef GPIO_InitStructure;
   /*-------------------------- GPIO Configuration ----------------------------*/
   GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6 | GPIO_Pin_7;
   GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
@@ -109,7 +113,14 @@ void usartinit(){
   /* Connect USART pins to AF */
   GPIO_PinAFConfig(GPIOB, GPIO_PinSource6, GPIO_AF_USART1); // USART1_TX
   GPIO_PinAFConfig(GPIOB, GPIO_PinSource7, GPIO_AF_USART1); // USART1_RX
-  
+}
+/**************************************************************************************/
+void USART1_Configuration(void)
+{
+  USART_InitTypeDef USART_InitStructure;
   /* USARTx configuration ------------------------------------------------------*/
   /* USARTx configured as follow:
         - BaudRate = 9600 baud
@@ -125,13 +136,22 @@ void usartinit(){
   USART_InitStructure.USART_Parity = USART_Parity_No;
   USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
  
-  //USART_InitStructure.USART_Mode = USART_Mode_Rx | USART_Mode_Tx;
-  USART_InitStructure.USART_Mode = USART_Mode_Tx;
+  USART_InitStructure.USART_Mode = USART_Mode_Rx | USART_Mode_Tx;
  
   USART_Init(USART1, &USART_InitStructure);
  
   USART_Cmd(USART1, ENABLE);
 }
+
+//! Initialize the USART
+void usartinit(){
+  RCC_Configuration();
+  GPIO_Configuration();
+  USART1_Configuration();
+}
 
 
 //! Initialize the STM32F4xx ports and USB.
@@ -142,6 +162,9 @@ void stm32f4xx_init(){
   ioinit();
   usartinit();
   
+  while(i--) stmdelay();
+  
+  serial0_tx(0xAA);
   
   return;
 }
@@ -159,12 +182,23 @@ unsigned char serial1_rx(){
 //! Transmit a byte.
 void serial0_tx(unsigned char x){
   
-  spiword(0xdead);
+  spiword(0xdeadbeef);
   
-  while(USART_GetFlagStatus(USART1, USART_FLAG_TXE) == RESET);
+  spiword(USART1->SR);
+  
+  while(USART_GetFlagStatus(USART1, USART_FLAG_TXE) == RESET) //original
+    spiword(USART1->SR);
   USART_SendData(USART1, (uint16_t) x);
   
-  spiword(0xbeef);
+  spiword(USART1->SR);
+  
+  stmdelay();
+  stmdelay();
+  stmdelay();
+  stmdelay();
+  stmdelay();
+  stmdelay();
+  
 }
 
 //! Transmit a byte on the second UART.
diff --git a/firmware/lib/stm32f4xx_rcc.c b/firmware/lib/stm32f4xx_rcc.c
new file mode 100644 (file)
index 0000000..39d1094
--- /dev/null
@@ -0,0 +1,1808 @@
+/**\r
+  ******************************************************************************\r
+  * @file    stm32f4xx_rcc.c\r
+  * @author  MCD Application Team\r
+  * @version V1.0.0\r
+  * @date    30-September-2011\r
+  * @brief   This file provides firmware functions to manage the following \r
+  *          functionalities of the Reset and clock control (RCC) peripheral:\r
+  *           - Internal/external clocks, PLL, CSS and MCO configuration\r
+  *           - System, AHB and APB busses clocks configuration\r
+  *           - Peripheral clocks configuration\r
+  *           - Interrupts and flags management\r
+  *\r
+  *  @verbatim\r
+  *               \r
+  *          ===================================================================\r
+  *                               RCC specific features\r
+  *          ===================================================================\r
+  *    \r
+  *          After reset the device is running from Internal High Speed oscillator \r
+  *          (HSI 16MHz) with Flash 0 wait state, Flash prefetch buffer, D-Cache \r
+  *          and I-Cache are disabled, and all peripherals are off except internal\r
+  *          SRAM, Flash and JTAG.\r
+  *           - There is no prescaler on High speed (AHB) and Low speed (APB) busses;\r
+  *             all peripherals mapped on these busses are running at HSI speed.\r
+  *              - The clock for all peripherals is switched off, except the SRAM and FLASH.\r
+  *           - All GPIOs are in input floating state, except the JTAG pins which\r
+  *             are assigned to be used for debug purpose.\r
+  *        \r
+  *          Once the device started from reset, the user application has to:        \r
+  *           - Configure the clock source to be used to drive the System clock\r
+  *             (if the application needs higher frequency/performance)\r
+  *           - Configure the System clock frequency and Flash settings  \r
+  *           - Configure the AHB and APB busses prescalers\r
+  *           - Enable the clock for the peripheral(s) to be used\r
+  *           - Configure the clock source(s) for peripherals which clocks are not\r
+  *             derived from the System clock (I2S, RTC, ADC, USB OTG FS/SDIO/RNG)      \r
+  *                        \r
+  *  @endverbatim\r
+  *    \r
+  ******************************************************************************\r
+  * @attention\r
+  *\r
+  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS\r
+  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE\r
+  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY\r
+  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING\r
+  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE\r
+  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.\r
+  *\r
+  * <h2><center>&copy; COPYRIGHT 2011 STMicroelectronics</center></h2>\r
+  ******************************************************************************\r
+  */\r
+\r
+/* Includes ------------------------------------------------------------------*/\r
+#include "stm32f4xx_rcc.h"\r
+\r
+/** @addtogroup STM32F4xx_StdPeriph_Driver\r
+  * @{\r
+  */\r
+\r
+/** @defgroup RCC \r
+  * @brief RCC driver modules\r
+  * @{\r
+  */ \r
+\r
+/* Private typedef -----------------------------------------------------------*/\r
+/* Private define ------------------------------------------------------------*/\r
+/* ------------ RCC registers bit address in the alias region ----------- */\r
+#define RCC_OFFSET                (RCC_BASE - PERIPH_BASE)\r
+/* --- CR Register ---*/\r
+/* Alias word address of HSION bit */\r
+#define CR_OFFSET                 (RCC_OFFSET + 0x00)\r
+#define HSION_BitNumber           0x00\r
+#define CR_HSION_BB               (PERIPH_BB_BASE + (CR_OFFSET * 32) + (HSION_BitNumber * 4))\r
+/* Alias word address of CSSON bit */\r
+#define CSSON_BitNumber           0x13\r
+#define CR_CSSON_BB               (PERIPH_BB_BASE + (CR_OFFSET * 32) + (CSSON_BitNumber * 4))\r
+/* Alias word address of PLLON bit */\r
+#define PLLON_BitNumber           0x18\r
+#define CR_PLLON_BB               (PERIPH_BB_BASE + (CR_OFFSET * 32) + (PLLON_BitNumber * 4))\r
+/* Alias word address of PLLI2SON bit */\r
+#define PLLI2SON_BitNumber        0x1A\r
+#define CR_PLLI2SON_BB            (PERIPH_BB_BASE + (CR_OFFSET * 32) + (PLLI2SON_BitNumber * 4))\r
+\r
+/* --- CFGR Register ---*/\r
+/* Alias word address of I2SSRC bit */\r
+#define CFGR_OFFSET               (RCC_OFFSET + 0x08)\r
+#define I2SSRC_BitNumber          0x17\r
+#define CFGR_I2SSRC_BB            (PERIPH_BB_BASE + (CFGR_OFFSET * 32) + (I2SSRC_BitNumber * 4))\r
+\r
+/* --- BDCR Register ---*/\r
+/* Alias word address of RTCEN bit */\r
+#define BDCR_OFFSET               (RCC_OFFSET + 0x70)\r
+#define RTCEN_BitNumber           0x0F\r
+#define BDCR_RTCEN_BB             (PERIPH_BB_BASE + (BDCR_OFFSET * 32) + (RTCEN_BitNumber * 4))\r
+/* Alias word address of BDRST bit */\r
+#define BDRST_BitNumber           0x10\r
+#define BDCR_BDRST_BB             (PERIPH_BB_BASE + (BDCR_OFFSET * 32) + (BDRST_BitNumber * 4))\r
+/* --- CSR Register ---*/\r
+/* Alias word address of LSION bit */\r
+#define CSR_OFFSET                (RCC_OFFSET + 0x74)\r
+#define LSION_BitNumber           0x00\r
+#define CSR_LSION_BB              (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (LSION_BitNumber * 4))\r
+/* ---------------------- RCC registers bit mask ------------------------ */\r
+/* CFGR register bit mask */\r
+#define CFGR_MCO2_RESET_MASK      ((uint32_t)0x07FFFFFF)\r
+#define CFGR_MCO1_RESET_MASK      ((uint32_t)0xF89FFFFF)\r
+\r
+/* RCC Flag Mask */\r
+#define FLAG_MASK                 ((uint8_t)0x1F)\r
+\r
+/* CR register byte 3 (Bits[23:16]) base address */\r
+#define CR_BYTE3_ADDRESS          ((uint32_t)0x40023802)\r
+\r
+/* CIR register byte 2 (Bits[15:8]) base address */\r
+#define CIR_BYTE2_ADDRESS         ((uint32_t)(RCC_BASE + 0x0C + 0x01))\r
+\r
+/* CIR register byte 3 (Bits[23:16]) base address */\r
+#define CIR_BYTE3_ADDRESS         ((uint32_t)(RCC_BASE + 0x0C + 0x02))\r
+\r
+/* BDCR register base address */\r
+#define BDCR_ADDRESS              (PERIPH_BASE + BDCR_OFFSET)\r
+\r
+/* Private macro -------------------------------------------------------------*/\r
+/* Private variables ---------------------------------------------------------*/\r
+//static __I uint8_t APBAHBPrescTable[16] = {0, 0, 0, 0, 1, 2, 3, 4, 1, 2, 3, 4, 6, 7, 8, 9};\r
+__attribute__ ((section (".text"))) uint8_t APBAHBPrescTable[16] = {0, 0, 0, 0, 1, 2, 3, 4, 1, 2, 3, 4, 6, 7, 8, 9};\r
+/* Private function prototypes -----------------------------------------------*/\r
+/* Private functions ---------------------------------------------------------*/\r
+\r
+/** @defgroup RCC_Private_Functions\r
+  * @{\r
+  */ \r
+\r
+/** @defgroup RCC_Group1 Internal and external clocks, PLL, CSS and MCO configuration functions\r
+ *  @brief   Internal and external clocks, PLL, CSS and MCO configuration functions \r
+ *\r
+@verbatim   \r
+ ===============================================================================\r
+      Internal/external clocks, PLL, CSS and MCO configuration functions\r
+ ===============================================================================  \r
+\r
+  This section provide functions allowing to configure the internal/external clocks,\r
+  PLLs, CSS and MCO pins.\r
+  \r
+  1. HSI (high-speed internal), 16 MHz factory-trimmed RC used directly or through\r
+     the PLL as System clock source.\r
+\r
+  2. LSI (low-speed internal), 32 KHz low consumption RC used as IWDG and/or RTC\r
+     clock source.\r
+\r
+  3. HSE (high-speed external), 4 to 26 MHz crystal oscillator used directly or\r
+     through the PLL as System clock source. Can be used also as RTC clock source.\r
+\r
+  4. LSE (low-speed external), 32 KHz oscillator used as RTC clock source.   \r
+\r
+  5. PLL (clocked by HSI or HSE), featuring two different output clocks:\r
+      - The first output is used to generate the high speed system clock (up to 168 MHz)\r
+      - The second output is used to generate the clock for the USB OTG FS (48 MHz),\r
+        the random analog generator (<=48 MHz) and the SDIO (<= 48 MHz).\r
+\r
+  6. PLLI2S (clocked by HSI or HSE), used to generate an accurate clock to achieve \r
+     high-quality audio performance on the I2S interface.\r
+  \r
+  7. CSS (Clock security system), once enable and if a HSE clock failure occurs \r
+     (HSE used directly or through PLL as System clock source), the System clock\r
+     is automatically switched to HSI and an interrupt is generated if enabled. \r
+     The interrupt is linked to the Cortex-M4 NMI (Non-Maskable Interrupt) \r
+     exception vector.   \r
+\r
+  8. MCO1 (microcontroller clock output), used to output HSI, LSE, HSE or PLL\r
+     clock (through a configurable prescaler) on PA8 pin.\r
+\r
+  9. MCO2 (microcontroller clock output), used to output HSE, PLL, SYSCLK or PLLI2S\r
+     clock (through a configurable prescaler) on PC9 pin.\r
+\r
+@endverbatim\r
+  * @{\r
+  */\r
+\r
+/**\r
+  * @brief  Resets the RCC clock configuration to the default reset state.\r
+  * @note   The default reset state of the clock configuration is given below:\r
+  *            - HSI ON and used as system clock source\r
+  *            - HSE, PLL and PLLI2S OFF\r
+  *            - AHB, APB1 and APB2 prescaler set to 1.\r
+  *            - CSS, MCO1 and MCO2 OFF\r
+  *            - All interrupts disabled\r
+  * @note   This function doesn't modify the configuration of the\r
+  *            - Peripheral clocks\r
+  *            - LSI, LSE and RTC clocks \r
+  * @param  None\r
+  * @retval None\r
+  */\r
+void RCC_DeInit(void)\r
+{\r
+  /* Set HSION bit */\r
+  RCC->CR |= (uint32_t)0x00000001;\r
+\r
+  /* Reset CFGR register */\r
+  RCC->CFGR = 0x00000000;\r
+\r
+  /* Reset HSEON, CSSON and PLLON bits */\r
+  RCC->CR &= (uint32_t)0xFEF6FFFF;\r
+\r
+  /* Reset PLLCFGR register */\r
+  RCC->PLLCFGR = 0x24003010;\r
+\r
+  /* Reset HSEBYP bit */\r
+  RCC->CR &= (uint32_t)0xFFFBFFFF;\r
+\r
+  /* Disable all interrupts */\r
+  RCC->CIR = 0x00000000;\r
+}\r
+\r
+/**\r
+  * @brief  Configures the External High Speed oscillator (HSE).\r
+  * @note   After enabling the HSE (RCC_HSE_ON or RCC_HSE_Bypass), the application\r
+  *         software should wait on HSERDY flag to be set indicating that HSE clock\r
+  *         is stable and can be used to clock the PLL and/or system clock.\r
+  * @note   HSE state can not be changed if it is used directly or through the\r
+  *         PLL as system clock. In this case, you have to select another source\r
+  *         of the system clock then change the HSE state (ex. disable it).\r
+  * @note   The HSE is stopped by hardware when entering STOP and STANDBY modes.  \r
+  * @note   This function reset the CSSON bit, so if the Clock security system(CSS)\r
+  *         was previously enabled you have to enable it again after calling this\r
+  *         function.    \r
+  * @param  RCC_HSE: specifies the new state of the HSE.\r
+  *          This parameter can be one of the following values:\r
+  *            @arg RCC_HSE_OFF: turn OFF the HSE oscillator, HSERDY flag goes low after\r
+  *                              6 HSE oscillator clock cycles.\r
+  *            @arg RCC_HSE_ON: turn ON the HSE oscillator\r
+  *            @arg RCC_HSE_Bypass: HSE oscillator bypassed with external clock\r
+  * @retval None\r
+  */\r
+void RCC_HSEConfig(uint8_t RCC_HSE)\r
+{\r
+  /* Check the parameters */\r
+  assert_param(IS_RCC_HSE(RCC_HSE));\r
+\r
+  /* Reset HSEON and HSEBYP bits before configuring the HSE ------------------*/\r
+  *(__IO uint8_t *) CR_BYTE3_ADDRESS = RCC_HSE_OFF;\r
+\r
+  /* Set the new HSE configuration -------------------------------------------*/\r
+  *(__IO uint8_t *) CR_BYTE3_ADDRESS = RCC_HSE;\r
+}\r
+\r
+/**\r
+  * @brief  Waits for HSE start-up.\r
+  * @note   This functions waits on HSERDY flag to be set and return SUCCESS if \r
+  *         this flag is set, otherwise returns ERROR if the timeout is reached \r
+  *         and this flag is not set. The timeout value is defined by the constant\r
+  *         HSE_STARTUP_TIMEOUT in stm32f4xx.h file. You can tailor it depending\r
+  *         on the HSE crystal used in your application. \r
+  * @param  None\r
+  * @retval An ErrorStatus enumeration value:\r
+  *          - SUCCESS: HSE oscillator is stable and ready to use\r
+  *          - ERROR: HSE oscillator not yet ready\r
+  */\r
+ErrorStatus RCC_WaitForHSEStartUp(void)\r
+{\r
+  __IO uint32_t startupcounter = 0;\r
+  ErrorStatus status = ERROR;\r
+  FlagStatus hsestatus = RESET;\r
+  /* Wait till HSE is ready and if Time out is reached exit */\r
+  do\r
+  {\r
+    hsestatus = RCC_GetFlagStatus(RCC_FLAG_HSERDY);\r
+    startupcounter++;\r
+  } while((startupcounter != HSE_STARTUP_TIMEOUT) && (hsestatus == RESET));\r
+\r
+  if (RCC_GetFlagStatus(RCC_FLAG_HSERDY) != RESET)\r
+  {\r
+    status = SUCCESS;\r
+  }\r
+  else\r
+  {\r
+    status = ERROR;\r
+  }\r
+  return (status);\r
+}\r
+\r
+/**\r
+  * @brief  Adjusts the Internal High Speed oscillator (HSI) calibration value.\r
+  * @note   The calibration is used to compensate for the variations in voltage\r
+  *         and temperature that influence the frequency of the internal HSI RC.\r
+  * @param  HSICalibrationValue: specifies the calibration trimming value.\r
+  *         This parameter must be a number between 0 and 0x1F.\r
+  * @retval None\r
+  */\r
+void RCC_AdjustHSICalibrationValue(uint8_t HSICalibrationValue)\r
+{\r
+  uint32_t tmpreg = 0;\r
+  /* Check the parameters */\r
+  assert_param(IS_RCC_CALIBRATION_VALUE(HSICalibrationValue));\r
+\r
+  tmpreg = RCC->CR;\r
+\r
+  /* Clear HSITRIM[4:0] bits */\r
+  tmpreg &= ~RCC_CR_HSITRIM;\r
+\r
+  /* Set the HSITRIM[4:0] bits according to HSICalibrationValue value */\r
+  tmpreg |= (uint32_t)HSICalibrationValue << 3;\r
+\r
+  /* Store the new value */\r
+  RCC->CR = tmpreg;\r
+}\r
+\r
+/**\r
+  * @brief  Enables or disables the Internal High Speed oscillator (HSI).\r
+  * @note   The HSI is stopped by hardware when entering STOP and STANDBY modes.\r
+  *         It is used (enabled by hardware) as system clock source after startup\r
+  *         from Reset, wakeup from STOP and STANDBY mode, or in case of failure\r
+  *         of the HSE used directly or indirectly as system clock (if the Clock\r
+  *         Security System CSS is enabled).             \r
+  * @note   HSI can not be stopped if it is used as system clock source. In this case,\r
+  *         you have to select another source of the system clock then stop the HSI.  \r
+  * @note   After enabling the HSI, the application software should wait on HSIRDY\r
+  *         flag to be set indicating that HSI clock is stable and can be used as\r
+  *         system clock source.  \r
+  * @param  NewState: new state of the HSI.\r
+  *          This parameter can be: ENABLE or DISABLE.\r
+  * @note   When the HSI is stopped, HSIRDY flag goes low after 6 HSI oscillator\r
+  *         clock cycles.  \r
+  * @retval None\r
+  */\r
+void RCC_HSICmd(FunctionalState NewState)\r
+{\r
+  /* Check the parameters */\r
+  assert_param(IS_FUNCTIONAL_STATE(NewState));\r
+\r
+  *(__IO uint32_t *) CR_HSION_BB = (uint32_t)NewState;\r
+}\r
+\r
+/**\r
+  * @brief  Configures the External Low Speed oscillator (LSE).\r
+  * @note   As the LSE is in the Backup domain and write access is denied to\r
+  *         this domain after reset, you have to enable write access using \r
+  *         PWR_BackupAccessCmd(ENABLE) function before to configure the LSE\r
+  *         (to be done once after reset).  \r
+  * @note   After enabling the LSE (RCC_LSE_ON or RCC_LSE_Bypass), the application\r
+  *         software should wait on LSERDY flag to be set indicating that LSE clock\r
+  *         is stable and can be used to clock the RTC.\r
+  * @param  RCC_LSE: specifies the new state of the LSE.\r
+  *          This parameter can be one of the following values:\r
+  *            @arg RCC_LSE_OFF: turn OFF the LSE oscillator, LSERDY flag goes low after\r
+  *                              6 LSE oscillator clock cycles.\r
+  *            @arg RCC_LSE_ON: turn ON the LSE oscillator\r
+  *            @arg RCC_LSE_Bypass: LSE oscillator bypassed with external clock\r
+  * @retval None\r
+  */\r
+void RCC_LSEConfig(uint8_t RCC_LSE)\r
+{\r
+  /* Check the parameters */\r
+  assert_param(IS_RCC_LSE(RCC_LSE));\r
+\r
+  /* Reset LSEON and LSEBYP bits before configuring the LSE ------------------*/\r
+  /* Reset LSEON bit */\r
+  *(__IO uint8_t *) BDCR_ADDRESS = RCC_LSE_OFF;\r
+\r
+  /* Reset LSEBYP bit */\r
+  *(__IO uint8_t *) BDCR_ADDRESS = RCC_LSE_OFF;\r
+\r
+  /* Configure LSE (RCC_LSE_OFF is already covered by the code section above) */\r
+  switch (RCC_LSE)\r
+  {\r
+    case RCC_LSE_ON:\r
+      /* Set LSEON bit */\r
+      *(__IO uint8_t *) BDCR_ADDRESS = RCC_LSE_ON;\r
+      break;\r
+    case RCC_LSE_Bypass:\r
+      /* Set LSEBYP and LSEON bits */\r
+      *(__IO uint8_t *) BDCR_ADDRESS = RCC_LSE_Bypass | RCC_LSE_ON;\r
+      break;\r
+    default:\r
+      break;\r
+  }\r
+}\r
+\r
+/**\r
+  * @brief  Enables or disables the Internal Low Speed oscillator (LSI).\r
+  * @note   After enabling the LSI, the application software should wait on \r
+  *         LSIRDY flag to be set indicating that LSI clock is stable and can\r
+  *         be used to clock the IWDG and/or the RTC.\r
+  * @note   LSI can not be disabled if the IWDG is running.  \r
+  * @param  NewState: new state of the LSI.\r
+  *          This parameter can be: ENABLE or DISABLE.\r
+  * @note   When the LSI is stopped, LSIRDY flag goes low after 6 LSI oscillator\r
+  *         clock cycles. \r
+  * @retval None\r
+  */\r
+void RCC_LSICmd(FunctionalState NewState)\r
+{\r
+  /* Check the parameters */\r
+  assert_param(IS_FUNCTIONAL_STATE(NewState));\r
+\r
+  *(__IO uint32_t *) CSR_LSION_BB = (uint32_t)NewState;\r
+}\r
+\r
+/**\r
+  * @brief  Configures the main PLL clock source, multiplication and division factors.\r
+  * @note   This function must be used only when the main PLL is disabled.\r
+  *  \r
+  * @param  RCC_PLLSource: specifies the PLL entry clock source.\r
+  *          This parameter can be one of the following values:\r
+  *            @arg RCC_PLLSource_HSI: HSI oscillator clock selected as PLL clock entry\r
+  *            @arg RCC_PLLSource_HSE: HSE oscillator clock selected as PLL clock entry\r
+  * @note   This clock source (RCC_PLLSource) is common for the main PLL and PLLI2S.  \r
+  *  \r
+  * @param  PLLM: specifies the division factor for PLL VCO input clock\r
+  *          This parameter must be a number between 0 and 63.\r
+  * @note   You have to set the PLLM parameter correctly to ensure that the VCO input\r
+  *         frequency ranges from 1 to 2 MHz. It is recommended to select a frequency\r
+  *         of 2 MHz to limit PLL jitter.\r
+  *  \r
+  * @param  PLLN: specifies the multiplication factor for PLL VCO output clock\r
+  *          This parameter must be a number between 192 and 432.\r
+  * @note   You have to set the PLLN parameter correctly to ensure that the VCO\r
+  *         output frequency is between 192 and 432 MHz.\r
+  *   \r
+  * @param  PLLP: specifies the division factor for main system clock (SYSCLK)\r
+  *          This parameter must be a number in the range {2, 4, 6, or 8}.\r
+  * @note   You have to set the PLLP parameter correctly to not exceed 168 MHz on\r
+  *         the System clock frequency.\r
+  *  \r
+  * @param  PLLQ: specifies the division factor for OTG FS, SDIO and RNG clocks\r
+  *          This parameter must be a number between 4 and 15.\r
+  * @note   If the USB OTG FS is used in your application, you have to set the\r
+  *         PLLQ parameter correctly to have 48 MHz clock for the USB. However,\r
+  *         the SDIO and RNG need a frequency lower than or equal to 48 MHz to work\r
+  *         correctly.\r
+  *   \r
+  * @retval None\r
+  */\r
+void RCC_PLLConfig(uint32_t RCC_PLLSource, uint32_t PLLM, uint32_t PLLN, uint32_t PLLP, uint32_t PLLQ)\r
+{\r
+  /* Check the parameters */\r
+  assert_param(IS_RCC_PLL_SOURCE(RCC_PLLSource));\r
+  assert_param(IS_RCC_PLLM_VALUE(PLLM));\r
+  assert_param(IS_RCC_PLLN_VALUE(PLLN));\r
+  assert_param(IS_RCC_PLLP_VALUE(PLLP));\r
+  assert_param(IS_RCC_PLLQ_VALUE(PLLQ));\r
+\r
+  RCC->PLLCFGR = PLLM | (PLLN << 6) | (((PLLP >> 1) -1) << 16) | (RCC_PLLSource) |\r
+                 (PLLQ << 24);\r
+}\r
+\r
+/**\r
+  * @brief  Enables or disables the main PLL.\r
+  * @note   After enabling the main PLL, the application software should wait on \r
+  *         PLLRDY flag to be set indicating that PLL clock is stable and can\r
+  *         be used as system clock source.\r
+  * @note   The main PLL can not be disabled if it is used as system clock source\r
+  * @note   The main PLL is disabled by hardware when entering STOP and STANDBY modes.\r
+  * @param  NewState: new state of the main PLL. This parameter can be: ENABLE or DISABLE.\r
+  * @retval None\r
+  */\r
+void RCC_PLLCmd(FunctionalState NewState)\r
+{\r
+  /* Check the parameters */\r
+  assert_param(IS_FUNCTIONAL_STATE(NewState));\r
+  *(__IO uint32_t *) CR_PLLON_BB = (uint32_t)NewState;\r
+}\r
+\r
+/**\r
+  * @brief  Configures the PLLI2S clock multiplication and division factors.\r
+  *  \r
+  * @note   This function must be used only when the PLLI2S is disabled.\r
+  * @note   PLLI2S clock source is common with the main PLL (configured in \r
+  *         RCC_PLLConfig function )  \r
+  *             \r
+  * @param  PLLI2SN: specifies the multiplication factor for PLLI2S VCO output clock\r
+  *          This parameter must be a number between 192 and 432.\r
+  * @note   You have to set the PLLI2SN parameter correctly to ensure that the VCO \r
+  *         output frequency is between 192 and 432 MHz.\r
+  *    \r
+  * @param  PLLI2SR: specifies the division factor for I2S clock\r
+  *          This parameter must be a number between 2 and 7.\r
+  * @note   You have to set the PLLI2SR parameter correctly to not exceed 192 MHz\r
+  *         on the I2S clock frequency.\r
+  *   \r
+  * @retval None\r
+  */\r
+void RCC_PLLI2SConfig(uint32_t PLLI2SN, uint32_t PLLI2SR)\r
+{\r
+  /* Check the parameters */\r
+  assert_param(IS_RCC_PLLI2SN_VALUE(PLLI2SN));\r
+  assert_param(IS_RCC_PLLI2SR_VALUE(PLLI2SR));\r
+\r
+  RCC->PLLI2SCFGR = (PLLI2SN << 6) | (PLLI2SR << 28);\r
+}\r
+\r
+/**\r
+  * @brief  Enables or disables the PLLI2S. \r
+  * @note   The PLLI2S is disabled by hardware when entering STOP and STANDBY modes.  \r
+  * @param  NewState: new state of the PLLI2S. This parameter can be: ENABLE or DISABLE.\r
+  * @retval None\r
+  */\r
+void RCC_PLLI2SCmd(FunctionalState NewState)\r
+{\r
+  /* Check the parameters */\r
+  assert_param(IS_FUNCTIONAL_STATE(NewState));\r
+  *(__IO uint32_t *) CR_PLLI2SON_BB = (uint32_t)NewState;\r
+}\r
+\r
+/**\r
+  * @brief  Enables or disables the Clock Security System.\r
+  * @note   If a failure is detected on the HSE oscillator clock, this oscillator\r
+  *         is automatically disabled and an interrupt is generated to inform the\r
+  *         software about the failure (Clock Security System Interrupt, CSSI),\r
+  *         allowing the MCU to perform rescue operations. The CSSI is linked to \r
+  *         the Cortex-M4 NMI (Non-Maskable Interrupt) exception vector.  \r
+  * @param  NewState: new state of the Clock Security System.\r
+  *         This parameter can be: ENABLE or DISABLE.\r
+  * @retval None\r
+  */\r
+void RCC_ClockSecuritySystemCmd(FunctionalState NewState)\r
+{\r
+  /* Check the parameters */\r
+  assert_param(IS_FUNCTIONAL_STATE(NewState));\r
+  *(__IO uint32_t *) CR_CSSON_BB = (uint32_t)NewState;\r
+}\r
+\r
+/**\r
+  * @brief  Selects the clock source to output on MCO1 pin(PA8).\r
+  * @note   PA8 should be configured in alternate function mode.\r
+  * @param  RCC_MCO1Source: specifies the clock source to output.\r
+  *          This parameter can be one of the following values:\r
+  *            @arg RCC_MCO1Source_HSI: HSI clock selected as MCO1 source\r
+  *            @arg RCC_MCO1Source_LSE: LSE clock selected as MCO1 source\r
+  *            @arg RCC_MCO1Source_HSE: HSE clock selected as MCO1 source\r
+  *            @arg RCC_MCO1Source_PLLCLK: main PLL clock selected as MCO1 source\r
+  * @param  RCC_MCO1Div: specifies the MCO1 prescaler.\r
+  *          This parameter can be one of the following values:\r
+  *            @arg RCC_MCO1Div_1: no division applied to MCO1 clock\r
+  *            @arg RCC_MCO1Div_2: division by 2 applied to MCO1 clock\r
+  *            @arg RCC_MCO1Div_3: division by 3 applied to MCO1 clock\r
+  *            @arg RCC_MCO1Div_4: division by 4 applied to MCO1 clock\r
+  *            @arg RCC_MCO1Div_5: division by 5 applied to MCO1 clock\r
+  * @retval None\r
+  */\r
+void RCC_MCO1Config(uint32_t RCC_MCO1Source, uint32_t RCC_MCO1Div)\r
+{\r
+  uint32_t tmpreg = 0;\r
+  \r
+  /* Check the parameters */\r
+  assert_param(IS_RCC_MCO1SOURCE(RCC_MCO1Source));\r
+  assert_param(IS_RCC_MCO1DIV(RCC_MCO1Div));  \r
+\r
+  tmpreg = RCC->CFGR;\r
+\r
+  /* Clear MCO1[1:0] and MCO1PRE[2:0] bits */\r
+  tmpreg &= CFGR_MCO1_RESET_MASK;\r
+\r
+  /* Select MCO1 clock source and prescaler */\r
+  tmpreg |= RCC_MCO1Source | RCC_MCO1Div;\r
+\r
+  /* Store the new value */\r
+  RCC->CFGR = tmpreg;  \r
+}\r
+\r
+/**\r
+  * @brief  Selects the clock source to output on MCO2 pin(PC9).\r
+  * @note   PC9 should be configured in alternate function mode.\r
+  * @param  RCC_MCO2Source: specifies the clock source to output.\r
+  *          This parameter can be one of the following values:\r
+  *            @arg RCC_MCO2Source_SYSCLK: System clock (SYSCLK) selected as MCO2 source\r
+  *            @arg RCC_MCO2Source_PLLI2SCLK: PLLI2S clock selected as MCO2 source\r
+  *            @arg RCC_MCO2Source_HSE: HSE clock selected as MCO2 source\r
+  *            @arg RCC_MCO2Source_PLLCLK: main PLL clock selected as MCO2 source\r
+  * @param  RCC_MCO2Div: specifies the MCO2 prescaler.\r
+  *          This parameter can be one of the following values:\r
+  *            @arg RCC_MCO2Div_1: no division applied to MCO2 clock\r
+  *            @arg RCC_MCO2Div_2: division by 2 applied to MCO2 clock\r
+  *            @arg RCC_MCO2Div_3: division by 3 applied to MCO2 clock\r
+  *            @arg RCC_MCO2Div_4: division by 4 applied to MCO2 clock\r
+  *            @arg RCC_MCO2Div_5: division by 5 applied to MCO2 clock\r
+  * @retval None\r
+  */\r
+void RCC_MCO2Config(uint32_t RCC_MCO2Source, uint32_t RCC_MCO2Div)\r
+{\r
+  uint32_t tmpreg = 0;\r
+  \r
+  /* Check the parameters */\r
+  assert_param(IS_RCC_MCO2SOURCE(RCC_MCO2Source));\r
+  assert_param(IS_RCC_MCO2DIV(RCC_MCO2Div));\r
+  \r
+  tmpreg = RCC->CFGR;\r
+  \r
+  /* Clear MCO2 and MCO2PRE[2:0] bits */\r
+  tmpreg &= CFGR_MCO2_RESET_MASK;\r
+\r
+  /* Select MCO2 clock source and prescaler */\r
+  tmpreg |= RCC_MCO2Source | RCC_MCO2Div;\r
+\r
+  /* Store the new value */\r
+  RCC->CFGR = tmpreg;  \r
+}\r
+\r
+/**\r
+  * @}\r
+  */\r
+\r
+/** @defgroup RCC_Group2 System AHB and APB busses clocks configuration functions\r
+ *  @brief   System, AHB and APB busses clocks configuration functions\r
+ *\r
+@verbatim   \r
+ ===============================================================================\r
+             System, AHB and APB busses clocks configuration functions\r
+ ===============================================================================  \r
+\r
+  This section provide functions allowing to configure the System, AHB, APB1 and \r
+  APB2 busses clocks.\r
+  \r
+  1. Several clock sources can be used to drive the System clock (SYSCLK): HSI,\r
+     HSE and PLL.\r
+     The AHB clock (HCLK) is derived from System clock through configurable prescaler\r
+     and used to clock the CPU, memory and peripherals mapped on AHB bus (DMA, GPIO...).\r
+     APB1 (PCLK1) and APB2 (PCLK2) clocks are derived from AHB clock through \r
+     configurable prescalers and used to clock the peripherals mapped on these busses.\r
+     You can use "RCC_GetClocksFreq()" function to retrieve the frequencies of these clocks.  \r
+\r
+@note All the peripheral clocks are derived from the System clock (SYSCLK) except:\r
+       - I2S: the I2S clock can be derived either from a specific PLL (PLLI2S) or\r
+          from an external clock mapped on the I2S_CKIN pin. \r
+          You have to use RCC_I2SCLKConfig() function to configure this clock. \r
+       - RTC: the RTC clock can be derived either from the LSI, LSE or HSE clock\r
+          divided by 2 to 31. You have to use RCC_RTCCLKConfig() and RCC_RTCCLKCmd()\r
+          functions to configure this clock. \r
+       - USB OTG FS, SDIO and RTC: USB OTG FS require a frequency equal to 48 MHz\r
+          to work correctly, while the SDIO require a frequency equal or lower than\r
+          to 48. This clock is derived of the main PLL through PLLQ divider.\r
+       - IWDG clock which is always the LSI clock.\r
+       \r
+  2. The maximum frequency of the SYSCLK and HCLK is 168 MHz, PCLK2 82 MHz and PCLK1 42 MHz.\r
+     Depending on the device voltage range, the maximum frequency should be \r
+     adapted accordingly:\r
+ +-------------------------------------------------------------------------------------+     \r
+ | Latency       |                HCLK clock frequency (MHz)                           |\r
+ |               |---------------------------------------------------------------------|     \r
+ |               | voltage range  | voltage range  | voltage range   | voltage range   |\r
+ |               | 2.7 V - 3.6 V  | 2.4 V - 2.7 V  | 2.1 V - 2.4 V   | 1.8 V - 2.1 V   |\r
+ |---------------|----------------|----------------|-----------------|-----------------|              \r
+ |0WS(1CPU cycle)|0 < HCLK <= 30  |0 < HCLK <= 24  |0 < HCLK <= 18   |0 < HCLK <= 16   |\r
+ |---------------|----------------|----------------|-----------------|-----------------|   \r
+ |1WS(2CPU cycle)|30 < HCLK <= 60 |24 < HCLK <= 48 |18 < HCLK <= 36  |16 < HCLK <= 32  | \r
+ |---------------|----------------|----------------|-----------------|-----------------|   \r
+ |2WS(3CPU cycle)|60 < HCLK <= 90 |48 < HCLK <= 72 |36 < HCLK <= 54  |32 < HCLK <= 48  |\r
+ |---------------|----------------|----------------|-----------------|-----------------| \r
+ |3WS(4CPU cycle)|90 < HCLK <= 120|72 < HCLK <= 96 |54 < HCLK <= 72  |48 < HCLK <= 64  |\r
+ |---------------|----------------|----------------|-----------------|-----------------| \r
+ |4WS(5CPU cycle)|120< HCLK <= 150|96 < HCLK <= 120|72 < HCLK <= 90  |64 < HCLK <= 80  |\r
+ |---------------|----------------|----------------|-----------------|-----------------| \r
+ |5WS(6CPU cycle)|120< HCLK <= 168|120< HCLK <= 144|90 < HCLK <= 108 |80 < HCLK <= 96  | \r
+ |---------------|----------------|----------------|-----------------|-----------------| \r
+ |6WS(7CPU cycle)|      NA        |144< HCLK <= 168|108 < HCLK <= 120|96 < HCLK <= 112 | \r
+ |---------------|----------------|----------------|-----------------|-----------------| \r
+ |7WS(8CPU cycle)|      NA        |      NA        |120 < HCLK <= 138|112 < HCLK <= 120| \r
+ +-------------------------------------------------------------------------------------+    \r
+   @note When VOS bit (in PWR_CR register) is reset to '0\92, the maximum value of HCLK is 144 MHz.\r
+         You can use PWR_MainRegulatorModeConfig() function to set or reset this bit.\r
+\r
+@endverbatim\r
+  * @{\r
+  */\r
+\r
+/**\r
+  * @brief  Configures the system clock (SYSCLK).\r
+  * @note   The HSI is used (enabled by hardware) as system clock source after\r
+  *         startup from Reset, wake-up from STOP and STANDBY mode, or in case\r
+  *         of failure of the HSE used directly or indirectly as system clock\r
+  *         (if the Clock Security System CSS is enabled).\r
+  * @note   A switch from one clock source to another occurs only if the target\r
+  *         clock source is ready (clock stable after startup delay or PLL locked). \r
+  *         If a clock source which is not yet ready is selected, the switch will\r
+  *         occur when the clock source will be ready. \r
+  *         You can use RCC_GetSYSCLKSource() function to know which clock is\r
+  *         currently used as system clock source. \r
+  * @param  RCC_SYSCLKSource: specifies the clock source used as system clock.\r
+  *          This parameter can be one of the following values:\r
+  *            @arg RCC_SYSCLKSource_HSI:    HSI selected as system clock source\r
+  *            @arg RCC_SYSCLKSource_HSE:    HSE selected as system clock source\r
+  *            @arg RCC_SYSCLKSource_PLLCLK: PLL selected as system clock source\r
+  * @retval None\r
+  */\r
+void RCC_SYSCLKConfig(uint32_t RCC_SYSCLKSource)\r
+{\r
+  uint32_t tmpreg = 0;\r
+\r
+  /* Check the parameters */\r
+  assert_param(IS_RCC_SYSCLK_SOURCE(RCC_SYSCLKSource));\r
+\r
+  tmpreg = RCC->CFGR;\r
+\r
+  /* Clear SW[1:0] bits */\r
+  tmpreg &= ~RCC_CFGR_SW;\r
+\r
+  /* Set SW[1:0] bits according to RCC_SYSCLKSource value */\r
+  tmpreg |= RCC_SYSCLKSource;\r
+\r
+  /* Store the new value */\r
+  RCC->CFGR = tmpreg;\r
+}\r
+\r
+/**\r
+  * @brief  Returns the clock source used as system clock.\r
+  * @param  None\r
+  * @retval The clock source used as system clock. The returned value can be one\r
+  *         of the following:\r
+  *              - 0x00: HSI used as system clock\r
+  *              - 0x04: HSE used as system clock\r
+  *              - 0x08: PLL used as system clock\r
+  */\r
+uint8_t RCC_GetSYSCLKSource(void)\r
+{\r
+  return ((uint8_t)(RCC->CFGR & RCC_CFGR_SWS));\r
+}\r
+\r
+/**\r
+  * @brief  Configures the AHB clock (HCLK).\r
+  * @note   Depending on the device voltage range, the software has to set correctly\r
+  *         these bits to ensure that HCLK not exceed the maximum allowed frequency\r
+  *         (for more details refer to section above\r
+  *           "CPU, AHB and APB busses clocks configuration functions")\r
+  * @param  RCC_SYSCLK: defines the AHB clock divider. This clock is derived from \r
+  *         the system clock (SYSCLK).\r
+  *          This parameter can be one of the following values:\r
+  *            @arg RCC_SYSCLK_Div1: AHB clock = SYSCLK\r
+  *            @arg RCC_SYSCLK_Div2: AHB clock = SYSCLK/2\r
+  *            @arg RCC_SYSCLK_Div4: AHB clock = SYSCLK/4\r
+  *            @arg RCC_SYSCLK_Div8: AHB clock = SYSCLK/8\r
+  *            @arg RCC_SYSCLK_Div16: AHB clock = SYSCLK/16\r
+  *            @arg RCC_SYSCLK_Div64: AHB clock = SYSCLK/64\r
+  *            @arg RCC_SYSCLK_Div128: AHB clock = SYSCLK/128\r
+  *            @arg RCC_SYSCLK_Div256: AHB clock = SYSCLK/256\r
+  *            @arg RCC_SYSCLK_Div512: AHB clock = SYSCLK/512\r
+  * @retval None\r
+  */\r
+void RCC_HCLKConfig(uint32_t RCC_SYSCLK)\r
+{\r
+  uint32_t tmpreg = 0;\r
+  \r
+  /* Check the parameters */\r
+  assert_param(IS_RCC_HCLK(RCC_SYSCLK));\r
+\r
+  tmpreg = RCC->CFGR;\r
+\r
+  /* Clear HPRE[3:0] bits */\r
+  tmpreg &= ~RCC_CFGR_HPRE;\r
+\r
+  /* Set HPRE[3:0] bits according to RCC_SYSCLK value */\r
+  tmpreg |= RCC_SYSCLK;\r
+\r
+  /* Store the new value */\r
+  RCC->CFGR = tmpreg;\r
+}\r
+\r
+\r
+/**\r
+  * @brief  Configures the Low Speed APB clock (PCLK1).\r
+  * @param  RCC_HCLK: defines the APB1 clock divider. This clock is derived from \r
+  *         the AHB clock (HCLK).\r
+  *          This parameter can be one of the following values:\r
+  *            @arg RCC_HCLK_Div1:  APB1 clock = HCLK\r
+  *            @arg RCC_HCLK_Div2:  APB1 clock = HCLK/2\r
+  *            @arg RCC_HCLK_Div4:  APB1 clock = HCLK/4\r
+  *            @arg RCC_HCLK_Div8:  APB1 clock = HCLK/8\r
+  *            @arg RCC_HCLK_Div16: APB1 clock = HCLK/16\r
+  * @retval None\r
+  */\r
+void RCC_PCLK1Config(uint32_t RCC_HCLK)\r
+{\r
+  uint32_t tmpreg = 0;\r
+\r
+  /* Check the parameters */\r
+  assert_param(IS_RCC_PCLK(RCC_HCLK));\r
+\r
+  tmpreg = RCC->CFGR;\r
+\r
+  /* Clear PPRE1[2:0] bits */\r
+  tmpreg &= ~RCC_CFGR_PPRE1;\r
+\r
+  /* Set PPRE1[2:0] bits according to RCC_HCLK value */\r
+  tmpreg |= RCC_HCLK;\r
+\r
+  /* Store the new value */\r
+  RCC->CFGR = tmpreg;\r
+}\r
+\r
+/**\r
+  * @brief  Configures the High Speed APB clock (PCLK2).\r
+  * @param  RCC_HCLK: defines the APB2 clock divider. This clock is derived from \r
+  *         the AHB clock (HCLK).\r
+  *          This parameter can be one of the following values:\r
+  *            @arg RCC_HCLK_Div1:  APB2 clock = HCLK\r
+  *            @arg RCC_HCLK_Div2:  APB2 clock = HCLK/2\r
+  *            @arg RCC_HCLK_Div4:  APB2 clock = HCLK/4\r
+  *            @arg RCC_HCLK_Div8:  APB2 clock = HCLK/8\r
+  *            @arg RCC_HCLK_Div16: APB2 clock = HCLK/16\r
+  * @retval None\r
+  */\r
+void RCC_PCLK2Config(uint32_t RCC_HCLK)\r
+{\r
+  uint32_t tmpreg = 0;\r
+\r
+  /* Check the parameters */\r
+  assert_param(IS_RCC_PCLK(RCC_HCLK));\r
+\r
+  tmpreg = RCC->CFGR;\r
+\r
+  /* Clear PPRE2[2:0] bits */\r
+  tmpreg &= ~RCC_CFGR_PPRE2;\r
+\r
+  /* Set PPRE2[2:0] bits according to RCC_HCLK value */\r
+  tmpreg |= RCC_HCLK << 3;\r
+\r
+  /* Store the new value */\r
+  RCC->CFGR = tmpreg;\r
+}\r
+\r
+/**\r
+  * @brief  Returns the frequencies of different on chip clocks; SYSCLK, HCLK, \r
+  *         PCLK1 and PCLK2.       \r
+  * \r
+  * @note   The system frequency computed by this function is not the real \r
+  *         frequency in the chip. It is calculated based on the predefined \r
+  *         constant and the selected clock source:\r
+  * @note     If SYSCLK source is HSI, function returns values based on HSI_VALUE(*)\r
+  * @note     If SYSCLK source is HSE, function returns values based on HSE_VALUE(**)\r
+  * @note     If SYSCLK source is PLL, function returns values based on HSE_VALUE(**) \r
+  *           or HSI_VALUE(*) multiplied/divided by the PLL factors.         \r
+  * @note     (*) HSI_VALUE is a constant defined in stm32f4xx.h file (default value\r
+  *               16 MHz) but the real value may vary depending on the variations\r
+  *               in voltage and temperature.\r
+  * @note     (**) HSE_VALUE is a constant defined in stm32f4xx.h file (default value\r
+  *                25 MHz), user has to ensure that HSE_VALUE is same as the real\r
+  *                frequency of the crystal used. Otherwise, this function may\r
+  *                have wrong result.\r
+  *                \r
+  * @note   The result of this function could be not correct when using fractional\r
+  *         value for HSE crystal.\r
+  *   \r
+  * @param  RCC_Clocks: pointer to a RCC_ClocksTypeDef structure which will hold\r
+  *          the clocks frequencies.\r
+  *     \r
+  * @note   This function can be used by the user application to compute the \r
+  *         baudrate for the communication peripherals or configure other parameters.\r
+  * @note   Each time SYSCLK, HCLK, PCLK1 and/or PCLK2 clock changes, this function\r
+  *         must be called to update the structure's field. Otherwise, any\r
+  *         configuration based on this function will be incorrect.\r
+  *    \r
+  * @retval None\r
+  */\r
+void RCC_GetClocksFreq(RCC_ClocksTypeDef* RCC_Clocks)\r
+{\r
+  uint32_t tmp = 0, presc = 0, pllvco = 0, pllp = 2, pllsource = 0, pllm = 2;\r
+\r
+  /* Get SYSCLK source -------------------------------------------------------*/\r
+  tmp = RCC->CFGR & RCC_CFGR_SWS;\r
+\r
+  switch (tmp)\r
+  {\r
+    case 0x00:  /* HSI used as system clock source */\r
+      RCC_Clocks->SYSCLK_Frequency = HSI_VALUE;\r
+      break;\r
+    case 0x04:  /* HSE used as system clock  source */\r
+      RCC_Clocks->SYSCLK_Frequency = HSE_VALUE;\r
+      break;\r
+    case 0x08:  /* PLL used as system clock  source */\r
+\r
+      /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLLM) * PLLN\r
+         SYSCLK = PLL_VCO / PLLP\r
+         */    \r
+      pllsource = (RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) >> 22;\r
+      pllm = RCC->PLLCFGR & RCC_PLLCFGR_PLLM;\r
+      \r
+      if (pllsource != 0)\r
+      {\r
+        /* HSE used as PLL clock source */\r
+        pllvco = (HSE_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6);\r
+      }\r
+      else\r
+      {\r
+        /* HSI used as PLL clock source */\r
+        pllvco = (HSI_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6);      \r
+      }\r
+\r
+      pllp = (((RCC->PLLCFGR & RCC_PLLCFGR_PLLP) >>16) + 1 ) *2;\r
+      RCC_Clocks->SYSCLK_Frequency = pllvco/pllp;\r
+      break;\r
+    default:\r
+      RCC_Clocks->SYSCLK_Frequency = HSI_VALUE;\r
+      break;\r
+  }\r
+  /* Compute HCLK, PCLK1 and PCLK2 clocks frequencies ------------------------*/\r
+\r
+  /* Get HCLK prescaler */\r
+  tmp = RCC->CFGR & RCC_CFGR_HPRE;\r
+  tmp = tmp >> 4;\r
+  presc = APBAHBPrescTable[tmp];\r
+  /* HCLK clock frequency */\r
+  RCC_Clocks->HCLK_Frequency = RCC_Clocks->SYSCLK_Frequency >> presc;\r
+\r
+  /* Get PCLK1 prescaler */\r
+  tmp = RCC->CFGR & RCC_CFGR_PPRE1;\r
+  tmp = tmp >> 10;\r
+  presc = APBAHBPrescTable[tmp];\r
+  /* PCLK1 clock frequency */\r
+  RCC_Clocks->PCLK1_Frequency = RCC_Clocks->HCLK_Frequency >> presc;\r
+\r
+  /* Get PCLK2 prescaler */\r
+  tmp = RCC->CFGR & RCC_CFGR_PPRE2;\r
+  tmp = tmp >> 13;\r
+  presc = APBAHBPrescTable[tmp];\r
+  /* PCLK2 clock frequency */\r
+  RCC_Clocks->PCLK2_Frequency = RCC_Clocks->HCLK_Frequency >> presc;\r
+}\r
+\r
+/**\r
+  * @}\r
+  */\r
+\r
+/** @defgroup RCC_Group3 Peripheral clocks configuration functions\r
+ *  @brief   Peripheral clocks configuration functions \r
+ *\r
+@verbatim   \r
+ ===============================================================================\r
+                   Peripheral clocks configuration functions\r
+ ===============================================================================  \r
+\r
+  This section provide functions allowing to configure the Peripheral clocks. \r
+  \r
+  1. The RTC clock which is derived from the LSI, LSE or HSE clock divided by 2 to 31.\r
+     \r
+  2. After restart from Reset or wakeup from STANDBY, all peripherals are off\r
+     except internal SRAM, Flash and JTAG. Before to start using a peripheral you\r
+     have to enable its interface clock. You can do this using RCC_AHBPeriphClockCmd()\r
+     , RCC_APB2PeriphClockCmd() and RCC_APB1PeriphClockCmd() functions.\r
+\r
+  3. To reset the peripherals configuration (to the default state after device reset)\r
+     you can use RCC_AHBPeriphResetCmd(), RCC_APB2PeriphResetCmd() and \r
+     RCC_APB1PeriphResetCmd() functions.\r
+     \r
+  4. To further reduce power consumption in SLEEP mode the peripheral clocks can\r
+     be disabled prior to executing the WFI or WFE instructions. You can do this\r
+     using RCC_AHBPeriphClockLPModeCmd(), RCC_APB2PeriphClockLPModeCmd() and\r
+     RCC_APB1PeriphClockLPModeCmd() functions.  \r
+\r
+@endverbatim\r
+  * @{\r
+  */\r
+\r
+/**\r
+  * @brief  Configures the RTC clock (RTCCLK).\r
+  * @note   As the RTC clock configuration bits are in the Backup domain and write\r
+  *         access is denied to this domain after reset, you have to enable write\r
+  *         access using PWR_BackupAccessCmd(ENABLE) function before to configure\r
+  *         the RTC clock source (to be done once after reset).    \r
+  * @note   Once the RTC clock is configured it can't be changed unless the  \r
+  *         Backup domain is reset using RCC_BackupResetCmd() function, or by\r
+  *         a Power On Reset (POR).\r
+  *    \r
+  * @param  RCC_RTCCLKSource: specifies the RTC clock source.\r
+  *          This parameter can be one of the following values:\r
+  *            @arg RCC_RTCCLKSource_LSE: LSE selected as RTC clock\r
+  *            @arg RCC_RTCCLKSource_LSI: LSI selected as RTC clock\r
+  *            @arg RCC_RTCCLKSource_HSE_Divx: HSE clock divided by x selected\r
+  *                                            as RTC clock, where x:[2,31]\r
+  *  \r
+  * @note   If the LSE or LSI is used as RTC clock source, the RTC continues to\r
+  *         work in STOP and STANDBY modes, and can be used as wakeup source.\r
+  *         However, when the HSE clock is used as RTC clock source, the RTC\r
+  *         cannot be used in STOP and STANDBY modes.    \r
+  * @note   The maximum input clock frequency for RTC is 1MHz (when using HSE as\r
+  *         RTC clock source).\r
+  *  \r
+  * @retval None\r
+  */\r
+void RCC_RTCCLKConfig(uint32_t RCC_RTCCLKSource)\r
+{\r
+  uint32_t tmpreg = 0;\r
+\r
+  /* Check the parameters */\r
+  assert_param(IS_RCC_RTCCLK_SOURCE(RCC_RTCCLKSource));\r
+\r
+  if ((RCC_RTCCLKSource & 0x00000300) == 0x00000300)\r
+  { /* If HSE is selected as RTC clock source, configure HSE division factor for RTC clock */\r
+    tmpreg = RCC->CFGR;\r
+\r
+    /* Clear RTCPRE[4:0] bits */\r
+    tmpreg &= ~RCC_CFGR_RTCPRE;\r
+\r
+    /* Configure HSE division factor for RTC clock */\r
+    tmpreg |= (RCC_RTCCLKSource & 0xFFFFCFF);\r
+\r
+    /* Store the new value */\r
+    RCC->CFGR = tmpreg;\r
+  }\r
+    \r
+  /* Select the RTC clock source */\r
+  RCC->BDCR |= (RCC_RTCCLKSource & 0x00000FFF);\r
+}\r
+\r
+/**\r
+  * @brief  Enables or disables the RTC clock.\r
+  * @note   This function must be used only after the RTC clock source was selected\r
+  *         using the RCC_RTCCLKConfig function.\r
+  * @param  NewState: new state of the RTC clock. This parameter can be: ENABLE or DISABLE.\r
+  * @retval None\r
+  */\r
+void RCC_RTCCLKCmd(FunctionalState NewState)\r
+{\r
+  /* Check the parameters */\r
+  assert_param(IS_FUNCTIONAL_STATE(NewState));\r
+\r
+  *(__IO uint32_t *) BDCR_RTCEN_BB = (uint32_t)NewState;\r
+}\r
+\r
+/**\r
+  * @brief  Forces or releases the Backup domain reset.\r
+  * @note   This function resets the RTC peripheral (including the backup registers)\r
+  *         and the RTC clock source selection in RCC_CSR register.\r
+  * @note   The BKPSRAM is not affected by this reset.    \r
+  * @param  NewState: new state of the Backup domain reset.\r
+  *          This parameter can be: ENABLE or DISABLE.\r
+  * @retval None\r
+  */\r
+void RCC_BackupResetCmd(FunctionalState NewState)\r
+{\r
+  /* Check the parameters */\r
+  assert_param(IS_FUNCTIONAL_STATE(NewState));\r
+  *(__IO uint32_t *) BDCR_BDRST_BB = (uint32_t)NewState;\r
+}\r
+\r
+/**\r
+  * @brief  Configures the I2S clock source (I2SCLK).\r
+  * @note   This function must be called before enabling the I2S APB clock.\r
+  * @param  RCC_I2SCLKSource: specifies the I2S clock source.\r
+  *          This parameter can be one of the following values:\r
+  *            @arg RCC_I2S2CLKSource_PLLI2S: PLLI2S clock used as I2S clock source\r
+  *            @arg RCC_I2S2CLKSource_Ext: External clock mapped on the I2S_CKIN pin\r
+  *                                        used as I2S clock source\r
+  * @retval None\r
+  */\r
+void RCC_I2SCLKConfig(uint32_t RCC_I2SCLKSource)\r
+{\r
+  /* Check the parameters */\r
+  assert_param(IS_RCC_I2SCLK_SOURCE(RCC_I2SCLKSource));\r
+\r
+  *(__IO uint32_t *) CFGR_I2SSRC_BB = RCC_I2SCLKSource;\r
+}\r
+\r
+/**\r
+  * @brief  Enables or disables the AHB1 peripheral clock.\r
+  * @note   After reset, the peripheral clock (used for registers read/write access)\r
+  *         is disabled and the application software has to enable this clock before \r
+  *         using it.   \r
+  * @param  RCC_AHBPeriph: specifies the AHB1 peripheral to gates its clock.\r
+  *          This parameter can be any combination of the following values:\r
+  *            @arg RCC_AHB1Periph_GPIOA:       GPIOA clock\r
+  *            @arg RCC_AHB1Periph_GPIOB:       GPIOB clock \r
+  *            @arg RCC_AHB1Periph_GPIOC:       GPIOC clock\r
+  *            @arg RCC_AHB1Periph_GPIOD:       GPIOD clock\r
+  *            @arg RCC_AHB1Periph_GPIOE:       GPIOE clock\r
+  *            @arg RCC_AHB1Periph_GPIOF:       GPIOF clock\r
+  *            @arg RCC_AHB1Periph_GPIOG:       GPIOG clock\r
+  *            @arg RCC_AHB1Periph_GPIOG:       GPIOG clock\r
+  *            @arg RCC_AHB1Periph_GPIOI:       GPIOI clock\r
+  *            @arg RCC_AHB1Periph_CRC:         CRC clock\r
+  *            @arg RCC_AHB1Periph_BKPSRAM:     BKPSRAM interface clock\r
+  *            @arg RCC_AHB1Periph_CCMDATARAMEN CCM data RAM interface clock\r
+  *            @arg RCC_AHB1Periph_DMA1:        DMA1 clock\r
+  *            @arg RCC_AHB1Periph_DMA2:        DMA2 clock\r
+  *            @arg RCC_AHB1Periph_ETH_MAC:     Ethernet MAC clock\r
+  *            @arg RCC_AHB1Periph_ETH_MAC_Tx:  Ethernet Transmission clock\r
+  *            @arg RCC_AHB1Periph_ETH_MAC_Rx:  Ethernet Reception clock\r
+  *            @arg RCC_AHB1Periph_ETH_MAC_PTP: Ethernet PTP clock\r
+  *            @arg RCC_AHB1Periph_OTG_HS:      USB OTG HS clock\r
+  *            @arg RCC_AHB1Periph_OTG_HS_ULPI: USB OTG HS ULPI clock\r
+  * @param  NewState: new state of the specified peripheral clock.\r
+  *          This parameter can be: ENABLE or DISABLE.\r
+  * @retval None\r
+  */\r
+void RCC_AHB1PeriphClockCmd(uint32_t RCC_AHB1Periph, FunctionalState NewState)\r
+{\r
+  /* Check the parameters */\r
+  assert_param(IS_RCC_AHB1_CLOCK_PERIPH(RCC_AHB1Periph));\r
+\r
+  assert_param(IS_FUNCTIONAL_STATE(NewState));\r
+  if (NewState != DISABLE)\r
+  {\r
+    RCC->AHB1ENR |= RCC_AHB1Periph;\r
+  }\r
+  else\r
+  {\r
+    RCC->AHB1ENR &= ~RCC_AHB1Periph;\r
+  }\r
+}\r
+\r
+/**\r
+  * @brief  Enables or disables the AHB2 peripheral clock.\r
+  * @note   After reset, the peripheral clock (used for registers read/write access)\r
+  *         is disabled and the application software has to enable this clock before \r
+  *         using it. \r
+  * @param  RCC_AHBPeriph: specifies the AHB2 peripheral to gates its clock.\r
+  *          This parameter can be any combination of the following values:\r
+  *            @arg RCC_AHB2Periph_DCMI:   DCMI clock\r
+  *            @arg RCC_AHB2Periph_CRYP:   CRYP clock\r
+  *            @arg RCC_AHB2Periph_HASH:   HASH clock\r
+  *            @arg RCC_AHB2Periph_RNG:    RNG clock\r
+  *            @arg RCC_AHB2Periph_OTG_FS: USB OTG FS clock\r
+  * @param  NewState: new state of the specified peripheral clock.\r
+  *          This parameter can be: ENABLE or DISABLE.\r
+  * @retval None\r
+  */\r
+void RCC_AHB2PeriphClockCmd(uint32_t RCC_AHB2Periph, FunctionalState NewState)\r
+{\r
+  /* Check the parameters */\r
+  assert_param(IS_RCC_AHB2_PERIPH(RCC_AHB2Periph));\r
+  assert_param(IS_FUNCTIONAL_STATE(NewState));\r
+\r
+  if (NewState != DISABLE)\r
+  {\r
+    RCC->AHB2ENR |= RCC_AHB2Periph;\r
+  }\r
+  else\r
+  {\r
+    RCC->AHB2ENR &= ~RCC_AHB2Periph;\r
+  }\r
+}\r
+\r
+/**\r
+  * @brief  Enables or disables the AHB3 peripheral clock.\r
+  * @note   After reset, the peripheral clock (used for registers read/write access)\r
+  *         is disabled and the application software has to enable this clock before \r
+  *         using it. \r
+  * @param  RCC_AHBPeriph: specifies the AHB3 peripheral to gates its clock.\r
+  *          This parameter must be: RCC_AHB3Periph_FSMC\r
+  * @param  NewState: new state of the specified peripheral clock.\r
+  *          This parameter can be: ENABLE or DISABLE.\r
+  * @retval None\r
+  */\r
+void RCC_AHB3PeriphClockCmd(uint32_t RCC_AHB3Periph, FunctionalState NewState)\r
+{\r
+  /* Check the parameters */\r
+  assert_param(IS_RCC_AHB3_PERIPH(RCC_AHB3Periph));  \r
+  assert_param(IS_FUNCTIONAL_STATE(NewState));\r
+\r
+  if (NewState != DISABLE)\r
+  {\r
+    RCC->AHB3ENR |= RCC_AHB3Periph;\r
+  }\r
+  else\r
+  {\r
+    RCC->AHB3ENR &= ~RCC_AHB3Periph;\r
+  }\r
+}\r
+\r
+/**\r
+  * @brief  Enables or disables the Low Speed APB (APB1) peripheral clock.\r
+  * @note   After reset, the peripheral clock (used for registers read/write access)\r
+  *         is disabled and the application software has to enable this clock before \r
+  *         using it. \r
+  * @param  RCC_APB1Periph: specifies the APB1 peripheral to gates its clock.\r
+  *          This parameter can be any combination of the following values:\r
+  *            @arg RCC_APB1Periph_TIM2:   TIM2 clock\r
+  *            @arg RCC_APB1Periph_TIM3:   TIM3 clock\r
+  *            @arg RCC_APB1Periph_TIM4:   TIM4 clock\r
+  *            @arg RCC_APB1Periph_TIM5:   TIM5 clock\r
+  *            @arg RCC_APB1Periph_TIM6:   TIM6 clock\r
+  *            @arg RCC_APB1Periph_TIM7:   TIM7 clock\r
+  *            @arg RCC_APB1Periph_TIM12:  TIM12 clock\r
+  *            @arg RCC_APB1Periph_TIM13:  TIM13 clock\r
+  *            @arg RCC_APB1Periph_TIM14:  TIM14 clock\r
+  *            @arg RCC_APB1Periph_WWDG:   WWDG clock\r
+  *            @arg RCC_APB1Periph_SPI2:   SPI2 clock\r
+  *            @arg RCC_APB1Periph_SPI3:   SPI3 clock\r
+  *            @arg RCC_APB1Periph_USART2: USART2 clock\r
+  *            @arg RCC_APB1Periph_USART3: USART3 clock\r
+  *            @arg RCC_APB1Periph_UART4:  UART4 clock\r
+  *            @arg RCC_APB1Periph_UART5:  UART5 clock\r
+  *            @arg RCC_APB1Periph_I2C1:   I2C1 clock\r
+  *            @arg RCC_APB1Periph_I2C2:   I2C2 clock\r
+  *            @arg RCC_APB1Periph_I2C3:   I2C3 clock\r
+  *            @arg RCC_APB1Periph_CAN1:   CAN1 clock\r
+  *            @arg RCC_APB1Periph_CAN2:   CAN2 clock\r
+  *            @arg RCC_APB1Periph_PWR:    PWR clock\r
+  *            @arg RCC_APB1Periph_DAC:    DAC clock\r
+  * @param  NewState: new state of the specified peripheral clock.\r
+  *          This parameter can be: ENABLE or DISABLE.\r
+  * @retval None\r
+  */\r
+void RCC_APB1PeriphClockCmd(uint32_t RCC_APB1Periph, FunctionalState NewState)\r
+{\r
+  /* Check the parameters */\r
+  assert_param(IS_RCC_APB1_PERIPH(RCC_APB1Periph));  \r
+  assert_param(IS_FUNCTIONAL_STATE(NewState));\r
+\r
+  if (NewState != DISABLE)\r
+  {\r
+    RCC->APB1ENR |= RCC_APB1Periph;\r
+  }\r
+  else\r
+  {\r
+    RCC->APB1ENR &= ~RCC_APB1Periph;\r
+  }\r
+}\r
+\r
+/**\r
+  * @brief  Enables or disables the High Speed APB (APB2) peripheral clock.\r
+  * @note   After reset, the peripheral clock (used for registers read/write access)\r
+  *         is disabled and the application software has to enable this clock before \r
+  *         using it.\r
+  * @param  RCC_APB2Periph: specifies the APB2 peripheral to gates its clock.\r
+  *          This parameter can be any combination of the following values:\r
+  *            @arg RCC_APB2Periph_TIM1:   TIM1 clock\r
+  *            @arg RCC_APB2Periph_TIM8:   TIM8 clock\r
+  *            @arg RCC_APB2Periph_USART1: USART1 clock\r
+  *            @arg RCC_APB2Periph_USART6: USART6 clock\r
+  *            @arg RCC_APB2Periph_ADC1:   ADC1 clock\r
+  *            @arg RCC_APB2Periph_ADC2:   ADC2 clock\r
+  *            @arg RCC_APB2Periph_ADC3:   ADC3 clock\r
+  *            @arg RCC_APB2Periph_SDIO:   SDIO clock\r
+  *            @arg RCC_APB2Periph_SPI1:   SPI1 clock\r
+  *            @arg RCC_APB2Periph_SYSCFG: SYSCFG clock\r
+  *            @arg RCC_APB2Periph_TIM9:   TIM9 clock\r
+  *            @arg RCC_APB2Periph_TIM10:  TIM10 clock\r
+  *            @arg RCC_APB2Periph_TIM11:  TIM11 clock\r
+  * @param  NewState: new state of the specified peripheral clock.\r
+  *          This parameter can be: ENABLE or DISABLE.\r
+  * @retval None\r
+  */\r
+void RCC_APB2PeriphClockCmd(uint32_t RCC_APB2Periph, FunctionalState NewState)\r
+{\r
+  /* Check the parameters */\r
+  assert_param(IS_RCC_APB2_PERIPH(RCC_APB2Periph));\r
+  assert_param(IS_FUNCTIONAL_STATE(NewState));\r
+\r
+  if (NewState != DISABLE)\r
+  {\r
+    RCC->APB2ENR |= RCC_APB2Periph;\r
+  }\r
+  else\r
+  {\r
+    RCC->APB2ENR &= ~RCC_APB2Periph;\r
+  }\r
+}\r
+\r
+/**\r
+  * @brief  Forces or releases AHB1 peripheral reset.\r
+  * @param  RCC_AHB1Periph: specifies the AHB1 peripheral to reset.\r
+  *          This parameter can be any combination of the following values:\r
+  *            @arg RCC_AHB1Periph_GPIOA:   GPIOA clock\r
+  *            @arg RCC_AHB1Periph_GPIOB:   GPIOB clock \r
+  *            @arg RCC_AHB1Periph_GPIOC:   GPIOC clock\r
+  *            @arg RCC_AHB1Periph_GPIOD:   GPIOD clock\r
+  *            @arg RCC_AHB1Periph_GPIOE:   GPIOE clock\r
+  *            @arg RCC_AHB1Periph_GPIOF:   GPIOF clock\r
+  *            @arg RCC_AHB1Periph_GPIOG:   GPIOG clock\r
+  *            @arg RCC_AHB1Periph_GPIOG:   GPIOG clock\r
+  *            @arg RCC_AHB1Periph_GPIOI:   GPIOI clock\r
+  *            @arg RCC_AHB1Periph_CRC:     CRC clock\r
+  *            @arg RCC_AHB1Periph_DMA1:    DMA1 clock\r
+  *            @arg RCC_AHB1Periph_DMA2:    DMA2 clock\r
+  *            @arg RCC_AHB1Periph_ETH_MAC: Ethernet MAC clock\r
+  *            @arg RCC_AHB1Periph_OTG_HS:  USB OTG HS clock\r
+  *                  \r
+  * @param  NewState: new state of the specified peripheral reset.\r
+  *          This parameter can be: ENABLE or DISABLE.\r
+  * @retval None\r
+  */\r
+void RCC_AHB1PeriphResetCmd(uint32_t RCC_AHB1Periph, FunctionalState NewState)\r
+{\r
+  /* Check the parameters */\r
+  assert_param(IS_RCC_AHB1_RESET_PERIPH(RCC_AHB1Periph));\r
+  assert_param(IS_FUNCTIONAL_STATE(NewState));\r
+\r
+  if (NewState != DISABLE)\r
+  {\r
+    RCC->AHB1RSTR |= RCC_AHB1Periph;\r
+  }\r
+  else\r
+  {\r
+    RCC->AHB1RSTR &= ~RCC_AHB1Periph;\r
+  }\r
+}\r
+\r
+/**\r
+  * @brief  Forces or releases AHB2 peripheral reset.\r
+  * @param  RCC_AHB2Periph: specifies the AHB2 peripheral to reset.\r
+  *          This parameter can be any combination of the following values:\r
+  *            @arg RCC_AHB2Periph_DCMI:   DCMI clock\r
+  *            @arg RCC_AHB2Periph_CRYP:   CRYP clock\r
+  *            @arg RCC_AHB2Periph_HASH:   HASH clock\r
+  *            @arg RCC_AHB2Periph_RNG:    RNG clock\r
+  *            @arg RCC_AHB2Periph_OTG_FS: USB OTG FS clock\r
+  * @param  NewState: new state of the specified peripheral reset.\r
+  *          This parameter can be: ENABLE or DISABLE.\r
+  * @retval None\r
+  */\r
+void RCC_AHB2PeriphResetCmd(uint32_t RCC_AHB2Periph, FunctionalState NewState)\r
+{\r
+  /* Check the parameters */\r
+  assert_param(IS_RCC_AHB2_PERIPH(RCC_AHB2Periph));\r
+  assert_param(IS_FUNCTIONAL_STATE(NewState));\r
+\r
+  if (NewState != DISABLE)\r
+  {\r
+    RCC->AHB2RSTR |= RCC_AHB2Periph;\r
+  }\r
+  else\r
+  {\r
+    RCC->AHB2RSTR &= ~RCC_AHB2Periph;\r
+  }\r
+}\r
+\r
+/**\r
+  * @brief  Forces or releases AHB3 peripheral reset.\r
+  * @param  RCC_AHB3Periph: specifies the AHB3 peripheral to reset.\r
+  *          This parameter must be: RCC_AHB3Periph_FSMC\r
+  * @param  NewState: new state of the specified peripheral reset.\r
+  *          This parameter can be: ENABLE or DISABLE.\r
+  * @retval None\r
+  */\r
+void RCC_AHB3PeriphResetCmd(uint32_t RCC_AHB3Periph, FunctionalState NewState)\r
+{\r
+  /* Check the parameters */\r
+  assert_param(IS_RCC_AHB3_PERIPH(RCC_AHB3Periph));\r
+  assert_param(IS_FUNCTIONAL_STATE(NewState));\r
+\r
+  if (NewState != DISABLE)\r
+  {\r
+    RCC->AHB3RSTR |= RCC_AHB3Periph;\r
+  }\r
+  else\r
+  {\r
+    RCC->AHB3RSTR &= ~RCC_AHB3Periph;\r
+  }\r
+}\r
+\r
+/**\r
+  * @brief  Forces or releases Low Speed APB (APB1) peripheral reset.\r
+  * @param  RCC_APB1Periph: specifies the APB1 peripheral to reset.\r
+  *          This parameter can be any combination of the following values:\r
+  *            @arg RCC_APB1Periph_TIM2:   TIM2 clock\r
+  *            @arg RCC_APB1Periph_TIM3:   TIM3 clock\r
+  *            @arg RCC_APB1Periph_TIM4:   TIM4 clock\r
+  *            @arg RCC_APB1Periph_TIM5:   TIM5 clock\r
+  *            @arg RCC_APB1Periph_TIM6:   TIM6 clock\r
+  *            @arg RCC_APB1Periph_TIM7:   TIM7 clock\r
+  *            @arg RCC_APB1Periph_TIM12:  TIM12 clock\r
+  *            @arg RCC_APB1Periph_TIM13:  TIM13 clock\r
+  *            @arg RCC_APB1Periph_TIM14:  TIM14 clock\r
+  *            @arg RCC_APB1Periph_WWDG:   WWDG clock\r
+  *            @arg RCC_APB1Periph_SPI2:   SPI2 clock\r
+  *            @arg RCC_APB1Periph_SPI3:   SPI3 clock\r
+  *            @arg RCC_APB1Periph_USART2: USART2 clock\r
+  *            @arg RCC_APB1Periph_USART3: USART3 clock\r
+  *            @arg RCC_APB1Periph_UART4:  UART4 clock\r
+  *            @arg RCC_APB1Periph_UART5:  UART5 clock\r
+  *            @arg RCC_APB1Periph_I2C1:   I2C1 clock\r
+  *            @arg RCC_APB1Periph_I2C2:   I2C2 clock\r
+  *            @arg RCC_APB1Periph_I2C3:   I2C3 clock\r
+  *            @arg RCC_APB1Periph_CAN1:   CAN1 clock\r
+  *            @arg RCC_APB1Periph_CAN2:   CAN2 clock\r
+  *            @arg RCC_APB1Periph_PWR:    PWR clock\r
+  *            @arg RCC_APB1Periph_DAC:    DAC clock\r
+  * @param  NewState: new state of the specified peripheral reset.\r
+  *          This parameter can be: ENABLE or DISABLE.\r
+  * @retval None\r
+  */\r
+void RCC_APB1PeriphResetCmd(uint32_t RCC_APB1Periph, FunctionalState NewState)\r
+{\r
+  /* Check the parameters */\r
+  assert_param(IS_RCC_APB1_PERIPH(RCC_APB1Periph));\r
+  assert_param(IS_FUNCTIONAL_STATE(NewState));\r
+  if (NewState != DISABLE)\r
+  {\r
+    RCC->APB1RSTR |= RCC_APB1Periph;\r
+  }\r
+  else\r
+  {\r
+    RCC->APB1RSTR &= ~RCC_APB1Periph;\r
+  }\r
+}\r
+\r
+/**\r
+  * @brief  Forces or releases High Speed APB (APB2) peripheral reset.\r
+  * @param  RCC_APB2Periph: specifies the APB2 peripheral to reset.\r
+  *          This parameter can be any combination of the following values:\r
+  *            @arg RCC_APB2Periph_TIM1:   TIM1 clock\r
+  *            @arg RCC_APB2Periph_TIM8:   TIM8 clock\r
+  *            @arg RCC_APB2Periph_USART1: USART1 clock\r
+  *            @arg RCC_APB2Periph_USART6: USART6 clock\r
+  *            @arg RCC_APB2Periph_ADC1:   ADC1 clock\r
+  *            @arg RCC_APB2Periph_ADC2:   ADC2 clock\r
+  *            @arg RCC_APB2Periph_ADC3:   ADC3 clock\r
+  *            @arg RCC_APB2Periph_SDIO:   SDIO clock\r
+  *            @arg RCC_APB2Periph_SPI1:   SPI1 clock\r
+  *            @arg RCC_APB2Periph_SYSCFG: SYSCFG clock\r
+  *            @arg RCC_APB2Periph_TIM9:   TIM9 clock\r
+  *            @arg RCC_APB2Periph_TIM10:  TIM10 clock\r
+  *            @arg RCC_APB2Periph_TIM11:  TIM11 clock\r
+  * @param  NewState: new state of the specified peripheral reset.\r
+  *          This parameter can be: ENABLE or DISABLE.\r
+  * @retval None\r
+  */\r
+void RCC_APB2PeriphResetCmd(uint32_t RCC_APB2Periph, FunctionalState NewState)\r
+{\r
+  /* Check the parameters */\r
+  assert_param(IS_RCC_APB2_RESET_PERIPH(RCC_APB2Periph));\r
+  assert_param(IS_FUNCTIONAL_STATE(NewState));\r
+  if (NewState != DISABLE)\r
+  {\r
+    RCC->APB2RSTR |= RCC_APB2Periph;\r
+  }\r
+  else\r
+  {\r
+    RCC->APB2RSTR &= ~RCC_APB2Periph;\r
+  }\r
+}\r
+\r
+/**\r
+  * @brief  Enables or disables the AHB1 peripheral clock during Low Power (Sleep) mode.\r
+  * @note   Peripheral clock gating in SLEEP mode can be used to further reduce\r
+  *         power consumption.\r
+  * @note   After wakeup from SLEEP mode, the peripheral clock is enabled again.\r
+  * @note   By default, all peripheral clocks are enabled during SLEEP mode.\r
+  * @param  RCC_AHBPeriph: specifies the AHB1 peripheral to gates its clock.\r
+  *          This parameter can be any combination of the following values:\r
+  *            @arg RCC_AHB1Periph_GPIOA:       GPIOA clock\r
+  *            @arg RCC_AHB1Periph_GPIOB:       GPIOB clock \r
+  *            @arg RCC_AHB1Periph_GPIOC:       GPIOC clock\r
+  *            @arg RCC_AHB1Periph_GPIOD:       GPIOD clock\r
+  *            @arg RCC_AHB1Periph_GPIOE:       GPIOE clock\r
+  *            @arg RCC_AHB1Periph_GPIOF:       GPIOF clock\r
+  *            @arg RCC_AHB1Periph_GPIOG:       GPIOG clock\r
+  *            @arg RCC_AHB1Periph_GPIOG:       GPIOG clock\r
+  *            @arg RCC_AHB1Periph_GPIOI:       GPIOI clock\r
+  *            @arg RCC_AHB1Periph_CRC:         CRC clock\r
+  *            @arg RCC_AHB1Periph_BKPSRAM:     BKPSRAM interface clock\r
+  *            @arg RCC_AHB1Periph_DMA1:        DMA1 clock\r
+  *            @arg RCC_AHB1Periph_DMA2:        DMA2 clock\r
+  *            @arg RCC_AHB1Periph_ETH_MAC:     Ethernet MAC clock\r
+  *            @arg RCC_AHB1Periph_ETH_MAC_Tx:  Ethernet Transmission clock\r
+  *            @arg RCC_AHB1Periph_ETH_MAC_Rx:  Ethernet Reception clock\r
+  *            @arg RCC_AHB1Periph_ETH_MAC_PTP: Ethernet PTP clock\r
+  *            @arg RCC_AHB1Periph_OTG_HS:      USB OTG HS clock\r
+  *            @arg RCC_AHB1Periph_OTG_HS_ULPI: USB OTG HS ULPI clock\r
+  * @param  NewState: new state of the specified peripheral clock.\r
+  *          This parameter can be: ENABLE or DISABLE.\r
+  * @retval None\r
+  */\r
+void RCC_AHB1PeriphClockLPModeCmd(uint32_t RCC_AHB1Periph, FunctionalState NewState)\r
+{\r
+  /* Check the parameters */\r
+  assert_param(IS_RCC_AHB1_LPMODE_PERIPH(RCC_AHB1Periph));\r
+  assert_param(IS_FUNCTIONAL_STATE(NewState));\r
+  if (NewState != DISABLE)\r
+  {\r
+    RCC->AHB1LPENR |= RCC_AHB1Periph;\r
+  }\r
+  else\r
+  {\r
+    RCC->AHB1LPENR &= ~RCC_AHB1Periph;\r
+  }\r
+}\r
+\r
+/**\r
+  * @brief  Enables or disables the AHB2 peripheral clock during Low Power (Sleep) mode.\r
+  * @note   Peripheral clock gating in SLEEP mode can be used to further reduce\r
+  *           power consumption.\r
+  * @note   After wakeup from SLEEP mode, the peripheral clock is enabled again.\r
+  * @note   By default, all peripheral clocks are enabled during SLEEP mode.\r
+  * @param  RCC_AHBPeriph: specifies the AHB2 peripheral to gates its clock.\r
+  *          This parameter can be any combination of the following values:\r
+  *            @arg RCC_AHB2Periph_DCMI:   DCMI clock\r
+  *            @arg RCC_AHB2Periph_CRYP:   CRYP clock\r
+  *            @arg RCC_AHB2Periph_HASH:   HASH clock\r
+  *            @arg RCC_AHB2Periph_RNG:    RNG clock\r
+  *            @arg RCC_AHB2Periph_OTG_FS: USB OTG FS clock  \r
+  * @param  NewState: new state of the specified peripheral clock.\r
+  *          This parameter can be: ENABLE or DISABLE.\r
+  * @retval None\r
+  */\r
+void RCC_AHB2PeriphClockLPModeCmd(uint32_t RCC_AHB2Periph, FunctionalState NewState)\r
+{\r
+  /* Check the parameters */\r
+  assert_param(IS_RCC_AHB2_PERIPH(RCC_AHB2Periph));\r
+  assert_param(IS_FUNCTIONAL_STATE(NewState));\r
+  if (NewState != DISABLE)\r
+  {\r
+    RCC->AHB2LPENR |= RCC_AHB2Periph;\r
+  }\r
+  else\r
+  {\r
+    RCC->AHB2LPENR &= ~RCC_AHB2Periph;\r
+  }\r
+}\r
+\r
+/**\r
+  * @brief  Enables or disables the AHB3 peripheral clock during Low Power (Sleep) mode.\r
+  * @note   Peripheral clock gating in SLEEP mode can be used to further reduce\r
+  *         power consumption.\r
+  * @note   After wakeup from SLEEP mode, the peripheral clock is enabled again.\r
+  * @note   By default, all peripheral clocks are enabled during SLEEP mode.\r
+  * @param  RCC_AHBPeriph: specifies the AHB3 peripheral to gates its clock.\r
+  *          This parameter must be: RCC_AHB3Periph_FSMC\r
+  * @param  NewState: new state of the specified peripheral clock.\r
+  *          This parameter can be: ENABLE or DISABLE.\r
+  * @retval None\r
+  */\r
+void RCC_AHB3PeriphClockLPModeCmd(uint32_t RCC_AHB3Periph, FunctionalState NewState)\r
+{\r
+  /* Check the parameters */\r
+  assert_param(IS_RCC_AHB3_PERIPH(RCC_AHB3Periph));\r
+  assert_param(IS_FUNCTIONAL_STATE(NewState));\r
+  if (NewState != DISABLE)\r
+  {\r
+    RCC->AHB3LPENR |= RCC_AHB3Periph;\r
+  }\r
+  else\r
+  {\r
+    RCC->AHB3LPENR &= ~RCC_AHB3Periph;\r
+  }\r
+}\r
+\r
+/**\r
+  * @brief  Enables or disables the APB1 peripheral clock during Low Power (Sleep) mode.\r
+  * @note   Peripheral clock gating in SLEEP mode can be used to further reduce\r
+  *         power consumption.\r
+  * @note   After wakeup from SLEEP mode, the peripheral clock is enabled again.\r
+  * @note   By default, all peripheral clocks are enabled during SLEEP mode.\r
+  * @param  RCC_APB1Periph: specifies the APB1 peripheral to gates its clock.\r
+  *          This parameter can be any combination of the following values:\r
+  *            @arg RCC_APB1Periph_TIM2:   TIM2 clock\r
+  *            @arg RCC_APB1Periph_TIM3:   TIM3 clock\r
+  *            @arg RCC_APB1Periph_TIM4:   TIM4 clock\r
+  *            @arg RCC_APB1Periph_TIM5:   TIM5 clock\r
+  *            @arg RCC_APB1Periph_TIM6:   TIM6 clock\r
+  *            @arg RCC_APB1Periph_TIM7:   TIM7 clock\r
+  *            @arg RCC_APB1Periph_TIM12:  TIM12 clock\r
+  *            @arg RCC_APB1Periph_TIM13:  TIM13 clock\r
+  *            @arg RCC_APB1Periph_TIM14:  TIM14 clock\r
+  *            @arg RCC_APB1Periph_WWDG:   WWDG clock\r
+  *            @arg RCC_APB1Periph_SPI2:   SPI2 clock\r
+  *            @arg RCC_APB1Periph_SPI3:   SPI3 clock\r
+  *            @arg RCC_APB1Periph_USART2: USART2 clock\r
+  *            @arg RCC_APB1Periph_USART3: USART3 clock\r
+  *            @arg RCC_APB1Periph_UART4:  UART4 clock\r
+  *            @arg RCC_APB1Periph_UART5:  UART5 clock\r
+  *            @arg RCC_APB1Periph_I2C1:   I2C1 clock\r
+  *            @arg RCC_APB1Periph_I2C2:   I2C2 clock\r
+  *            @arg RCC_APB1Periph_I2C3:   I2C3 clock\r
+  *            @arg RCC_APB1Periph_CAN1:   CAN1 clock\r
+  *            @arg RCC_APB1Periph_CAN2:   CAN2 clock\r
+  *            @arg RCC_APB1Periph_PWR:    PWR clock\r
+  *            @arg RCC_APB1Periph_DAC:    DAC clock\r
+  * @param  NewState: new state of the specified peripheral clock.\r
+  *          This parameter can be: ENABLE or DISABLE.\r
+  * @retval None\r
+  */\r
+void RCC_APB1PeriphClockLPModeCmd(uint32_t RCC_APB1Periph, FunctionalState NewState)\r
+{\r
+  /* Check the parameters */\r
+  assert_param(IS_RCC_APB1_PERIPH(RCC_APB1Periph));\r
+  assert_param(IS_FUNCTIONAL_STATE(NewState));\r
+  if (NewState != DISABLE)\r
+  {\r
+    RCC->APB1LPENR |= RCC_APB1Periph;\r
+  }\r
+  else\r
+  {\r
+    RCC->APB1LPENR &= ~RCC_APB1Periph;\r
+  }\r
+}\r
+\r
+/**\r
+  * @brief  Enables or disables the APB2 peripheral clock during Low Power (Sleep) mode.\r
+  * @note   Peripheral clock gating in SLEEP mode can be used to further reduce\r
+  *         power consumption.\r
+  * @note   After wakeup from SLEEP mode, the peripheral clock is enabled again.\r
+  * @note   By default, all peripheral clocks are enabled during SLEEP mode.\r
+  * @param  RCC_APB2Periph: specifies the APB2 peripheral to gates its clock.\r
+  *          This parameter can be any combination of the following values:\r
+  *            @arg RCC_APB2Periph_TIM1:   TIM1 clock\r
+  *            @arg RCC_APB2Periph_TIM8:   TIM8 clock\r
+  *            @arg RCC_APB2Periph_USART1: USART1 clock\r
+  *            @arg RCC_APB2Periph_USART6: USART6 clock\r
+  *            @arg RCC_APB2Periph_ADC1:   ADC1 clock\r
+  *            @arg RCC_APB2Periph_ADC2:   ADC2 clock\r
+  *            @arg RCC_APB2Periph_ADC3:   ADC3 clock\r
+  *            @arg RCC_APB2Periph_SDIO:   SDIO clock\r
+  *            @arg RCC_APB2Periph_SPI1:   SPI1 clock\r
+  *            @arg RCC_APB2Periph_SYSCFG: SYSCFG clock\r
+  *            @arg RCC_APB2Periph_TIM9:   TIM9 clock\r
+  *            @arg RCC_APB2Periph_TIM10:  TIM10 clock\r
+  *            @arg RCC_APB2Periph_TIM11:  TIM11 clock\r
+  * @param  NewState: new state of the specified peripheral clock.\r
+  *          This parameter can be: ENABLE or DISABLE.\r
+  * @retval None\r
+  */\r
+void RCC_APB2PeriphClockLPModeCmd(uint32_t RCC_APB2Periph, FunctionalState NewState)\r
+{\r
+  /* Check the parameters */\r
+  assert_param(IS_RCC_APB2_PERIPH(RCC_APB2Periph));\r
+  assert_param(IS_FUNCTIONAL_STATE(NewState));\r
+  if (NewState != DISABLE)\r
+  {\r
+    RCC->APB2LPENR |= RCC_APB2Periph;\r
+  }\r
+  else\r
+  {\r
+    RCC->APB2LPENR &= ~RCC_APB2Periph;\r
+  }\r
+}\r
+\r
+/**\r
+  * @}\r
+  */\r
+\r
+/** @defgroup RCC_Group4 Interrupts and flags management functions\r
+ *  @brief   Interrupts and flags management functions \r
+ *\r
+@verbatim   \r
+ ===============================================================================\r
+                   Interrupts and flags management functions\r
+ ===============================================================================  \r
+\r
+@endverbatim\r
+  * @{\r
+  */\r
+\r
+/**\r
+  * @brief  Enables or disables the specified RCC interrupts.\r
+  * @param  RCC_IT: specifies the RCC interrupt sources to be enabled or disabled.\r
+  *          This parameter can be any combination of the following values:\r
+  *            @arg RCC_IT_LSIRDY: LSI ready interrupt\r
+  *            @arg RCC_IT_LSERDY: LSE ready interrupt\r
+  *            @arg RCC_IT_HSIRDY: HSI ready interrupt\r
+  *            @arg RCC_IT_HSERDY: HSE ready interrupt\r
+  *            @arg RCC_IT_PLLRDY: main PLL ready interrupt\r
+  *            @arg RCC_IT_PLLI2SRDY: PLLI2S ready interrupt  \r
+  * @param  NewState: new state of the specified RCC interrupts.\r
+  *          This parameter can be: ENABLE or DISABLE.\r
+  * @retval None\r
+  */\r
+void RCC_ITConfig(uint8_t RCC_IT, FunctionalState NewState)\r
+{\r
+  /* Check the parameters */\r
+  assert_param(IS_RCC_IT(RCC_IT));\r
+  assert_param(IS_FUNCTIONAL_STATE(NewState));\r
+  if (NewState != DISABLE)\r
+  {\r
+    /* Perform Byte access to RCC_CIR[14:8] bits to enable the selected interrupts */\r
+    *(__IO uint8_t *) CIR_BYTE2_ADDRESS |= RCC_IT;\r
+  }\r
+  else\r
+  {\r
+    /* Perform Byte access to RCC_CIR[14:8] bits to disable the selected interrupts */\r
+    *(__IO uint8_t *) CIR_BYTE2_ADDRESS &= (uint8_t)~RCC_IT;\r
+  }\r
+}\r
+\r
+/**\r
+  * @brief  Checks whether the specified RCC flag is set or not.\r
+  * @param  RCC_FLAG: specifies the flag to check.\r
+  *          This parameter can be one of the following values:\r
+  *            @arg RCC_FLAG_HSIRDY: HSI oscillator clock ready\r
+  *            @arg RCC_FLAG_HSERDY: HSE oscillator clock ready\r
+  *            @arg RCC_FLAG_PLLRDY: main PLL clock ready\r
+  *            @arg RCC_FLAG_PLLI2SRDY: PLLI2S clock ready\r
+  *            @arg RCC_FLAG_LSERDY: LSE oscillator clock ready\r
+  *            @arg RCC_FLAG_LSIRDY: LSI oscillator clock ready\r
+  *            @arg RCC_FLAG_BORRST: POR/PDR or BOR reset\r
+  *            @arg RCC_FLAG_PINRST: Pin reset\r
+  *            @arg RCC_FLAG_PORRST: POR/PDR reset\r
+  *            @arg RCC_FLAG_SFTRST: Software reset\r
+  *            @arg RCC_FLAG_IWDGRST: Independent Watchdog reset\r
+  *            @arg RCC_FLAG_WWDGRST: Window Watchdog reset\r
+  *            @arg RCC_FLAG_LPWRRST: Low Power reset\r
+  * @retval The new state of RCC_FLAG (SET or RESET).\r
+  */\r
+FlagStatus RCC_GetFlagStatus(uint8_t RCC_FLAG)\r
+{\r
+  uint32_t tmp = 0;\r
+  uint32_t statusreg = 0;\r
+  FlagStatus bitstatus = RESET;\r
+\r
+  /* Check the parameters */\r
+  assert_param(IS_RCC_FLAG(RCC_FLAG));\r
+\r
+  /* Get the RCC register index */\r
+  tmp = RCC_FLAG >> 5;\r
+  if (tmp == 1)               /* The flag to check is in CR register */\r
+  {\r
+    statusreg = RCC->CR;\r
+  }\r
+  else if (tmp == 2)          /* The flag to check is in BDCR register */\r
+  {\r
+    statusreg = RCC->BDCR;\r
+  }\r
+  else                       /* The flag to check is in CSR register */\r
+  {\r
+    statusreg = RCC->CSR;\r
+  }\r
+\r
+  /* Get the flag position */\r
+  tmp = RCC_FLAG & FLAG_MASK;\r
+  if ((statusreg & ((uint32_t)1 << tmp)) != (uint32_t)RESET)\r
+  {\r
+    bitstatus = SET;\r
+  }\r
+  else\r
+  {\r
+    bitstatus = RESET;\r
+  }\r
+  /* Return the flag status */\r
+  return bitstatus;\r
+}\r
+\r
+/**\r
+  * @brief  Clears the RCC reset flags.\r
+  *         The reset flags are: RCC_FLAG_PINRST, RCC_FLAG_PORRST,  RCC_FLAG_SFTRST,\r
+  *         RCC_FLAG_IWDGRST, RCC_FLAG_WWDGRST, RCC_FLAG_LPWRRST\r
+  * @param  None\r
+  * @retval None\r
+  */\r
+void RCC_ClearFlag(void)\r
+{\r
+  /* Set RMVF bit to clear the reset flags */\r
+  RCC->CSR |= RCC_CSR_RMVF;\r
+}\r
+\r
+/**\r
+  * @brief  Checks whether the specified RCC interrupt has occurred or not.\r
+  * @param  RCC_IT: specifies the RCC interrupt source to check.\r
+  *          This parameter can be one of the following values:\r
+  *            @arg RCC_IT_LSIRDY: LSI ready interrupt\r
+  *            @arg RCC_IT_LSERDY: LSE ready interrupt\r
+  *            @arg RCC_IT_HSIRDY: HSI ready interrupt\r
+  *            @arg RCC_IT_HSERDY: HSE ready interrupt\r
+  *            @arg RCC_IT_PLLRDY: main PLL ready interrupt\r
+  *            @arg RCC_IT_PLLI2SRDY: PLLI2S ready interrupt  \r
+  *            @arg RCC_IT_CSS: Clock Security System interrupt\r
+  * @retval The new state of RCC_IT (SET or RESET).\r
+  */\r
+ITStatus RCC_GetITStatus(uint8_t RCC_IT)\r
+{\r
+  ITStatus bitstatus = RESET;\r
+\r
+  /* Check the parameters */\r
+  assert_param(IS_RCC_GET_IT(RCC_IT));\r
+\r
+  /* Check the status of the specified RCC interrupt */\r
+  if ((RCC->CIR & RCC_IT) != (uint32_t)RESET)\r
+  {\r
+    bitstatus = SET;\r
+  }\r
+  else\r
+  {\r
+    bitstatus = RESET;\r
+  }\r
+  /* Return the RCC_IT status */\r
+  return  bitstatus;\r
+}\r
+\r
+/**\r
+  * @brief  Clears the RCC's interrupt pending bits.\r
+  * @param  RCC_IT: specifies the interrupt pending bit to clear.\r
+  *          This parameter can be any combination of the following values:\r
+  *            @arg RCC_IT_LSIRDY: LSI ready interrupt\r
+  *            @arg RCC_IT_LSERDY: LSE ready interrupt\r
+  *            @arg RCC_IT_HSIRDY: HSI ready interrupt\r
+  *            @arg RCC_IT_HSERDY: HSE ready interrupt\r
+  *            @arg RCC_IT_PLLRDY: main PLL ready interrupt\r
+  *            @arg RCC_IT_PLLI2SRDY: PLLI2S ready interrupt  \r
+  *            @arg RCC_IT_CSS: Clock Security System interrupt\r
+  * @retval None\r
+  */\r
+void RCC_ClearITPendingBit(uint8_t RCC_IT)\r
+{\r
+  /* Check the parameters */\r
+  assert_param(IS_RCC_CLEAR_IT(RCC_IT));\r
+\r
+  /* Perform Byte access to RCC_CIR[23:16] bits to clear the selected interrupt\r
+     pending bits */\r
+  *(__IO uint8_t *) CIR_BYTE3_ADDRESS = RCC_IT;\r
+}\r
+\r
+/**\r
+  * @}\r
+  */ \r
+\r
+/**\r
+  * @}\r
+  */ \r
+\r
+/**\r
+  * @}\r
+  */ \r
+\r
+/**\r
+  * @}\r
+  */ \r
+\r
+/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/\r
index 0ffcea0..51aaba1 100644 (file)
 \r
   uint32_t SystemCoreClock = 168000000;\r
 \r
-  __I uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9};\r
+//__I uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9};\r
+__attribute__ ((section (".text"))) uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9};\r
 \r
 /**\r
   * @}\r
@@ -208,6 +209,8 @@ static void SetSysClock(void);
   */\r
 void SystemInit(void)\r
 {\r
+  SystemCoreClock = 168000000; //In case global variables aren't initted.\r
+  \r
   /* Reset the RCC clock configuration to the default reset state ------------*/\r
   /* Set HSION bit */\r
   RCC->CR |= (uint32_t)0x00000001;\r