Modules | Classes | Functions | Variables
STM32F30x_StdPeriph_Driver
Collaboration diagram for STM32F30x_StdPeriph_Driver:

Modules

 ADC
 ADC driver modules.
 
 CAN
 CAN driver modules.
 
 COMP
 COMP driver modules.
 
 CRC
 CRC driver modules.
 
 DAC
 DAC driver modules.
 
 DBGMCU
 DBGMCU driver modules.
 
 DMA
 DMA driver modules.
 
 EXTI
 EXTI driver modules.
 
 FLASH
 FLASH driver modules.
 
 GPIO
 GPIO driver modules.
 
 HRTIM
 HRTIM driver module.
 
 I2C
 I2C driver modules.
 
 IWDG
 IWDG driver modules.
 
 MISC
 MISC driver modules.
 
 OPAMP
 OPAMP driver modules.
 
 PWR
 PWR driver modules.
 
 RCC
 RCC driver modules.
 
 RTC
 RTC driver modules.
 
 SPI
 SPI driver modules.
 
 SYSCFG
 SYSCFG driver modules.
 
 TIM
 TIM driver modules.
 
 USART
 USART driver modules.
 
 WWDG
 WWDG driver modules.
 

Classes

struct  ADC_InjectedInitTypeDef
 ADC Init structure definition. More...
 

Functions

void NVIC_Init (NVIC_InitTypeDef *NVIC_InitStruct)
 Initializes the NVIC peripheral according to the specified parameters in the NVIC_InitStruct. More...
 
void NVIC_PriorityGroupConfig (uint32_t NVIC_PriorityGroup)
 Configures the priority grouping: pre-emption priority and subpriority. More...
 
void NVIC_SetVectorTable (uint32_t NVIC_VectTab, uint32_t Offset)
 Sets the vector table location and Offset. More...
 
void NVIC_SystemLPConfig (uint8_t LowPowerMode, FunctionalState NewState)
 Selects the condition for the system to enter low power mode. More...
 
void SysTick_CLKSourceConfig (uint32_t SysTick_CLKSource)
 Configures the SysTick clock source. More...
 

Variables

uint32_t RCC_ClocksTypeDef::ADC12CLK_Frequency
 
uint32_t RCC_ClocksTypeDef::ADC34CLK_Frequency
 
uint32_t RCC_ClocksTypeDef::HCLK_Frequency
 
uint32_t RCC_ClocksTypeDef::HRTIM1CLK_Frequency
 
uint32_t RCC_ClocksTypeDef::I2C1CLK_Frequency
 
uint32_t RCC_ClocksTypeDef::I2C2CLK_Frequency
 
uint32_t RCC_ClocksTypeDef::I2C3CLK_Frequency
 
uint32_t RCC_ClocksTypeDef::PCLK1_Frequency
 
uint32_t RCC_ClocksTypeDef::PCLK2_Frequency
 
uint32_t RCC_ClocksTypeDef::SYSCLK_Frequency
 
uint32_t RCC_ClocksTypeDef::TIM15CLK_Frequency
 
uint32_t RCC_ClocksTypeDef::TIM16CLK_Frequency
 
uint32_t RCC_ClocksTypeDef::TIM17CLK_Frequency
 
uint32_t RCC_ClocksTypeDef::TIM1CLK_Frequency
 
uint32_t RCC_ClocksTypeDef::TIM8CLK_Frequency
 
uint32_t RCC_ClocksTypeDef::UART4CLK_Frequency
 
uint32_t RCC_ClocksTypeDef::UART5CLK_Frequency
 
uint32_t RCC_ClocksTypeDef::USART1CLK_Frequency
 
uint32_t RCC_ClocksTypeDef::USART2CLK_Frequency
 
uint32_t RCC_ClocksTypeDef::USART3CLK_Frequency
 

Detailed Description

< Includes ----------------------------------------------------------——

< Define to prevent recursive inclusion --------------------------———

< Includes ----------------------------------------------------------——

Function Documentation

void NVIC_Init ( NVIC_InitTypeDef NVIC_InitStruct)

Initializes the NVIC peripheral according to the specified parameters in the NVIC_InitStruct.

Note
To configure interrupts priority correctly, the NVIC_PriorityGroupConfig() function should be called before.
Parameters
NVIC_InitStructpointer to a NVIC_InitTypeDef structure that contains the configuration information for the specified NVIC peripheral.
Return values
None
Parameters
NVIC_InitStructpointer to a NVIC_InitTypeDef structure that contains the configuration information for the specified NVIC peripheral.
Return values
None

Definition at line 136 of file airbourne/airbourne/lib/STM32F4xx_StdPeriph_Driver/src/misc.c.

void NVIC_PriorityGroupConfig ( uint32_t  NVIC_PriorityGroup)

Configures the priority grouping: pre-emption priority and subpriority.

Parameters
NVIC_PriorityGroupspecifies the priority grouping bits length. This parameter can be one of the following values:
  • NVIC_PriorityGroup_0: 0 bits for pre-emption priority 4 bits for subpriority
  • NVIC_PriorityGroup_1: 1 bits for pre-emption priority 3 bits for subpriority
  • NVIC_PriorityGroup_2: 2 bits for pre-emption priority 2 bits for subpriority
  • NVIC_PriorityGroup_3: 3 bits for pre-emption priority 1 bits for subpriority
  • NVIC_PriorityGroup_4: 4 bits for pre-emption priority 0 bits for subpriority
Note
When the NVIC_PriorityGroup_0 is selected, IRQ pre-emption is no more possible. The pending IRQ priority will be managed only by the subpriority.
Return values
None
Parameters
NVIC_PriorityGroupspecifies the priority grouping bits length. This parameter can be one of the following values:
  • NVIC_PriorityGroup_0: 0 bits for pre-emption priority 4 bits for subpriority
  • NVIC_PriorityGroup_1: 1 bits for pre-emption priority 3 bits for subpriority
  • NVIC_PriorityGroup_2: 2 bits for pre-emption priority 2 bits for subpriority
  • NVIC_PriorityGroup_3: 3 bits for pre-emption priority 1 bits for subpriority
  • NVIC_PriorityGroup_4: 4 bits for pre-emption priority 0 bits for subpriority
Return values
None
Parameters
NVIC_PriorityGroupspecifies the priority grouping bits length. This parameter can be one of the following values:
  • NVIC_PriorityGroup_0: 0 bits for pre-emption priority. 4 bits for subpriority.
  • NVIC_PriorityGroup_1: 1 bits for pre-emption priority. 3 bits for subpriority.
  • NVIC_PriorityGroup_2: 2 bits for pre-emption priority. 2 bits for subpriority.
  • NVIC_PriorityGroup_3: 3 bits for pre-emption priority. 1 bits for subpriority.
  • NVIC_PriorityGroup_4: 4 bits for pre-emption priority. 0 bits for subpriority.
Note
When NVIC_PriorityGroup_0 is selected, it will no be any nested interrupt. This interrupts priority is managed only with subpriority.
Return values
None

Definition at line 118 of file airbourne/airbourne/lib/STM32F4xx_StdPeriph_Driver/src/misc.c.

void NVIC_SetVectorTable ( uint32_t  NVIC_VectTab,
uint32_t  Offset 
)

Sets the vector table location and Offset.

Parameters
NVIC_VectTabspecifies if the vector table is in RAM or FLASH memory. This parameter can be one of the following values:
  • NVIC_VectTab_RAM: Vector Table in internal SRAM.
  • NVIC_VectTab_FLASH: Vector Table in internal FLASH.
OffsetVector Table base offset field. This value must be a multiple of 0x200.
Return values
None
Parameters
NVIC_VectTabspecifies if the vector table is in RAM or FLASH memory. This parameter can be one of the following values:
  • NVIC_VectTab_RAM
  • NVIC_VectTab_FLASH
OffsetVector Table base offset field. This value must be a multiple of 0x200.
Return values
None

Definition at line 180 of file airbourne/airbourne/lib/STM32F4xx_StdPeriph_Driver/src/misc.c.

void NVIC_SystemLPConfig ( uint8_t  LowPowerMode,
FunctionalState  NewState 
)

Selects the condition for the system to enter low power mode.

Parameters
LowPowerModeSpecifies the new mode for the system to enter low power mode. This parameter can be one of the following values:
  • NVIC_LP_SEVONPEND: Low Power SEV on Pend.
  • NVIC_LP_SLEEPDEEP: Low Power DEEPSLEEP request.
  • NVIC_LP_SLEEPONEXIT: Low Power Sleep on Exit.
NewStatenew state of LP condition. This parameter can be: ENABLE or DISABLE.
Return values
None
Parameters
LowPowerModeSpecifies the new mode for the system to enter low power mode. This parameter can be one of the following values:
  • NVIC_LP_SEVONPEND
  • NVIC_LP_SLEEPDEEP
  • NVIC_LP_SLEEPONEXIT
NewStatenew state of LP condition. This parameter can be: ENABLE or DISABLE.
Return values
None

Definition at line 199 of file airbourne/airbourne/lib/STM32F4xx_StdPeriph_Driver/src/misc.c.

void SysTick_CLKSourceConfig ( uint32_t  SysTick_CLKSource)

Configures the SysTick clock source.

Parameters
SysTick_CLKSourcespecifies the SysTick clock source. This parameter can be one of the following values:
  • SysTick_CLKSource_HCLK_Div8: AHB clock divided by 8 selected as SysTick clock source.
  • SysTick_CLKSource_HCLK: AHB clock selected as SysTick clock source.
Return values
None

Definition at line 223 of file airbourne/airbourne/lib/STM32F4xx_StdPeriph_Driver/src/misc.c.

Variable Documentation

uint32_t RCC_ClocksTypeDef::ADC12CLK_Frequency

Definition at line 56 of file stm32f30x_rcc.h.

uint32_t RCC_ClocksTypeDef::ADC34CLK_Frequency

Definition at line 57 of file stm32f30x_rcc.h.

uint32_t RCC_ClocksTypeDef::HCLK_Frequency

HCLK clock frequency expressed in Hz

returns HCLK clock frequency expressed in Hz

Definition at line 51 of file CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_rcc.h.

uint32_t RCC_ClocksTypeDef::HRTIM1CLK_Frequency

Definition at line 62 of file stm32f30x_rcc.h.

uint32_t RCC_ClocksTypeDef::I2C1CLK_Frequency

Definition at line 58 of file stm32f30x_rcc.h.

uint32_t RCC_ClocksTypeDef::I2C2CLK_Frequency

Definition at line 59 of file stm32f30x_rcc.h.

uint32_t RCC_ClocksTypeDef::I2C3CLK_Frequency

Definition at line 60 of file stm32f30x_rcc.h.

uint32_t RCC_ClocksTypeDef::PCLK1_Frequency

PCLK1 clock frequency expressed in Hz

returns PCLK1 clock frequency expressed in Hz

Definition at line 52 of file CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_rcc.h.

uint32_t RCC_ClocksTypeDef::PCLK2_Frequency

PCLK2 clock frequency expressed in Hz

returns PCLK2 clock frequency expressed in Hz

Definition at line 53 of file CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_rcc.h.

uint32_t RCC_ClocksTypeDef::SYSCLK_Frequency

SYSCLK clock frequency expressed in Hz

returns SYSCLK clock frequency expressed in Hz

Definition at line 50 of file CMSIS/CM4/DeviceSupport/ST/STM32F4xx/stm32f4xx_rcc.h.

uint32_t RCC_ClocksTypeDef::TIM15CLK_Frequency

Definition at line 69 of file stm32f30x_rcc.h.

uint32_t RCC_ClocksTypeDef::TIM16CLK_Frequency

Definition at line 70 of file stm32f30x_rcc.h.

uint32_t RCC_ClocksTypeDef::TIM17CLK_Frequency

Definition at line 71 of file stm32f30x_rcc.h.

uint32_t RCC_ClocksTypeDef::TIM1CLK_Frequency

Definition at line 61 of file stm32f30x_rcc.h.

uint32_t RCC_ClocksTypeDef::TIM8CLK_Frequency

Definition at line 63 of file stm32f30x_rcc.h.

uint32_t RCC_ClocksTypeDef::UART4CLK_Frequency

Definition at line 67 of file stm32f30x_rcc.h.

uint32_t RCC_ClocksTypeDef::UART5CLK_Frequency

Definition at line 68 of file stm32f30x_rcc.h.

uint32_t RCC_ClocksTypeDef::USART1CLK_Frequency

Definition at line 64 of file stm32f30x_rcc.h.

uint32_t RCC_ClocksTypeDef::USART2CLK_Frequency

Definition at line 65 of file stm32f30x_rcc.h.

uint32_t RCC_ClocksTypeDef::USART3CLK_Frequency

Definition at line 66 of file stm32f30x_rcc.h.



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