get GPIO and USART ports working.

The STM32F3DISCOVERY board would crash when setting GPIOA Pin_13 or
Pin_14 to analog mode so they are excluded in the gpio initialisation.

The USART GPIO configuration did not work when using the F10x code.  The
USART status and DMA registers are different too.
This commit is contained in:
Dominic Clifton 2014-04-25 15:19:28 +01:00
parent 2cc3a50c01
commit 8d9ce86a5a
9 changed files with 3720 additions and 3 deletions

View File

@ -0,0 +1,535 @@
/**
******************************************************************************
* @file stm32f30x_gpio.c
* @author MCD Application Team
* @version V1.1.1
* @date 04-April-2014
* @brief This file provides firmware functions to manage the following
* functionalities of the GPIO peripheral:
* + Initialization and Configuration functions
* + GPIO Read and Write functions
* + GPIO Alternate functions configuration functions
*
* @verbatim
===============================================================================
##### How to use this driver #####
===============================================================================
[..]
(#) Enable the GPIO AHB clock using RCC_AHBPeriphClockCmd()
(#) Configure the GPIO pin(s) using GPIO_Init()
Four possible configuration are available for each pin:
(++) Input: Floating, Pull-up, Pull-down.
(++) Output: Push-Pull (Pull-up, Pull-down or no Pull),
Open Drain (Pull-up, Pull-down or no Pull).
In output mode, the speed is configurable: Low, Medium, Fast or High.
(++) Alternate Function: Push-Pull (Pull-up, Pull-down or no Pull),
Open Drain (Pull-up, Pull-down or no Pull).
(++) Analog: required mode when a pin is to be used as ADC channel,
DAC output or comparator input.
(#) Peripherals alternate function:
(++) For ADC, DAC and comparators, configure the desired pin in
analog mode using GPIO_InitStruct->GPIO_Mode = GPIO_Mode_AN
(++) For other peripherals (TIM, USART...):
(+++) Connect the pin to the desired peripherals' Alternate
Function (AF) using GPIO_PinAFConfig() function.
(+++) Configure the desired pin in alternate function mode using
GPIO_InitStruct->GPIO_Mode = GPIO_Mode_AF
(+++) Select the type, pull-up/pull-down and output speed via
GPIO_PuPd, GPIO_OType and GPIO_Speed members.
(+++) Call GPIO_Init() function.
(#) To get the level of a pin configured in input mode use GPIO_ReadInputDataBit()
(#) To set/reset the level of a pin configured in output mode use
GPIO_SetBits()/GPIO_ResetBits()
(#) During and just after reset, the alternate functions are not active
and the GPIO pins are configured in input floating mode (except JTAG pins).
(#) The LSE oscillator pins OSC32_IN and OSC32_OUT can be used as
general-purpose (PC14 and PC15, respectively) when the LSE
oscillator is off. The LSE has priority over the GPIO function.
(#) The HSE oscillator pins OSC_IN/OSC_OUT can be used as general-purpose
(PF0 and PF1 respectively) when the HSE oscillator is off. The HSE has
the priority over the GPIO function.
@endverbatim
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2014 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
* You may not use this file except in compliance with the License.
* You may obtain a copy of the License at:
*
* http://www.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "stm32f30x_gpio.h"
#include "stm32f30x_rcc.h"
/** @addtogroup STM32F30x_StdPeriph_Driver
* @{
*/
/** @defgroup GPIO
* @brief GPIO driver modules
* @{
*/
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/** @defgroup GPIO_Private_Functions
* @{
*/
/** @defgroup GPIO_Group1 Initialization and Configuration
* @brief Initialization and Configuration
*
@verbatim
===============================================================================
##### Initialization and Configuration #####
===============================================================================
@endverbatim
* @{
*/
/**
* @brief Deinitializes the GPIOx peripheral registers to their default reset
* values.
* @param GPIOx: where x can be (A, B, C, D, E or F) to select the GPIO peripheral.
* @retval None
*/
void GPIO_DeInit(GPIO_TypeDef* GPIOx)
{
/* Check the parameters */
assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
if(GPIOx == GPIOA)
{
RCC_AHBPeriphResetCmd(RCC_AHBPeriph_GPIOA, ENABLE);
RCC_AHBPeriphResetCmd(RCC_AHBPeriph_GPIOA, DISABLE);
}
else if(GPIOx == GPIOB)
{
RCC_AHBPeriphResetCmd(RCC_AHBPeriph_GPIOB, ENABLE);
RCC_AHBPeriphResetCmd(RCC_AHBPeriph_GPIOB, DISABLE);
}
else if(GPIOx == GPIOC)
{
RCC_AHBPeriphResetCmd(RCC_AHBPeriph_GPIOC, ENABLE);
RCC_AHBPeriphResetCmd(RCC_AHBPeriph_GPIOC, DISABLE);
}
else if(GPIOx == GPIOD)
{
RCC_AHBPeriphResetCmd(RCC_AHBPeriph_GPIOD, ENABLE);
RCC_AHBPeriphResetCmd(RCC_AHBPeriph_GPIOD, DISABLE);
}
else if(GPIOx == GPIOE)
{
RCC_AHBPeriphResetCmd(RCC_AHBPeriph_GPIOE, ENABLE);
RCC_AHBPeriphResetCmd(RCC_AHBPeriph_GPIOE, DISABLE);
}
else
{
if(GPIOx == GPIOF)
{
RCC_AHBPeriphResetCmd(RCC_AHBPeriph_GPIOF, ENABLE);
RCC_AHBPeriphResetCmd(RCC_AHBPeriph_GPIOF, DISABLE);
}
}
}
/**
* @brief Initializes the GPIOx peripheral according to the specified
* parameters in the GPIO_InitStruct.
* @param GPIOx: where x can be (A, B, C, D, E or F) to select the GPIO peripheral.
* @param GPIO_InitStruct: pointer to a GPIO_InitTypeDef structure that
* contains the configuration information for the specified GPIO
* peripheral.
* @note GPIO_Pin: selects the pin to be configured:
* GPIO_Pin_0->GPIO_Pin_15 for GPIOA, GPIOB, GPIOC, GPIOD and GPIOE;
* GPIO_Pin_0->GPIO_Pin_2, GPIO_Pin_4, GPIO_Pin_6, GPIO_Pin_9
* and GPIO_Pin_10 for GPIOF.
* @retval None
*/
void GPIO_Init(GPIO_TypeDef* GPIOx, GPIO_InitTypeDef* GPIO_InitStruct)
{
uint32_t pinpos = 0x00, pos = 0x00 , currentpin = 0x00;
uint32_t tmpreg = 0x00;
/* Check the parameters */
assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
assert_param(IS_GPIO_PIN(GPIO_InitStruct->GPIO_Pin));
assert_param(IS_GPIO_MODE(GPIO_InitStruct->GPIO_Mode));
assert_param(IS_GPIO_PUPD(GPIO_InitStruct->GPIO_PuPd));
/*-------------------------- Configure the port pins -----------------------*/
/*-- GPIO Mode Configuration --*/
for (pinpos = 0x00; pinpos < 0x10; pinpos++)
{
pos = ((uint32_t)0x01) << pinpos;
/* Get the port pins position */
currentpin = (GPIO_InitStruct->GPIO_Pin) & pos;
if (currentpin == pos)
{
if ((GPIO_InitStruct->GPIO_Mode == GPIO_Mode_OUT) || (GPIO_InitStruct->GPIO_Mode == GPIO_Mode_AF))
{
/* Check Speed mode parameters */
assert_param(IS_GPIO_SPEED(GPIO_InitStruct->GPIO_Speed));
/* Speed mode configuration */
GPIOx->OSPEEDR &= ~(GPIO_OSPEEDER_OSPEEDR0 << (pinpos * 2));
GPIOx->OSPEEDR |= ((uint32_t)(GPIO_InitStruct->GPIO_Speed) << (pinpos * 2));
/* Check Output mode parameters */
assert_param(IS_GPIO_OTYPE(GPIO_InitStruct->GPIO_OType));
/* Output mode configuration */
GPIOx->OTYPER &= ~((GPIO_OTYPER_OT_0) << ((uint16_t)pinpos));
GPIOx->OTYPER |= (uint16_t)(((uint16_t)GPIO_InitStruct->GPIO_OType) << ((uint16_t)pinpos));
}
GPIOx->MODER &= ~(GPIO_MODER_MODER0 << (pinpos * 2));
GPIOx->MODER |= (((uint32_t)GPIO_InitStruct->GPIO_Mode) << (pinpos * 2));
/* Use temporary variable to update PUPDR register configuration, to avoid
unexpected transition in the GPIO pin configuration. */
tmpreg = GPIOx->PUPDR;
tmpreg &= ~(GPIO_PUPDR_PUPDR0 << ((uint16_t)pinpos * 2));
tmpreg |= (((uint32_t)GPIO_InitStruct->GPIO_PuPd) << (pinpos * 2));
GPIOx->PUPDR = tmpreg;
}
}
}
/**
* @brief Fills each GPIO_InitStruct member with its default value.
* @param GPIO_InitStruct: pointer to a GPIO_InitTypeDef structure which will
* be initialized.
* @retval None
*/
void GPIO_StructInit(GPIO_InitTypeDef* GPIO_InitStruct)
{
/* Reset GPIO init structure parameters values */
GPIO_InitStruct->GPIO_Pin = GPIO_Pin_All;
GPIO_InitStruct->GPIO_Mode = GPIO_Mode_IN;
GPIO_InitStruct->GPIO_Speed = GPIO_Speed_2MHz;
GPIO_InitStruct->GPIO_OType = GPIO_OType_PP;
GPIO_InitStruct->GPIO_PuPd = GPIO_PuPd_NOPULL;
}
/**
* @brief Locks GPIO Pins configuration registers.
* The locked registers are GPIOx_MODER, GPIOx_OTYPER, GPIOx_OSPEEDR,
* GPIOx_PUPDR, GPIOx_AFRL and GPIOx_AFRH.
* @note The configuration of the locked GPIO pins can no longer be modified
* until the next reset.
* @param GPIOx: where x can be (A or B or D) to select the GPIO peripheral.
* @param GPIO_Pin: specifies the port bit to be written.
* This parameter can be any combination of GPIO_Pin_x where x can be (0..15).
* @retval None
*/
void GPIO_PinLockConfig(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin)
{
uint32_t tmp = 0x00010000;
/* Check the parameters */
assert_param(IS_GPIO_LIST_PERIPH(GPIOx));
assert_param(IS_GPIO_PIN(GPIO_Pin));
tmp |= GPIO_Pin;
/* Set LCKK bit */
GPIOx->LCKR = tmp;
/* Reset LCKK bit */
GPIOx->LCKR = GPIO_Pin;
/* Set LCKK bit */
GPIOx->LCKR = tmp;
/* Read LCKK bit */
tmp = GPIOx->LCKR;
/* Read LCKK bit */
tmp = GPIOx->LCKR;
}
/**
* @}
*/
/** @defgroup GPIO_Group2 GPIO Read and Write
* @brief GPIO Read and Write
*
@verbatim
===============================================================================
##### GPIO Read and Write #####
===============================================================================
@endverbatim
* @{
*/
/**
* @brief Reads the specified input port pin.
* @param GPIOx: where x can be (A, B, C, D, E or F) to select the GPIO peripheral.
* @param GPIO_Pin: specifies the port bit to read.
* @note This parameter can be GPIO_Pin_x where x can be :
* (0..15) for GPIOA, GPIOB, GPIOC, GPIOD or GPIOE;
* (0..2, 4, 6, 9..10) for GPIOF.
* @retval The input port pin value.
*/
uint8_t GPIO_ReadInputDataBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin)
{
uint8_t bitstatus = 0x00;
/* Check the parameters */
assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
assert_param(IS_GET_GPIO_PIN(GPIO_Pin));
if ((GPIOx->IDR & GPIO_Pin) != (uint32_t)Bit_RESET)
{
bitstatus = (uint8_t)Bit_SET;
}
else
{
bitstatus = (uint8_t)Bit_RESET;
}
return bitstatus;
}
/**
* @brief Reads the specified input port pin.
* @param GPIOx: where x can be (A, B, C, D, E or F) to select the GPIO peripheral.
* @retval The input port pin value.
*/
uint16_t GPIO_ReadInputData(GPIO_TypeDef* GPIOx)
{
/* Check the parameters */
assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
return ((uint16_t)GPIOx->IDR);
}
/**
* @brief Reads the specified output data port bit.
* @param GPIOx: where x can be (A, B, C, D, E or F) to select the GPIO peripheral.
* @param GPIO_Pin: Specifies the port bit to read.
* @note This parameter can be GPIO_Pin_x where x can be :
* (0..15) for GPIOA, GPIOB, GPIOC, GPIOD or GPIOE;
* (0..2, 4, 6, 9..10) for GPIOF.
* @retval The output port pin value.
*/
uint8_t GPIO_ReadOutputDataBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin)
{
uint8_t bitstatus = 0x00;
/* Check the parameters */
assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
assert_param(IS_GET_GPIO_PIN(GPIO_Pin));
if ((GPIOx->ODR & GPIO_Pin) != (uint32_t)Bit_RESET)
{
bitstatus = (uint8_t)Bit_SET;
}
else
{
bitstatus = (uint8_t)Bit_RESET;
}
return bitstatus;
}
/**
* @brief Reads the specified GPIO output data port.
* @param GPIOx: where x can be (A, B, C, D, E or F) to select the GPIO peripheral.
* @retval GPIO output data port value.
*/
uint16_t GPIO_ReadOutputData(GPIO_TypeDef* GPIOx)
{
/* Check the parameters */
assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
return ((uint16_t)GPIOx->ODR);
}
/**
* @brief Sets the selected data port bits.
* @param GPIOx: where x can be (A, B, C, D, E or F) to select the GPIO peripheral.
* @param GPIO_Pin: specifies the port bits to be written.
* @note This parameter can be GPIO_Pin_x where x can be :
* (0..15) for GPIOA, GPIOB, GPIOC, GPIOD or GPIOE;
* (0..2, 4, 6, 9..10) for GPIOF.
* @retval None
*/
void GPIO_SetBits(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin)
{
/* Check the parameters */
assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
assert_param(IS_GPIO_PIN(GPIO_Pin));
GPIOx->BSRR = GPIO_Pin;
}
/**
* @brief Clears the selected data port bits.
* @param GPIOx: where x can be (A, B, C, D, E or F) to select the GPIO peripheral.
* @param GPIO_Pin: specifies the port bits to be written.
* @note This parameter can be GPIO_Pin_x where x can be :
* (0..15) for GPIOA, GPIOB, GPIOC, GPIOD or GPIOE;
* (0..2, 4, 6, 9..10) for GPIOF.
* @retval None
*/
void GPIO_ResetBits(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin)
{
/* Check the parameters */
assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
assert_param(IS_GPIO_PIN(GPIO_Pin));
GPIOx->BRR = GPIO_Pin;
}
/**
* @brief Sets or clears the selected data port bit.
* @param GPIOx: where x can be (A, B, C, D, E or F) to select the GPIO peripheral.
* @param GPIO_Pin: specifies the port bit to be written.
* @note This parameter can be GPIO_Pin_x where x can be :
* (0..15) for GPIOA, GPIOB, GPIOC, GPIOD or GPIOE;
* (0..2, 4, 6, 9..10) for GPIOF.
* @param BitVal: specifies the value to be written to the selected bit.
* This parameter can be one of the BitAction enumeration values:
* @arg Bit_RESET: to clear the port pin
* @arg Bit_SET: to set the port pin
* @retval None
*/
void GPIO_WriteBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin, BitAction BitVal)
{
/* Check the parameters */
assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
assert_param(IS_GET_GPIO_PIN(GPIO_Pin));
assert_param(IS_GPIO_BIT_ACTION(BitVal));
if (BitVal != Bit_RESET)
{
GPIOx->BSRR = GPIO_Pin;
}
else
{
GPIOx->BRR = GPIO_Pin ;
}
}
/**
* @brief Writes data to the specified GPIO data port.
* @param GPIOx: where x can be (A, B, C, D, E or F) to select the GPIO peripheral.
* @param PortVal: specifies the value to be written to the port output data
* register.
* @retval None
*/
void GPIO_Write(GPIO_TypeDef* GPIOx, uint16_t PortVal)
{
/* Check the parameters */
assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
GPIOx->ODR = PortVal;
}
/**
* @}
*/
/** @defgroup GPIO_Group3 GPIO Alternate functions configuration functions
* @brief GPIO Alternate functions configuration functions
*
@verbatim
===============================================================================
##### GPIO Alternate functions configuration functions #####
===============================================================================
@endverbatim
* @{
*/
/**
* @brief Writes data to the specified GPIO data port.
* @param GPIOx: where x can be (A, B, C, D, E or F) to select the GPIO peripheral.
* @param GPIO_PinSource: specifies the pin for the Alternate function.
* This parameter can be GPIO_PinSourcex where x can be (0..15).
* @param GPIO_AF: selects the pin to be used as Alternate function.
* This parameter can be one of the following value:
* @arg GPIO_AF_0: JTCK-SWCLK, JTDI, JTDO/TRACESW0, JTMS-SWDAT, MCO, NJTRST,
* TRACED, TRACECK.
* @arg GPIO_AF_1: OUT, TIM2, TIM15, TIM16, TIM17.
* @arg GPIO_AF_2: COMP1_OUT, TIM1, TIM2, TIM3, TIM4, TIM8, TIM15, TIM16.
* @arg GPIO_AF_3: COMP7_OUT, TIM8, TIM15, Touch, HRTIM.
* @arg GPIO_AF_4: I2C1, I2C2, TIM1, TIM8, TIM16, TIM17.
* @arg GPIO_AF_5: IR_OUT, I2S2, I2S3, SPI1, SPI2, TIM8, USART4, USART5
* @arg GPIO_AF_6: IR_OUT, I2S2, I2S3, SPI2, SPI3, TIM1, TIM8
* @arg GPIO_AF_7: AOP2_OUT, CAN, COMP3_OUT, COMP5_OUT, COMP6_OUT, USART1,
* USART2, USART3.
* @arg GPIO_AF_8: COMP1_OUT, COMP2_OUT, COMP3_OUT, COMP4_OUT, COMP5_OUT,
* COMP6_OUT.
* @arg GPIO_AF_9: AOP4_OUT, CAN, TIM1, TIM8, TIM15.
* @arg GPIO_AF_10: AOP1_OUT, AOP3_OUT, TIM2, TIM3, TIM4, TIM8, TIM17.
* @arg GPIO_AF_11: TIM1, TIM8.
* @arg GPIO_AF_12: TIM1, HRTIM.
* @arg GPIO_AF_13: HRTIM, AOP2_OUT.
* @arg GPIO_AF_14: USBDM, USBDP.
* @arg GPIO_AF_15: OUT.
* @note The pin should already been configured in Alternate Function mode(AF)
* using GPIO_InitStruct->GPIO_Mode = GPIO_Mode_AF
* @note Refer to the Alternate function mapping table in the device datasheet
* for the detailed mapping of the system and peripherals alternate
* function I/O pins.
* @retval None
*/
void GPIO_PinAFConfig(GPIO_TypeDef* GPIOx, uint16_t GPIO_PinSource, uint8_t GPIO_AF)
{
uint32_t temp = 0x00;
uint32_t temp_2 = 0x00;
/* Check the parameters */
assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
assert_param(IS_GPIO_PIN_SOURCE(GPIO_PinSource));
assert_param(IS_GPIO_AF(GPIO_AF));
temp = ((uint32_t)(GPIO_AF) << ((uint32_t)((uint32_t)GPIO_PinSource & (uint32_t)0x07) * 4));
GPIOx->AFR[GPIO_PinSource >> 0x03] &= ~((uint32_t)0xF << ((uint32_t)((uint32_t)GPIO_PinSource & (uint32_t)0x07) * 4));
temp_2 = GPIOx->AFR[GPIO_PinSource >> 0x03] | temp;
GPIOx->AFR[GPIO_PinSource >> 0x03] = temp_2;
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,400 @@
/**
******************************************************************************
* @file stm32f30x_gpio.h
* @author MCD Application Team
* @version V1.1.1
* @date 04-April-2014
* @brief This file contains all the functions prototypes for the GPIO
* firmware library.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2014 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
* You may not use this file except in compliance with the License.
* You may obtain a copy of the License at:
*
* http://www.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32F30x_GPIO_H
#define __STM32F30x_GPIO_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32f30x.h"
/** @addtogroup STM32F30x_StdPeriph_Driver
* @{
*/
/** @addtogroup GPIO
* @{
*/
/* Exported types ------------------------------------------------------------*/
#define IS_GPIO_ALL_PERIPH(PERIPH) (((PERIPH) == GPIOA) || \
((PERIPH) == GPIOB) || \
((PERIPH) == GPIOC) || \
((PERIPH) == GPIOD) || \
((PERIPH) == GPIOE) || \
((PERIPH) == GPIOF))
#define IS_GPIO_LIST_PERIPH(PERIPH) (((PERIPH) == GPIOA) || \
((PERIPH) == GPIOB) || \
((PERIPH) == GPIOD))
/** @defgroup Configuration_Mode_enumeration
* @{
*/
typedef enum
{
GPIO_Mode_IN = 0x00, /*!< GPIO Input Mode */
GPIO_Mode_OUT = 0x01, /*!< GPIO Output Mode */
GPIO_Mode_AF = 0x02, /*!< GPIO Alternate function Mode */
GPIO_Mode_AN = 0x03 /*!< GPIO Analog In/Out Mode */
}GPIOMode_TypeDef;
#define IS_GPIO_MODE(MODE) (((MODE) == GPIO_Mode_IN)|| ((MODE) == GPIO_Mode_OUT) || \
((MODE) == GPIO_Mode_AF)|| ((MODE) == GPIO_Mode_AN))
/**
* @}
*/
/** @defgroup Output_type_enumeration
* @{
*/
typedef enum
{
GPIO_OType_PP = 0x00,
GPIO_OType_OD = 0x01
}GPIOOType_TypeDef;
#define IS_GPIO_OTYPE(OTYPE) (((OTYPE) == GPIO_OType_PP) || ((OTYPE) == GPIO_OType_OD))
/**
* @}
*/
/** @defgroup Output_Maximum_frequency_enumeration
* @{
*/
typedef enum
{
GPIO_Speed_Level_1 = 0x01, /*!< Fast Speed */
GPIO_Speed_Level_2 = 0x02, /*!< Meduim Speed */
GPIO_Speed_Level_3 = 0x03 /*!< High Speed */
}GPIOSpeed_TypeDef;
#define IS_GPIO_SPEED(SPEED) (((SPEED) == GPIO_Speed_Level_1) || ((SPEED) == GPIO_Speed_Level_2) || \
((SPEED) == GPIO_Speed_Level_3))
/**
* @}
*/
/** @defgroup Configuration_Pull-Up_Pull-Down_enumeration
* @{
*/
typedef enum
{
GPIO_PuPd_NOPULL = 0x00,
GPIO_PuPd_UP = 0x01,
GPIO_PuPd_DOWN = 0x02
}GPIOPuPd_TypeDef;
#define IS_GPIO_PUPD(PUPD) (((PUPD) == GPIO_PuPd_NOPULL) || ((PUPD) == GPIO_PuPd_UP) || \
((PUPD) == GPIO_PuPd_DOWN))
/**
* @}
*/
/** @defgroup Bit_SET_and_Bit_RESET_enumeration
* @{
*/
typedef enum
{
Bit_RESET = 0,
Bit_SET
}BitAction;
#define IS_GPIO_BIT_ACTION(ACTION) (((ACTION) == Bit_RESET) || ((ACTION) == Bit_SET))
/**
* @}
*/
/**
* @brief GPIO Init structure definition
*/
typedef struct
{
uint32_t GPIO_Pin; /*!< Specifies the GPIO pins to be configured.
This parameter can be any value of @ref GPIO_pins_define */
GPIOMode_TypeDef GPIO_Mode; /*!< Specifies the operating mode for the selected pins.
This parameter can be a value of @ref GPIOMode_TypeDef */
GPIOSpeed_TypeDef GPIO_Speed; /*!< Specifies the speed for the selected pins.
This parameter can be a value of @ref GPIOSpeed_TypeDef */
GPIOOType_TypeDef GPIO_OType; /*!< Specifies the operating output type for the selected pins.
This parameter can be a value of @ref GPIOOType_TypeDef */
GPIOPuPd_TypeDef GPIO_PuPd; /*!< Specifies the operating Pull-up/Pull down for the selected pins.
This parameter can be a value of @ref GPIOPuPd_TypeDef */
}GPIO_InitTypeDef;
/* Exported constants --------------------------------------------------------*/
/** @defgroup GPIO_Exported_Constants
* @{
*/
/** @defgroup GPIO_pins_define
* @{
*/
#define GPIO_Pin_0 ((uint16_t)0x0001) /*!< Pin 0 selected */
#define GPIO_Pin_1 ((uint16_t)0x0002) /*!< Pin 1 selected */
#define GPIO_Pin_2 ((uint16_t)0x0004) /*!< Pin 2 selected */
#define GPIO_Pin_3 ((uint16_t)0x0008) /*!< Pin 3 selected */
#define GPIO_Pin_4 ((uint16_t)0x0010) /*!< Pin 4 selected */
#define GPIO_Pin_5 ((uint16_t)0x0020) /*!< Pin 5 selected */
#define GPIO_Pin_6 ((uint16_t)0x0040) /*!< Pin 6 selected */
#define GPIO_Pin_7 ((uint16_t)0x0080) /*!< Pin 7 selected */
#define GPIO_Pin_8 ((uint16_t)0x0100) /*!< Pin 8 selected */
#define GPIO_Pin_9 ((uint16_t)0x0200) /*!< Pin 9 selected */
#define GPIO_Pin_10 ((uint16_t)0x0400) /*!< Pin 10 selected */
#define GPIO_Pin_11 ((uint16_t)0x0800) /*!< Pin 11 selected */
#define GPIO_Pin_12 ((uint16_t)0x1000) /*!< Pin 12 selected */
#define GPIO_Pin_13 ((uint16_t)0x2000) /*!< Pin 13 selected */
#define GPIO_Pin_14 ((uint16_t)0x4000) /*!< Pin 14 selected */
#define GPIO_Pin_15 ((uint16_t)0x8000) /*!< Pin 15 selected */
#define GPIO_Pin_All ((uint16_t)0xFFFF) /*!< All pins selected */
#define IS_GPIO_PIN(PIN) ((PIN) != (uint16_t)0x00)
#define IS_GET_GPIO_PIN(PIN) (((PIN) == GPIO_Pin_0) || \
((PIN) == GPIO_Pin_1) || \
((PIN) == GPIO_Pin_2) || \
((PIN) == GPIO_Pin_3) || \
((PIN) == GPIO_Pin_4) || \
((PIN) == GPIO_Pin_5) || \
((PIN) == GPIO_Pin_6) || \
((PIN) == GPIO_Pin_7) || \
((PIN) == GPIO_Pin_8) || \
((PIN) == GPIO_Pin_9) || \
((PIN) == GPIO_Pin_10) || \
((PIN) == GPIO_Pin_11) || \
((PIN) == GPIO_Pin_12) || \
((PIN) == GPIO_Pin_13) || \
((PIN) == GPIO_Pin_14) || \
((PIN) == GPIO_Pin_15))
/**
* @}
*/
/** @defgroup GPIO_Pin_sources
* @{
*/
#define GPIO_PinSource0 ((uint8_t)0x00)
#define GPIO_PinSource1 ((uint8_t)0x01)
#define GPIO_PinSource2 ((uint8_t)0x02)
#define GPIO_PinSource3 ((uint8_t)0x03)
#define GPIO_PinSource4 ((uint8_t)0x04)
#define GPIO_PinSource5 ((uint8_t)0x05)
#define GPIO_PinSource6 ((uint8_t)0x06)
#define GPIO_PinSource7 ((uint8_t)0x07)
#define GPIO_PinSource8 ((uint8_t)0x08)
#define GPIO_PinSource9 ((uint8_t)0x09)
#define GPIO_PinSource10 ((uint8_t)0x0A)
#define GPIO_PinSource11 ((uint8_t)0x0B)
#define GPIO_PinSource12 ((uint8_t)0x0C)
#define GPIO_PinSource13 ((uint8_t)0x0D)
#define GPIO_PinSource14 ((uint8_t)0x0E)
#define GPIO_PinSource15 ((uint8_t)0x0F)
#define IS_GPIO_PIN_SOURCE(PINSOURCE) (((PINSOURCE) == GPIO_PinSource0) || \
((PINSOURCE) == GPIO_PinSource1) || \
((PINSOURCE) == GPIO_PinSource2) || \
((PINSOURCE) == GPIO_PinSource3) || \
((PINSOURCE) == GPIO_PinSource4) || \
((PINSOURCE) == GPIO_PinSource5) || \
((PINSOURCE) == GPIO_PinSource6) || \
((PINSOURCE) == GPIO_PinSource7) || \
((PINSOURCE) == GPIO_PinSource8) || \
((PINSOURCE) == GPIO_PinSource9) || \
((PINSOURCE) == GPIO_PinSource10) || \
((PINSOURCE) == GPIO_PinSource11) || \
((PINSOURCE) == GPIO_PinSource12) || \
((PINSOURCE) == GPIO_PinSource13) || \
((PINSOURCE) == GPIO_PinSource14) || \
((PINSOURCE) == GPIO_PinSource15))
/**
* @}
*/
/** @defgroup GPIO_Alternate_function_selection_define
* @{
*/
/**
* @brief AF 0 selection
*/
#define GPIO_AF_0 ((uint8_t)0x00) /* JTCK-SWCLK, JTDI, JTDO/TRACESW0, JTMS-SWDAT,
MCO, NJTRST, TRACED, TRACECK */
/**
* @brief AF 1 selection
*/
#define GPIO_AF_1 ((uint8_t)0x01) /* OUT, TIM2, TIM15, TIM16, TIM17 */
/**
* @brief AF 2 selection
*/
#define GPIO_AF_2 ((uint8_t)0x02) /* COMP1_OUT, TIM1, TIM2, TIM3, TIM4, TIM8, TIM15, TIM16 */
/**
* @brief AF 3 selection
*/
#define GPIO_AF_3 ((uint8_t)0x03) /* COMP7_OUT, TIM8, TIM15, Touch, HRTIM1 */
/**
* @brief AF 4 selection
*/
#define GPIO_AF_4 ((uint8_t)0x04) /* I2C1, I2C2, TIM1, TIM8, TIM16, TIM17 */
/**
* @brief AF 5 selection
*/
#define GPIO_AF_5 ((uint8_t)0x05) /* IR_OUT, I2S2, I2S3, SPI1, SPI2, TIM8, USART4, USART5 */
/**
* @brief AF 6 selection
*/
#define GPIO_AF_6 ((uint8_t)0x06) /* IR_OUT, I2S2, I2S3, SPI2, SPI3, TIM1, TIM8 */
/**
* @brief AF 7 selection
*/
#define GPIO_AF_7 ((uint8_t)0x07) /* AOP2_OUT, CAN, COMP3_OUT, COMP5_OUT, COMP6_OUT,
USART1, USART2, USART3 */
/**
* @brief AF 8 selection
*/
#define GPIO_AF_8 ((uint8_t)0x08) /* COMP1_OUT, COMP2_OUT, COMP3_OUT, COMP4_OUT,
COMP5_OUT, COMP6_OUT */
/**
* @brief AF 9 selection
*/
#define GPIO_AF_9 ((uint8_t)0x09) /* AOP4_OUT, CAN, TIM1, TIM8, TIM15 */
/**
* @brief AF 10 selection
*/
#define GPIO_AF_10 ((uint8_t)0x0A) /* AOP1_OUT, AOP3_OUT, TIM2, TIM3, TIM4, TIM8, TIM17 */
/**
* @brief AF 11 selection
*/
#define GPIO_AF_11 ((uint8_t)0x0B) /* TIM1, TIM8 */
/**
* @brief AF 12 selection
*/
#define GPIO_AF_12 ((uint8_t)0x0C) /* TIM1, HRTIM1 */
/**
* @brief AF 13 selection
*/
#define GPIO_AF_13 ((uint8_t)0x0D) /* HRTIM1, AOP2_OUT */
/**
* @brief AF 14 selection
*/
#define GPIO_AF_14 ((uint8_t)0x0E) /* USBDM, USBDP */
/**
* @brief AF 15 selection
*/
#define GPIO_AF_15 ((uint8_t)0x0F) /* OUT */
#define IS_GPIO_AF(AF) (((AF) == GPIO_AF_0)||((AF) == GPIO_AF_1)||\
((AF) == GPIO_AF_2)||((AF) == GPIO_AF_3)||\
((AF) == GPIO_AF_4)||((AF) == GPIO_AF_5)||\
((AF) == GPIO_AF_6)||((AF) == GPIO_AF_7)||\
((AF) == GPIO_AF_8)||((AF) == GPIO_AF_9)||\
((AF) == GPIO_AF_10)||((AF) == GPIO_AF_11)||\
((AF) == GPIO_AF_12)||((AF) == GPIO_AF_13)||\
((AF) == GPIO_AF_14)||((AF) == GPIO_AF_15))
/**
* @}
*/
/** @defgroup GPIO_Speed_Legacy
* @{
*/
#define GPIO_Speed_10MHz GPIO_Speed_Level_1 /*!< Fast Speed:10MHz */
#define GPIO_Speed_2MHz GPIO_Speed_Level_2 /*!< Medium Speed:2MHz */
#define GPIO_Speed_50MHz GPIO_Speed_Level_3 /*!< High Speed:50MHz */
/**
* @}
*/
/**
* @}
*/
/* Exported macro ------------------------------------------------------------*/
/* Exported functions ------------------------------------------------------- */
/* Function used to set the GPIO configuration to the default reset state *****/
void GPIO_DeInit(GPIO_TypeDef* GPIOx);
/* Initialization and Configuration functions *********************************/
void GPIO_Init(GPIO_TypeDef* GPIOx, GPIO_InitTypeDef* GPIO_InitStruct);
void GPIO_StructInit(GPIO_InitTypeDef* GPIO_InitStruct);
void GPIO_PinLockConfig(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin);
/* GPIO Read and Write functions **********************************************/
uint8_t GPIO_ReadInputDataBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin);
uint16_t GPIO_ReadInputData(GPIO_TypeDef* GPIOx);
uint8_t GPIO_ReadOutputDataBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin);
uint16_t GPIO_ReadOutputData(GPIO_TypeDef* GPIOx);
void GPIO_SetBits(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin);
void GPIO_ResetBits(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin);
void GPIO_WriteBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin, BitAction BitVal);
void GPIO_Write(GPIO_TypeDef* GPIOx, uint16_t PortVal);
/* GPIO Alternate functions configuration functions ***************************/
void GPIO_PinAFConfig(GPIO_TypeDef* GPIOx, uint16_t GPIO_PinSource, uint8_t GPIO_AF);
#ifdef __cplusplus
}
#endif
#endif /* __STM32F30x_GPIO_H */
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,699 @@
/**
******************************************************************************
* @file stm32f30x_rcc.h
* @author MCD Application Team
* @version V1.1.1
* @date 04-April-2014
* @brief This file contains all the functions prototypes for the RCC
* firmware library.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2014 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
* You may not use this file except in compliance with the License.
* You may obtain a copy of the License at:
*
* http://www.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32F30x_RCC_H
#define __STM32F30x_RCC_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32f30x.h"
/** @addtogroup STM32F30x_StdPeriph_Driver
* @{
*/
/** @addtogroup RCC
* @{
*/
/* Exported types ------------------------------------------------------------*/
typedef struct
{
uint32_t SYSCLK_Frequency;
uint32_t HCLK_Frequency;
uint32_t PCLK1_Frequency;
uint32_t PCLK2_Frequency;
uint32_t ADC12CLK_Frequency;
uint32_t ADC34CLK_Frequency;
uint32_t I2C1CLK_Frequency;
uint32_t I2C2CLK_Frequency;
uint32_t I2C3CLK_Frequency;
uint32_t TIM1CLK_Frequency;
uint32_t HRTIM1CLK_Frequency;
uint32_t TIM8CLK_Frequency;
uint32_t USART1CLK_Frequency;
uint32_t USART2CLK_Frequency;
uint32_t USART3CLK_Frequency;
uint32_t UART4CLK_Frequency;
uint32_t UART5CLK_Frequency;
uint32_t TIM15CLK_Frequency;
uint32_t TIM16CLK_Frequency;
uint32_t TIM17CLK_Frequency;
}RCC_ClocksTypeDef;
/* Exported constants --------------------------------------------------------*/
/** @defgroup RCC_Exported_Constants
* @{
*/
/** @defgroup RCC_HSE_configuration
* @{
*/
#define RCC_HSE_OFF ((uint8_t)0x00)
#define RCC_HSE_ON ((uint8_t)0x01)
#define RCC_HSE_Bypass ((uint8_t)0x05)
#define IS_RCC_HSE(HSE) (((HSE) == RCC_HSE_OFF) || ((HSE) == RCC_HSE_ON) || \
((HSE) == RCC_HSE_Bypass))
/**
* @}
*/
/** @defgroup RCC_PLL_Clock_Source
* @{
*/
#define RCC_PLLSource_HSI_Div2 RCC_CFGR_PLLSRC_HSI_Div2
#define RCC_PLLSource_PREDIV1 RCC_CFGR_PLLSRC_PREDIV1
#define IS_RCC_PLL_SOURCE(SOURCE) (((SOURCE) == RCC_PLLSource_HSI_Div2) || \
((SOURCE) == RCC_PLLSource_PREDIV1))
/**
* @}
*/
/** @defgroup RCC_PLL_Multiplication_Factor
* @{
*/
#define RCC_PLLMul_2 RCC_CFGR_PLLMULL2
#define RCC_PLLMul_3 RCC_CFGR_PLLMULL3
#define RCC_PLLMul_4 RCC_CFGR_PLLMULL4
#define RCC_PLLMul_5 RCC_CFGR_PLLMULL5
#define RCC_PLLMul_6 RCC_CFGR_PLLMULL6
#define RCC_PLLMul_7 RCC_CFGR_PLLMULL7
#define RCC_PLLMul_8 RCC_CFGR_PLLMULL8
#define RCC_PLLMul_9 RCC_CFGR_PLLMULL9
#define RCC_PLLMul_10 RCC_CFGR_PLLMULL10
#define RCC_PLLMul_11 RCC_CFGR_PLLMULL11
#define RCC_PLLMul_12 RCC_CFGR_PLLMULL12
#define RCC_PLLMul_13 RCC_CFGR_PLLMULL13
#define RCC_PLLMul_14 RCC_CFGR_PLLMULL14
#define RCC_PLLMul_15 RCC_CFGR_PLLMULL15
#define RCC_PLLMul_16 RCC_CFGR_PLLMULL16
#define IS_RCC_PLL_MUL(MUL) (((MUL) == RCC_PLLMul_2) || ((MUL) == RCC_PLLMul_3) || \
((MUL) == RCC_PLLMul_4) || ((MUL) == RCC_PLLMul_5) || \
((MUL) == RCC_PLLMul_6) || ((MUL) == RCC_PLLMul_7) || \
((MUL) == RCC_PLLMul_8) || ((MUL) == RCC_PLLMul_9) || \
((MUL) == RCC_PLLMul_10) || ((MUL) == RCC_PLLMul_11) || \
((MUL) == RCC_PLLMul_12) || ((MUL) == RCC_PLLMul_13) || \
((MUL) == RCC_PLLMul_14) || ((MUL) == RCC_PLLMul_15) || \
((MUL) == RCC_PLLMul_16))
/**
* @}
*/
/** @defgroup RCC_PREDIV1_division_factor
* @{
*/
#define RCC_PREDIV1_Div1 RCC_CFGR2_PREDIV1_DIV1
#define RCC_PREDIV1_Div2 RCC_CFGR2_PREDIV1_DIV2
#define RCC_PREDIV1_Div3 RCC_CFGR2_PREDIV1_DIV3
#define RCC_PREDIV1_Div4 RCC_CFGR2_PREDIV1_DIV4
#define RCC_PREDIV1_Div5 RCC_CFGR2_PREDIV1_DIV5
#define RCC_PREDIV1_Div6 RCC_CFGR2_PREDIV1_DIV6
#define RCC_PREDIV1_Div7 RCC_CFGR2_PREDIV1_DIV7
#define RCC_PREDIV1_Div8 RCC_CFGR2_PREDIV1_DIV8
#define RCC_PREDIV1_Div9 RCC_CFGR2_PREDIV1_DIV9
#define RCC_PREDIV1_Div10 RCC_CFGR2_PREDIV1_DIV10
#define RCC_PREDIV1_Div11 RCC_CFGR2_PREDIV1_DIV11
#define RCC_PREDIV1_Div12 RCC_CFGR2_PREDIV1_DIV12
#define RCC_PREDIV1_Div13 RCC_CFGR2_PREDIV1_DIV13
#define RCC_PREDIV1_Div14 RCC_CFGR2_PREDIV1_DIV14
#define RCC_PREDIV1_Div15 RCC_CFGR2_PREDIV1_DIV15
#define RCC_PREDIV1_Div16 RCC_CFGR2_PREDIV1_DIV16
#define IS_RCC_PREDIV1(PREDIV1) (((PREDIV1) == RCC_PREDIV1_Div1) || ((PREDIV1) == RCC_PREDIV1_Div2) || \
((PREDIV1) == RCC_PREDIV1_Div3) || ((PREDIV1) == RCC_PREDIV1_Div4) || \
((PREDIV1) == RCC_PREDIV1_Div5) || ((PREDIV1) == RCC_PREDIV1_Div6) || \
((PREDIV1) == RCC_PREDIV1_Div7) || ((PREDIV1) == RCC_PREDIV1_Div8) || \
((PREDIV1) == RCC_PREDIV1_Div9) || ((PREDIV1) == RCC_PREDIV1_Div10) || \
((PREDIV1) == RCC_PREDIV1_Div11) || ((PREDIV1) == RCC_PREDIV1_Div12) || \
((PREDIV1) == RCC_PREDIV1_Div13) || ((PREDIV1) == RCC_PREDIV1_Div14) || \
((PREDIV1) == RCC_PREDIV1_Div15) || ((PREDIV1) == RCC_PREDIV1_Div16))
/**
* @}
*/
/** @defgroup RCC_System_Clock_Source
* @{
*/
#define RCC_SYSCLKSource_HSI RCC_CFGR_SW_HSI
#define RCC_SYSCLKSource_HSE RCC_CFGR_SW_HSE
#define RCC_SYSCLKSource_PLLCLK RCC_CFGR_SW_PLL
#define IS_RCC_SYSCLK_SOURCE(SOURCE) (((SOURCE) == RCC_SYSCLKSource_HSI) || \
((SOURCE) == RCC_SYSCLKSource_HSE) || \
((SOURCE) == RCC_SYSCLKSource_PLLCLK))
/**
* @}
*/
/** @defgroup RCC_AHB_Clock_Source
* @{
*/
#define RCC_SYSCLK_Div1 RCC_CFGR_HPRE_DIV1
#define RCC_SYSCLK_Div2 RCC_CFGR_HPRE_DIV2
#define RCC_SYSCLK_Div4 RCC_CFGR_HPRE_DIV4
#define RCC_SYSCLK_Div8 RCC_CFGR_HPRE_DIV8
#define RCC_SYSCLK_Div16 RCC_CFGR_HPRE_DIV16
#define RCC_SYSCLK_Div64 RCC_CFGR_HPRE_DIV64
#define RCC_SYSCLK_Div128 RCC_CFGR_HPRE_DIV128
#define RCC_SYSCLK_Div256 RCC_CFGR_HPRE_DIV256
#define RCC_SYSCLK_Div512 RCC_CFGR_HPRE_DIV512
#define IS_RCC_HCLK(HCLK) (((HCLK) == RCC_SYSCLK_Div1) || ((HCLK) == RCC_SYSCLK_Div2) || \
((HCLK) == RCC_SYSCLK_Div4) || ((HCLK) == RCC_SYSCLK_Div8) || \
((HCLK) == RCC_SYSCLK_Div16) || ((HCLK) == RCC_SYSCLK_Div64) || \
((HCLK) == RCC_SYSCLK_Div128) || ((HCLK) == RCC_SYSCLK_Div256) || \
((HCLK) == RCC_SYSCLK_Div512))
/**
* @}
*/
/** @defgroup RCC_APB1_APB2_clock_source
* @{
*/
#define RCC_HCLK_Div1 ((uint32_t)0x00000000)
#define RCC_HCLK_Div2 ((uint32_t)0x00000400)
#define RCC_HCLK_Div4 ((uint32_t)0x00000500)
#define RCC_HCLK_Div8 ((uint32_t)0x00000600)
#define RCC_HCLK_Div16 ((uint32_t)0x00000700)
#define IS_RCC_PCLK(PCLK) (((PCLK) == RCC_HCLK_Div1) || ((PCLK) == RCC_HCLK_Div2) || \
((PCLK) == RCC_HCLK_Div4) || ((PCLK) == RCC_HCLK_Div8) || \
((PCLK) == RCC_HCLK_Div16))
/**
* @}
*/
/** @defgroup RCC_ADC_clock_source
* @{
*/
/* ADC1 & ADC2 */
#define RCC_ADC12PLLCLK_OFF ((uint32_t)0x00000000)
#define RCC_ADC12PLLCLK_Div1 ((uint32_t)0x00000100)
#define RCC_ADC12PLLCLK_Div2 ((uint32_t)0x00000110)
#define RCC_ADC12PLLCLK_Div4 ((uint32_t)0x00000120)
#define RCC_ADC12PLLCLK_Div6 ((uint32_t)0x00000130)
#define RCC_ADC12PLLCLK_Div8 ((uint32_t)0x00000140)
#define RCC_ADC12PLLCLK_Div10 ((uint32_t)0x00000150)
#define RCC_ADC12PLLCLK_Div12 ((uint32_t)0x00000160)
#define RCC_ADC12PLLCLK_Div16 ((uint32_t)0x00000170)
#define RCC_ADC12PLLCLK_Div32 ((uint32_t)0x00000180)
#define RCC_ADC12PLLCLK_Div64 ((uint32_t)0x00000190)
#define RCC_ADC12PLLCLK_Div128 ((uint32_t)0x000001A0)
#define RCC_ADC12PLLCLK_Div256 ((uint32_t)0x000001B0)
/* ADC3 & ADC4 */
#define RCC_ADC34PLLCLK_OFF ((uint32_t)0x10000000)
#define RCC_ADC34PLLCLK_Div1 ((uint32_t)0x10002000)
#define RCC_ADC34PLLCLK_Div2 ((uint32_t)0x10002200)
#define RCC_ADC34PLLCLK_Div4 ((uint32_t)0x10002400)
#define RCC_ADC34PLLCLK_Div6 ((uint32_t)0x10002600)
#define RCC_ADC34PLLCLK_Div8 ((uint32_t)0x10002800)
#define RCC_ADC34PLLCLK_Div10 ((uint32_t)0x10002A00)
#define RCC_ADC34PLLCLK_Div12 ((uint32_t)0x10002C00)
#define RCC_ADC34PLLCLK_Div16 ((uint32_t)0x10002E00)
#define RCC_ADC34PLLCLK_Div32 ((uint32_t)0x10003000)
#define RCC_ADC34PLLCLK_Div64 ((uint32_t)0x10003200)
#define RCC_ADC34PLLCLK_Div128 ((uint32_t)0x10003400)
#define RCC_ADC34PLLCLK_Div256 ((uint32_t)0x10003600)
#define IS_RCC_ADCCLK(ADCCLK) (((ADCCLK) == RCC_ADC12PLLCLK_OFF) || ((ADCCLK) == RCC_ADC12PLLCLK_Div1) || \
((ADCCLK) == RCC_ADC12PLLCLK_Div2) || ((ADCCLK) == RCC_ADC12PLLCLK_Div4) || \
((ADCCLK) == RCC_ADC12PLLCLK_Div6) || ((ADCCLK) == RCC_ADC12PLLCLK_Div8) || \
((ADCCLK) == RCC_ADC12PLLCLK_Div10) || ((ADCCLK) == RCC_ADC12PLLCLK_Div12) || \
((ADCCLK) == RCC_ADC12PLLCLK_Div16) || ((ADCCLK) == RCC_ADC12PLLCLK_Div32) || \
((ADCCLK) == RCC_ADC12PLLCLK_Div64) || ((ADCCLK) == RCC_ADC12PLLCLK_Div128) || \
((ADCCLK) == RCC_ADC12PLLCLK_Div256) || ((ADCCLK) == RCC_ADC34PLLCLK_OFF) || \
((ADCCLK) == RCC_ADC34PLLCLK_Div1) || ((ADCCLK) == RCC_ADC34PLLCLK_Div2) || \
((ADCCLK) == RCC_ADC34PLLCLK_Div4) || ((ADCCLK) == RCC_ADC34PLLCLK_Div6) || \
((ADCCLK) == RCC_ADC34PLLCLK_Div8) || ((ADCCLK) == RCC_ADC34PLLCLK_Div10) || \
((ADCCLK) == RCC_ADC34PLLCLK_Div12) || ((ADCCLK) == RCC_ADC34PLLCLK_Div16) || \
((ADCCLK) == RCC_ADC34PLLCLK_Div32) || ((ADCCLK) == RCC_ADC34PLLCLK_Div64) || \
((ADCCLK) == RCC_ADC34PLLCLK_Div128) || ((ADCCLK) == RCC_ADC34PLLCLK_Div256))
/**
* @}
*/
/** @defgroup RCC_TIM_clock_source
* @{
*/
#define RCC_TIM1CLK_HCLK ((uint32_t)0x00000000)
#define RCC_TIM1CLK_PLLCLK RCC_CFGR3_TIM1SW
#define RCC_TIM8CLK_HCLK ((uint32_t)0x10000000)
#define RCC_TIM8CLK_PLLCLK ((uint32_t)0x10000200)
#define RCC_TIM15CLK_HCLK ((uint32_t)0x20000000)
#define RCC_TIM15CLK_PLLCLK ((uint32_t)0x20000400)
#define RCC_TIM16CLK_HCLK ((uint32_t)0x30000000)
#define RCC_TIM16CLK_PLLCLK ((uint32_t)0x30000800)
#define RCC_TIM17CLK_HCLK ((uint32_t)0x40000000)
#define RCC_TIM17CLK_PLLCLK ((uint32_t)0x40002000)
#define IS_RCC_TIMCLK(TIMCLK) (((TIMCLK) == RCC_TIM1CLK_HCLK) || ((TIMCLK) == RCC_TIM1CLK_PLLCLK) || \
((TIMCLK) == RCC_TIM8CLK_HCLK) || ((TIMCLK) == RCC_TIM8CLK_PLLCLK) || \
((TIMCLK) == RCC_TIM15CLK_HCLK) || ((TIMCLK) == RCC_TIM15CLK_PLLCLK) || \
((TIMCLK) == RCC_TIM16CLK_HCLK) || ((TIMCLK) == RCC_TIM16CLK_PLLCLK) || \
((TIMCLK) == RCC_TIM17CLK_HCLK) || ((TIMCLK) == RCC_TIM17CLK_PLLCLK))
/**
* @}
*/
/** @defgroup RCC_HRTIM_clock_source
* @{
*/
#define RCC_HRTIM1CLK_HCLK ((uint32_t)0x00000000)
#define RCC_HRTIM1CLK_PLLCLK RCC_CFGR3_HRTIM1SW
#define IS_RCC_HRTIMCLK(HRTIMCLK) (((HRTIMCLK) == RCC_HRTIM1CLK_HCLK) || ((HRTIMCLK) == RCC_HRTIM1CLK_PLLCLK))
/**
* @}
*/
/** @defgroup RCC_I2C_clock_source
* @{
*/
#define RCC_I2C1CLK_HSI ((uint32_t)0x00000000)
#define RCC_I2C1CLK_SYSCLK RCC_CFGR3_I2C1SW
#define RCC_I2C2CLK_HSI ((uint32_t)0x10000000)
#define RCC_I2C2CLK_SYSCLK ((uint32_t)0x10000020)
#define RCC_I2C3CLK_HSI ((uint32_t)0x20000000)
#define RCC_I2C3CLK_SYSCLK ((uint32_t)0x20000040)
#define IS_RCC_I2CCLK(I2CCLK) (((I2CCLK) == RCC_I2C1CLK_HSI) || ((I2CCLK) == RCC_I2C1CLK_SYSCLK) || \
((I2CCLK) == RCC_I2C2CLK_HSI) || ((I2CCLK) == RCC_I2C2CLK_SYSCLK) || \
((I2CCLK) == RCC_I2C3CLK_HSI) || ((I2CCLK) == RCC_I2C3CLK_SYSCLK))
/**
* @}
*/
/** @defgroup RCC_USART_clock_source
* @{
*/
#define RCC_USART1CLK_PCLK ((uint32_t)0x10000000)
#define RCC_USART1CLK_SYSCLK ((uint32_t)0x10000001)
#define RCC_USART1CLK_LSE ((uint32_t)0x10000002)
#define RCC_USART1CLK_HSI ((uint32_t)0x10000003)
#define RCC_USART2CLK_PCLK ((uint32_t)0x20000000)
#define RCC_USART2CLK_SYSCLK ((uint32_t)0x20010000)
#define RCC_USART2CLK_LSE ((uint32_t)0x20020000)
#define RCC_USART2CLK_HSI ((uint32_t)0x20030000)
#define RCC_USART3CLK_PCLK ((uint32_t)0x30000000)
#define RCC_USART3CLK_SYSCLK ((uint32_t)0x30040000)
#define RCC_USART3CLK_LSE ((uint32_t)0x30080000)
#define RCC_USART3CLK_HSI ((uint32_t)0x300C0000)
#define RCC_UART4CLK_PCLK ((uint32_t)0x40000000)
#define RCC_UART4CLK_SYSCLK ((uint32_t)0x40100000)
#define RCC_UART4CLK_LSE ((uint32_t)0x40200000)
#define RCC_UART4CLK_HSI ((uint32_t)0x40300000)
#define RCC_UART5CLK_PCLK ((uint32_t)0x50000000)
#define RCC_UART5CLK_SYSCLK ((uint32_t)0x50400000)
#define RCC_UART5CLK_LSE ((uint32_t)0x50800000)
#define RCC_UART5CLK_HSI ((uint32_t)0x50C00000)
#define IS_RCC_USARTCLK(USARTCLK) (((USARTCLK) == RCC_USART1CLK_PCLK) || ((USARTCLK) == RCC_USART1CLK_SYSCLK) || \
((USARTCLK) == RCC_USART1CLK_LSE) || ((USARTCLK) == RCC_USART1CLK_HSI) ||\
((USARTCLK) == RCC_USART2CLK_PCLK) || ((USARTCLK) == RCC_USART2CLK_SYSCLK) || \
((USARTCLK) == RCC_USART2CLK_LSE) || ((USARTCLK) == RCC_USART2CLK_HSI) || \
((USARTCLK) == RCC_USART3CLK_PCLK) || ((USARTCLK) == RCC_USART3CLK_SYSCLK) || \
((USARTCLK) == RCC_USART3CLK_LSE) || ((USARTCLK) == RCC_USART3CLK_HSI) || \
((USARTCLK) == RCC_UART4CLK_PCLK) || ((USARTCLK) == RCC_UART4CLK_SYSCLK) || \
((USARTCLK) == RCC_UART4CLK_LSE) || ((USARTCLK) == RCC_UART4CLK_HSI) || \
((USARTCLK) == RCC_UART5CLK_PCLK) || ((USARTCLK) == RCC_UART5CLK_SYSCLK) || \
((USARTCLK) == RCC_UART5CLK_LSE) || ((USARTCLK) == RCC_UART5CLK_HSI))
/**
* @}
*/
/** @defgroup RCC_Interrupt_Source
* @{
*/
#define RCC_IT_LSIRDY ((uint8_t)0x01)
#define RCC_IT_LSERDY ((uint8_t)0x02)
#define RCC_IT_HSIRDY ((uint8_t)0x04)
#define RCC_IT_HSERDY ((uint8_t)0x08)
#define RCC_IT_PLLRDY ((uint8_t)0x10)
#define RCC_IT_CSS ((uint8_t)0x80)
#define IS_RCC_IT(IT) ((((IT) & (uint8_t)0xC0) == 0x00) && ((IT) != 0x00))
#define IS_RCC_GET_IT(IT) (((IT) == RCC_IT_LSIRDY) || ((IT) == RCC_IT_LSERDY) || \
((IT) == RCC_IT_HSIRDY) || ((IT) == RCC_IT_HSERDY) || \
((IT) == RCC_IT_PLLRDY) || ((IT) == RCC_IT_CSS))
#define IS_RCC_CLEAR_IT(IT) ((((IT) & (uint8_t)0x40) == 0x00) && ((IT) != 0x00))
/**
* @}
*/
/** @defgroup RCC_LSE_configuration
* @{
*/
#define RCC_LSE_OFF ((uint32_t)0x00000000)
#define RCC_LSE_ON RCC_BDCR_LSEON
#define RCC_LSE_Bypass ((uint32_t)(RCC_BDCR_LSEON | RCC_BDCR_LSEBYP))
#define IS_RCC_LSE(LSE) (((LSE) == RCC_LSE_OFF) || ((LSE) == RCC_LSE_ON) || \
((LSE) == RCC_LSE_Bypass))
/**
* @}
*/
/** @defgroup RCC_RTC_Clock_Source
* @{
*/
#define RCC_RTCCLKSource_LSE RCC_BDCR_RTCSEL_LSE
#define RCC_RTCCLKSource_LSI RCC_BDCR_RTCSEL_LSI
#define RCC_RTCCLKSource_HSE_Div32 RCC_BDCR_RTCSEL_HSE
#define IS_RCC_RTCCLK_SOURCE(SOURCE) (((SOURCE) == RCC_RTCCLKSource_LSE) || \
((SOURCE) == RCC_RTCCLKSource_LSI) || \
((SOURCE) == RCC_RTCCLKSource_HSE_Div32))
/**
* @}
*/
/** @defgroup RCC_I2S_Clock_Source
* @{
*/
#define RCC_I2S2CLKSource_SYSCLK ((uint8_t)0x00)
#define RCC_I2S2CLKSource_Ext ((uint8_t)0x01)
#define IS_RCC_I2SCLK_SOURCE(SOURCE) (((SOURCE) == RCC_I2S2CLKSource_SYSCLK) || ((SOURCE) == RCC_I2S2CLKSource_Ext))
/** @defgroup RCC_LSE_Drive_Configuration
* @{
*/
#define RCC_LSEDrive_Low ((uint32_t)0x00000000)
#define RCC_LSEDrive_MediumLow RCC_BDCR_LSEDRV_0
#define RCC_LSEDrive_MediumHigh RCC_BDCR_LSEDRV_1
#define RCC_LSEDrive_High RCC_BDCR_LSEDRV
#define IS_RCC_LSE_DRIVE(DRIVE) (((DRIVE) == RCC_LSEDrive_Low) || ((DRIVE) == RCC_LSEDrive_MediumLow) || \
((DRIVE) == RCC_LSEDrive_MediumHigh) || ((DRIVE) == RCC_LSEDrive_High))
/**
* @}
*/
/** @defgroup RCC_AHB_Peripherals
* @{
*/
#define RCC_AHBPeriph_ADC34 RCC_AHBENR_ADC34EN
#define RCC_AHBPeriph_ADC12 RCC_AHBENR_ADC12EN
#define RCC_AHBPeriph_GPIOA RCC_AHBENR_GPIOAEN
#define RCC_AHBPeriph_GPIOB RCC_AHBENR_GPIOBEN
#define RCC_AHBPeriph_GPIOC RCC_AHBENR_GPIOCEN
#define RCC_AHBPeriph_GPIOD RCC_AHBENR_GPIODEN
#define RCC_AHBPeriph_GPIOE RCC_AHBENR_GPIOEEN
#define RCC_AHBPeriph_GPIOF RCC_AHBENR_GPIOFEN
#define RCC_AHBPeriph_TS RCC_AHBENR_TSEN
#define RCC_AHBPeriph_CRC RCC_AHBENR_CRCEN
#define RCC_AHBPeriph_FLITF RCC_AHBENR_FLITFEN
#define RCC_AHBPeriph_SRAM RCC_AHBENR_SRAMEN
#define RCC_AHBPeriph_DMA2 RCC_AHBENR_DMA2EN
#define RCC_AHBPeriph_DMA1 RCC_AHBENR_DMA1EN
#define IS_RCC_AHB_PERIPH(PERIPH) ((((PERIPH) & 0xCE81FFA8) == 0x00) && ((PERIPH) != 0x00))
#define IS_RCC_AHB_RST_PERIPH(PERIPH) ((((PERIPH) & 0xCE81FFFF) == 0x00) && ((PERIPH) != 0x00))
/**
* @}
*/
/** @defgroup RCC_APB2_Peripherals
* @{
*/
#define RCC_APB2Periph_SYSCFG RCC_APB2ENR_SYSCFGEN
#define RCC_APB2Periph_TIM1 RCC_APB2ENR_TIM1EN
#define RCC_APB2Periph_SPI1 RCC_APB2ENR_SPI1EN
#define RCC_APB2Periph_TIM8 RCC_APB2ENR_TIM8EN
#define RCC_APB2Periph_USART1 RCC_APB2ENR_USART1EN
#define RCC_APB2Periph_TIM15 RCC_APB2ENR_TIM15EN
#define RCC_APB2Periph_TIM16 RCC_APB2ENR_TIM16EN
#define RCC_APB2Periph_TIM17 RCC_APB2ENR_TIM17EN
#define RCC_APB2Periph_HRTIM1 RCC_APB2ENR_HRTIM1
#define IS_RCC_APB2_PERIPH(PERIPH) ((((PERIPH) & 0xDFF887FE) == 0x00) && ((PERIPH) != 0x00))
/**
* @}
*/
/** @defgroup RCC_APB1_Peripherals
* @{
*/
#define RCC_APB1Periph_TIM2 RCC_APB1ENR_TIM2EN
#define RCC_APB1Periph_TIM3 RCC_APB1ENR_TIM3EN
#define RCC_APB1Periph_TIM4 RCC_APB1ENR_TIM4EN
#define RCC_APB1Periph_TIM6 RCC_APB1ENR_TIM6EN
#define RCC_APB1Periph_TIM7 RCC_APB1ENR_TIM7EN
#define RCC_APB1Periph_WWDG RCC_APB1ENR_WWDGEN
#define RCC_APB1Periph_SPI2 RCC_APB1ENR_SPI2EN
#define RCC_APB1Periph_SPI3 RCC_APB1ENR_SPI3EN
#define RCC_APB1Periph_USART2 RCC_APB1ENR_USART2EN
#define RCC_APB1Periph_USART3 RCC_APB1ENR_USART3EN
#define RCC_APB1Periph_UART4 RCC_APB1ENR_UART4EN
#define RCC_APB1Periph_UART5 RCC_APB1ENR_UART5EN
#define RCC_APB1Periph_I2C1 RCC_APB1ENR_I2C1EN
#define RCC_APB1Periph_I2C2 RCC_APB1ENR_I2C2EN
#define RCC_APB1Periph_USB RCC_APB1ENR_USBEN
#define RCC_APB1Periph_CAN1 RCC_APB1ENR_CAN1EN
#define RCC_APB1Periph_PWR RCC_APB1ENR_PWREN
#define RCC_APB1Periph_DAC1 RCC_APB1ENR_DAC1EN
#define RCC_APB1Periph_I2C3 RCC_APB1ENR_I2C3EN
#define RCC_APB1Periph_DAC2 RCC_APB1ENR_DAC2EN
#define RCC_APB1Periph_DAC RCC_APB1Periph_DAC1
#define IS_RCC_APB1_PERIPH(PERIPH) ((((PERIPH) & 0x890137C8) == 0x00) && ((PERIPH) != 0x00))
/**
* @}
*/
/** @defgroup RCC_MCO_Clock_Source
* @{
*/
#define RCC_MCOSource_NoClock ((uint8_t)0x00)
#define RCC_MCOSource_LSI ((uint8_t)0x02)
#define RCC_MCOSource_LSE ((uint8_t)0x03)
#define RCC_MCOSource_SYSCLK ((uint8_t)0x04)
#define RCC_MCOSource_HSI ((uint8_t)0x05)
#define RCC_MCOSource_HSE ((uint8_t)0x06)
#define RCC_MCOSource_PLLCLK_Div2 ((uint8_t)0x07)
#define IS_RCC_MCO_SOURCE(SOURCE) (((SOURCE) == RCC_MCOSource_NoClock) ||((SOURCE) == RCC_MCOSource_SYSCLK) ||\
((SOURCE) == RCC_MCOSource_HSI) || ((SOURCE) == RCC_MCOSource_HSE) || \
((SOURCE) == RCC_MCOSource_LSI) || ((SOURCE) == RCC_MCOSource_LSE) || \
((SOURCE) == RCC_MCOSource_PLLCLK_Div2))
/**
* @}
*/
/** @defgroup RCC_MCOPrescaler
* @{
*/
#define RCC_MCOPrescaler_1 RCC_CFGR_MCO_PRE_1
#define RCC_MCOPrescaler_2 RCC_CFGR_MCO_PRE_2
#define RCC_MCOPrescaler_4 RCC_CFGR_MCO_PRE_4
#define RCC_MCOPrescaler_8 RCC_CFGR_MCO_PRE_8
#define RCC_MCOPrescaler_16 RCC_CFGR_MCO_PRE_16
#define RCC_MCOPrescaler_32 RCC_CFGR_MCO_PRE_32
#define RCC_MCOPrescaler_64 RCC_CFGR_MCO_PRE_64
#define RCC_MCOPrescaler_128 RCC_CFGR_MCO_PRE_128
#define IS_RCC_MCO_PRESCALER(PRESCALER) (((PRESCALER) == RCC_MCOPrescaler_1) || \
((PRESCALER) == RCC_MCOPrescaler_2) || \
((PRESCALER) == RCC_MCOPrescaler_4) || \
((PRESCALER) == RCC_MCOPrescaler_8) || \
((PRESCALER) == RCC_MCOPrescaler_16) || \
((PRESCALER) == RCC_MCOPrescaler_32) || \
((PRESCALER) == RCC_MCOPrescaler_64) || \
((PRESCALER) == RCC_MCOPrescaler_128))
/**
* @}
*/
/** @defgroup RCC_USB_Device_clock_source
* @{
*/
#define RCC_USBCLKSource_PLLCLK_1Div5 ((uint8_t)0x00)
#define RCC_USBCLKSource_PLLCLK_Div1 ((uint8_t)0x01)
#define IS_RCC_USBCLK_SOURCE(SOURCE) (((SOURCE) == RCC_USBCLKSource_PLLCLK_1Div5) || \
((SOURCE) == RCC_USBCLKSource_PLLCLK_Div1))
/**
* @}
*/
/** @defgroup RCC_Flag
* @{
*/
#define RCC_FLAG_HSIRDY ((uint8_t)0x01)
#define RCC_FLAG_HSERDY ((uint8_t)0x11)
#define RCC_FLAG_PLLRDY ((uint8_t)0x19)
#define RCC_FLAG_MCOF ((uint8_t)0x9C)
#define RCC_FLAG_LSERDY ((uint8_t)0x21)
#define RCC_FLAG_LSIRDY ((uint8_t)0x41)
#define RCC_FLAG_OBLRST ((uint8_t)0x59)
#define RCC_FLAG_PINRST ((uint8_t)0x5A)
#define RCC_FLAG_PORRST ((uint8_t)0x5B)
#define RCC_FLAG_SFTRST ((uint8_t)0x5C)
#define RCC_FLAG_IWDGRST ((uint8_t)0x5D)
#define RCC_FLAG_WWDGRST ((uint8_t)0x5E)
#define RCC_FLAG_LPWRRST ((uint8_t)0x5F)
#define IS_RCC_FLAG(FLAG) (((FLAG) == RCC_FLAG_HSIRDY) || ((FLAG) == RCC_FLAG_HSERDY) || \
((FLAG) == RCC_FLAG_PLLRDY) || ((FLAG) == RCC_FLAG_LSERDY) || \
((FLAG) == RCC_FLAG_LSIRDY) || ((FLAG) == RCC_FLAG_OBLRST) || \
((FLAG) == RCC_FLAG_PINRST) || ((FLAG) == RCC_FLAG_PORRST) || \
((FLAG) == RCC_FLAG_SFTRST) || ((FLAG) == RCC_FLAG_IWDGRST)|| \
((FLAG) == RCC_FLAG_WWDGRST)|| ((FLAG) == RCC_FLAG_LPWRRST)|| \
((FLAG) == RCC_FLAG_MCOF))
#define IS_RCC_HSI_CALIBRATION_VALUE(VALUE) ((VALUE) <= 0x1F)
/**
* @}
*/
/**
* @}
*/
/* Exported macro ------------------------------------------------------------*/
/* Exported functions ------------------------------------------------------- */
/* Function used to set the RCC clock configuration to the default reset state */
void RCC_DeInit(void);
/* Internal/external clocks, PLL, CSS and MCO configuration functions *********/
void RCC_HSEConfig(uint8_t RCC_HSE);
ErrorStatus RCC_WaitForHSEStartUp(void);
void RCC_AdjustHSICalibrationValue(uint8_t HSICalibrationValue);
void RCC_HSICmd(FunctionalState NewState);
void RCC_LSEConfig(uint32_t RCC_LSE);
void RCC_LSEDriveConfig(uint32_t RCC_LSEDrive);
void RCC_LSICmd(FunctionalState NewState);
void RCC_PLLConfig(uint32_t RCC_PLLSource, uint32_t RCC_PLLMul);
void RCC_PLLCmd(FunctionalState NewState);
void RCC_PREDIV1Config(uint32_t RCC_PREDIV1_Div);
void RCC_ClockSecuritySystemCmd(FunctionalState NewState);
#ifdef STM32F303xC
void RCC_MCOConfig(uint8_t RCC_MCOSource);
#else
void RCC_MCOConfig(uint8_t RCC_MCOSource,uint32_t RCC_MCOPrescaler);
#endif /* STM32F303xC */
/* System, AHB and APB busses clocks configuration functions ******************/
void RCC_SYSCLKConfig(uint32_t RCC_SYSCLKSource);
uint8_t RCC_GetSYSCLKSource(void);
void RCC_HCLKConfig(uint32_t RCC_SYSCLK);
void RCC_PCLK1Config(uint32_t RCC_HCLK);
void RCC_PCLK2Config(uint32_t RCC_HCLK);
void RCC_GetClocksFreq(RCC_ClocksTypeDef* RCC_Clocks);
/* Peripheral clocks configuration functions **********************************/
void RCC_ADCCLKConfig(uint32_t RCC_PLLCLK);
void RCC_I2CCLKConfig(uint32_t RCC_I2CCLK);
void RCC_TIMCLKConfig(uint32_t RCC_TIMCLK);
void RCC_HRTIM1CLKConfig(uint32_t RCC_HRTIMCLK);
void RCC_I2SCLKConfig(uint32_t RCC_I2SCLKSource);
void RCC_USARTCLKConfig(uint32_t RCC_USARTCLK);
void RCC_USBCLKConfig(uint32_t RCC_USBCLKSource);
void RCC_RTCCLKConfig(uint32_t RCC_RTCCLKSource);
void RCC_RTCCLKCmd(FunctionalState NewState);
void RCC_BackupResetCmd(FunctionalState NewState);
void RCC_AHBPeriphClockCmd(uint32_t RCC_AHBPeriph, FunctionalState NewState);
void RCC_APB2PeriphClockCmd(uint32_t RCC_APB2Periph, FunctionalState NewState);
void RCC_APB1PeriphClockCmd(uint32_t RCC_APB1Periph, FunctionalState NewState);
void RCC_AHBPeriphResetCmd(uint32_t RCC_AHBPeriph, FunctionalState NewState);
void RCC_APB2PeriphResetCmd(uint32_t RCC_APB2Periph, FunctionalState NewState);
void RCC_APB1PeriphResetCmd(uint32_t RCC_APB1Periph, FunctionalState NewState);
/* Interrupts and flags management functions **********************************/
void RCC_ITConfig(uint8_t RCC_IT, FunctionalState NewState);
FlagStatus RCC_GetFlagStatus(uint8_t RCC_FLAG);
void RCC_ClearFlag(void);
ITStatus RCC_GetITStatus(uint8_t RCC_IT);
void RCC_ClearITPendingBit(uint8_t RCC_IT);
#ifdef __cplusplus
}
#endif
#endif /* __STM32F30x_RCC_H */
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -1,5 +1,6 @@
#pragma once #pragma once
#ifdef STM32F10X_MD
typedef enum typedef enum
{ {
Mode_AIN = 0x0, Mode_AIN = 0x0,
@ -11,6 +12,45 @@ typedef enum
Mode_AF_OD = 0x1C, Mode_AF_OD = 0x1C,
Mode_AF_PP = 0x18 Mode_AF_PP = 0x18
} GPIO_Mode; } GPIO_Mode;
#endif
#ifdef STM32F303xC
/*
typedef enum
{
GPIO_Mode_IN = 0x00, // GPIO Input Mode
GPIO_Mode_OUT = 0x01, // GPIO Output Mode
GPIO_Mode_AF = 0x02, // GPIO Alternate function Mode
GPIO_Mode_AN = 0x03 // GPIO Analog In/Out Mode
}GPIOMode_TypeDef;
typedef enum
{
GPIO_OType_PP = 0x00,
GPIO_OType_OD = 0x01
}GPIOOType_TypeDef;
typedef enum
{
GPIO_PuPd_NOPULL = 0x00,
GPIO_PuPd_UP = 0x01,
GPIO_PuPd_DOWN = 0x02
}GPIOPuPd_TypeDef;
*/
typedef enum
{
Mode_AIN = (GPIO_PuPd_NOPULL << 2) | GPIO_Mode_AN,
Mode_IN_FLOATING = (GPIO_PuPd_NOPULL << 2) | GPIO_Mode_IN,
Mode_IPD = (GPIO_PuPd_DOWN << 2) | GPIO_Mode_IN,
Mode_IPU = (GPIO_PuPd_UP << 2) | GPIO_Mode_IN,
Mode_Out_OD = (GPIO_OType_OD << 4) | GPIO_Mode_OUT,
Mode_Out_PP = (GPIO_OType_PP << 4) | GPIO_Mode_OUT,
Mode_AF_OD = (GPIO_OType_OD << 4) | GPIO_Mode_AF,
Mode_AF_PP = (GPIO_OType_PP << 4) | GPIO_Mode_AF
} GPIO_Mode;
#endif
typedef enum typedef enum
{ {

View File

@ -6,9 +6,66 @@
#include "gpio_common.h" #include "gpio_common.h"
#define MODE_OFFSET 0
#define PUPD_OFFSET 2
#define OUTPUT_OFFSET 4
#define MODE_MASK ((1|2) << MODE_OFFSET)
#define PUPD_MASK ((1|2) << PUPD_OFFSET)
#define OUTPUT_MASK ((1|2) << OUTPUT_OFFSET)
/*
typedef enum
{
Mode_AIN = (GPIO_PuPd_NOPULL << 2) | GPIO_Mode_AN,
Mode_IN_FLOATING = (GPIO_PuPd_NOPULL << 2) | GPIO_Mode_IN,
Mode_IPD = (GPIO_PuPd_DOWN << 2) | GPIO_Mode_IN,
Mode_IPU = (GPIO_PuPd_UP << 2) | GPIO_Mode_IN,
Mode_Out_OD = (GPIO_OType_OD << 4) | GPIO_Mode_OUT,
Mode_Out_PP = (GPIO_OType_PP << 4) | GPIO_Mode_OUT,
Mode_AF_OD = (GPIO_OType_OD << 4) | GPIO_Mode_AF,
Mode_AF_PP = (GPIO_OType_PP << 4) | GPIO_Mode_AF
} GPIO_Mode;
*/
//#define GPIO_Speed_10MHz GPIO_Speed_Level_1 Fast Speed:10MHz
//#define GPIO_Speed_2MHz GPIO_Speed_Level_2 Medium Speed:2MHz
//#define GPIO_Speed_50MHz GPIO_Speed_Level_3 High Speed:50MHz
void gpioInit(GPIO_TypeDef *gpio, gpio_config_t *config) void gpioInit(GPIO_TypeDef *gpio, gpio_config_t *config)
{ {
// FIXME implement // FIXME implement
GPIO_InitTypeDef GPIO_InitStructure;
uint32_t pinIndex;
for (pinIndex = 0; pinIndex < 16; pinIndex++) {
// are we doing this pin?
uint32_t pinMask = (0x1 << pinIndex);
if (config->pin & pinMask) {
GPIO_InitStructure.GPIO_Pin = pinMask;
GPIO_InitStructure.GPIO_Mode = (config->mode >> MODE_OFFSET) & MODE_MASK;
GPIOSpeed_TypeDef speed = GPIO_Speed_10MHz;
switch (config->speed) {
case Speed_10MHz:
speed = GPIO_Speed_Level_1;
break;
case Speed_2MHz:
speed = GPIO_Speed_Level_2;
break;
case Speed_50MHz:
speed = GPIO_Speed_Level_3;
break;
}
GPIO_InitStructure.GPIO_Speed = speed;
GPIO_InitStructure.GPIO_OType = (config->mode >> OUTPUT_OFFSET) & OUTPUT_MASK;
GPIO_InitStructure.GPIO_PuPd = (config->mode >> PUPD_OFFSET) & PUPD_MASK;
GPIO_Init(gpio, &GPIO_InitStructure);
}
}
} }
void gpioExtiLineConfig(uint8_t portsrc, uint8_t pinsrc) void gpioExtiLineConfig(uint8_t portsrc, uint8_t pinsrc)

View File

@ -25,7 +25,6 @@ uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode)
uartPort_t *s; uartPort_t *s;
static volatile uint8_t rx1Buffer[UART1_RX_BUFFER_SIZE]; static volatile uint8_t rx1Buffer[UART1_RX_BUFFER_SIZE];
static volatile uint8_t tx1Buffer[UART1_TX_BUFFER_SIZE]; static volatile uint8_t tx1Buffer[UART1_TX_BUFFER_SIZE];
gpio_config_t gpio;
NVIC_InitTypeDef NVIC_InitStructure; NVIC_InitTypeDef NVIC_InitStructure;
s = &uartPort1; s = &uartPort1;
@ -42,8 +41,34 @@ uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode)
s->txDMAChannel = DMA1_Channel4; s->txDMAChannel = DMA1_Channel4;
RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1, ENABLE); RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1, ENABLE);
// USART1_TX PA9 // USART1_TX PA9
// USART1_RX PA10 // USART1_RX PA10
#ifdef STM32F303xC
#define UART1_TX_PIN GPIO_Pin_9
#define UART1_RX_PIN GPIO_Pin_10
#define UART1_GPIO GPIOA
#define UART1_TX_PINSOURCE GPIO_PinSource9
#define UART1_RX_PINSOURCE GPIO_PinSource10
GPIO_InitTypeDef GPIO_InitStructure;
GPIO_InitStructure.GPIO_Pin = UART1_TX_PIN | UART1_RX_PIN;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP;
GPIO_PinAFConfig(UART1_GPIO, UART1_TX_PINSOURCE, GPIO_AF_7);
GPIO_PinAFConfig(UART1_GPIO, UART1_RX_PINSOURCE, GPIO_AF_7);
GPIO_Init(UART1_GPIO, &GPIO_InitStructure);
#endif
#ifdef STM32F10X_MD
gpio_config_t gpio;
gpio.speed = Speed_2MHz; gpio.speed = Speed_2MHz;
gpio.pin = Pin_9; gpio.pin = Pin_9;
gpio.mode = Mode_AF_PP; gpio.mode = Mode_AF_PP;
@ -53,6 +78,7 @@ uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode)
gpio.mode = Mode_IPU; gpio.mode = Mode_IPU;
if (mode & MODE_RX) if (mode & MODE_RX)
gpioInit(GPIOA, &gpio); gpioInit(GPIOA, &gpio);
#endif
// DMA TX Interrupt // DMA TX Interrupt
NVIC_InitStructure.NVIC_IRQChannel = DMA1_Channel4_IRQn; NVIC_InitStructure.NVIC_IRQChannel = DMA1_Channel4_IRQn;
@ -146,7 +172,6 @@ serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback,
if (mode & MODE_TX) if (mode & MODE_TX)
USART_InitStructure.USART_Mode |= USART_Mode_Tx; USART_InitStructure.USART_Mode |= USART_Mode_Tx;
USART_Init(USARTx, &USART_InitStructure); USART_Init(USARTx, &USART_InitStructure);
USART_Cmd(USARTx, ENABLE);
DMA_StructInit(&DMA_InitStructure); DMA_StructInit(&DMA_InitStructure);
DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&USARTx->RDR; DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&USARTx->RDR;
@ -200,6 +225,8 @@ serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback,
} }
} }
USART_Cmd(USARTx, ENABLE);
return (serialPort_t *)s; return (serialPort_t *)s;
} }

View File

@ -110,9 +110,15 @@ void systemInit(bool overclock)
RCC_ClearFlag(); RCC_ClearFlag();
// Make all GPIO in by default to save power and reduce noise // Make all GPIO in by default to save power and reduce noise
gpio.pin = Pin_All;
gpio.mode = Mode_AIN; gpio.mode = Mode_AIN;
gpio.pin = Pin_All;
#ifdef STM32F3DISCOVERY
gpio.pin = Pin_All & ~(Pin_13|Pin_14);
gpioInit(GPIOA, &gpio); gpioInit(GPIOA, &gpio);
gpio.pin = Pin_All;
#else
gpioInit(GPIOA, &gpio);
#endif
gpioInit(GPIOB, &gpio); gpioInit(GPIOB, &gpio);
gpioInit(GPIOC, &gpio); gpioInit(GPIOC, &gpio);

View File

@ -4,6 +4,8 @@
#ifdef STM32F3DISCOVERY #ifdef STM32F3DISCOVERY
#include "stm32f30x_conf.h" #include "stm32f30x_conf.h"
#include "stm32f30x_rcc.h"
#include "stm32f30x_gpio.h"
#include "core_cm4.h" #include "core_cm4.h"
// FIXME use correct ID // FIXME use correct ID