Macros | Functions | Variables
stm32f10x_rcc.c File Reference

This file provides all the RCC firmware functions. More...

#include "stm32f10x_rcc.h"
Include dependency graph for stm32f10x_rcc.c:

Go to the source code of this file.

Macros

#define BDCR_ADDRESS   (PERIPH_BASE + BDCR_OFFSET)
 
#define BDCR_BDRST_BB   (PERIPH_BB_BASE + (BDCR_OFFSET * 32) + (BDRST_BitNumber * 4))
 
#define BDCR_OFFSET   (RCC_OFFSET + 0x20)
 
#define BDCR_RTCEN_BB   (PERIPH_BB_BASE + (BDCR_OFFSET * 32) + (RTCEN_BitNumber * 4))
 
#define BDRST_BitNumber   0x10
 
#define CFGR_ADCPRE_Reset_Mask   ((uint32_t)0xFFFF3FFF)
 
#define CFGR_ADCPRE_Set_Mask   ((uint32_t)0x0000C000)
 
#define CFGR_BYTE4_ADDRESS   ((uint32_t)0x40021007)
 
#define CFGR_HPRE_Reset_Mask   ((uint32_t)0xFFFFFF0F)
 
#define CFGR_HPRE_Set_Mask   ((uint32_t)0x000000F0)
 
#define CFGR_OFFSET   (RCC_OFFSET + 0x04)
 
#define CFGR_PLL_Mask   ((uint32_t)0xFFC0FFFF)
 
#define CFGR_PLLMull_Mask   ((uint32_t)0x003C0000)
 
#define CFGR_PLLSRC_Mask   ((uint32_t)0x00010000)
 
#define CFGR_PLLXTPRE_Mask   ((uint32_t)0x00020000)
 
#define CFGR_PPRE1_Reset_Mask   ((uint32_t)0xFFFFF8FF)
 
#define CFGR_PPRE1_Set_Mask   ((uint32_t)0x00000700)
 
#define CFGR_PPRE2_Reset_Mask   ((uint32_t)0xFFFFC7FF)
 
#define CFGR_PPRE2_Set_Mask   ((uint32_t)0x00003800)
 
#define CFGR_SW_Mask   ((uint32_t)0xFFFFFFFC)
 
#define CFGR_SWS_Mask   ((uint32_t)0x0000000C)
 
#define CFGR_USBPRE_BB   (PERIPH_BB_BASE + (CFGR_OFFSET * 32) + (USBPRE_BitNumber * 4))
 
#define CIR_BYTE2_ADDRESS   ((uint32_t)0x40021009)
 
#define CIR_BYTE3_ADDRESS   ((uint32_t)0x4002100A)
 
#define CR_CSSON_BB   (PERIPH_BB_BASE + (CR_OFFSET * 32) + (CSSON_BitNumber * 4))
 
#define CR_HSEBYP_Reset   ((uint32_t)0xFFFBFFFF)
 
#define CR_HSEBYP_Set   ((uint32_t)0x00040000)
 
#define CR_HSEON_Reset   ((uint32_t)0xFFFEFFFF)
 
#define CR_HSEON_Set   ((uint32_t)0x00010000)
 
#define CR_HSION_BB   (PERIPH_BB_BASE + (CR_OFFSET * 32) + (HSION_BitNumber * 4))
 
#define CR_HSITRIM_Mask   ((uint32_t)0xFFFFFF07)
 
#define CR_OFFSET   (RCC_OFFSET + 0x00)
 
#define CR_PLLON_BB   (PERIPH_BB_BASE + (CR_OFFSET * 32) + (PLLON_BitNumber * 4))
 
#define CSR_LSION_BB   (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (LSION_BitNumber * 4))
 
#define CSR_OFFSET   (RCC_OFFSET + 0x24)
 
#define CSR_RMVF_Set   ((uint32_t)0x01000000)
 
#define CSSON_BitNumber   0x13
 
#define FLAG_Mask   ((uint8_t)0x1F)
 
#define HSION_BitNumber   0x00
 
#define LSION_BitNumber   0x00
 
#define PLLON_BitNumber   0x18
 
#define RCC_OFFSET   (RCC_BASE - PERIPH_BASE)
 
#define RTCEN_BitNumber   0x0F
 
#define USBPRE_BitNumber   0x16
 

Functions

void RCC_ADCCLKConfig (uint32_t RCC_PCLK2)
 Configures the ADC clock (ADCCLK). More...
 
void RCC_AdjustHSICalibrationValue (uint8_t HSICalibrationValue)
 Adjusts the Internal High Speed oscillator (HSI) calibration value. More...
 
void RCC_AHBPeriphClockCmd (uint32_t RCC_AHBPeriph, FunctionalState NewState)
 Enables or disables the AHB peripheral clock. More...
 
void RCC_APB1PeriphClockCmd (uint32_t RCC_APB1Periph, FunctionalState NewState)
 Enables or disables the Low Speed APB (APB1) peripheral clock. More...
 
void RCC_APB1PeriphResetCmd (uint32_t RCC_APB1Periph, FunctionalState NewState)
 Forces or releases Low Speed APB (APB1) peripheral reset. More...
 
void RCC_APB2PeriphClockCmd (uint32_t RCC_APB2Periph, FunctionalState NewState)
 Enables or disables the High Speed APB (APB2) peripheral clock. More...
 
void RCC_APB2PeriphResetCmd (uint32_t RCC_APB2Periph, FunctionalState NewState)
 Forces or releases High Speed APB (APB2) peripheral reset. More...
 
void RCC_BackupResetCmd (FunctionalState NewState)
 Forces or releases the Backup domain reset. More...
 
void RCC_ClearFlag (void)
 Clears the RCC reset flags. More...
 
void RCC_ClearITPendingBit (uint8_t RCC_IT)
 Clears the RCC's interrupt pending bits. More...
 
void RCC_ClockSecuritySystemCmd (FunctionalState NewState)
 Enables or disables the Clock Security System. More...
 
void RCC_DeInit (void)
 Resets the RCC clock configuration to the default reset state. More...
 
void RCC_GetClocksFreq (RCC_ClocksTypeDef *RCC_Clocks)
 Returns the frequencies of different on chip clocks. More...
 
FlagStatus RCC_GetFlagStatus (uint8_t RCC_FLAG)
 Checks whether the specified RCC flag is set or not. More...
 
ITStatus RCC_GetITStatus (uint8_t RCC_IT)
 Checks whether the specified RCC interrupt has occurred or not. More...
 
uint8_t RCC_GetSYSCLKSource (void)
 Returns the clock source used as system clock. More...
 
void RCC_HCLKConfig (uint32_t RCC_SYSCLK)
 Configures the AHB clock (HCLK). More...
 
void RCC_HSEConfig (uint32_t RCC_HSE)
 Configures the External High Speed oscillator (HSE). More...
 
void RCC_HSICmd (FunctionalState NewState)
 Enables or disables the Internal High Speed oscillator (HSI). More...
 
void RCC_ITConfig (uint8_t RCC_IT, FunctionalState NewState)
 Enables or disables the specified RCC interrupts. More...
 
void RCC_LSEConfig (uint8_t RCC_LSE)
 Configures the External Low Speed oscillator (LSE). More...
 
void RCC_LSICmd (FunctionalState NewState)
 Enables or disables the Internal Low Speed oscillator (LSI). More...
 
void RCC_MCOConfig (uint8_t RCC_MCO)
 Selects the clock source to output on MCO pin. More...
 
void RCC_PCLK1Config (uint32_t RCC_HCLK)
 Configures the Low Speed APB clock (PCLK1). More...
 
void RCC_PCLK2Config (uint32_t RCC_HCLK)
 Configures the High Speed APB clock (PCLK2). More...
 
void RCC_PLLCmd (FunctionalState NewState)
 Enables or disables the PLL. More...
 
void RCC_PLLConfig (uint32_t RCC_PLLSource, uint32_t RCC_PLLMul)
 Configures the PLL clock source and multiplication factor. More...
 
void RCC_RTCCLKCmd (FunctionalState NewState)
 Enables or disables the RTC clock. More...
 
void RCC_RTCCLKConfig (uint32_t RCC_RTCCLKSource)
 Configures the RTC clock (RTCCLK). More...
 
void RCC_SYSCLKConfig (uint32_t RCC_SYSCLKSource)
 Configures the system clock (SYSCLK). More...
 
void RCC_USBCLKConfig (uint32_t RCC_USBCLKSource)
 Configures the USB clock (USBCLK). More...
 
ErrorStatus RCC_WaitForHSEStartUp (void)
 Waits for HSE start-up. More...
 

Variables

static __I uint8_t ADCPrescTable [4] = {2, 4, 6, 8}
 
static __I uint8_t APBAHBPrescTable [16] = {0, 0, 0, 0, 1, 2, 3, 4, 1, 2, 3, 4, 6, 7, 8, 9}
 
uint32_t hse_value
 

Detailed Description

This file provides all the RCC firmware functions.

Author
MCD Application Team
Version
V3.5.0
Date
11-March-2011
Attention

THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.

© COPYRIGHT 2011 STMicroelectronics

Definition in file stm32f10x_rcc.c.



rosflight_firmware
Author(s): Daniel Koch , James Jackson
autogenerated on Thu Apr 15 2021 05:07:52