mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-18 22:05:17 +03:00
Fix unused param, add PERIPH_DRIVER flag for F4, tidied up F1 and F3 in prep.
This commit is contained in:
parent
2dca6a5bbc
commit
e6780bd4d8
139 changed files with 13074 additions and 10 deletions
File diff suppressed because it is too large
Load diff
File diff suppressed because it is too large
Load diff
|
@ -0,0 +1,504 @@
|
|||
/**
|
||||
******************************************************************************
|
||||
* @file stm32f30x_comp.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 7 analog comparators (COMP1, COMP2...COMP7) peripheral:
|
||||
* + Comparators configuration
|
||||
* + Window mode control
|
||||
*
|
||||
@verbatim
|
||||
|
||||
==============================================================================
|
||||
##### COMP Peripheral features #####
|
||||
==============================================================================
|
||||
[..]
|
||||
The device integrates 7 analog comparators COMP1, COMP2...COMP7:
|
||||
(#) The non inverting input and inverting input can be set to GPIO pins
|
||||
as shown in table1. COMP Inputs below.
|
||||
|
||||
(#) The COMP output is internally is available using COMP_GetOutputLevel()
|
||||
and can be set on GPIO pins. Refer to table 2. COMP Outputs below.
|
||||
|
||||
(#) The COMP output can be redirected to embedded timers (TIM1, TIM2, TIM3...)
|
||||
Refer to table 3. COMP Outputs redirection to embedded timers below.
|
||||
|
||||
(#) The comparators COMP1 and COMP2, COMP3 and COMP4, COMP5 and COMP6 can be combined in window
|
||||
mode and only COMP1, COMP3 and COMP5 non inverting input can be used as non-inverting input.
|
||||
|
||||
(#) The seven comparators have interrupt capability with wake-up
|
||||
from Sleep and Stop modes (through the EXTI controller):
|
||||
(++) COMP1 is internally connected to EXTI Line 21
|
||||
(++) COMP2 is internally connected to EXTI Line 22
|
||||
(++) COMP3 is internally connected to EXTI Line 29
|
||||
(++) COMP4 is internally connected to EXTI Line 30
|
||||
(++) COMP5 is internally connected to EXTI Line 31
|
||||
(++) COMP6 is internally connected to EXTI Line 32
|
||||
(++) COMP7 is internally connected to EXTI Line 33
|
||||
|
||||
[..] Table 1. COMP Inputs
|
||||
+------------------------------------------------------------------------------------------+
|
||||
| | | COMP1 | COMP2 | COMP3 | COMP4 | COMP5 | COMP6 | COMP7 |
|
||||
|-----------------|----------------|---------------|---------------------------------------|
|
||||
| | 1/4 VREFINT | OK | OK | OK | OK | OK | OK | OK |
|
||||
| | 1/2 VREFINT | OK | OK | OK | OK | OK | OK | OK |
|
||||
| | 3/4 VREFINT | OK | OK | OK | OK | OK | OK | OK |
|
||||
| Inverting Input | VREFINT | OK | OK | OK | OK | OK | OK | OK |
|
||||
| | DAC1 OUT1(PA4) | OK | OK | OK | OK | OK | OK | OK |
|
||||
| | DAC1 OUT2(PA5) | OK | OK | OK | OK | OK | OK | OK |
|
||||
| | IO1 | PA0 | PA2 | PD15 | PE8 | PD13 | PD10 | PC0 |
|
||||
| | IO2 | --- | --- | PB12 | PB2 | PB10 | PB15 | --- |
|
||||
| | DAC2 OUT1(PA6) | --- | OK | --- | OK | --- | OK | --- |
|
||||
|-----------------|----------------|-------|-------|-------|-------|-------|-------|-------|
|
||||
| Non Inverting | IO1 | PA1 | PA7 | PB14 | PB0 | PD12 | PD11 | PA0 |
|
||||
| Input | IO2 | --- | PA3 | PD14 | PE7 | PB13 | PB11 | PC1 |
|
||||
+------------------------------------------------------------------------------------------+
|
||||
|
||||
[..] Table 2. COMP Outputs
|
||||
+-------------------------------------------------------+
|
||||
| COMP1 | COMP2 | COMP3 | COMP4 | COMP5 | COMP6 | COMP7 |
|
||||
|-------|-------|-------|-------|-------|-------|-------|
|
||||
| PA0 | PA2 | PB1 | PC8 | PC7 | PA10 | PC2 |
|
||||
| PF4 | PA7 | --- | PA8 | PA9 | PC6 | --- |
|
||||
| PA6 | PA12 | --- | --- | --- | --- | --- |
|
||||
| PA11 | PB9 | --- | --- | --- | --- | --- |
|
||||
| PB8 | --- | --- | --- | --- | --- | --- |
|
||||
+-------------------------------------------------------+
|
||||
|
||||
[..] Table 3. COMP Outputs redirection to embedded timers
|
||||
+----------------------------------------------------------------------------------------------------------------------+
|
||||
| COMP1 | COMP2 | COMP3 | COMP4 | COMP5 | COMP6 | COMP7 |
|
||||
|----------------|----------------|----------------|----------------|----------------|----------------|----------------|
|
||||
| TIM1 BKIN | TIM1 BKIN | TIM1 BKIN | TIM1 BKIN | TIM1 BKIN | TIM1 BKIN | TIM1 BKIN |
|
||||
| | | | | | | |
|
||||
| TIM1 BKIN2 | TIM1 BKIN2 | TIM1 BKIN2 | TIM1 BKIN2 | TIM1 BKIN2 | TIM1 BKIN2 | TIM1 BKIN2 |
|
||||
| | | | | | | |
|
||||
| TIM8 BKIN | TIM8 BKIN | TIM8 BKIN | TIM8 BKIN | TIM8 BKIN | TIM8 BKIN | TIM8 BKIN |
|
||||
| | | | | | | |
|
||||
| TIM8 BKIN2 | TIM8 BKIN2 | TIM8 BKIN2 | TIM8 BKIN2 | TIM8 BKIN2 | TIM8 BKIN2 | TIM8 BKIN2 |
|
||||
| | | | | | | |
|
||||
| TIM1 BKIN2 | TIM1 BKIN2 | TIM1 BKIN2 | TIM1 BKIN2 | TIM1 BKIN2 | TIM1 BKIN2 | TIM1 BKIN2 |
|
||||
| + | + | + | + | + | + | + |
|
||||
| TIM8BKIN2 | TIM8BKIN2 | TIM8BKIN2 | TIM8BKIN2 | TIM8BKIN2 | TIM8BKIN2 | TIM8BKIN2 |
|
||||
| | | | | | | |
|
||||
| TIM1 OCREFCLR | TIM1 OCREFCLR | TIM1 OCREFCLR | TIM8 OCREFCLR | TIM8 OCREFCLR | TIM8 OCREFCLR | TIM1 OCREFCLR |
|
||||
| | | | | | | |
|
||||
| TIM1 IC1 | TIM1 IC1 | TIM2 OCREFCLR | TIM3 IC3 | TIM2 IC1 | TIM2 IC2 | TIM8 OCREFCLR |
|
||||
| | | | | | | |
|
||||
| TIM2 IC4 | TIM2 IC4 | TIM3 IC2 | TIM3 OCREFCLR | TIM3 OCREFCLR | TIM2 OCREFCLR | TIM2 IC3 |
|
||||
| | | | | | | |
|
||||
| TIM2 OCREFCLR | TIM2 OCREFCLR | TIM4 IC1 | TIM4 IC2 | TIM4 IC3 | TIM16 OCREFCLR| TIM1 IC2 |
|
||||
| | | | | | | |
|
||||
| TIM3 IC1 | TIM3 IC1 | TIM15 IC1 | TIM15 OCREFCLR| TIM16 BKIN | TIM16 IC1 | TIM17 OCREFCLR|
|
||||
| | | | | | | |
|
||||
| TIM3 OCREFCLR | TIM3 OCREFCLR | TIM15 BKIN | TIM15 IC2 | TIM17 IC1 | TIM4 IC4 | TIM17 BKIN |
|
||||
+----------------------------------------------------------------------------------------------------------------------+
|
||||
|
||||
[..] Table 4. COMP Outputs blanking sources
|
||||
+----------------------------------------------------------------------------------------------------------------------+
|
||||
| COMP1 | COMP2 | COMP3 | COMP4 | COMP5 | COMP6 | COMP7 |
|
||||
|----------------|----------------|----------------|----------------|----------------|----------------|----------------|
|
||||
| TIM1 OC5 | TIM1 OC5 | TIM1 OC5 | TIM3 OC4 | TIM3 OC3 | TIM2 OC4 | TIM1 OC5 |
|
||||
| | | | | | | |
|
||||
| TIM2 OC3 | TIM2 OC3 | -------- | TIM8 OC5 | TIM8 OC5 | TIM8 OC5 | TIM8 OC5 |
|
||||
| | | | | | | |
|
||||
| TIM3 OC3 | TIM3 OC3 | TIM2 OC4 | TIM15 OC1 | TIM8 BKIN | TIM15 OC2 | TIM15 OC2 |
|
||||
| | | | | | | |
|
||||
+----------------------------------------------------------------------------------------------------------------------+
|
||||
|
||||
|
||||
##### How to use this driver #####
|
||||
==============================================================================
|
||||
[..]
|
||||
This driver provides functions to configure and program the Comparators
|
||||
of all STM32F30x devices.
|
||||
|
||||
To use the comparator, perform the following steps:
|
||||
|
||||
(#) Enable the SYSCFG APB clock to get write access to comparator
|
||||
register using RCC_APB2PeriphClockCmd(RCC_APB2Periph_SYSCFG, ENABLE);
|
||||
|
||||
(#) Configure the comparator input in analog mode using GPIO_Init()
|
||||
|
||||
(#) Configure the comparator output in alternate function mode
|
||||
using GPIO_Init() and use GPIO_PinAFConfig() function to map the
|
||||
comparator output to the GPIO pin
|
||||
|
||||
(#) Configure the comparator using COMP_Init() function:
|
||||
(++) Select the inverting input
|
||||
(++) Select the non-inverting input
|
||||
(++) Select the output polarity
|
||||
(++) Select the output redirection
|
||||
(++) Select the hysteresis level
|
||||
(++) Select the power mode
|
||||
|
||||
(#) Enable the comparator using COMP_Cmd() function
|
||||
|
||||
(#) If required enable the COMP interrupt by configuring and enabling
|
||||
EXTI line in Interrupt mode and selecting the desired sensitivity
|
||||
level using EXTI_Init() function. After that enable the comparator
|
||||
interrupt vector using NVIC_Init() function.
|
||||
|
||||
@endverbatim
|
||||
*
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© 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_comp.h"
|
||||
|
||||
/** @addtogroup STM32F30x_StdPeriph_Driver
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @defgroup COMP
|
||||
* @brief COMP driver modules
|
||||
* @{
|
||||
*/
|
||||
|
||||
/* Private typedef -----------------------------------------------------------*/
|
||||
/* Private define ------------------------------------------------------------*/
|
||||
/* CSR register Mask */
|
||||
#define COMP_CSR_CLEAR_MASK ((uint32_t)0x00000003)
|
||||
|
||||
/* Private macro -------------------------------------------------------------*/
|
||||
/* Private variables ---------------------------------------------------------*/
|
||||
/* Private function prototypes -----------------------------------------------*/
|
||||
/* Private functions ---------------------------------------------------------*/
|
||||
|
||||
/** @defgroup COMP_Private_Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @defgroup COMP_Group1 Initialization and Configuration functions
|
||||
* @brief Initialization and Configuration functions
|
||||
*
|
||||
@verbatim
|
||||
===============================================================================
|
||||
##### Initialization and Configuration functions #####
|
||||
===============================================================================
|
||||
|
||||
@endverbatim
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief Deinitializes COMP peripheral registers to their default reset values.
|
||||
* @note Deinitialization can't be performed if the COMP configuration is locked.
|
||||
* To unlock the configuration, perform a system reset.
|
||||
* @param COMP_Selection: the selected comparator.
|
||||
* This parameter can be COMP_Selection_COMPx where x can be 1 to 7
|
||||
* to select the COMP peripheral.
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
void COMP_DeInit(uint32_t COMP_Selection)
|
||||
{
|
||||
/*!< Set COMP_CSR register to reset value */
|
||||
*(__IO uint32_t *) (COMP_BASE + COMP_Selection) = ((uint32_t)0x00000000);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Initializes the COMP peripheral according to the specified parameters
|
||||
* in COMP_InitStruct
|
||||
* @note If the selected comparator is locked, initialization can't be performed.
|
||||
* To unlock the configuration, perform a system reset.
|
||||
* @note By default, PA1 is selected as COMP1 non inverting input.
|
||||
* To use PA4 as COMP1 non inverting input call COMP_SwitchCmd() after COMP_Init()
|
||||
* @param COMP_Selection: the selected comparator.
|
||||
* This parameter can be COMP_Selection_COMPx where x can be 1 to 7
|
||||
* to select the COMP peripheral.
|
||||
* @param COMP_InitStruct: pointer to an COMP_InitTypeDef structure that contains
|
||||
* the configuration information for the specified COMP peripheral.
|
||||
* - COMP_InvertingInput specifies the inverting input of COMP
|
||||
* - COMP_NonInvertingInput specifies the non inverting input of COMP
|
||||
* - COMP_Output connect COMP output to selected timer
|
||||
* input (Input capture / Output Compare Reference Clear / Break Input)
|
||||
* - COMP_BlankingSrce specifies the blanking source of COMP
|
||||
* - COMP_OutputPol select output polarity
|
||||
* - COMP_Hysteresis configures COMP hysteresis value
|
||||
* - COMP_Mode configures COMP power mode
|
||||
* @retval None
|
||||
*/
|
||||
void COMP_Init(uint32_t COMP_Selection, COMP_InitTypeDef* COMP_InitStruct)
|
||||
{
|
||||
uint32_t tmpreg = 0;
|
||||
|
||||
/* Check the parameters */
|
||||
assert_param(IS_COMP_ALL_PERIPH(COMP_Selection));
|
||||
assert_param(IS_COMP_INVERTING_INPUT(COMP_InitStruct->COMP_InvertingInput));
|
||||
assert_param(IS_COMP_NONINVERTING_INPUT(COMP_InitStruct->COMP_NonInvertingInput));
|
||||
assert_param(IS_COMP_OUTPUT(COMP_InitStruct->COMP_Output));
|
||||
assert_param(IS_COMP_BLANKING_SOURCE(COMP_InitStruct->COMP_BlankingSrce));
|
||||
assert_param(IS_COMP_OUTPUT_POL(COMP_InitStruct->COMP_OutputPol));
|
||||
assert_param(IS_COMP_HYSTERESIS(COMP_InitStruct->COMP_Hysteresis));
|
||||
assert_param(IS_COMP_MODE(COMP_InitStruct->COMP_Mode));
|
||||
|
||||
/*!< Get the COMPx_CSR register value */
|
||||
tmpreg = *(__IO uint32_t *) (COMP_BASE + COMP_Selection);
|
||||
|
||||
/*!< Clear the COMP1SW1, COMPxINSEL, COMPxOUTSEL, COMPxPOL, COMPxHYST and COMPxMODE bits */
|
||||
tmpreg &= (uint32_t) (COMP_CSR_CLEAR_MASK);
|
||||
|
||||
/*!< Configure COMP: inverting input, output redirection, hysteresis value and power mode */
|
||||
/*!< Set COMPxINSEL bits according to COMP_InitStruct->COMP_InvertingInput value */
|
||||
/*!< Set COMPxNONINSEL bits according to COMP_InitStruct->COMP_NonInvertingInput value */
|
||||
/*!< Set COMPxBLANKING bits according to COMP_InitStruct->COMP_BlankingSrce value */
|
||||
/*!< Set COMPxOUTSEL bits according to COMP_InitStruct->COMP_Output value */
|
||||
/*!< Set COMPxPOL bit according to COMP_InitStruct->COMP_OutputPol value */
|
||||
/*!< Set COMPxHYST bits according to COMP_InitStruct->COMP_Hysteresis value */
|
||||
/*!< Set COMPxMODE bits according to COMP_InitStruct->COMP_Mode value */
|
||||
tmpreg |= (uint32_t)(COMP_InitStruct->COMP_InvertingInput | COMP_InitStruct->COMP_NonInvertingInput |
|
||||
COMP_InitStruct->COMP_Output | COMP_InitStruct->COMP_OutputPol | COMP_InitStruct->COMP_BlankingSrce |
|
||||
COMP_InitStruct->COMP_Hysteresis | COMP_InitStruct->COMP_Mode);
|
||||
|
||||
/*!< Write to COMPx_CSR register */
|
||||
*(__IO uint32_t *) (COMP_BASE + COMP_Selection) = tmpreg;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Fills each COMP_InitStruct member with its default value.
|
||||
* @param COMP_InitStruct: pointer to an COMP_InitTypeDef structure which will
|
||||
* be initialized.
|
||||
* @retval None
|
||||
*/
|
||||
void COMP_StructInit(COMP_InitTypeDef* COMP_InitStruct)
|
||||
{
|
||||
COMP_InitStruct->COMP_InvertingInput = COMP_InvertingInput_1_4VREFINT;
|
||||
COMP_InitStruct->COMP_NonInvertingInput = COMP_NonInvertingInput_IO1;
|
||||
COMP_InitStruct->COMP_Output = COMP_Output_None;
|
||||
COMP_InitStruct->COMP_BlankingSrce = COMP_BlankingSrce_None;
|
||||
COMP_InitStruct->COMP_OutputPol = COMP_OutputPol_NonInverted;
|
||||
COMP_InitStruct->COMP_Hysteresis = COMP_Hysteresis_No;
|
||||
COMP_InitStruct->COMP_Mode = COMP_Mode_UltraLowPower;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Enable or disable the COMP peripheral.
|
||||
* @note If the selected comparator is locked, enable/disable can't be performed.
|
||||
* To unlock the configuration, perform a system reset.
|
||||
* @param COMP_Selection: the selected comparator.
|
||||
* This parameter can be COMP_Selection_COMPx where x can be 1 to 7
|
||||
* to select the COMP peripheral.
|
||||
* @param NewState: new state of the COMP peripheral.
|
||||
* This parameter can be: ENABLE or DISABLE.
|
||||
* When enabled, the comparator compares the non inverting input with
|
||||
* the inverting input and the comparison result is available
|
||||
* on comparator output.
|
||||
* When disabled, the comparator doesn't perform comparison and the
|
||||
* output level is low.
|
||||
* @retval None
|
||||
*/
|
||||
void COMP_Cmd(uint32_t COMP_Selection, FunctionalState NewState)
|
||||
{
|
||||
/* Check the parameters */
|
||||
assert_param(IS_COMP_ALL_PERIPH(COMP_Selection));
|
||||
assert_param(IS_FUNCTIONAL_STATE(NewState));
|
||||
|
||||
if (NewState != DISABLE)
|
||||
{
|
||||
/* Enable the selected COMPx peripheral */
|
||||
*(__IO uint32_t *) (COMP_BASE + COMP_Selection) |= (uint32_t) (COMP_CSR_COMPxEN);
|
||||
}
|
||||
else
|
||||
{
|
||||
/* Disable the selected COMP peripheral */
|
||||
*(__IO uint32_t *) (COMP_BASE + COMP_Selection) &= (uint32_t)(~COMP_CSR_COMPxEN);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Close or Open the SW1 switch.
|
||||
* @note If the COMP1 is locked, Close/Open the SW1 switch can't be performed.
|
||||
* To unlock the configuration, perform a system reset.
|
||||
* @note This switch is solely intended to redirect signals onto high
|
||||
* impedance input, such as COMP1 non-inverting input (highly resistive switch)
|
||||
* @param NewState: New state of the analog switch.
|
||||
* This parameter can be
|
||||
* ENABLE so the SW1 is closed; PA1 is connected to PA4
|
||||
* or DISABLE so the SW1 switch is open; PA1 is disconnected from PA4
|
||||
* @retval None
|
||||
*/
|
||||
void COMP_SwitchCmd(uint32_t COMP_Selection, FunctionalState NewState)
|
||||
{
|
||||
/* Check the parameter */
|
||||
assert_param(IS_FUNCTIONAL_STATE(NewState));
|
||||
|
||||
if (NewState != DISABLE)
|
||||
{
|
||||
/* Close SW1 switch */
|
||||
*(__IO uint32_t *) (COMP_BASE + COMP_Selection) |= (uint32_t) (COMP_CSR_COMP1SW1);
|
||||
}
|
||||
else
|
||||
{
|
||||
/* Open SW1 switch */
|
||||
*(__IO uint32_t *) (COMP_BASE + COMP_Selection) &= (uint32_t)(~COMP_CSR_COMP1SW1);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Return the output level (high or low) of the selected comparator.
|
||||
* The output level depends on the selected polarity.
|
||||
* If the polarity is not inverted:
|
||||
* - Comparator output is low when the non-inverting input is at a lower
|
||||
* voltage than the inverting input
|
||||
* - Comparator output is high when the non-inverting input is at a higher
|
||||
* voltage than the inverting input
|
||||
* If the polarity is inverted:
|
||||
* - Comparator output is high when the non-inverting input is at a lower
|
||||
* voltage than the inverting input
|
||||
* - Comparator output is low when the non-inverting input is at a higher
|
||||
* voltage than the inverting input
|
||||
* @param COMP_Selection: the selected comparator.
|
||||
* This parameter can be COMP_Selection_COMPx where x can be 1 to 7
|
||||
* to select the COMP peripheral.
|
||||
* @retval Returns the selected comparator output level: low or high.
|
||||
*
|
||||
*/
|
||||
uint32_t COMP_GetOutputLevel(uint32_t COMP_Selection)
|
||||
{
|
||||
uint32_t compout = 0x0;
|
||||
|
||||
/* Check the parameters */
|
||||
assert_param(IS_COMP_ALL_PERIPH(COMP_Selection));
|
||||
|
||||
/* Check if selected comparator output is high */
|
||||
if ((*(__IO uint32_t *) (COMP_BASE + COMP_Selection) & (COMP_CSR_COMPxOUT)) != 0)
|
||||
{
|
||||
compout = COMP_OutputLevel_High;
|
||||
}
|
||||
else
|
||||
{
|
||||
compout = COMP_OutputLevel_Low;
|
||||
}
|
||||
|
||||
/* Return the comparator output level */
|
||||
return (uint32_t)(compout);
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/** @defgroup COMP_Group2 Window mode control function
|
||||
* @brief Window mode control function
|
||||
*
|
||||
@verbatim
|
||||
===============================================================================
|
||||
##### Window mode control function #####
|
||||
===============================================================================
|
||||
|
||||
@endverbatim
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief Enables or disables the window mode.
|
||||
* Window mode for comparators makes use of two comparators:
|
||||
* COMP1 and COM2, COMP3 and COMP4, COMP5 and COMP6.
|
||||
* In window mode, COMPx and COMPx-1 (where x can be 2, 4 or 6)
|
||||
* non inverting inputs are connected together and only COMPx-1 non
|
||||
* inverting input can be used.
|
||||
* e.g When window mode enabled for COMP4, COMP3 non inverting input (PB14 or PD14)
|
||||
* is to be used.
|
||||
* @note If the COMPx is locked, ENABLE/DISABLE the window mode can't be performed.
|
||||
* To unlock the configuration, perform a system reset.
|
||||
* @param COMP_Selection: the selected comparator.
|
||||
* This parameter can be COMP_Selection_COMPx where x can be 2, 4 or 6
|
||||
* to select the COMP peripheral.
|
||||
* param NewState: new state of the window mode.
|
||||
* This parameter can be ENABLE or DISABLE.
|
||||
* When enbaled, COMPx and COMPx-1 non inverting inputs are connected together.
|
||||
* When disabled, COMPx and COMPx-1 non inverting inputs are disconnected.
|
||||
* @retval None
|
||||
*/
|
||||
void COMP_WindowCmd(uint32_t COMP_Selection, FunctionalState NewState)
|
||||
{
|
||||
/* Check the parameters */
|
||||
assert_param(IS_FUNCTIONAL_STATE(NewState));
|
||||
assert_param(IS_COMP_WINDOW(COMP_Selection));
|
||||
|
||||
if (NewState != DISABLE)
|
||||
{
|
||||
/* Enable the window mode */
|
||||
*(__IO uint32_t *) (COMP_BASE + COMP_Selection) |= (uint32_t) COMP_CSR_COMPxWNDWEN;
|
||||
}
|
||||
else
|
||||
{
|
||||
/* Disable the window mode */
|
||||
*(__IO uint32_t *) (COMP_BASE + COMP_Selection) &= (uint32_t)(~COMP_CSR_COMPxWNDWEN);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/** @defgroup COMP_Group3 COMP configuration locking function
|
||||
* @brief COMP1, COMP2,...COMP7 configuration locking function
|
||||
* COMP1, COMP2,...COMP7 configuration can be locked each separately.
|
||||
* Unlocking is performed by system reset.
|
||||
*
|
||||
@verbatim
|
||||
===============================================================================
|
||||
##### Configuration Lock function #####
|
||||
===============================================================================
|
||||
|
||||
@endverbatim
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief Lock the selected comparator (COMP1/COMP2) configuration.
|
||||
* @note Locking the configuration means that all control bits are read-only.
|
||||
* To unlock the comparator configuration, perform a system reset.
|
||||
* @param COMP_Selection: the selected comparator.
|
||||
* This parameter can be COMP_Selection_COMPx where x can be 1 to 7
|
||||
* to select the COMP peripheral.
|
||||
* @retval None
|
||||
*/
|
||||
void COMP_LockConfig(uint32_t COMP_Selection)
|
||||
{
|
||||
/* Check the parameter */
|
||||
assert_param(IS_COMP_ALL_PERIPH(COMP_Selection));
|
||||
|
||||
/* Set the lock bit corresponding to selected comparator */
|
||||
*(__IO uint32_t *) (COMP_BASE + COMP_Selection) |= (uint32_t) (COMP_CSR_COMPxLOCK);
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
|
@ -0,0 +1,354 @@
|
|||
/**
|
||||
******************************************************************************
|
||||
* @file stm32f30x_crc.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 CRC computation unit peripheral:
|
||||
* + Configuration of the CRC computation unit
|
||||
* + CRC computation of one/many 32-bit data
|
||||
* + CRC Independent register (IDR) access
|
||||
*
|
||||
@verbatim
|
||||
|
||||
===============================================================================
|
||||
##### How to use this driver #####
|
||||
===============================================================================
|
||||
[..]
|
||||
(#) Enable CRC AHB clock using RCC_AHBPeriphClockCmd(RCC_AHBPeriph_CRC, ENABLE)
|
||||
function.
|
||||
(#) Select the polynomial size: 7-bit, 8-bit, 16-bit or 32-bit.
|
||||
(#) Set the polynomial coefficients using CRC_SetPolynomial();
|
||||
(#) If required, select the reverse operation on input data
|
||||
using CRC_ReverseInputDataSelect();
|
||||
(#) If required, enable the reverse operation on output data
|
||||
using CRC_ReverseOutputDataCmd(Enable);
|
||||
(#) If required, set the initialization remainder value using
|
||||
CRC_SetInitRegister();
|
||||
(#) use CRC_CalcCRC() function to compute the CRC of a 32-bit data
|
||||
or use CRC_CalcBlockCRC() function to compute the CRC if a 32-bit
|
||||
data buffer.
|
||||
|
||||
@endverbatim
|
||||
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© 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_crc.h"
|
||||
|
||||
/** @addtogroup STM32F30x_StdPeriph_Driver
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @defgroup CRC
|
||||
* @brief CRC driver modules
|
||||
* @{
|
||||
*/
|
||||
|
||||
/* Private typedef -----------------------------------------------------------*/
|
||||
/* Private define ------------------------------------------------------------*/
|
||||
/* Private macro -------------------------------------------------------------*/
|
||||
/* Private variables ---------------------------------------------------------*/
|
||||
/* Private function prototypes -----------------------------------------------*/
|
||||
/* Private functions ---------------------------------------------------------*/
|
||||
|
||||
/** @defgroup CRC_Private_Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @defgroup CRC_Group1 Configuration of the CRC computation unit functions
|
||||
* @brief Configuration of the CRC computation unit functions
|
||||
*
|
||||
@verbatim
|
||||
===============================================================================
|
||||
##### CRC configuration functions #####
|
||||
===============================================================================
|
||||
|
||||
@endverbatim
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief Deinitializes CRC peripheral registers to their default reset values.
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
void CRC_DeInit(void)
|
||||
{
|
||||
/* Set DR register to reset value */
|
||||
CRC->DR = 0xFFFFFFFF;
|
||||
/* Set the POL register to the reset value: 0x04C11DB7 */
|
||||
CRC->POL = 0x04C11DB7;
|
||||
/* Reset IDR register */
|
||||
CRC->IDR = 0x00;
|
||||
/* Set INIT register to reset value */
|
||||
CRC->INIT = 0xFFFFFFFF;
|
||||
/* Reset the CRC calculation unit */
|
||||
CRC->CR = CRC_CR_RESET;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Resets the CRC calculation unit and sets INIT register content in DR register.
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
void CRC_ResetDR(void)
|
||||
{
|
||||
/* Reset CRC generator */
|
||||
CRC->CR |= CRC_CR_RESET;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Selects the polynomial size.
|
||||
* @param CRC_PolSize: Specifies the polynomial size.
|
||||
* This parameter can be:
|
||||
* @arg CRC_PolSize_7: 7-bit polynomial for CRC calculation
|
||||
* @arg CRC_PolSize_8: 8-bit polynomial for CRC calculation
|
||||
* @arg CRC_PolSize_16: 16-bit polynomial for CRC calculation
|
||||
* @arg CRC_PolSize_32: 32-bit polynomial for CRC calculation
|
||||
* @retval None
|
||||
*/
|
||||
void CRC_PolynomialSizeSelect(uint32_t CRC_PolSize)
|
||||
{
|
||||
uint32_t tmpcr = 0;
|
||||
|
||||
/* Check the parameter */
|
||||
assert_param(IS_CRC_POL_SIZE(CRC_PolSize));
|
||||
|
||||
/* Get CR register value */
|
||||
tmpcr = CRC->CR;
|
||||
|
||||
/* Reset POL_SIZE bits */
|
||||
tmpcr &= (uint32_t)~((uint32_t)CRC_CR_POLSIZE);
|
||||
/* Set the polynomial size */
|
||||
tmpcr |= (uint32_t)CRC_PolSize;
|
||||
|
||||
/* Write to CR register */
|
||||
CRC->CR = (uint32_t)tmpcr;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Selects the reverse operation to be performed on input data.
|
||||
* @param CRC_ReverseInputData: Specifies the reverse operation on input data.
|
||||
* This parameter can be:
|
||||
* @arg CRC_ReverseInputData_No: No reverse operation is performed
|
||||
* @arg CRC_ReverseInputData_8bits: reverse operation performed on 8 bits
|
||||
* @arg CRC_ReverseInputData_16bits: reverse operation performed on 16 bits
|
||||
* @arg CRC_ReverseInputData_32bits: reverse operation performed on 32 bits
|
||||
* @retval None
|
||||
*/
|
||||
void CRC_ReverseInputDataSelect(uint32_t CRC_ReverseInputData)
|
||||
{
|
||||
uint32_t tmpcr = 0;
|
||||
|
||||
/* Check the parameter */
|
||||
assert_param(IS_CRC_REVERSE_INPUT_DATA(CRC_ReverseInputData));
|
||||
|
||||
/* Get CR register value */
|
||||
tmpcr = CRC->CR;
|
||||
|
||||
/* Reset REV_IN bits */
|
||||
tmpcr &= (uint32_t)~((uint32_t)CRC_CR_REV_IN);
|
||||
/* Set the reverse operation */
|
||||
tmpcr |= (uint32_t)CRC_ReverseInputData;
|
||||
|
||||
/* Write to CR register */
|
||||
CRC->CR = (uint32_t)tmpcr;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Enables or disable the reverse operation on output data.
|
||||
* The reverse operation on output data is performed on 32-bit.
|
||||
* @param NewState: new state of the reverse operation on output data.
|
||||
* This parameter can be: ENABLE or DISABLE.
|
||||
* @retval None
|
||||
*/
|
||||
void CRC_ReverseOutputDataCmd(FunctionalState NewState)
|
||||
{
|
||||
/* Check the parameters */
|
||||
assert_param(IS_FUNCTIONAL_STATE(NewState));
|
||||
|
||||
if (NewState != DISABLE)
|
||||
{
|
||||
/* Enable reverse operation on output data */
|
||||
CRC->CR |= CRC_CR_REV_OUT;
|
||||
}
|
||||
else
|
||||
{
|
||||
/* Disable reverse operation on output data */
|
||||
CRC->CR &= (uint32_t)~((uint32_t)CRC_CR_REV_OUT);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Initializes the INIT register.
|
||||
* @note After resetting CRC calculation unit, CRC_InitValue is stored in DR register
|
||||
* @param CRC_InitValue: Programmable initial CRC value
|
||||
* @retval None
|
||||
*/
|
||||
void CRC_SetInitRegister(uint32_t CRC_InitValue)
|
||||
{
|
||||
CRC->INIT = CRC_InitValue;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Initializes the polynomail coefficients.
|
||||
* @param CRC_Pol: Polynomial to be used for CRC calculation.
|
||||
* @retval None
|
||||
*/
|
||||
void CRC_SetPolynomial(uint32_t CRC_Pol)
|
||||
{
|
||||
CRC->POL = CRC_Pol;
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/** @defgroup CRC_Group2 CRC computation of one/many 32-bit data functions
|
||||
* @brief CRC computation of one/many 32-bit data functions
|
||||
*
|
||||
@verbatim
|
||||
===============================================================================
|
||||
##### CRC computation functions #####
|
||||
===============================================================================
|
||||
|
||||
@endverbatim
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief Computes the 32-bit CRC of a given data word(32-bit).
|
||||
* @param CRC_Data: data word(32-bit) to compute its CRC
|
||||
* @retval 32-bit CRC
|
||||
*/
|
||||
uint32_t CRC_CalcCRC(uint32_t CRC_Data)
|
||||
{
|
||||
CRC->DR = CRC_Data;
|
||||
|
||||
return (CRC->DR);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Computes the 16-bit CRC of a given 16-bit data.
|
||||
* @param CRC_Data: data half-word(16-bit) to compute its CRC
|
||||
* @retval 16-bit CRC
|
||||
*/
|
||||
uint32_t CRC_CalcCRC16bits(uint16_t CRC_Data)
|
||||
{
|
||||
*(uint16_t*)(CRC_BASE) = (uint16_t) CRC_Data;
|
||||
|
||||
return (CRC->DR);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Computes the 8-bit CRC of a given 8-bit data.
|
||||
* @param CRC_Data: 8-bit data to compute its CRC
|
||||
* @retval 8-bit CRC
|
||||
*/
|
||||
uint32_t CRC_CalcCRC8bits(uint8_t CRC_Data)
|
||||
{
|
||||
*(uint8_t*)(CRC_BASE) = (uint8_t) CRC_Data;
|
||||
|
||||
return (CRC->DR);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Computes the 32-bit CRC of a given buffer of data word(32-bit).
|
||||
* @param pBuffer: pointer to the buffer containing the data to be computed
|
||||
* @param BufferLength: length of the buffer to be computed
|
||||
* @retval 32-bit CRC
|
||||
*/
|
||||
uint32_t CRC_CalcBlockCRC(uint32_t pBuffer[], uint32_t BufferLength)
|
||||
{
|
||||
uint32_t index = 0;
|
||||
|
||||
for(index = 0; index < BufferLength; index++)
|
||||
{
|
||||
CRC->DR = pBuffer[index];
|
||||
}
|
||||
return (CRC->DR);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Returns the current CRC value.
|
||||
* @param None
|
||||
* @retval 32-bit CRC
|
||||
*/
|
||||
uint32_t CRC_GetCRC(void)
|
||||
{
|
||||
return (CRC->DR);
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/** @defgroup CRC_Group3 CRC Independent Register (IDR) access functions
|
||||
* @brief CRC Independent Register (IDR) access (write/read) functions
|
||||
*
|
||||
@verbatim
|
||||
===============================================================================
|
||||
##### CRC Independent Register (IDR) access functions #####
|
||||
===============================================================================
|
||||
|
||||
@endverbatim
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief Stores an 8-bit data in the Independent Data(ID) register.
|
||||
* @param CRC_IDValue: 8-bit value to be stored in the ID register
|
||||
* @retval None
|
||||
*/
|
||||
void CRC_SetIDRegister(uint8_t CRC_IDValue)
|
||||
{
|
||||
CRC->IDR = CRC_IDValue;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Returns the 8-bit data stored in the Independent Data(ID) register
|
||||
* @param None
|
||||
* @retval 8-bit value of the ID register
|
||||
*/
|
||||
uint8_t CRC_GetIDRegister(void)
|
||||
{
|
||||
return (CRC->IDR);
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
|
@ -0,0 +1,754 @@
|
|||
/**
|
||||
******************************************************************************
|
||||
* @file stm32f30x_dac.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 Digital-to-Analog Converter (DAC) peripheral:
|
||||
* + DAC channels configuration: trigger, output buffer, data format
|
||||
* + DMA management
|
||||
* + Interrupts and flags management
|
||||
*
|
||||
@verbatim
|
||||
|
||||
===============================================================================
|
||||
##### DAC Peripheral features #####
|
||||
===============================================================================
|
||||
[..] The device integrates two 12-bit Digital Analog Converters that can
|
||||
be used independently or simultaneously (dual mode):
|
||||
(#) DAC1 integrates two DAC channels:
|
||||
(++) DAC1 channel 1 with DAC1_OUT1 as output
|
||||
(++) DAC1 channel 2 with DAC1_OUT2 as output
|
||||
(++) The two channels can be used independently or simultaneously (dual mode)
|
||||
|
||||
(#) DAC2 integrates only one channel DAC2 channel 1 with DAC2_OUT1 as output
|
||||
|
||||
[..] Digital to Analog conversion can be non-triggered using DAC_Trigger_None
|
||||
and DAC_OUT1/DAC_OUT2 is available once writing to DHRx register using
|
||||
DAC_SetChannel1Data()/DAC_SetChannel2Data.
|
||||
|
||||
[..] Digital to Analog conversion can be triggered by:
|
||||
(#) External event: EXTI Line 9 (any GPIOx_Pin9) using DAC_Trigger_Ext_IT9.
|
||||
The used pin (GPIOx_Pin9) must be configured in input mode.
|
||||
|
||||
(#) Timers TRGO: TIM2, TIM8/TIM3, TIM4, TIM6, TIM7, and TIM15
|
||||
(DAC_Trigger_T2_TRGO, DAC_Trigger_T4_TRGO...)
|
||||
The timer TRGO event should be selected using TIM_SelectOutputTrigger()
|
||||
(++) To trigger DAC conversions by TIM3 instead of TIM8 follow
|
||||
this sequence:
|
||||
(+++) Enable SYSCFG APB clock by calling
|
||||
RCC_APB2PeriphClockCmd(RCC_APB2Periph_SYSCFG, ENABLE);
|
||||
(+++) Select DAC_Trigger_T3_TRGO when calling DAC_Init()
|
||||
(+++) Remap the DAC trigger from TIM8 to TIM3 by calling
|
||||
SYSCFG_TriggerRemapConfig(SYSCFG_TriggerRemap_DACTIM3, ENABLE)
|
||||
(#) Software using DAC_Trigger_Software
|
||||
|
||||
[..] Each DAC channel integrates an output buffer that can be used to
|
||||
reduce the output impedance, and to drive external loads directly
|
||||
without having to add an external operational amplifier.
|
||||
To enable, the output buffer use
|
||||
DAC_InitStructure.DAC_OutputBuffer = DAC_OutputBuffer_Enable;
|
||||
|
||||
[..] Refer to the device datasheet for more details about output impedance
|
||||
value with and without output buffer.
|
||||
|
||||
[..] Both DAC channels can be used to generate:
|
||||
(+) Noise wave using DAC_WaveGeneration_Noise
|
||||
(+) Triangle wave using DAC_WaveGeneration_Triangle
|
||||
|
||||
[..] Wave generation can be disabled using DAC_WaveGeneration_None
|
||||
|
||||
[..] The DAC data format can be:
|
||||
(+) 8-bit right alignment using DAC_Align_8b_R
|
||||
(+) 12-bit left alignment using DAC_Align_12b_L
|
||||
(+) 12-bit right alignment using DAC_Align_12b_R
|
||||
|
||||
[..] The analog output voltage on each DAC channel pin is determined
|
||||
by the following equation:
|
||||
(+) DAC_OUTx = VREF+ * DOR / 4095 with DOR is the Data Output Register.
|
||||
VREF+ is the input voltage reference (refer to the device datasheet)
|
||||
e.g. To set DAC_OUT1 to 0.7V, use DAC_SetChannel1Data(DAC_Align_12b_R, 868);
|
||||
Assuming that VREF+ = 3.3, DAC_OUT1 = (3.3 * 868) / 4095 = 0.7V
|
||||
|
||||
[..] A DMA1 request can be generated when an external trigger (but not
|
||||
a software trigger) occurs if DMA1 requests are enabled using
|
||||
DAC_DMACmd()
|
||||
DMA1 requests are mapped as following:
|
||||
(+) DAC channel1 is mapped on DMA1 channel3 which must be already
|
||||
configured
|
||||
(+) DAC channel2 is mapped on DMA1 channel4 which must be already
|
||||
configured
|
||||
|
||||
##### How to use this driver #####
|
||||
===============================================================================
|
||||
[..]
|
||||
(+) Enable DAC APB1 clock to get write access to DAC registers
|
||||
using RCC_APB1PeriphClockCmd(RCC_APB1Periph_DAC, ENABLE)
|
||||
|
||||
(+) Configure DACx_OUTy (DAC1_OUT1: PA4, DAC1_OUT2: PA5, DAC2_OUT1: PA6)
|
||||
in analog mode.
|
||||
|
||||
(+) Configure the DAC channel using DAC_Init()
|
||||
|
||||
(+) Enable the DAC channel using DAC_Cmd()
|
||||
|
||||
@endverbatim
|
||||
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© 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_dac.h"
|
||||
#include "stm32f30x_rcc.h"
|
||||
|
||||
/** @addtogroup STM32F30x_StdPeriph_Driver
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @defgroup DAC
|
||||
* @brief DAC driver modules
|
||||
* @{
|
||||
*/
|
||||
|
||||
/* Private typedef -----------------------------------------------------------*/
|
||||
/* Private define ------------------------------------------------------------*/
|
||||
|
||||
/* CR register Mask */
|
||||
#define CR_CLEAR_MASK ((uint32_t)0x00000FFE)
|
||||
|
||||
/* DAC Dual Channels SWTRIG masks */
|
||||
#define DUAL_SWTRIG_SET ((uint32_t)0x00000003)
|
||||
#define DUAL_SWTRIG_RESET ((uint32_t)0xFFFFFFFC)
|
||||
|
||||
/* DHR registers offsets */
|
||||
#define DHR12R1_OFFSET ((uint32_t)0x00000008)
|
||||
#define DHR12R2_OFFSET ((uint32_t)0x00000014)
|
||||
#define DHR12RD_OFFSET ((uint32_t)0x00000020)
|
||||
|
||||
/* DOR register offset */
|
||||
#define DOR_OFFSET ((uint32_t)0x0000002C)
|
||||
|
||||
/* Private macro -------------------------------------------------------------*/
|
||||
/* Private variables ---------------------------------------------------------*/
|
||||
/* Private function prototypes -----------------------------------------------*/
|
||||
/* Private functions ---------------------------------------------------------*/
|
||||
|
||||
/** @defgroup DAC_Private_Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @defgroup DAC_Group1 DAC channels configuration
|
||||
* @brief DAC channels configuration: trigger, output buffer, data format
|
||||
*
|
||||
@verbatim
|
||||
===============================================================================
|
||||
##### DAC channels configuration: trigger, output buffer, data format #####
|
||||
===============================================================================
|
||||
|
||||
@endverbatim
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief Deinitializes the DAC peripheral registers to their default reset values.
|
||||
* @param DACx: where x can be 1 or 2 to select the DAC peripheral.
|
||||
* @retval None
|
||||
*/
|
||||
void DAC_DeInit(DAC_TypeDef* DACx)
|
||||
{
|
||||
/* Check the parameters */
|
||||
assert_param(IS_DAC_ALL_PERIPH(DACx));
|
||||
|
||||
if (DACx == DAC1)
|
||||
{
|
||||
/* Enable DAC1 reset state */
|
||||
RCC_APB1PeriphResetCmd(RCC_APB1Periph_DAC1, ENABLE);
|
||||
/* Release DAC1 from reset state */
|
||||
RCC_APB1PeriphResetCmd(RCC_APB1Periph_DAC1, DISABLE);
|
||||
}
|
||||
else
|
||||
{
|
||||
/* Enable DAC2 reset state */
|
||||
RCC_APB1PeriphResetCmd(RCC_APB1Periph_DAC2, ENABLE);
|
||||
/* Release DAC2 from reset state */
|
||||
RCC_APB1PeriphResetCmd(RCC_APB1Periph_DAC2, DISABLE);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Initializes the DAC peripheral according to the specified
|
||||
* parameters in the DAC_InitStruct.
|
||||
* @param DACx: where x can be 1 or 2 to select the DAC peripheral.
|
||||
* @param DAC_Channel: the selected DAC channel.
|
||||
* This parameter can be one of the following values:
|
||||
* @arg DAC_Channel_1: DAC Channel1 selected
|
||||
* @arg DAC_Channel_2: DAC Channel2 selected
|
||||
* @param DAC_InitStruct: pointer to a DAC_InitTypeDef structure that
|
||||
* contains the configuration information for the specified DAC channel.
|
||||
* @retval None
|
||||
*/
|
||||
void DAC_Init(DAC_TypeDef* DACx, uint32_t DAC_Channel, DAC_InitTypeDef* DAC_InitStruct)
|
||||
{
|
||||
uint32_t tmpreg1 = 0, tmpreg2 = 0;
|
||||
|
||||
/* Check the DAC parameters */
|
||||
assert_param(IS_DAC_ALL_PERIPH(DACx));
|
||||
assert_param(IS_DAC_TRIGGER(DAC_InitStruct->DAC_Trigger));
|
||||
assert_param(IS_DAC_GENERATE_WAVE(DAC_InitStruct->DAC_WaveGeneration));
|
||||
assert_param(IS_DAC_LFSR_UNMASK_TRIANGLE_AMPLITUDE(DAC_InitStruct->DAC_LFSRUnmask_TriangleAmplitude));
|
||||
assert_param(IS_DAC_BUFFER_SWITCH_STATE(DAC_InitStruct->DAC_Buffer_Switch));
|
||||
|
||||
/*---------------------------- DAC CR Configuration --------------------------*/
|
||||
/* Get the DAC CR value */
|
||||
tmpreg1 = DACx->CR;
|
||||
/* Clear BOFFx, TENx, TSELx, WAVEx and MAMPx bits */
|
||||
tmpreg1 &= ~(CR_CLEAR_MASK << DAC_Channel);
|
||||
/* Configure for the selected DAC channel: buffer output, trigger, wave generation,
|
||||
mask/amplitude for wave generation */
|
||||
|
||||
/* Set TSELx and TENx bits according to DAC_Trigger value */
|
||||
/* Set WAVEx bits according to DAC_WaveGeneration value */
|
||||
/* Set MAMPx bits according to DAC_LFSRUnmask_TriangleAmplitude value */
|
||||
/* Set BOFFx OUTENx bit according to DAC_Buffer_Switch value */
|
||||
tmpreg2 = (DAC_InitStruct->DAC_Trigger | DAC_InitStruct->DAC_WaveGeneration |
|
||||
DAC_InitStruct->DAC_LFSRUnmask_TriangleAmplitude | DAC_InitStruct->DAC_Buffer_Switch);
|
||||
|
||||
/* Calculate CR register value depending on DAC_Channel */
|
||||
tmpreg1 |= tmpreg2 << DAC_Channel;
|
||||
/* Write to DAC CR */
|
||||
DACx->CR = tmpreg1;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Fills each DAC_InitStruct member with its default value.
|
||||
* @param DAC_InitStruct: pointer to a DAC_InitTypeDef structure which will
|
||||
* be initialized.
|
||||
* @retval None
|
||||
*/
|
||||
void DAC_StructInit(DAC_InitTypeDef* DAC_InitStruct)
|
||||
{
|
||||
/*--------------- Reset DAC init structure parameters values -----------------*/
|
||||
/* Initialize the DAC_Trigger member */
|
||||
DAC_InitStruct->DAC_Trigger = DAC_Trigger_None;
|
||||
/* Initialize the DAC_WaveGeneration member */
|
||||
DAC_InitStruct->DAC_WaveGeneration = DAC_WaveGeneration_None;
|
||||
/* Initialize the DAC_LFSRUnmask_TriangleAmplitude member */
|
||||
DAC_InitStruct->DAC_LFSRUnmask_TriangleAmplitude = DAC_LFSRUnmask_Bit0;
|
||||
/* Initialize the DAC_Buffer_Switch member */
|
||||
DAC_InitStruct->DAC_Buffer_Switch = DAC_BufferSwitch_Enable;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Enables or disables the specified DAC channel.
|
||||
* @param DACx: where x can be 1 or 2 to select the DAC peripheral.
|
||||
* @param DAC_Channel: The selected DAC channel.
|
||||
* This parameter can be one of the following values:
|
||||
* @arg DAC_Channel_1: DAC Channel1 selected
|
||||
* @arg DAC_Channel_2: DAC Channel2 selected
|
||||
* @param NewState: new state of the DAC channel.
|
||||
* This parameter can be: ENABLE or DISABLE.
|
||||
* @note When the DAC channel is enabled the trigger source can no more
|
||||
* be modified.
|
||||
* @retval None
|
||||
*/
|
||||
void DAC_Cmd(DAC_TypeDef* DACx, uint32_t DAC_Channel, FunctionalState NewState)
|
||||
{
|
||||
/* Check the parameters */
|
||||
assert_param(IS_DAC_ALL_PERIPH(DACx));
|
||||
assert_param(IS_DAC_CHANNEL(DAC_Channel));
|
||||
assert_param(IS_FUNCTIONAL_STATE(NewState));
|
||||
|
||||
if (NewState != DISABLE)
|
||||
{
|
||||
/* Enable the selected DAC channel */
|
||||
DACx->CR |= (DAC_CR_EN1 << DAC_Channel);
|
||||
}
|
||||
else
|
||||
{
|
||||
/* Disable the selected DAC channel */
|
||||
DACx->CR &= (~(DAC_CR_EN1 << DAC_Channel));
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Enables or disables the selected DAC channel software trigger.
|
||||
* @param DACx: where x can be 1 or 2 to select the DAC peripheral.
|
||||
* @param DAC_Channel: the selected DAC channel.
|
||||
* This parameter can be one of the following values:
|
||||
* @arg DAC_Channel_1: DAC Channel1 selected
|
||||
* @arg DAC_Channel_2: DAC Channel2 selected
|
||||
* @param NewState: new state of the selected DAC channel software trigger.
|
||||
* This parameter can be: ENABLE or DISABLE.
|
||||
* @retval None
|
||||
*/
|
||||
void DAC_SoftwareTriggerCmd(DAC_TypeDef* DACx, uint32_t DAC_Channel, FunctionalState NewState)
|
||||
{
|
||||
/* Check the parameters */
|
||||
assert_param(IS_DAC_ALL_PERIPH(DACx));
|
||||
assert_param(IS_DAC_CHANNEL(DAC_Channel));
|
||||
assert_param(IS_FUNCTIONAL_STATE(NewState));
|
||||
|
||||
if (NewState != DISABLE)
|
||||
{
|
||||
/* Enable software trigger for the selected DAC channel */
|
||||
DACx->SWTRIGR |= (uint32_t)DAC_SWTRIGR_SWTRIG1 << (DAC_Channel >> 4);
|
||||
}
|
||||
else
|
||||
{
|
||||
/* Disable software trigger for the selected DAC channel */
|
||||
DACx->SWTRIGR &= ~((uint32_t)DAC_SWTRIGR_SWTRIG1 << (DAC_Channel >> 4));
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Enables or disables simultaneously the two DAC channels software
|
||||
* triggers.
|
||||
* @param DACx: where x can be 1 to select the DAC1 peripheral.
|
||||
* @note Dual trigger is not applicable for DAC2 (DAC2 integrates one channel).
|
||||
* @param NewState: new state of the DAC channels software triggers.
|
||||
* This parameter can be: ENABLE or DISABLE.
|
||||
* @retval None
|
||||
*/
|
||||
void DAC_DualSoftwareTriggerCmd(DAC_TypeDef* DACx, FunctionalState NewState)
|
||||
{
|
||||
/* Check the parameters */
|
||||
assert_param(IS_DAC_LIST1_PERIPH(DACx));
|
||||
assert_param(IS_FUNCTIONAL_STATE(NewState));
|
||||
|
||||
if (NewState != DISABLE)
|
||||
{
|
||||
/* Enable software trigger for both DAC channels */
|
||||
DACx->SWTRIGR |= DUAL_SWTRIG_SET;
|
||||
}
|
||||
else
|
||||
{
|
||||
/* Disable software trigger for both DAC channels */
|
||||
DACx->SWTRIGR &= DUAL_SWTRIG_RESET;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Enables or disables the selected DAC channel wave generation.
|
||||
* @param DACx: where x can be 1 to select the DAC1 peripheral.
|
||||
* @note Wave generation is not available in DAC2.
|
||||
* @param DAC_Channel: the selected DAC channel.
|
||||
* This parameter can be one of the following values:
|
||||
* @arg DAC_Channel_1: DAC Channel1 selected
|
||||
* @arg DAC_Channel_2: DAC Channel2 selected
|
||||
* @param DAC_Wave: Specifies the wave type to enable or disable.
|
||||
* This parameter can be one of the following values:
|
||||
* @arg DAC_Wave_Noise: noise wave generation
|
||||
* @arg DAC_Wave_Triangle: triangle wave generation
|
||||
* @param NewState: new state of the selected DAC channel wave generation.
|
||||
* This parameter can be: ENABLE or DISABLE.
|
||||
* @note
|
||||
* @retval None
|
||||
*/
|
||||
void DAC_WaveGenerationCmd(DAC_TypeDef* DACx, uint32_t DAC_Channel, uint32_t DAC_Wave, FunctionalState NewState)
|
||||
{
|
||||
/* Check the parameters */
|
||||
assert_param(IS_DAC_LIST1_PERIPH(DACx));
|
||||
assert_param(IS_DAC_CHANNEL(DAC_Channel));
|
||||
assert_param(IS_DAC_WAVE(DAC_Wave));
|
||||
assert_param(IS_FUNCTIONAL_STATE(NewState));
|
||||
|
||||
if (NewState != DISABLE)
|
||||
{
|
||||
/* Enable the selected wave generation for the selected DAC channel */
|
||||
DACx->CR |= DAC_Wave << DAC_Channel;
|
||||
}
|
||||
else
|
||||
{
|
||||
/* Disable the selected wave generation for the selected DAC channel */
|
||||
DACx->CR &= ~(DAC_Wave << DAC_Channel);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Set the specified data holding register value for DAC channel1.
|
||||
* @param DACx: where x can be 1 or 2 to select the DAC peripheral.
|
||||
* @param DAC_Align: Specifies the data alignment for DAC channel1.
|
||||
* This parameter can be one of the following values:
|
||||
* @arg DAC_Align_8b_R: 8bit right data alignment selected
|
||||
* @arg DAC_Align_12b_L: 12bit left data alignment selected
|
||||
* @arg DAC_Align_12b_R: 12bit right data alignment selected
|
||||
* @param Data: Data to be loaded in the selected data holding register.
|
||||
* @retval None
|
||||
*/
|
||||
void DAC_SetChannel1Data(DAC_TypeDef* DACx, uint32_t DAC_Align, uint16_t Data)
|
||||
{
|
||||
__IO uint32_t tmp = 0;
|
||||
|
||||
/* Check the parameters */
|
||||
assert_param(IS_DAC_ALL_PERIPH(DACx));
|
||||
assert_param(IS_DAC_ALIGN(DAC_Align));
|
||||
assert_param(IS_DAC_DATA(Data));
|
||||
|
||||
tmp = (uint32_t)DACx;
|
||||
tmp += DHR12R1_OFFSET + DAC_Align;
|
||||
|
||||
/* Set the DAC channel1 selected data holding register */
|
||||
*(__IO uint32_t *) tmp = Data;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Set the specified data holding register value for DAC channel2.
|
||||
* @param DACx: where x can be 1 to select the DAC peripheral.
|
||||
* @note This function is available only for DAC1.
|
||||
* @param DAC_Align: Specifies the data alignment for DAC channel2.
|
||||
* This parameter can be one of the following values:
|
||||
* @arg DAC_Align_8b_R: 8bit right data alignment selected
|
||||
* @arg DAC_Align_12b_L: 12bit left data alignment selected
|
||||
* @arg DAC_Align_12b_R: 12bit right data alignment selected
|
||||
* @param Data : Data to be loaded in the selected data holding register.
|
||||
* @retval None
|
||||
*/
|
||||
void DAC_SetChannel2Data(DAC_TypeDef* DACx, uint32_t DAC_Align, uint16_t Data)
|
||||
{
|
||||
__IO uint32_t tmp = 0;
|
||||
|
||||
/* Check the parameters */
|
||||
assert_param(IS_DAC_LIST1_PERIPH(DACx));
|
||||
assert_param(IS_DAC_ALIGN(DAC_Align));
|
||||
assert_param(IS_DAC_DATA(Data));
|
||||
|
||||
tmp = (uint32_t)DACx;
|
||||
tmp += DHR12R2_OFFSET + DAC_Align;
|
||||
|
||||
/* Set the DAC channel2 selected data holding register */
|
||||
*(__IO uint32_t *)tmp = Data;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Set the specified data holding register value for dual channel DAC.
|
||||
* @param DACx: where x can be 1 to select the DAC peripheral.
|
||||
* @note This function isn't applicable for DAC2.
|
||||
* @param DAC_Align: Specifies the data alignment for dual channel DAC.
|
||||
* This parameter can be one of the following values:
|
||||
* @arg DAC_Align_8b_R: 8bit right data alignment selected
|
||||
* @arg DAC_Align_12b_L: 12bit left data alignment selected
|
||||
* @arg DAC_Align_12b_R: 12bit right data alignment selected
|
||||
* @param Data2: Data for DAC Channel2 to be loaded in the selected data
|
||||
* holding register.
|
||||
* @param Data1: Data for DAC Channel1 to be loaded in the selected data
|
||||
* holding register.
|
||||
* @note In dual mode, a unique register access is required to write in both
|
||||
* DAC channels at the same time.
|
||||
* @retval None
|
||||
*/
|
||||
void DAC_SetDualChannelData(DAC_TypeDef* DACx, uint32_t DAC_Align, uint16_t Data2, uint16_t Data1)
|
||||
{
|
||||
uint32_t data = 0, tmp = 0;
|
||||
|
||||
/* Check the parameters */
|
||||
assert_param(IS_DAC_LIST1_PERIPH(DACx));
|
||||
assert_param(IS_DAC_ALIGN(DAC_Align));
|
||||
assert_param(IS_DAC_DATA(Data1));
|
||||
assert_param(IS_DAC_DATA(Data2));
|
||||
|
||||
/* Calculate and set dual DAC data holding register value */
|
||||
if (DAC_Align == DAC_Align_8b_R)
|
||||
{
|
||||
data = ((uint32_t)Data2 << 8) | Data1;
|
||||
}
|
||||
else
|
||||
{
|
||||
data = ((uint32_t)Data2 << 16) | Data1;
|
||||
}
|
||||
|
||||
tmp = (uint32_t)DACx;
|
||||
tmp += DHR12RD_OFFSET + DAC_Align;
|
||||
|
||||
/* Set the dual DAC selected data holding register */
|
||||
*(__IO uint32_t *)tmp = data;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Returns the last data output value of the selected DAC channel.
|
||||
* @param DACx: where x can be 1 or 2 to select the DAC peripheral.
|
||||
* @param DAC_Channel: the selected DAC channel.
|
||||
* This parameter can be one of the following values:
|
||||
* @arg DAC_Channel_1: DAC Channel1 selected
|
||||
* @arg DAC_Channel_2: DAC Channel2 selected
|
||||
* @retval The selected DAC channel data output value.
|
||||
*/
|
||||
uint16_t DAC_GetDataOutputValue(DAC_TypeDef* DACx, uint32_t DAC_Channel)
|
||||
{
|
||||
__IO uint32_t tmp = 0;
|
||||
|
||||
/* Check the parameters */
|
||||
assert_param(IS_DAC_ALL_PERIPH(DACx));
|
||||
assert_param(IS_DAC_CHANNEL(DAC_Channel));
|
||||
|
||||
tmp = (uint32_t) DACx;
|
||||
tmp += DOR_OFFSET + ((uint32_t)DAC_Channel >> 2);
|
||||
|
||||
/* Returns the DAC channel data output register value */
|
||||
return (uint16_t) (*(__IO uint32_t*) tmp);
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/** @defgroup DAC_Group2 DMA management functions
|
||||
* @brief DMA management functions
|
||||
*
|
||||
@verbatim
|
||||
===============================================================================
|
||||
##### DMA management functions #####
|
||||
===============================================================================
|
||||
|
||||
@endverbatim
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief Enables or disables the specified DAC channel DMA request.
|
||||
* When enabled DMA1 is generated when an external trigger (EXTI Line9,
|
||||
* TIM2, TIM4, TIM6, TIM7 or TIM9 but not a software trigger) occurs
|
||||
* @param DACx: where x can be 1 or 2 to select the DAC peripheral.
|
||||
* @param DAC_Channel: the selected DAC channel.
|
||||
* This parameter can be one of the following values:
|
||||
* @arg DAC_Channel_1: DAC Channel1 selected
|
||||
* @arg DAC_Channel_2: DAC Channel2 selected
|
||||
* @param NewState: new state of the selected DAC channel DMA request.
|
||||
* This parameter can be: ENABLE or DISABLE.
|
||||
* @note The DAC channel1 (channel2) is mapped on DMA1 channel3 (channel4) which
|
||||
* must be already configured.
|
||||
* @retval None
|
||||
*/
|
||||
void DAC_DMACmd(DAC_TypeDef* DACx, uint32_t DAC_Channel, FunctionalState NewState)
|
||||
{
|
||||
/* Check the parameters */
|
||||
assert_param(IS_DAC_ALL_PERIPH(DACx));
|
||||
assert_param(IS_DAC_CHANNEL(DAC_Channel));
|
||||
assert_param(IS_FUNCTIONAL_STATE(NewState));
|
||||
|
||||
if (NewState != DISABLE)
|
||||
{
|
||||
/* Enable the selected DAC channel DMA request */
|
||||
DACx->CR |= (DAC_CR_DMAEN1 << DAC_Channel);
|
||||
}
|
||||
else
|
||||
{
|
||||
/* Disable the selected DAC channel DMA request */
|
||||
DACx->CR &= (~(DAC_CR_DMAEN1 << DAC_Channel));
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/** @defgroup DAC_Group3 Interrupts and flags management functions
|
||||
* @brief Interrupts and flags management functions
|
||||
*
|
||||
@verbatim
|
||||
===============================================================================
|
||||
##### Interrupts and flags management functions #####
|
||||
===============================================================================
|
||||
|
||||
@endverbatim
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief Enables or disables the specified DAC interrupts.
|
||||
* @param DACx: where x can be 1 or 2 to select the DAC peripheral.
|
||||
* @param DAC_Channel: the selected DAC channel.
|
||||
* This parameter can be one of the following values:
|
||||
* @arg DAC_Channel_1: DAC Channel1 selected
|
||||
* @arg DAC_Channel_2: DAC Channel2 selected
|
||||
* @param DAC_IT: specifies the DAC interrupt sources to be enabled or disabled.
|
||||
* This parameter can be:
|
||||
* @arg DAC_IT_DMAUDR: DMA underrun interrupt mask
|
||||
* @note The DMA underrun occurs when a second external trigger arrives before
|
||||
* the acknowledgement for the first external trigger is received (first request).
|
||||
* @param NewState: new state of the specified DAC interrupts.
|
||||
* This parameter can be: ENABLE or DISABLE.
|
||||
* @retval None
|
||||
*/
|
||||
void DAC_ITConfig(DAC_TypeDef* DACx, uint32_t DAC_Channel, uint32_t DAC_IT, FunctionalState NewState)
|
||||
{
|
||||
/* Check the parameters */
|
||||
assert_param(IS_DAC_ALL_PERIPH(DACx));
|
||||
assert_param(IS_DAC_CHANNEL(DAC_Channel));
|
||||
assert_param(IS_FUNCTIONAL_STATE(NewState));
|
||||
assert_param(IS_DAC_IT(DAC_IT));
|
||||
|
||||
if (NewState != DISABLE)
|
||||
{
|
||||
/* Enable the selected DAC interrupts */
|
||||
DACx->CR |= (DAC_IT << DAC_Channel);
|
||||
}
|
||||
else
|
||||
{
|
||||
/* Disable the selected DAC interrupts */
|
||||
DACx->CR &= (~(uint32_t)(DAC_IT << DAC_Channel));
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Checks whether the specified DAC flag is set or not.
|
||||
* @param DACx: where x can be 1 or 2 to select the DAC peripheral.
|
||||
* @param DAC_Channel: thee selected DAC channel.
|
||||
* This parameter can be one of the following values:
|
||||
* @arg DAC_Channel_1: DAC Channel1 selected
|
||||
* @arg DAC_Channel_2: DAC Channel2 selected
|
||||
* @param DAC_FLAG: specifies the flag to check.
|
||||
* This parameter can be:
|
||||
* @arg DAC_FLAG_DMAUDR: DMA underrun flag
|
||||
* @note The DMA underrun occurs when a second external trigger arrives before
|
||||
* the acknowledgement for the first external trigger is received (first request).
|
||||
* @retval The new state of DAC_FLAG (SET or RESET).
|
||||
*/
|
||||
FlagStatus DAC_GetFlagStatus(DAC_TypeDef* DACx, uint32_t DAC_Channel, uint32_t DAC_FLAG)
|
||||
{
|
||||
FlagStatus bitstatus = RESET;
|
||||
|
||||
/* Check the parameters */
|
||||
assert_param(IS_DAC_ALL_PERIPH(DACx));
|
||||
assert_param(IS_DAC_CHANNEL(DAC_Channel));
|
||||
assert_param(IS_DAC_FLAG(DAC_FLAG));
|
||||
|
||||
/* Check the status of the specified DAC flag */
|
||||
if ((DACx->SR & (DAC_FLAG << DAC_Channel)) != (uint8_t)RESET)
|
||||
{
|
||||
/* DAC_FLAG is set */
|
||||
bitstatus = SET;
|
||||
}
|
||||
else
|
||||
{
|
||||
/* DAC_FLAG is reset */
|
||||
bitstatus = RESET;
|
||||
}
|
||||
/* Return the DAC_FLAG status */
|
||||
return bitstatus;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Clears the DAC channel's pending flags.
|
||||
* @param DACx: where x can be 1 or 2 to select the DAC peripheral.
|
||||
* @param DAC_Channel: the selected DAC channel.
|
||||
* This parameter can be one of the following values:
|
||||
* @arg DAC_Channel_1: DAC Channel1 selected
|
||||
* @arg DAC_Channel_2: DAC Channel2 selected
|
||||
* @param DAC_FLAG: specifies the flag to clear.
|
||||
* This parameter can be:
|
||||
* @arg DAC_FLAG_DMAUDR: DMA underrun flag
|
||||
* @retval None
|
||||
*/
|
||||
void DAC_ClearFlag(DAC_TypeDef* DACx, uint32_t DAC_Channel, uint32_t DAC_FLAG)
|
||||
{
|
||||
/* Check the parameters */
|
||||
assert_param(IS_DAC_ALL_PERIPH(DACx));
|
||||
assert_param(IS_DAC_CHANNEL(DAC_Channel));
|
||||
assert_param(IS_DAC_FLAG(DAC_FLAG));
|
||||
|
||||
/* Clear the selected DAC flags */
|
||||
DACx->SR = (DAC_FLAG << DAC_Channel);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Checks whether the specified DAC interrupt has occurred or not.
|
||||
* @param DACx: where x can be 1 or 2 to select the DAC peripheral.
|
||||
* @param DAC_Channel: the selected DAC channel.
|
||||
* This parameter can be one of the following values:
|
||||
* @arg DAC_Channel_1: DAC Channel1 selected
|
||||
* @arg DAC_Channel_2: DAC Channel2 selected
|
||||
* @param DAC_IT: specifies the DAC interrupt source to check.
|
||||
* This parameter can be:
|
||||
* @arg DAC_IT_DMAUDR: DMA underrun interrupt mask
|
||||
* @note The DMA underrun occurs when a second external trigger arrives before
|
||||
* the acknowledgement for the first external trigger is received (first request).
|
||||
* @retval The new state of DAC_IT (SET or RESET).
|
||||
*/
|
||||
ITStatus DAC_GetITStatus(DAC_TypeDef* DACx, uint32_t DAC_Channel, uint32_t DAC_IT)
|
||||
{
|
||||
ITStatus bitstatus = RESET;
|
||||
uint32_t enablestatus = 0;
|
||||
|
||||
/* Check the parameters */
|
||||
assert_param(IS_DAC_ALL_PERIPH(DACx));
|
||||
assert_param(IS_DAC_CHANNEL(DAC_Channel));
|
||||
assert_param(IS_DAC_IT(DAC_IT));
|
||||
|
||||
/* Get the DAC_IT enable bit status */
|
||||
enablestatus = (DACx->CR & (DAC_IT << DAC_Channel)) ;
|
||||
|
||||
/* Check the status of the specified DAC interrupt */
|
||||
if (((DACx->SR & (DAC_IT << DAC_Channel)) != (uint32_t)RESET) && enablestatus)
|
||||
{
|
||||
/* DAC_IT is set */
|
||||
bitstatus = SET;
|
||||
}
|
||||
else
|
||||
{
|
||||
/* DAC_IT is reset */
|
||||
bitstatus = RESET;
|
||||
}
|
||||
/* Return the DAC_IT status */
|
||||
return bitstatus;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Clears the DAC channel's interrupt pending bits.
|
||||
* @param DACx: where x can be 1 or 2 to select the DAC peripheral.
|
||||
* @param DAC_Channel: the selected DAC channel.
|
||||
* This parameter can be one of the following values:
|
||||
* @arg DAC_Channel_1: DAC Channel1 selected
|
||||
* @arg DAC_Channel_2: DAC Channel2 selected
|
||||
* @param DAC_IT: specifies the DAC interrupt pending bit to clear.
|
||||
* This parameter can be the following values:
|
||||
* @arg DAC_IT_DMAUDR: DMA underrun interrupt mask
|
||||
* @retval None
|
||||
*/
|
||||
void DAC_ClearITPendingBit(DAC_TypeDef* DACx, uint32_t DAC_Channel, uint32_t DAC_IT)
|
||||
{
|
||||
/* Check the parameters */
|
||||
assert_param(IS_DAC_ALL_PERIPH(DACx));
|
||||
assert_param(IS_DAC_CHANNEL(DAC_Channel));
|
||||
assert_param(IS_DAC_IT(DAC_IT));
|
||||
|
||||
/* Clear the selected DAC interrupt pending bits */
|
||||
DACx->SR = (DAC_IT << DAC_Channel);
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
||||
|
|
@ -0,0 +1,213 @@
|
|||
/**
|
||||
******************************************************************************
|
||||
* @file stm32f30x_dbgmcu.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 Debug MCU (DBGMCU) peripheral:
|
||||
* + Device and Revision ID management
|
||||
* + Peripherals Configuration
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© 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_dbgmcu.h"
|
||||
|
||||
/** @addtogroup STM32F30x_StdPeriph_Driver
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @defgroup DBGMCU
|
||||
* @brief DBGMCU driver modules
|
||||
* @{
|
||||
*/
|
||||
|
||||
/* Private typedef -----------------------------------------------------------*/
|
||||
/* Private define ------------------------------------------------------------*/
|
||||
#define IDCODE_DEVID_MASK ((uint32_t)0x00000FFF)
|
||||
|
||||
/* Private macro -------------------------------------------------------------*/
|
||||
/* Private variables ---------------------------------------------------------*/
|
||||
/* Private function prototypes -----------------------------------------------*/
|
||||
/* Private functions ---------------------------------------------------------*/
|
||||
|
||||
/** @defgroup DBGMCU_Private_Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @defgroup DBGMCU_Group1 Device and Revision ID management functions
|
||||
* @brief Device and Revision ID management functions
|
||||
*
|
||||
@verbatim
|
||||
==============================================================================
|
||||
##### Device and Revision ID management functions #####
|
||||
==============================================================================
|
||||
|
||||
@endverbatim
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief Returns the device revision identifier.
|
||||
* @param None
|
||||
* @retval Device revision identifier
|
||||
*/
|
||||
uint32_t DBGMCU_GetREVID(void)
|
||||
{
|
||||
return(DBGMCU->IDCODE >> 16);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Returns the device identifier.
|
||||
* @param None
|
||||
* @retval Device identifier
|
||||
*/
|
||||
uint32_t DBGMCU_GetDEVID(void)
|
||||
{
|
||||
return(DBGMCU->IDCODE & IDCODE_DEVID_MASK);
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/** @defgroup DBGMCU_Group2 Peripherals Configuration functions
|
||||
* @brief Peripherals Configuration
|
||||
*
|
||||
@verbatim
|
||||
==============================================================================
|
||||
##### Peripherals Configuration functions #####
|
||||
==============================================================================
|
||||
|
||||
@endverbatim
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief Configures low power mode behavior when the MCU is in Debug mode.
|
||||
* @param DBGMCU_Periph: specifies the low power mode.
|
||||
* This parameter can be any combination of the following values:
|
||||
* @arg DBGMCU_SLEEP: Keep debugger connection during SLEEP mode.
|
||||
* @arg DBGMCU_STOP: Keep debugger connection during STOP mode.
|
||||
* @arg DBGMCU_STANDBY: Keep debugger connection during STANDBY mode.
|
||||
* @param NewState: new state of the specified low power mode in Debug mode.
|
||||
* This parameter can be: ENABLE or DISABLE.
|
||||
* @retval None
|
||||
*/
|
||||
void DBGMCU_Config(uint32_t DBGMCU_Periph, FunctionalState NewState)
|
||||
{
|
||||
/* Check the parameters */
|
||||
assert_param(IS_DBGMCU_PERIPH(DBGMCU_Periph));
|
||||
assert_param(IS_FUNCTIONAL_STATE(NewState));
|
||||
if (NewState != DISABLE)
|
||||
{
|
||||
DBGMCU->CR |= DBGMCU_Periph;
|
||||
}
|
||||
else
|
||||
{
|
||||
DBGMCU->CR &= ~DBGMCU_Periph;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Configures APB1 peripheral behavior when the MCU is in Debug mode.
|
||||
* @param DBGMCU_Periph: specifies the APB1 peripheral.
|
||||
* This parameter can be any combination of the following values:
|
||||
* @arg DBGMCU_TIM2_STOP: TIM2 counter stopped when Core is halted.
|
||||
* @arg DBGMCU_TIM3_STOP: TIM3 counter stopped when Core is halted.
|
||||
* @arg DBGMCU_TIM4_STOP: TIM4 counter stopped when Core is halted.
|
||||
* @arg DBGMCU_TIM6_STOP: TIM6 counter stopped when Core is halted.
|
||||
* @arg DBGMCU_TIM7_STOP: TIM7 counter stopped when Core is halted.
|
||||
* @arg DBGMCU_RTC_STOP: RTC Calendar and Wakeup counter are stopped when
|
||||
* Core is halted.
|
||||
* @arg DBGMCU_WWDG_STOP: Debug WWDG stopped when Core is halted.
|
||||
* @arg DBGMCU_IWDG_STOP: Debug IWDG stopped when Core is halted.
|
||||
* @arg DBGMCU_I2C1_SMBUS_TIMEOUT: I2C1 SMBUS timeout mode stopped when
|
||||
* Core is halted.
|
||||
* @arg DBGMCU_I2C2_SMBUS_TIMEOUT: I2C2 SMBUS timeout mode stopped when
|
||||
* Core is halted.
|
||||
* @arg DBGMCU_CAN1_STOP: Debug CAN2 stopped when Core is halted.
|
||||
* @param NewState: new state of the specified APB1 peripheral in Debug mode.
|
||||
* This parameter can be: ENABLE or DISABLE.
|
||||
* @retval None
|
||||
*/
|
||||
void DBGMCU_APB1PeriphConfig(uint32_t DBGMCU_Periph, FunctionalState NewState)
|
||||
{
|
||||
/* Check the parameters */
|
||||
assert_param(IS_DBGMCU_APB1PERIPH(DBGMCU_Periph));
|
||||
assert_param(IS_FUNCTIONAL_STATE(NewState));
|
||||
|
||||
if (NewState != DISABLE)
|
||||
{
|
||||
DBGMCU->APB1FZ |= DBGMCU_Periph;
|
||||
}
|
||||
else
|
||||
{
|
||||
DBGMCU->APB1FZ &= ~DBGMCU_Periph;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Configures APB2 peripheral behavior when the MCU is in Debug mode.
|
||||
* @param DBGMCU_Periph: specifies the APB2 peripheral.
|
||||
* This parameter can be any combination of the following values:
|
||||
* @arg DBGMCU_TIM1_STOP: TIM1 counter stopped when Core is halted.
|
||||
* @arg DBGMCU_TIM8_STOP: TIM8 counter stopped when Core is halted.
|
||||
* @arg DBGMCU_TIM15_STOP: TIM15 counter stopped when Core is halted.
|
||||
* @arg DBGMCU_TIM16_STOP: TIM16 counter stopped when Core is halted.
|
||||
* @arg DBGMCU_TIM17_STOP: TIM17 counter stopped when Core is halted.
|
||||
* @param NewState: new state of the specified APB2 peripheral in Debug mode.
|
||||
* This parameter can be: ENABLE or DISABLE.
|
||||
* @retval None
|
||||
*/
|
||||
void DBGMCU_APB2PeriphConfig(uint32_t DBGMCU_Periph, FunctionalState NewState)
|
||||
{
|
||||
/* Check the parameters */
|
||||
assert_param(IS_DBGMCU_APB2PERIPH(DBGMCU_Periph));
|
||||
assert_param(IS_FUNCTIONAL_STATE(NewState));
|
||||
|
||||
if (NewState != DISABLE)
|
||||
{
|
||||
DBGMCU->APB2FZ |= DBGMCU_Periph;
|
||||
}
|
||||
else
|
||||
{
|
||||
DBGMCU->APB2FZ &= ~DBGMCU_Periph;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
|
@ -0,0 +1,866 @@
|
|||
/**
|
||||
******************************************************************************
|
||||
* @file stm32f30x_dma.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 Direct Memory Access controller (DMA):
|
||||
* + Initialization and Configuration
|
||||
* + Data Counter
|
||||
* + Interrupts and flags management
|
||||
*
|
||||
@verbatim
|
||||
|
||||
===============================================================================
|
||||
##### How to use this driver #####
|
||||
===============================================================================
|
||||
[..]
|
||||
(#) Enable The DMA controller clock using
|
||||
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1, ENABLE) function for DMA1 or
|
||||
using RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA2, ENABLE) function for DMA2.
|
||||
(#) Enable and configure the peripheral to be connected to the DMA channel
|
||||
(except for internal SRAM / FLASH memories: no initialization is necessary).
|
||||
(#) For a given Channel, program the Source and Destination addresses,
|
||||
the transfer Direction, the Buffer Size, the Peripheral and Memory
|
||||
Incrementation mode and Data Size, the Circular or Normal mode,
|
||||
the channel transfer Priority and the Memory-to-Memory transfer
|
||||
mode (if needed) using the DMA_Init() function.
|
||||
(#) Enable the NVIC and the corresponding interrupt(s) using the function
|
||||
DMA_ITConfig() if you need to use DMA interrupts.
|
||||
(#) Enable the DMA channel using the DMA_Cmd() function.
|
||||
(#) Activate the needed channel Request using PPP_DMACmd() function for
|
||||
any PPP peripheral except internal SRAM and FLASH (ie. SPI, USART ...)
|
||||
The function allowing this operation is provided in each PPP peripheral
|
||||
driver (ie. SPI_DMACmd for SPI peripheral).
|
||||
(#) Optionally, you can configure the number of data to be transferred
|
||||
when the channel is disabled (ie. after each Transfer Complete event
|
||||
or when a Transfer Error occurs) using the function DMA_SetCurrDataCounter().
|
||||
And you can get the number of remaining data to be transferred using
|
||||
the function DMA_GetCurrDataCounter() at run time (when the DMA channel is
|
||||
enabled and running).
|
||||
(#) To control DMA events you can use one of the following two methods:
|
||||
(##) Check on DMA channel flags using the function DMA_GetFlagStatus().
|
||||
(##) Use DMA interrupts through the function DMA_ITConfig() at initialization
|
||||
phase and DMA_GetITStatus() function into interrupt routines in
|
||||
communication phase.
|
||||
After checking on a flag you should clear it using DMA_ClearFlag()
|
||||
function. And after checking on an interrupt event you should
|
||||
clear it using DMA_ClearITPendingBit() function.
|
||||
|
||||
@endverbatim
|
||||
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© 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_dma.h"
|
||||
|
||||
/** @addtogroup STM32F30x_StdPeriph_Driver
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @defgroup DMA
|
||||
* @brief DMA driver modules
|
||||
* @{
|
||||
*/
|
||||
|
||||
/* Private typedef -----------------------------------------------------------*/
|
||||
/* Private define ------------------------------------------------------------*/
|
||||
#define CCR_CLEAR_MASK ((uint32_t)0xFFFF800F) /* DMA Channel config registers Masks */
|
||||
#define FLAG_Mask ((uint32_t)0x10000000) /* DMA2 FLAG mask */
|
||||
|
||||
|
||||
/* DMA1 Channelx interrupt pending bit masks */
|
||||
#define DMA1_CHANNEL1_IT_MASK ((uint32_t)(DMA_ISR_GIF1 | DMA_ISR_TCIF1 | DMA_ISR_HTIF1 | DMA_ISR_TEIF1))
|
||||
#define DMA1_CHANNEL2_IT_MASK ((uint32_t)(DMA_ISR_GIF2 | DMA_ISR_TCIF2 | DMA_ISR_HTIF2 | DMA_ISR_TEIF2))
|
||||
#define DMA1_CHANNEL3_IT_MASK ((uint32_t)(DMA_ISR_GIF3 | DMA_ISR_TCIF3 | DMA_ISR_HTIF3 | DMA_ISR_TEIF3))
|
||||
#define DMA1_CHANNEL4_IT_MASK ((uint32_t)(DMA_ISR_GIF4 | DMA_ISR_TCIF4 | DMA_ISR_HTIF4 | DMA_ISR_TEIF4))
|
||||
#define DMA1_CHANNEL5_IT_MASK ((uint32_t)(DMA_ISR_GIF5 | DMA_ISR_TCIF5 | DMA_ISR_HTIF5 | DMA_ISR_TEIF5))
|
||||
#define DMA1_CHANNEL6_IT_MASK ((uint32_t)(DMA_ISR_GIF6 | DMA_ISR_TCIF6 | DMA_ISR_HTIF6 | DMA_ISR_TEIF6))
|
||||
#define DMA1_CHANNEL7_IT_MASK ((uint32_t)(DMA_ISR_GIF7 | DMA_ISR_TCIF7 | DMA_ISR_HTIF7 | DMA_ISR_TEIF7))
|
||||
|
||||
/* DMA2 Channelx interrupt pending bit masks */
|
||||
#define DMA2_CHANNEL1_IT_MASK ((uint32_t)(DMA_ISR_GIF1 | DMA_ISR_TCIF1 | DMA_ISR_HTIF1 | DMA_ISR_TEIF1))
|
||||
#define DMA2_CHANNEL2_IT_MASK ((uint32_t)(DMA_ISR_GIF2 | DMA_ISR_TCIF2 | DMA_ISR_HTIF2 | DMA_ISR_TEIF2))
|
||||
#define DMA2_CHANNEL3_IT_MASK ((uint32_t)(DMA_ISR_GIF3 | DMA_ISR_TCIF3 | DMA_ISR_HTIF3 | DMA_ISR_TEIF3))
|
||||
#define DMA2_CHANNEL4_IT_MASK ((uint32_t)(DMA_ISR_GIF4 | DMA_ISR_TCIF4 | DMA_ISR_HTIF4 | DMA_ISR_TEIF4))
|
||||
#define DMA2_CHANNEL5_IT_MASK ((uint32_t)(DMA_ISR_GIF5 | DMA_ISR_TCIF5 | DMA_ISR_HTIF5 | DMA_ISR_TEIF5))
|
||||
|
||||
/* Private macro -------------------------------------------------------------*/
|
||||
/* Private variables ---------------------------------------------------------*/
|
||||
/* Private function prototypes -----------------------------------------------*/
|
||||
/* Private functions ---------------------------------------------------------*/
|
||||
|
||||
/** @defgroup DMA_Private_Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @defgroup DMA_Group1 Initialization and Configuration functions
|
||||
* @brief Initialization and Configuration functions
|
||||
*
|
||||
@verbatim
|
||||
===============================================================================
|
||||
##### Initialization and Configuration functions #####
|
||||
===============================================================================
|
||||
[..] This subsection provides functions allowing to initialize the DMA channel
|
||||
source and destination addresses, incrementation and data sizes, transfer
|
||||
direction, buffer size, circular/normal mode selection, memory-to-memory
|
||||
mode selection and channel priority value.
|
||||
[..] The DMA_Init() function follows the DMA configuration procedures as described
|
||||
in reference manual (RM00316).
|
||||
|
||||
@endverbatim
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief Deinitializes the DMAy Channelx registers to their default reset
|
||||
* values.
|
||||
* @param DMAy_Channelx: where y can be 1 or 2 to select the DMA and
|
||||
* x can be 1 to 7 for DMA1 and 1 to 5 for DMA2 to select the DMA Channel.
|
||||
* @retval None
|
||||
*/
|
||||
void DMA_DeInit(DMA_Channel_TypeDef* DMAy_Channelx)
|
||||
{
|
||||
/* Check the parameters */
|
||||
assert_param(IS_DMA_ALL_PERIPH(DMAy_Channelx));
|
||||
|
||||
/* Disable the selected DMAy Channelx */
|
||||
DMAy_Channelx->CCR &= (uint16_t)(~DMA_CCR_EN);
|
||||
|
||||
/* Reset DMAy Channelx control register */
|
||||
DMAy_Channelx->CCR = 0;
|
||||
|
||||
/* Reset DMAy Channelx remaining bytes register */
|
||||
DMAy_Channelx->CNDTR = 0;
|
||||
|
||||
/* Reset DMAy Channelx peripheral address register */
|
||||
DMAy_Channelx->CPAR = 0;
|
||||
|
||||
/* Reset DMAy Channelx memory address register */
|
||||
DMAy_Channelx->CMAR = 0;
|
||||
|
||||
if (DMAy_Channelx == DMA1_Channel1)
|
||||
{
|
||||
/* Reset interrupt pending bits for DMA1 Channel1 */
|
||||
DMA1->IFCR |= DMA1_CHANNEL1_IT_MASK;
|
||||
}
|
||||
else if (DMAy_Channelx == DMA1_Channel2)
|
||||
{
|
||||
/* Reset interrupt pending bits for DMA1 Channel2 */
|
||||
DMA1->IFCR |= DMA1_CHANNEL2_IT_MASK;
|
||||
}
|
||||
else if (DMAy_Channelx == DMA1_Channel3)
|
||||
{
|
||||
/* Reset interrupt pending bits for DMA1 Channel3 */
|
||||
DMA1->IFCR |= DMA1_CHANNEL3_IT_MASK;
|
||||
}
|
||||
else if (DMAy_Channelx == DMA1_Channel4)
|
||||
{
|
||||
/* Reset interrupt pending bits for DMA1 Channel4 */
|
||||
DMA1->IFCR |= DMA1_CHANNEL4_IT_MASK;
|
||||
}
|
||||
else if (DMAy_Channelx == DMA1_Channel5)
|
||||
{
|
||||
/* Reset interrupt pending bits for DMA1 Channel5 */
|
||||
DMA1->IFCR |= DMA1_CHANNEL5_IT_MASK;
|
||||
}
|
||||
else if (DMAy_Channelx == DMA1_Channel6)
|
||||
{
|
||||
/* Reset interrupt pending bits for DMA1 Channel6 */
|
||||
DMA1->IFCR |= DMA1_CHANNEL6_IT_MASK;
|
||||
}
|
||||
else if (DMAy_Channelx == DMA1_Channel7)
|
||||
{
|
||||
/* Reset interrupt pending bits for DMA1 Channel7 */
|
||||
DMA1->IFCR |= DMA1_CHANNEL7_IT_MASK;
|
||||
}
|
||||
else if (DMAy_Channelx == DMA2_Channel1)
|
||||
{
|
||||
/* Reset interrupt pending bits for DMA2 Channel1 */
|
||||
DMA2->IFCR |= DMA2_CHANNEL1_IT_MASK;
|
||||
}
|
||||
else if (DMAy_Channelx == DMA2_Channel2)
|
||||
{
|
||||
/* Reset interrupt pending bits for DMA2 Channel2 */
|
||||
DMA2->IFCR |= DMA2_CHANNEL2_IT_MASK;
|
||||
}
|
||||
else if (DMAy_Channelx == DMA2_Channel3)
|
||||
{
|
||||
/* Reset interrupt pending bits for DMA2 Channel3 */
|
||||
DMA2->IFCR |= DMA2_CHANNEL3_IT_MASK;
|
||||
}
|
||||
else if (DMAy_Channelx == DMA2_Channel4)
|
||||
{
|
||||
/* Reset interrupt pending bits for DMA2 Channel4 */
|
||||
DMA2->IFCR |= DMA2_CHANNEL4_IT_MASK;
|
||||
}
|
||||
else
|
||||
{
|
||||
if (DMAy_Channelx == DMA2_Channel5)
|
||||
{
|
||||
/* Reset interrupt pending bits for DMA2 Channel5 */
|
||||
DMA2->IFCR |= DMA2_CHANNEL5_IT_MASK;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Initializes the DMAy Channelx according to the specified parameters
|
||||
* in the DMA_InitStruct.
|
||||
* @param DMAy_Channelx: where y can be 1 or 2 to select the DMA and
|
||||
* x can be 1 to 7 for DMA1 and 1 to 5 for DMA2 to select the DMA Channel.
|
||||
* @param DMA_InitStruct: pointer to a DMA_InitTypeDef structure that contains
|
||||
* the configuration information for the specified DMA Channel.
|
||||
* @retval None
|
||||
*/
|
||||
void DMA_Init(DMA_Channel_TypeDef* DMAy_Channelx, DMA_InitTypeDef* DMA_InitStruct)
|
||||
{
|
||||
uint32_t tmpreg = 0;
|
||||
|
||||
/* Check the parameters */
|
||||
assert_param(IS_DMA_ALL_PERIPH(DMAy_Channelx));
|
||||
assert_param(IS_DMA_DIR(DMA_InitStruct->DMA_DIR));
|
||||
assert_param(IS_DMA_PERIPHERAL_INC_STATE(DMA_InitStruct->DMA_PeripheralInc));
|
||||
assert_param(IS_DMA_MEMORY_INC_STATE(DMA_InitStruct->DMA_MemoryInc));
|
||||
assert_param(IS_DMA_PERIPHERAL_DATA_SIZE(DMA_InitStruct->DMA_PeripheralDataSize));
|
||||
assert_param(IS_DMA_MEMORY_DATA_SIZE(DMA_InitStruct->DMA_MemoryDataSize));
|
||||
assert_param(IS_DMA_MODE(DMA_InitStruct->DMA_Mode));
|
||||
assert_param(IS_DMA_PRIORITY(DMA_InitStruct->DMA_Priority));
|
||||
assert_param(IS_DMA_M2M_STATE(DMA_InitStruct->DMA_M2M));
|
||||
|
||||
/*--------------------------- DMAy Channelx CCR Configuration ----------------*/
|
||||
/* Get the DMAy_Channelx CCR value */
|
||||
tmpreg = DMAy_Channelx->CCR;
|
||||
|
||||
/* Clear MEM2MEM, PL, MSIZE, PSIZE, MINC, PINC, CIRC and DIR bits */
|
||||
tmpreg &= CCR_CLEAR_MASK;
|
||||
|
||||
/* Configure DMAy Channelx: data transfer, data size, priority level and mode */
|
||||
/* Set DIR bit according to DMA_DIR value */
|
||||
/* Set CIRC bit according to DMA_Mode value */
|
||||
/* Set PINC bit according to DMA_PeripheralInc value */
|
||||
/* Set MINC bit according to DMA_MemoryInc value */
|
||||
/* Set PSIZE bits according to DMA_PeripheralDataSize value */
|
||||
/* Set MSIZE bits according to DMA_MemoryDataSize value */
|
||||
/* Set PL bits according to DMA_Priority value */
|
||||
/* Set the MEM2MEM bit according to DMA_M2M value */
|
||||
tmpreg |= DMA_InitStruct->DMA_DIR | DMA_InitStruct->DMA_Mode |
|
||||
DMA_InitStruct->DMA_PeripheralInc | DMA_InitStruct->DMA_MemoryInc |
|
||||
DMA_InitStruct->DMA_PeripheralDataSize | DMA_InitStruct->DMA_MemoryDataSize |
|
||||
DMA_InitStruct->DMA_Priority | DMA_InitStruct->DMA_M2M;
|
||||
|
||||
/* Write to DMAy Channelx CCR */
|
||||
DMAy_Channelx->CCR = tmpreg;
|
||||
|
||||
/*--------------------------- DMAy Channelx CNDTR Configuration --------------*/
|
||||
/* Write to DMAy Channelx CNDTR */
|
||||
DMAy_Channelx->CNDTR = DMA_InitStruct->DMA_BufferSize;
|
||||
|
||||
/*--------------------------- DMAy Channelx CPAR Configuration ---------------*/
|
||||
/* Write to DMAy Channelx CPAR */
|
||||
DMAy_Channelx->CPAR = DMA_InitStruct->DMA_PeripheralBaseAddr;
|
||||
|
||||
/*--------------------------- DMAy Channelx CMAR Configuration ---------------*/
|
||||
/* Write to DMAy Channelx CMAR */
|
||||
DMAy_Channelx->CMAR = DMA_InitStruct->DMA_MemoryBaseAddr;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Fills each DMA_InitStruct member with its default value.
|
||||
* @param DMA_InitStruct: pointer to a DMA_InitTypeDef structure which will
|
||||
* be initialized.
|
||||
* @retval None
|
||||
*/
|
||||
void DMA_StructInit(DMA_InitTypeDef* DMA_InitStruct)
|
||||
{
|
||||
/*-------------- Reset DMA init structure parameters values ------------------*/
|
||||
/* Initialize the DMA_PeripheralBaseAddr member */
|
||||
DMA_InitStruct->DMA_PeripheralBaseAddr = 0;
|
||||
/* Initialize the DMA_MemoryBaseAddr member */
|
||||
DMA_InitStruct->DMA_MemoryBaseAddr = 0;
|
||||
/* Initialize the DMA_DIR member */
|
||||
DMA_InitStruct->DMA_DIR = DMA_DIR_PeripheralSRC;
|
||||
/* Initialize the DMA_BufferSize member */
|
||||
DMA_InitStruct->DMA_BufferSize = 0;
|
||||
/* Initialize the DMA_PeripheralInc member */
|
||||
DMA_InitStruct->DMA_PeripheralInc = DMA_PeripheralInc_Disable;
|
||||
/* Initialize the DMA_MemoryInc member */
|
||||
DMA_InitStruct->DMA_MemoryInc = DMA_MemoryInc_Disable;
|
||||
/* Initialize the DMA_PeripheralDataSize member */
|
||||
DMA_InitStruct->DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte;
|
||||
/* Initialize the DMA_MemoryDataSize member */
|
||||
DMA_InitStruct->DMA_MemoryDataSize = DMA_MemoryDataSize_Byte;
|
||||
/* Initialize the DMA_Mode member */
|
||||
DMA_InitStruct->DMA_Mode = DMA_Mode_Normal;
|
||||
/* Initialize the DMA_Priority member */
|
||||
DMA_InitStruct->DMA_Priority = DMA_Priority_Low;
|
||||
/* Initialize the DMA_M2M member */
|
||||
DMA_InitStruct->DMA_M2M = DMA_M2M_Disable;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Enables or disables the specified DMAy Channelx.
|
||||
* @param DMAy_Channelx: where y can be 1 or 2 to select the DMA and
|
||||
* x can be 1 to 7 for DMA1 and 1 to 5 for DMA2 to select the DMA Channel.
|
||||
* @param NewState: new state of the DMAy Channelx.
|
||||
* This parameter can be: ENABLE or DISABLE.
|
||||
* @retval None
|
||||
*/
|
||||
void DMA_Cmd(DMA_Channel_TypeDef* DMAy_Channelx, FunctionalState NewState)
|
||||
{
|
||||
/* Check the parameters */
|
||||
assert_param(IS_DMA_ALL_PERIPH(DMAy_Channelx));
|
||||
assert_param(IS_FUNCTIONAL_STATE(NewState));
|
||||
|
||||
if (NewState != DISABLE)
|
||||
{
|
||||
/* Enable the selected DMAy Channelx */
|
||||
DMAy_Channelx->CCR |= DMA_CCR_EN;
|
||||
}
|
||||
else
|
||||
{
|
||||
/* Disable the selected DMAy Channelx */
|
||||
DMAy_Channelx->CCR &= (uint16_t)(~DMA_CCR_EN);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/** @defgroup DMA_Group2 Data Counter functions
|
||||
* @brief Data Counter functions
|
||||
*
|
||||
@verbatim
|
||||
===============================================================================
|
||||
##### Data Counter functions #####
|
||||
===============================================================================
|
||||
[..] This subsection provides function allowing to configure and read the buffer
|
||||
size (number of data to be transferred).The DMA data counter can be written
|
||||
only when the DMA channel is disabled (ie. after transfer complete event).
|
||||
[..] The following function can be used to write the Channel data counter value:
|
||||
(+) void DMA_SetCurrDataCounter(DMA_Channel_TypeDef* DMAy_Channelx, uint16_t DataNumber).
|
||||
[..]
|
||||
(@) It is advised to use this function rather than DMA_Init() in situations
|
||||
where only the Data buffer needs to be reloaded.
|
||||
[..] The DMA data counter can be read to indicate the number of remaining transfers
|
||||
for the relative DMA channel. This counter is decremented at the end of each
|
||||
data transfer and when the transfer is complete:
|
||||
(+) If Normal mode is selected: the counter is set to 0.
|
||||
(+) If Circular mode is selected: the counter is reloaded with the initial
|
||||
value(configured before enabling the DMA channel).
|
||||
[..] The following function can be used to read the Channel data counter value:
|
||||
(+) uint16_t DMA_GetCurrDataCounter(DMA_Channel_TypeDef* DMAy_Channelx).
|
||||
|
||||
@endverbatim
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief Sets the number of data units in the current DMAy Channelx transfer.
|
||||
* @param DMAy_Channelx: where y can be 1 or 2 to select the DMA and
|
||||
* x can be 1 to 7 for DMA1 and 1 to 5 for DMA2 to select the DMA Channel.
|
||||
* @param DataNumber: The number of data units in the current DMAy Channelx
|
||||
* transfer.
|
||||
* @note This function can only be used when the DMAy_Channelx is disabled.
|
||||
* @retval None.
|
||||
*/
|
||||
void DMA_SetCurrDataCounter(DMA_Channel_TypeDef* DMAy_Channelx, uint16_t DataNumber)
|
||||
{
|
||||
/* Check the parameters */
|
||||
assert_param(IS_DMA_ALL_PERIPH(DMAy_Channelx));
|
||||
|
||||
/*--------------------------- DMAy Channelx CNDTR Configuration --------------*/
|
||||
/* Write to DMAy Channelx CNDTR */
|
||||
DMAy_Channelx->CNDTR = DataNumber;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Returns the number of remaining data units in the current
|
||||
* DMAy Channelx transfer.
|
||||
* @param DMAy_Channelx: where y can be 1 or 2 to select the DMA and
|
||||
* x can be 1 to 7 for DMA1 and 1 to 5 for DMA2 to select the DMA Channel.
|
||||
* @retval The number of remaining data units in the current DMAy Channelx
|
||||
* transfer.
|
||||
*/
|
||||
uint16_t DMA_GetCurrDataCounter(DMA_Channel_TypeDef* DMAy_Channelx)
|
||||
{
|
||||
/* Check the parameters */
|
||||
assert_param(IS_DMA_ALL_PERIPH(DMAy_Channelx));
|
||||
/* Return the number of remaining data units for DMAy Channelx */
|
||||
return ((uint16_t)(DMAy_Channelx->CNDTR));
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/** @defgroup DMA_Group3 Interrupts and flags management functions
|
||||
* @brief Interrupts and flags management functions
|
||||
*
|
||||
@verbatim
|
||||
===============================================================================
|
||||
##### Interrupts and flags management functions #####
|
||||
===============================================================================
|
||||
[..] This subsection provides functions allowing to configure the DMA Interrupt
|
||||
sources and check or clear the flags or pending bits status.
|
||||
The user should identify which mode will be used in his application to manage
|
||||
the DMA controller events: Polling mode or Interrupt mode.
|
||||
|
||||
*** Polling Mode ***
|
||||
====================
|
||||
[..] Each DMA channel can be managed through 4 event Flags (y : DMA Controller
|
||||
number, x : DMA channel number):
|
||||
(#) DMAy_FLAG_TCx : to indicate that a Transfer Complete event occurred.
|
||||
(#) DMAy_FLAG_HTx : to indicate that a Half-Transfer Complete event occurred.
|
||||
(#) DMAy_FLAG_TEx : to indicate that a Transfer Error occurred.
|
||||
(#) DMAy_FLAG_GLx : to indicate that at least one of the events described
|
||||
above occurred.
|
||||
[..]
|
||||
(@) Clearing DMAy_FLAG_GLx results in clearing all other pending flags of the
|
||||
same channel (DMAy_FLAG_TCx, DMAy_FLAG_HTx and DMAy_FLAG_TEx).
|
||||
[..] In this Mode it is advised to use the following functions:
|
||||
(+) FlagStatus DMA_GetFlagStatus(uint32_t DMA_FLAG);
|
||||
(+) void DMA_ClearFlag(uint32_t DMA_FLAG);
|
||||
|
||||
*** Interrupt Mode ***
|
||||
======================
|
||||
[..] Each DMA channel can be managed through 4 Interrupts:
|
||||
(+) Interrupt Source
|
||||
(##) DMA_IT_TC: specifies the interrupt source for the Transfer Complete
|
||||
event.
|
||||
(##) DMA_IT_HT: specifies the interrupt source for the Half-transfer Complete
|
||||
event.
|
||||
(##) DMA_IT_TE: specifies the interrupt source for the transfer errors event.
|
||||
(##) DMA_IT_GL: to indicate that at least one of the interrupts described
|
||||
above occurred.
|
||||
-@@- Clearing DMA_IT_GL interrupt results in clearing all other interrupts of
|
||||
the same channel (DMA_IT_TCx, DMA_IT_HT and DMA_IT_TE).
|
||||
[..] In this Mode it is advised to use the following functions:
|
||||
(+) void DMA_ITConfig(DMA_Channel_TypeDef* DMAy_Channelx, uint32_t DMA_IT, FunctionalState NewState);
|
||||
(+) ITStatus DMA_GetITStatus(uint32_t DMA_IT);
|
||||
(+) void DMA_ClearITPendingBit(uint32_t DMA_IT);
|
||||
|
||||
@endverbatim
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief Enables or disables the specified DMAy Channelx interrupts.
|
||||
* @param DMAy_Channelx: where y can be 1 or 2 to select the DMA and
|
||||
* x can be 1 to 7 for DMA1 and 1 to 5 for DMA2 to select the DMA Channel.
|
||||
* @param DMA_IT: specifies the DMA interrupts sources to be enabled
|
||||
* or disabled.
|
||||
* This parameter can be any combination of the following values:
|
||||
* @arg DMA_IT_TC: Transfer complete interrupt mask
|
||||
* @arg DMA_IT_HT: Half transfer interrupt mask
|
||||
* @arg DMA_IT_TE: Transfer error interrupt mask
|
||||
* @param NewState: new state of the specified DMA interrupts.
|
||||
* This parameter can be: ENABLE or DISABLE.
|
||||
* @retval None
|
||||
*/
|
||||
void DMA_ITConfig(DMA_Channel_TypeDef* DMAy_Channelx, uint32_t DMA_IT, FunctionalState NewState)
|
||||
{
|
||||
/* Check the parameters */
|
||||
assert_param(IS_DMA_ALL_PERIPH(DMAy_Channelx));
|
||||
assert_param(IS_DMA_CONFIG_IT(DMA_IT));
|
||||
assert_param(IS_FUNCTIONAL_STATE(NewState));
|
||||
|
||||
if (NewState != DISABLE)
|
||||
{
|
||||
/* Enable the selected DMA interrupts */
|
||||
DMAy_Channelx->CCR |= DMA_IT;
|
||||
}
|
||||
else
|
||||
{
|
||||
/* Disable the selected DMA interrupts */
|
||||
DMAy_Channelx->CCR &= ~DMA_IT;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Checks whether the specified DMAy Channelx flag is set or not.
|
||||
* @param DMAy_FLAG: specifies the flag to check.
|
||||
* This parameter can be one of the following values:
|
||||
* @arg DMA1_FLAG_GL1: DMA1 Channel1 global flag.
|
||||
* @arg DMA1_FLAG_TC1: DMA1 Channel1 transfer complete flag.
|
||||
* @arg DMA1_FLAG_HT1: DMA1 Channel1 half transfer flag.
|
||||
* @arg DMA1_FLAG_TE1: DMA1 Channel1 transfer error flag.
|
||||
* @arg DMA1_FLAG_GL2: DMA1 Channel2 global flag.
|
||||
* @arg DMA1_FLAG_TC2: DMA1 Channel2 transfer complete flag.
|
||||
* @arg DMA1_FLAG_HT2: DMA1 Channel2 half transfer flag.
|
||||
* @arg DMA1_FLAG_TE2: DMA1 Channel2 transfer error flag.
|
||||
* @arg DMA1_FLAG_GL3: DMA1 Channel3 global flag.
|
||||
* @arg DMA1_FLAG_TC3: DMA1 Channel3 transfer complete flag.
|
||||
* @arg DMA1_FLAG_HT3: DMA1 Channel3 half transfer flag.
|
||||
* @arg DMA1_FLAG_TE3: DMA1 Channel3 transfer error flag.
|
||||
* @arg DMA1_FLAG_GL4: DMA1 Channel4 global flag.
|
||||
* @arg DMA1_FLAG_TC4: DMA1 Channel4 transfer complete flag.
|
||||
* @arg DMA1_FLAG_HT4: DMA1 Channel4 half transfer flag.
|
||||
* @arg DMA1_FLAG_TE4: DMA1 Channel4 transfer error flag.
|
||||
* @arg DMA1_FLAG_GL5: DMA1 Channel5 global flag.
|
||||
* @arg DMA1_FLAG_TC5: DMA1 Channel5 transfer complete flag.
|
||||
* @arg DMA1_FLAG_HT5: DMA1 Channel5 half transfer flag.
|
||||
* @arg DMA1_FLAG_TE5: DMA1 Channel5 transfer error flag.
|
||||
* @arg DMA1_FLAG_GL6: DMA1 Channel6 global flag.
|
||||
* @arg DMA1_FLAG_TC6: DMA1 Channel6 transfer complete flag.
|
||||
* @arg DMA1_FLAG_HT6: DMA1 Channel6 half transfer flag.
|
||||
* @arg DMA1_FLAG_TE6: DMA1 Channel6 transfer error flag.
|
||||
* @arg DMA1_FLAG_GL7: DMA1 Channel7 global flag.
|
||||
* @arg DMA1_FLAG_TC7: DMA1 Channel7 transfer complete flag.
|
||||
* @arg DMA1_FLAG_HT7: DMA1 Channel7 half transfer flag.
|
||||
* @arg DMA1_FLAG_TE7: DMA1 Channel7 transfer error flag.
|
||||
* @arg DMA2_FLAG_GL1: DMA2 Channel1 global flag.
|
||||
* @arg DMA2_FLAG_TC1: DMA2 Channel1 transfer complete flag.
|
||||
* @arg DMA2_FLAG_HT1: DMA2 Channel1 half transfer flag.
|
||||
* @arg DMA2_FLAG_TE1: DMA2 Channel1 transfer error flag.
|
||||
* @arg DMA2_FLAG_GL2: DMA2 Channel2 global flag.
|
||||
* @arg DMA2_FLAG_TC2: DMA2 Channel2 transfer complete flag.
|
||||
* @arg DMA2_FLAG_HT2: DMA2 Channel2 half transfer flag.
|
||||
* @arg DMA2_FLAG_TE2: DMA2 Channel2 transfer error flag.
|
||||
* @arg DMA2_FLAG_GL3: DMA2 Channel3 global flag.
|
||||
* @arg DMA2_FLAG_TC3: DMA2 Channel3 transfer complete flag.
|
||||
* @arg DMA2_FLAG_HT3: DMA2 Channel3 half transfer flag.
|
||||
* @arg DMA2_FLAG_TE3: DMA2 Channel3 transfer error flag.
|
||||
* @arg DMA2_FLAG_GL4: DMA2 Channel4 global flag.
|
||||
* @arg DMA2_FLAG_TC4: DMA2 Channel4 transfer complete flag.
|
||||
* @arg DMA2_FLAG_HT4: DMA2 Channel4 half transfer flag.
|
||||
* @arg DMA2_FLAG_TE4: DMA2 Channel4 transfer error flag.
|
||||
* @arg DMA2_FLAG_GL5: DMA2 Channel5 global flag.
|
||||
* @arg DMA2_FLAG_TC5: DMA2 Channel5 transfer complete flag.
|
||||
* @arg DMA2_FLAG_HT5: DMA2 Channel5 half transfer flag.
|
||||
* @arg DMA2_FLAG_TE5: DMA2 Channel5 transfer error flag.
|
||||
*
|
||||
* @note
|
||||
* The Global flag (DMAy_FLAG_GLx) is set whenever any of the other flags
|
||||
* relative to the same channel is set (Transfer Complete, Half-transfer
|
||||
* Complete or Transfer Error flags: DMAy_FLAG_TCx, DMAy_FLAG_HTx or
|
||||
* DMAy_FLAG_TEx).
|
||||
*
|
||||
* @retval The new state of DMAy_FLAG (SET or RESET).
|
||||
*/
|
||||
FlagStatus DMA_GetFlagStatus(uint32_t DMAy_FLAG)
|
||||
{
|
||||
FlagStatus bitstatus = RESET;
|
||||
uint32_t tmpreg = 0;
|
||||
|
||||
/* Check the parameters */
|
||||
assert_param(IS_DMA_GET_FLAG(DMAy_FLAG));
|
||||
|
||||
/* Calculate the used DMAy */
|
||||
if ((DMAy_FLAG & FLAG_Mask) != (uint32_t)RESET)
|
||||
{
|
||||
/* Get DMA2 ISR register value */
|
||||
tmpreg = DMA2->ISR ;
|
||||
}
|
||||
else
|
||||
{
|
||||
/* Get DMA1 ISR register value */
|
||||
tmpreg = DMA1->ISR ;
|
||||
}
|
||||
|
||||
/* Check the status of the specified DMAy flag */
|
||||
if ((tmpreg & DMAy_FLAG) != (uint32_t)RESET)
|
||||
{
|
||||
/* DMAy_FLAG is set */
|
||||
bitstatus = SET;
|
||||
}
|
||||
else
|
||||
{
|
||||
/* DMAy_FLAG is reset */
|
||||
bitstatus = RESET;
|
||||
}
|
||||
|
||||
/* Return the DMAy_FLAG status */
|
||||
return bitstatus;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Clears the DMAy Channelx's pending flags.
|
||||
* @param DMAy_FLAG: specifies the flag to clear.
|
||||
* This parameter can be any combination (for the same DMA) of the following values:
|
||||
* @arg DMA1_FLAG_GL1: DMA1 Channel1 global flag.
|
||||
* @arg DMA1_FLAG_TC1: DMA1 Channel1 transfer complete flag.
|
||||
* @arg DMA1_FLAG_HT1: DMA1 Channel1 half transfer flag.
|
||||
* @arg DMA1_FLAG_TE1: DMA1 Channel1 transfer error flag.
|
||||
* @arg DMA1_FLAG_GL2: DMA1 Channel2 global flag.
|
||||
* @arg DMA1_FLAG_TC2: DMA1 Channel2 transfer complete flag.
|
||||
* @arg DMA1_FLAG_HT2: DMA1 Channel2 half transfer flag.
|
||||
* @arg DMA1_FLAG_TE2: DMA1 Channel2 transfer error flag.
|
||||
* @arg DMA1_FLAG_GL3: DMA1 Channel3 global flag.
|
||||
* @arg DMA1_FLAG_TC3: DMA1 Channel3 transfer complete flag.
|
||||
* @arg DMA1_FLAG_HT3: DMA1 Channel3 half transfer flag.
|
||||
* @arg DMA1_FLAG_TE3: DMA1 Channel3 transfer error flag.
|
||||
* @arg DMA1_FLAG_GL4: DMA1 Channel4 global flag.
|
||||
* @arg DMA1_FLAG_TC4: DMA1 Channel4 transfer complete flag.
|
||||
* @arg DMA1_FLAG_HT4: DMA1 Channel4 half transfer flag.
|
||||
* @arg DMA1_FLAG_TE4: DMA1 Channel4 transfer error flag.
|
||||
* @arg DMA1_FLAG_GL5: DMA1 Channel5 global flag.
|
||||
* @arg DMA1_FLAG_TC5: DMA1 Channel5 transfer complete flag.
|
||||
* @arg DMA1_FLAG_HT5: DMA1 Channel5 half transfer flag.
|
||||
* @arg DMA1_FLAG_TE5: DMA1 Channel5 transfer error flag.
|
||||
* @arg DMA1_FLAG_GL6: DMA1 Channel6 global flag.
|
||||
* @arg DMA1_FLAG_TC6: DMA1 Channel6 transfer complete flag.
|
||||
* @arg DMA1_FLAG_HT6: DMA1 Channel6 half transfer flag.
|
||||
* @arg DMA1_FLAG_TE6: DMA1 Channel6 transfer error flag.
|
||||
* @arg DMA1_FLAG_GL7: DMA1 Channel7 global flag.
|
||||
* @arg DMA1_FLAG_TC7: DMA1 Channel7 transfer complete flag.
|
||||
* @arg DMA1_FLAG_HT7: DMA1 Channel7 half transfer flag.
|
||||
* @arg DMA1_FLAG_TE7: DMA1 Channel7 transfer error flag.
|
||||
* @arg DMA2_FLAG_GL1: DMA2 Channel1 global flag.
|
||||
* @arg DMA2_FLAG_TC1: DMA2 Channel1 transfer complete flag.
|
||||
* @arg DMA2_FLAG_HT1: DMA2 Channel1 half transfer flag.
|
||||
* @arg DMA2_FLAG_TE1: DMA2 Channel1 transfer error flag.
|
||||
* @arg DMA2_FLAG_GL2: DMA2 Channel2 global flag.
|
||||
* @arg DMA2_FLAG_TC2: DMA2 Channel2 transfer complete flag.
|
||||
* @arg DMA2_FLAG_HT2: DMA2 Channel2 half transfer flag.
|
||||
* @arg DMA2_FLAG_TE2: DMA2 Channel2 transfer error flag.
|
||||
* @arg DMA2_FLAG_GL3: DMA2 Channel3 global flag.
|
||||
* @arg DMA2_FLAG_TC3: DMA2 Channel3 transfer complete flag.
|
||||
* @arg DMA2_FLAG_HT3: DMA2 Channel3 half transfer flag.
|
||||
* @arg DMA2_FLAG_TE3: DMA2 Channel3 transfer error flag.
|
||||
* @arg DMA2_FLAG_GL4: DMA2 Channel4 global flag.
|
||||
* @arg DMA2_FLAG_TC4: DMA2 Channel4 transfer complete flag.
|
||||
* @arg DMA2_FLAG_HT4: DMA2 Channel4 half transfer flag.
|
||||
* @arg DMA2_FLAG_TE4: DMA2 Channel4 transfer error flag.
|
||||
* @arg DMA2_FLAG_GL5: DMA2 Channel5 global flag.
|
||||
* @arg DMA2_FLAG_TC5: DMA2 Channel5 transfer complete flag.
|
||||
* @arg DMA2_FLAG_HT5: DMA2 Channel5 half transfer flag.
|
||||
* @arg DMA2_FLAG_TE5: DMA2 Channel5 transfer error flag.
|
||||
*
|
||||
* @note
|
||||
* Clearing the Global flag (DMAy_FLAG_GLx) results in clearing all other flags
|
||||
* relative to the same channel (Transfer Complete, Half-transfer Complete and
|
||||
* Transfer Error flags: DMAy_FLAG_TCx, DMAy_FLAG_HTx and DMAy_FLAG_TEx).
|
||||
*
|
||||
* @retval None
|
||||
*/
|
||||
void DMA_ClearFlag(uint32_t DMAy_FLAG)
|
||||
{
|
||||
/* Check the parameters */
|
||||
assert_param(IS_DMA_CLEAR_FLAG(DMAy_FLAG));
|
||||
|
||||
/* Calculate the used DMAy */
|
||||
if ((DMAy_FLAG & FLAG_Mask) != (uint32_t)RESET)
|
||||
{
|
||||
/* Clear the selected DMAy flags */
|
||||
DMA2->IFCR = DMAy_FLAG;
|
||||
}
|
||||
else
|
||||
{
|
||||
/* Clear the selected DMAy flags */
|
||||
DMA1->IFCR = DMAy_FLAG;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Checks whether the specified DMAy Channelx interrupt has occurred or not.
|
||||
* @param DMAy_IT: specifies the DMAy interrupt source to check.
|
||||
* This parameter can be one of the following values:
|
||||
* @arg DMA1_IT_GL1: DMA1 Channel1 global interrupt.
|
||||
* @arg DMA1_IT_TC1: DMA1 Channel1 transfer complete interrupt.
|
||||
* @arg DMA1_IT_HT1: DMA1 Channel1 half transfer interrupt.
|
||||
* @arg DMA1_IT_TE1: DMA1 Channel1 transfer error interrupt.
|
||||
* @arg DMA1_IT_GL2: DMA1 Channel2 global interrupt.
|
||||
* @arg DMA1_IT_TC2: DMA1 Channel2 transfer complete interrupt.
|
||||
* @arg DMA1_IT_HT2: DMA1 Channel2 half transfer interrupt.
|
||||
* @arg DMA1_IT_TE2: DMA1 Channel2 transfer error interrupt.
|
||||
* @arg DMA1_IT_GL3: DMA1 Channel3 global interrupt.
|
||||
* @arg DMA1_IT_TC3: DMA1 Channel3 transfer complete interrupt.
|
||||
* @arg DMA1_IT_HT3: DMA1 Channel3 half transfer interrupt.
|
||||
* @arg DMA1_IT_TE3: DMA1 Channel3 transfer error interrupt.
|
||||
* @arg DMA1_IT_GL4: DMA1 Channel4 global interrupt.
|
||||
* @arg DMA1_IT_TC4: DMA1 Channel4 transfer complete interrupt.
|
||||
* @arg DMA1_IT_HT4: DMA1 Channel4 half transfer interrupt.
|
||||
* @arg DMA1_IT_TE4: DMA1 Channel4 transfer error interrupt.
|
||||
* @arg DMA1_IT_GL5: DMA1 Channel5 global interrupt.
|
||||
* @arg DMA1_IT_TC5: DMA1 Channel5 transfer complete interrupt.
|
||||
* @arg DMA1_IT_HT5: DMA1 Channel5 half transfer interrupt.
|
||||
* @arg DMA1_IT_TE5: DMA1 Channel5 transfer error interrupt.
|
||||
* @arg DMA1_IT_GL6: DMA1 Channel6 global interrupt.
|
||||
* @arg DMA1_IT_TC6: DMA1 Channel6 transfer complete interrupt.
|
||||
* @arg DMA1_IT_HT6: DMA1 Channel6 half transfer interrupt.
|
||||
* @arg DMA1_IT_TE6: DMA1 Channel6 transfer error interrupt.
|
||||
* @arg DMA1_IT_GL7: DMA1 Channel7 global interrupt.
|
||||
* @arg DMA1_IT_TC7: DMA1 Channel7 transfer complete interrupt.
|
||||
* @arg DMA1_IT_HT7: DMA1 Channel7 half transfer interrupt.
|
||||
* @arg DMA1_IT_TE7: DMA1 Channel7 transfer error interrupt.
|
||||
* @arg DMA2_IT_GL1: DMA2 Channel1 global interrupt.
|
||||
* @arg DMA2_IT_TC1: DMA2 Channel1 transfer complete interrupt.
|
||||
* @arg DMA2_IT_HT1: DMA2 Channel1 half transfer interrupt.
|
||||
* @arg DMA2_IT_TE1: DMA2 Channel1 transfer error interrupt.
|
||||
* @arg DMA2_IT_GL2: DMA2 Channel2 global interrupt.
|
||||
* @arg DMA2_IT_TC2: DMA2 Channel2 transfer complete interrupt.
|
||||
* @arg DMA2_IT_HT2: DMA2 Channel2 half transfer interrupt.
|
||||
* @arg DMA2_IT_TE2: DMA2 Channel2 transfer error interrupt.
|
||||
* @arg DMA2_IT_GL3: DMA2 Channel3 global interrupt.
|
||||
* @arg DMA2_IT_TC3: DMA2 Channel3 transfer complete interrupt.
|
||||
* @arg DMA2_IT_HT3: DMA2 Channel3 half transfer interrupt.
|
||||
* @arg DMA2_IT_TE3: DMA2 Channel3 transfer error interrupt.
|
||||
* @arg DMA2_IT_GL4: DMA2 Channel4 global interrupt.
|
||||
* @arg DMA2_IT_TC4: DMA2 Channel4 transfer complete interrupt.
|
||||
* @arg DMA2_IT_HT4: DMA2 Channel4 half transfer interrupt.
|
||||
* @arg DMA2_IT_TE4: DMA2 Channel4 transfer error interrupt.
|
||||
* @arg DMA2_IT_GL5: DMA2 Channel5 global interrupt.
|
||||
* @arg DMA2_IT_TC5: DMA2 Channel5 transfer complete interrupt.
|
||||
* @arg DMA2_IT_HT5: DMA2 Channel5 half transfer interrupt.
|
||||
* @arg DMA2_IT_TE5: DMA2 Channel5 transfer error interrupt.
|
||||
*
|
||||
* @note
|
||||
* The Global interrupt (DMAy_FLAG_GLx) is set whenever any of the other
|
||||
* interrupts relative to the same channel is set (Transfer Complete,
|
||||
* Half-transfer Complete or Transfer Error interrupts: DMAy_IT_TCx,
|
||||
* DMAy_IT_HTx or DMAy_IT_TEx).
|
||||
*
|
||||
* @retval The new state of DMAy_IT (SET or RESET).
|
||||
*/
|
||||
ITStatus DMA_GetITStatus(uint32_t DMAy_IT)
|
||||
{
|
||||
ITStatus bitstatus = RESET;
|
||||
uint32_t tmpreg = 0;
|
||||
|
||||
/* Check the parameters */
|
||||
assert_param(IS_DMA_GET_IT(DMAy_IT));
|
||||
|
||||
/* Calculate the used DMA */
|
||||
if ((DMAy_IT & FLAG_Mask) != (uint32_t)RESET)
|
||||
{
|
||||
/* Get DMA2 ISR register value */
|
||||
tmpreg = DMA2->ISR;
|
||||
}
|
||||
else
|
||||
{
|
||||
/* Get DMA1 ISR register value */
|
||||
tmpreg = DMA1->ISR;
|
||||
}
|
||||
|
||||
/* Check the status of the specified DMAy interrupt */
|
||||
if ((tmpreg & DMAy_IT) != (uint32_t)RESET)
|
||||
{
|
||||
/* DMAy_IT is set */
|
||||
bitstatus = SET;
|
||||
}
|
||||
else
|
||||
{
|
||||
/* DMAy_IT is reset */
|
||||
bitstatus = RESET;
|
||||
}
|
||||
/* Return the DMAy_IT status */
|
||||
return bitstatus;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Clears the DMAy Channelx's interrupt pending bits.
|
||||
* @param DMAy_IT: specifies the DMAy interrupt pending bit to clear.
|
||||
* This parameter can be any combination (for the same DMA) of the following values:
|
||||
* @arg DMA1_IT_GL1: DMA1 Channel1 global interrupt.
|
||||
* @arg DMA1_IT_TC1: DMA1 Channel1 transfer complete interrupt.
|
||||
* @arg DMA1_IT_HT1: DMA1 Channel1 half transfer interrupt.
|
||||
* @arg DMA1_IT_TE1: DMA1 Channel1 transfer error interrupt.
|
||||
* @arg DMA1_IT_GL2: DMA1 Channel2 global interrupt.
|
||||
* @arg DMA1_IT_TC2: DMA1 Channel2 transfer complete interrupt.
|
||||
* @arg DMA1_IT_HT2: DMA1 Channel2 half transfer interrupt.
|
||||
* @arg DMA1_IT_TE2: DMA1 Channel2 transfer error interrupt.
|
||||
* @arg DMA1_IT_GL3: DMA1 Channel3 global interrupt.
|
||||
* @arg DMA1_IT_TC3: DMA1 Channel3 transfer complete interrupt.
|
||||
* @arg DMA1_IT_HT3: DMA1 Channel3 half transfer interrupt.
|
||||
* @arg DMA1_IT_TE3: DMA1 Channel3 transfer error interrupt.
|
||||
* @arg DMA1_IT_GL4: DMA1 Channel4 global interrupt.
|
||||
* @arg DMA1_IT_TC4: DMA1 Channel4 transfer complete interrupt.
|
||||
* @arg DMA1_IT_HT4: DMA1 Channel4 half transfer interrupt.
|
||||
* @arg DMA1_IT_TE4: DMA1 Channel4 transfer error interrupt.
|
||||
* @arg DMA1_IT_GL5: DMA1 Channel5 global interrupt.
|
||||
* @arg DMA1_IT_TC5: DMA1 Channel5 transfer complete interrupt.
|
||||
* @arg DMA1_IT_HT5: DMA1 Channel5 half transfer interrupt.
|
||||
* @arg DMA1_IT_TE5: DMA1 Channel5 transfer error interrupt.
|
||||
* @arg DMA1_IT_GL6: DMA1 Channel6 global interrupt.
|
||||
* @arg DMA1_IT_TC6: DMA1 Channel6 transfer complete interrupt.
|
||||
* @arg DMA1_IT_HT6: DMA1 Channel6 half transfer interrupt.
|
||||
* @arg DMA1_IT_TE6: DMA1 Channel6 transfer error interrupt.
|
||||
* @arg DMA1_IT_GL7: DMA1 Channel7 global interrupt.
|
||||
* @arg DMA1_IT_TC7: DMA1 Channel7 transfer complete interrupt.
|
||||
* @arg DMA1_IT_HT7: DMA1 Channel7 half transfer interrupt.
|
||||
* @arg DMA1_IT_TE7: DMA1 Channel7 transfer error interrupt.
|
||||
* @arg DMA2_IT_GL1: DMA2 Channel1 global interrupt.
|
||||
* @arg DMA2_IT_TC1: DMA2 Channel1 transfer complete interrupt.
|
||||
* @arg DMA2_IT_HT1: DMA2 Channel1 half transfer interrupt.
|
||||
* @arg DMA2_IT_TE1: DMA2 Channel1 transfer error interrupt.
|
||||
* @arg DMA2_IT_GL2: DMA2 Channel2 global interrupt.
|
||||
* @arg DMA2_IT_TC2: DMA2 Channel2 transfer complete interrupt.
|
||||
* @arg DMA2_IT_HT2: DMA2 Channel2 half transfer interrupt.
|
||||
* @arg DMA2_IT_TE2: DMA2 Channel2 transfer error interrupt.
|
||||
* @arg DMA2_IT_GL3: DMA2 Channel3 global interrupt.
|
||||
* @arg DMA2_IT_TC3: DMA2 Channel3 transfer complete interrupt.
|
||||
* @arg DMA2_IT_HT3: DMA2 Channel3 half transfer interrupt.
|
||||
* @arg DMA2_IT_TE3: DMA2 Channel3 transfer error interrupt.
|
||||
* @arg DMA2_IT_GL4: DMA2 Channel4 global interrupt.
|
||||
* @arg DMA2_IT_TC4: DMA2 Channel4 transfer complete interrupt.
|
||||
* @arg DMA2_IT_HT4: DMA2 Channel4 half transfer interrupt.
|
||||
* @arg DMA2_IT_TE4: DMA2 Channel4 transfer error interrupt.
|
||||
* @arg DMA2_IT_GL5: DMA2 Channel5 global interrupt.
|
||||
* @arg DMA2_IT_TC5: DMA2 Channel5 transfer complete interrupt.
|
||||
* @arg DMA2_IT_HT5: DMA2 Channel5 half transfer interrupt.
|
||||
* @arg DMA2_IT_TE5: DMA2 Channel5 transfer error interrupt.
|
||||
*
|
||||
* @note
|
||||
* Clearing the Global interrupt (DMAy_IT_GLx) results in clearing all other
|
||||
* interrupts relative to the same channel (Transfer Complete, Half-transfer
|
||||
* Complete and Transfer Error interrupts: DMAy_IT_TCx, DMAy_IT_HTx and
|
||||
* DMAy_IT_TEx).
|
||||
*
|
||||
* @retval None
|
||||
*/
|
||||
void DMA_ClearITPendingBit(uint32_t DMAy_IT)
|
||||
{
|
||||
/* Check the parameters */
|
||||
assert_param(IS_DMA_CLEAR_IT(DMAy_IT));
|
||||
|
||||
/* Calculate the used DMAy */
|
||||
if ((DMAy_IT & FLAG_Mask) != (uint32_t)RESET)
|
||||
{
|
||||
/* Clear the selected DMAy interrupt pending bits */
|
||||
DMA2->IFCR = DMAy_IT;
|
||||
}
|
||||
else
|
||||
{
|
||||
/* Clear the selected DMAy interrupt pending bits */
|
||||
DMA1->IFCR = DMAy_IT;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
|
@ -0,0 +1,349 @@
|
|||
/**
|
||||
******************************************************************************
|
||||
* @file stm32f30x_exti.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 EXTI peripheral:
|
||||
* + Initialization and Configuration
|
||||
* + Interrupts and flags management
|
||||
*
|
||||
@verbatim
|
||||
===============================================================================
|
||||
##### EXTI features #####
|
||||
===============================================================================
|
||||
[..] External interrupt/event lines are mapped as following:
|
||||
(#) All available GPIO pins are connected to the 16 external
|
||||
interrupt/event lines from EXTI0 to EXTI15.
|
||||
(#) EXTI line 16 is connected to the PVD output
|
||||
(#) EXTI line 17 is connected to the RTC Alarm event
|
||||
(#) EXTI line 18 is connected to USB Device wakeup event
|
||||
(#) EXTI line 19 is connected to the RTC Tamper and TimeStamp events
|
||||
(#) EXTI line 20 is connected to the RTC wakeup event
|
||||
(#) EXTI line 21 is connected to the Comparator 1 wakeup event
|
||||
(#) EXTI line 22 is connected to the Comparator 2 wakeup event
|
||||
(#) EXTI line 23 is connected to the I2C1 wakeup event
|
||||
(#) EXTI line 24 is connected to the I2C2 wakeup event
|
||||
(#) EXTI line 25 is connected to the USART1 wakeup event
|
||||
(#) EXTI line 26 is connected to the USART2 wakeup event
|
||||
(#) EXTI line 27 is reserved
|
||||
(#) EXTI line 28 is connected to the USART3 wakeup event
|
||||
(#) EXTI line 29 is connected to the Comparator 3 event
|
||||
(#) EXTI line 30 is connected to the Comparator 4 event
|
||||
(#) EXTI line 31 is connected to the Comparator 5 event
|
||||
(#) EXTI line 32 is connected to the Comparator 6 event
|
||||
(#) EXTI line 33 is connected to the Comparator 7 event
|
||||
(#) EXTI line 34 is connected for thr UART4 wakeup event
|
||||
(#) EXTI line 35 is connected for the UART5 wakeup event
|
||||
|
||||
##### How to use this driver #####
|
||||
===============================================================================
|
||||
[..] In order to use an I/O pin as an external interrupt source,
|
||||
follow steps below:
|
||||
(#) Configure the I/O in input mode using GPIO_Init().
|
||||
(#) Select the input source pin for the EXTI line using
|
||||
SYSCFG_EXTILineConfig().
|
||||
(#) Select the mode(interrupt, event) and configure the trigger
|
||||
selection (Rising, falling or both) using EXTI_Init(). For the
|
||||
internal interrupt, the trigger selection is not needed
|
||||
(the active edge is always the rising one).
|
||||
(#) Configure NVIC IRQ channel mapped to the EXTI line using NVIC_Init().
|
||||
(#) Optionally, you can generate a software interrupt using the function
|
||||
EXTI_GenerateSWInterrupt().
|
||||
[..]
|
||||
(@) SYSCFG APB clock must be enabled to get write access to SYSCFG_EXTICRx
|
||||
registers using RCC_APB2PeriphClockCmd(RCC_APB2Periph_SYSCFG, ENABLE);
|
||||
|
||||
@endverbatim
|
||||
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© 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_exti.h"
|
||||
|
||||
/** @addtogroup STM32F30x_StdPeriph_Driver
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @defgroup EXTI
|
||||
* @brief EXTI driver modules
|
||||
* @{
|
||||
*/
|
||||
|
||||
|
||||
/* Private typedef -----------------------------------------------------------*/
|
||||
/* Private define ------------------------------------------------------------*/
|
||||
#define EXTI_LINENONE ((uint32_t)0x00000) /* No interrupt selected */
|
||||
|
||||
/* Private macro -------------------------------------------------------------*/
|
||||
/* Private variables ---------------------------------------------------------*/
|
||||
/* Private function prototypes -----------------------------------------------*/
|
||||
/* Private functions ---------------------------------------------------------*/
|
||||
|
||||
/** @defgroup EXTI_Private_Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @defgroup EXTI_Group1 Initialization and Configuration functions
|
||||
* @brief Initialization and Configuration functions
|
||||
*
|
||||
@verbatim
|
||||
===============================================================================
|
||||
##### Initialization and Configuration functions #####
|
||||
===============================================================================
|
||||
|
||||
@endverbatim
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief Deinitializes the EXTI peripheral registers to their default reset
|
||||
* values.
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
void EXTI_DeInit(void)
|
||||
{
|
||||
EXTI->IMR = 0x1F800000;
|
||||
EXTI->EMR = 0x00000000;
|
||||
EXTI->RTSR = 0x00000000;
|
||||
EXTI->FTSR = 0x00000000;
|
||||
EXTI->SWIER = 0x00000000;
|
||||
EXTI->PR = 0xE07FFFFF;
|
||||
EXTI->IMR2 = 0x0000000C;
|
||||
EXTI->EMR2 = 0x00000000;
|
||||
EXTI->RTSR2 = 0x00000000;
|
||||
EXTI->FTSR2 = 0x00000000;
|
||||
EXTI->SWIER2 = 0x00000000;
|
||||
EXTI->PR2 = 0x00000003;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Initializes the EXTI peripheral according to the specified
|
||||
* parameters in the EXTI_InitStruct.
|
||||
* EXTI_Line specifies the EXTI line (EXTI0....EXTI35).
|
||||
* EXTI_Mode specifies which EXTI line is used as interrupt or an event.
|
||||
* EXTI_Trigger selects the trigger. When the trigger occurs, interrupt
|
||||
* pending bit will be set.
|
||||
* EXTI_LineCmd controls (Enable/Disable) the EXTI line.
|
||||
* @param EXTI_InitStruct: pointer to a EXTI_InitTypeDef structure that
|
||||
* contains the configuration information for the EXTI peripheral.
|
||||
* @retval None
|
||||
*/
|
||||
|
||||
|
||||
void EXTI_Init(EXTI_InitTypeDef* EXTI_InitStruct)
|
||||
{
|
||||
uint32_t tmp = 0;
|
||||
|
||||
/* Check the parameters */
|
||||
assert_param(IS_EXTI_MODE(EXTI_InitStruct->EXTI_Mode));
|
||||
assert_param(IS_EXTI_TRIGGER(EXTI_InitStruct->EXTI_Trigger));
|
||||
assert_param(IS_EXTI_LINE_ALL(EXTI_InitStruct->EXTI_Line));
|
||||
assert_param(IS_FUNCTIONAL_STATE(EXTI_InitStruct->EXTI_LineCmd));
|
||||
|
||||
tmp = (uint32_t)EXTI_BASE;
|
||||
|
||||
if (EXTI_InitStruct->EXTI_LineCmd != DISABLE)
|
||||
{
|
||||
/* Clear EXTI line configuration */
|
||||
*(__IO uint32_t *) (((uint32_t) &(EXTI->IMR)) + ((EXTI_InitStruct->EXTI_Line) >> 5 ) * 0x20) &= ~(uint32_t)(1 << (EXTI_InitStruct->EXTI_Line & 0x1F));
|
||||
*(__IO uint32_t *) (((uint32_t) &(EXTI->EMR)) + ((EXTI_InitStruct->EXTI_Line) >> 5 ) * 0x20) &= ~(uint32_t)(1 << (EXTI_InitStruct->EXTI_Line & 0x1F));
|
||||
|
||||
tmp += EXTI_InitStruct->EXTI_Mode + (((EXTI_InitStruct->EXTI_Line) >> 5 ) * 0x20);
|
||||
|
||||
*(__IO uint32_t *) tmp |= (uint32_t)(1 << (EXTI_InitStruct->EXTI_Line & 0x1F));
|
||||
|
||||
tmp = (uint32_t)EXTI_BASE;
|
||||
|
||||
/* Clear Rising Falling edge configuration */
|
||||
*(__IO uint32_t *) (((uint32_t) &(EXTI->RTSR)) + ((EXTI_InitStruct->EXTI_Line) >> 5 ) * 0x20) &= ~(uint32_t)(1 << (EXTI_InitStruct->EXTI_Line & 0x1F));
|
||||
*(__IO uint32_t *) (((uint32_t) &(EXTI->FTSR)) + ((EXTI_InitStruct->EXTI_Line) >> 5 ) * 0x20) &= ~(uint32_t)(1 << (EXTI_InitStruct->EXTI_Line & 0x1F));
|
||||
|
||||
/* Select the trigger for the selected interrupts */
|
||||
if (EXTI_InitStruct->EXTI_Trigger == EXTI_Trigger_Rising_Falling)
|
||||
{
|
||||
/* Rising Falling edge */
|
||||
*(__IO uint32_t *) (((uint32_t) &(EXTI->RTSR)) + ((EXTI_InitStruct->EXTI_Line) >> 5 ) * 0x20) |= (uint32_t)(1 << (EXTI_InitStruct->EXTI_Line & 0x1F));
|
||||
*(__IO uint32_t *) (((uint32_t) &(EXTI->FTSR)) + ((EXTI_InitStruct->EXTI_Line) >> 5 ) * 0x20) |= (uint32_t)(1 << (EXTI_InitStruct->EXTI_Line & 0x1F));
|
||||
}
|
||||
else
|
||||
{
|
||||
tmp += EXTI_InitStruct->EXTI_Trigger + (((EXTI_InitStruct->EXTI_Line) >> 5 ) * 0x20);
|
||||
|
||||
*(__IO uint32_t *) tmp |= (uint32_t)(1 << (EXTI_InitStruct->EXTI_Line & 0x1F));
|
||||
}
|
||||
}
|
||||
|
||||
else
|
||||
{
|
||||
tmp += EXTI_InitStruct->EXTI_Mode + (((EXTI_InitStruct->EXTI_Line) >> 5 ) * 0x20);
|
||||
|
||||
/* Disable the selected external lines */
|
||||
*(__IO uint32_t *) tmp &= ~(uint32_t)(1 << (EXTI_InitStruct->EXTI_Line & 0x1F));
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Fills each EXTI_InitStruct member with its reset value.
|
||||
* @param EXTI_InitStruct: pointer to a EXTI_InitTypeDef structure which will
|
||||
* be initialized.
|
||||
* @retval None
|
||||
*/
|
||||
void EXTI_StructInit(EXTI_InitTypeDef* EXTI_InitStruct)
|
||||
{
|
||||
EXTI_InitStruct->EXTI_Line = EXTI_LINENONE;
|
||||
EXTI_InitStruct->EXTI_Mode = EXTI_Mode_Interrupt;
|
||||
EXTI_InitStruct->EXTI_Trigger = EXTI_Trigger_Rising_Falling;
|
||||
EXTI_InitStruct->EXTI_LineCmd = DISABLE;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Generates a Software interrupt on selected EXTI line.
|
||||
* @param EXTI_Line: specifies the EXTI line on which the software interrupt
|
||||
* will be generated.
|
||||
* This parameter can be any combination of EXTI_Linex where x can be (0..20).
|
||||
* @retval None
|
||||
*/
|
||||
void EXTI_GenerateSWInterrupt(uint32_t EXTI_Line)
|
||||
{
|
||||
/* Check the parameters */
|
||||
assert_param(IS_EXTI_LINE_EXT(EXTI_Line));
|
||||
|
||||
*(__IO uint32_t *) (((uint32_t) &(EXTI->SWIER)) + ((EXTI_Line) >> 5 ) * 0x20) |= (uint32_t)(1 << (EXTI_Line & 0x1F));
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/** @defgroup EXTI_Group2 Interrupts and flags management functions
|
||||
* @brief EXTI Interrupts and flags management functions
|
||||
*
|
||||
@verbatim
|
||||
===============================================================================
|
||||
##### Interrupts and flags management functions #####
|
||||
===============================================================================
|
||||
[..]
|
||||
This section provides functions allowing to configure the EXTI Interrupts
|
||||
sources and check or clear the flags or pending bits status.
|
||||
|
||||
@endverbatim
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief Checks whether the specified EXTI line flag is set or not.
|
||||
* @param EXTI_Line: specifies the EXTI line flag to check.
|
||||
* This parameter can be any combination of EXTI_Linex where x can be (0..20).
|
||||
* @retval The new state of EXTI_Line (SET or RESET).
|
||||
*/
|
||||
FlagStatus EXTI_GetFlagStatus(uint32_t EXTI_Line)
|
||||
{
|
||||
FlagStatus bitstatus = RESET;
|
||||
|
||||
/* Check the parameters */
|
||||
assert_param(IS_GET_EXTI_LINE(EXTI_Line));
|
||||
|
||||
if ((*(__IO uint32_t *) (((uint32_t) &(EXTI->PR)) + ((EXTI_Line) >> 5 ) * 0x20)& (uint32_t)(1 << (EXTI_Line & 0x1F))) != (uint32_t)RESET)
|
||||
{
|
||||
bitstatus = SET;
|
||||
}
|
||||
else
|
||||
{
|
||||
bitstatus = RESET;
|
||||
}
|
||||
return bitstatus;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Clears the EXTI's line pending flags.
|
||||
* @param EXTI_Line: specifies the EXTI lines flags to clear.
|
||||
* This parameter can be any combination of EXTI_Linex where x can be (0..20).
|
||||
* @retval None
|
||||
*/
|
||||
void EXTI_ClearFlag(uint32_t EXTI_Line)
|
||||
{
|
||||
/* Check the parameters */
|
||||
assert_param(IS_EXTI_LINE_EXT(EXTI_Line));
|
||||
|
||||
*(__IO uint32_t *) (((uint32_t) &(EXTI->PR)) + ((EXTI_Line) >> 5 ) * 0x20) = (1 << (EXTI_Line & 0x1F));
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Checks whether the specified EXTI line is asserted or not.
|
||||
* @param EXTI_Line: specifies the EXTI line to check.
|
||||
* This parameter can be any combination of EXTI_Linex where x can be (0..20).
|
||||
* @retval The new state of EXTI_Line (SET or RESET).
|
||||
*/
|
||||
ITStatus EXTI_GetITStatus(uint32_t EXTI_Line)
|
||||
{
|
||||
ITStatus bitstatus = RESET;
|
||||
|
||||
/* Check the parameters */
|
||||
assert_param(IS_GET_EXTI_LINE(EXTI_Line));
|
||||
|
||||
if ((*(__IO uint32_t *) (((uint32_t) &(EXTI->PR)) + ((EXTI_Line) >> 5 ) * 0x20)& (uint32_t)(1 << (EXTI_Line & 0x1F))) != (uint32_t)RESET)
|
||||
{
|
||||
bitstatus = SET;
|
||||
}
|
||||
else
|
||||
{
|
||||
bitstatus = RESET;
|
||||
}
|
||||
return bitstatus;
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Clears the EXTI's line pending bits.
|
||||
* @param EXTI_Line: specifies the EXTI lines to clear.
|
||||
* This parameter can be any combination of EXTI_Linex where x can be (0..20).
|
||||
* @retval None
|
||||
*/
|
||||
void EXTI_ClearITPendingBit(uint32_t EXTI_Line)
|
||||
{
|
||||
/* Check the parameters */
|
||||
assert_param(IS_EXTI_LINE_EXT(EXTI_Line));
|
||||
|
||||
*(__IO uint32_t *) (((uint32_t) &(EXTI->PR)) + ((EXTI_Line) >> 5 ) * 0x20) = (1 << (EXTI_Line & 0x1F));
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
File diff suppressed because it is too large
Load diff
|
@ -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>© 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****/
|
File diff suppressed because it is too large
Load diff
File diff suppressed because it is too large
Load diff
|
@ -0,0 +1,288 @@
|
|||
/**
|
||||
******************************************************************************
|
||||
* @file stm32f30x_iwdg.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 Independent watchdog (IWDG) peripheral:
|
||||
* + Prescaler and Counter configuration
|
||||
* + IWDG activation
|
||||
* + Flag management
|
||||
*
|
||||
@verbatim
|
||||
|
||||
===============================================================================
|
||||
##### IWDG features #####
|
||||
===============================================================================
|
||||
[..] The IWDG can be started by either software or hardware (configurable
|
||||
through option byte).
|
||||
[..] The IWDG is clocked by its own dedicated low-speed clock (LSI) and
|
||||
thus stays active even if the main clock fails.
|
||||
Once the IWDG is started, the LSI is forced ON and cannot be disabled
|
||||
(LSI cannot be disabled too), and the counter starts counting down from
|
||||
the reset value of 0xFFF. When it reaches the end of count value (0x000)
|
||||
a system reset is generated.
|
||||
The IWDG counter should be reloaded at regular intervals to prevent
|
||||
an MCU reset.
|
||||
[..] The IWDG is implemented in the VDD voltage domain that is still functional
|
||||
in STOP and STANDBY mode (IWDG reset can wake-up from STANDBY).
|
||||
[..] IWDGRST flag in RCC_CSR register can be used to inform when a IWDG
|
||||
reset occurs.
|
||||
[..] Min-max timeout value @41KHz (LSI): ~0.1ms / ~25.5s
|
||||
The IWDG timeout may vary due to LSI frequency dispersion. STM32F30x
|
||||
devices provide the capability to measure the LSI frequency (LSI clock
|
||||
connected internally to TIM16 CH1 input capture). The measured value
|
||||
can be used to have an IWDG timeout with an acceptable accuracy.
|
||||
For more information, please refer to the STM32F30x Reference manual.
|
||||
|
||||
##### How to use this driver #####
|
||||
===============================================================================
|
||||
[..] This driver allows to use IWDG peripheral with either window option enabled
|
||||
or disabled. To do so follow one of the two procedures below.
|
||||
(#) Window option is enabled:
|
||||
(++) Start the IWDG using IWDG_Enable() function, when the IWDG is used
|
||||
in software mode (no need to enable the LSI, it will be enabled
|
||||
by hardware).
|
||||
(++) Enable write access to IWDG_PR and IWDG_RLR registers using
|
||||
IWDG_WriteAccessCmd(IWDG_WriteAccess_Enable) function.
|
||||
(++) Configure the IWDG prescaler using IWDG_SetPrescaler() function.
|
||||
(++) Configure the IWDG counter value using IWDG_SetReload() function.
|
||||
This value will be loaded in the IWDG counter each time the counter
|
||||
is reloaded, then the IWDG will start counting down from this value.
|
||||
(++) Wait for the IWDG registers to be updated using IWDG_GetFlagStatus() function.
|
||||
(++) Configure the IWDG refresh window using IWDG_SetWindowValue() function.
|
||||
|
||||
(#) Window option is disabled:
|
||||
(++) Enable write access to IWDG_PR and IWDG_RLR registers using
|
||||
IWDG_WriteAccessCmd(IWDG_WriteAccess_Enable) function.
|
||||
(++) Configure the IWDG prescaler using IWDG_SetPrescaler() function.
|
||||
(++) Configure the IWDG counter value using IWDG_SetReload() function.
|
||||
This value will be loaded in the IWDG counter each time the counter
|
||||
is reloaded, then the IWDG will start counting down from this value.
|
||||
(++) Wait for the IWDG registers to be updated using IWDG_GetFlagStatus() function.
|
||||
(++) reload the IWDG counter at regular intervals during normal operation
|
||||
to prevent an MCU reset, using IWDG_ReloadCounter() function.
|
||||
(++) Start the IWDG using IWDG_Enable() function, when the IWDG is used
|
||||
in software mode (no need to enable the LSI, it will be enabled
|
||||
by hardware).
|
||||
|
||||
@endverbatim
|
||||
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© 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_iwdg.h"
|
||||
|
||||
/** @addtogroup STM32F30x_StdPeriph_Driver
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @defgroup IWDG
|
||||
* @brief IWDG driver modules
|
||||
* @{
|
||||
*/
|
||||
|
||||
/* Private typedef -----------------------------------------------------------*/
|
||||
/* Private define ------------------------------------------------------------*/
|
||||
/* ---------------------- IWDG registers bit mask ----------------------------*/
|
||||
/* KR register bit mask */
|
||||
#define KR_KEY_RELOAD ((uint16_t)0xAAAA)
|
||||
#define KR_KEY_ENABLE ((uint16_t)0xCCCC)
|
||||
|
||||
/* Private macro -------------------------------------------------------------*/
|
||||
/* Private variables ---------------------------------------------------------*/
|
||||
/* Private function prototypes -----------------------------------------------*/
|
||||
/* Private functions ---------------------------------------------------------*/
|
||||
|
||||
/** @defgroup IWDG_Private_Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @defgroup IWDG_Group1 Prescaler and Counter configuration functions
|
||||
* @brief Prescaler and Counter configuration functions
|
||||
*
|
||||
@verbatim
|
||||
===============================================================================
|
||||
##### Prescaler and Counter configuration functions #####
|
||||
===============================================================================
|
||||
|
||||
@endverbatim
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief Enables or disables write access to IWDG_PR and IWDG_RLR registers.
|
||||
* @param IWDG_WriteAccess: new state of write access to IWDG_PR and IWDG_RLR registers.
|
||||
* This parameter can be one of the following values:
|
||||
* @arg IWDG_WriteAccess_Enable: Enable write access to IWDG_PR and IWDG_RLR registers
|
||||
* @arg IWDG_WriteAccess_Disable: Disable write access to IWDG_PR and IWDG_RLR registers
|
||||
* @retval None
|
||||
*/
|
||||
void IWDG_WriteAccessCmd(uint16_t IWDG_WriteAccess)
|
||||
{
|
||||
/* Check the parameters */
|
||||
assert_param(IS_IWDG_WRITE_ACCESS(IWDG_WriteAccess));
|
||||
IWDG->KR = IWDG_WriteAccess;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Sets IWDG Prescaler value.
|
||||
* @param IWDG_Prescaler: specifies the IWDG Prescaler value.
|
||||
* This parameter can be one of the following values:
|
||||
* @arg IWDG_Prescaler_4: IWDG prescaler set to 4
|
||||
* @arg IWDG_Prescaler_8: IWDG prescaler set to 8
|
||||
* @arg IWDG_Prescaler_16: IWDG prescaler set to 16
|
||||
* @arg IWDG_Prescaler_32: IWDG prescaler set to 32
|
||||
* @arg IWDG_Prescaler_64: IWDG prescaler set to 64
|
||||
* @arg IWDG_Prescaler_128: IWDG prescaler set to 128
|
||||
* @arg IWDG_Prescaler_256: IWDG prescaler set to 256
|
||||
* @retval None
|
||||
*/
|
||||
void IWDG_SetPrescaler(uint8_t IWDG_Prescaler)
|
||||
{
|
||||
/* Check the parameters */
|
||||
assert_param(IS_IWDG_PRESCALER(IWDG_Prescaler));
|
||||
IWDG->PR = IWDG_Prescaler;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Sets IWDG Reload value.
|
||||
* @param Reload: specifies the IWDG Reload value.
|
||||
* This parameter must be a number between 0 and 0x0FFF.
|
||||
* @retval None
|
||||
*/
|
||||
void IWDG_SetReload(uint16_t Reload)
|
||||
{
|
||||
/* Check the parameters */
|
||||
assert_param(IS_IWDG_RELOAD(Reload));
|
||||
IWDG->RLR = Reload;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Reloads IWDG counter with value defined in the reload register
|
||||
* (write access to IWDG_PR and IWDG_RLR registers disabled).
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
void IWDG_ReloadCounter(void)
|
||||
{
|
||||
IWDG->KR = KR_KEY_RELOAD;
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @brief Sets the IWDG window value.
|
||||
* @param WindowValue: specifies the window value to be compared to the downcounter.
|
||||
* @retval None
|
||||
*/
|
||||
void IWDG_SetWindowValue(uint16_t WindowValue)
|
||||
{
|
||||
/* Check the parameters */
|
||||
assert_param(IS_IWDG_WINDOW_VALUE(WindowValue));
|
||||
IWDG->WINR = WindowValue;
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/** @defgroup IWDG_Group2 IWDG activation function
|
||||
* @brief IWDG activation function
|
||||
*
|
||||
@verbatim
|
||||
===============================================================================
|
||||
##### IWDG activation function #####
|
||||
===============================================================================
|
||||
|
||||
@endverbatim
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief Enables IWDG (write access to IWDG_PR and IWDG_RLR registers disabled).
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
void IWDG_Enable(void)
|
||||
{
|
||||
IWDG->KR = KR_KEY_ENABLE;
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/** @defgroup IWDG_Group3 Flag management function
|
||||
* @brief Flag management function
|
||||
*
|
||||
@verbatim
|
||||
===============================================================================
|
||||
##### Flag management function #####
|
||||
===============================================================================
|
||||
|
||||
@endverbatim
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief Checks whether the specified IWDG flag is set or not.
|
||||
* @param IWDG_FLAG: specifies the flag to check.
|
||||
* This parameter can be one of the following values:
|
||||
* @arg IWDG_FLAG_PVU: Prescaler Value Update on going
|
||||
* @arg IWDG_FLAG_RVU: Reload Value Update on going
|
||||
* @arg IWDG_FLAG_WVU: Counter Window Value Update on going
|
||||
* @retval The new state of IWDG_FLAG (SET or RESET).
|
||||
*/
|
||||
FlagStatus IWDG_GetFlagStatus(uint16_t IWDG_FLAG)
|
||||
{
|
||||
FlagStatus bitstatus = RESET;
|
||||
/* Check the parameters */
|
||||
assert_param(IS_IWDG_FLAG(IWDG_FLAG));
|
||||
if ((IWDG->SR & IWDG_FLAG) != (uint32_t)RESET)
|
||||
{
|
||||
bitstatus = SET;
|
||||
}
|
||||
else
|
||||
{
|
||||
bitstatus = RESET;
|
||||
}
|
||||
/* Return the flag status */
|
||||
return bitstatus;
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
|
@ -0,0 +1,230 @@
|
|||
/**
|
||||
******************************************************************************
|
||||
* @file stm32f30x_misc.c
|
||||
* @author MCD Application Team
|
||||
* @version V1.1.1
|
||||
* @date 04-April-2014
|
||||
* @brief This file provides all the miscellaneous firmware functions (add-on
|
||||
* to CMSIS functions).
|
||||
*
|
||||
@verbatim
|
||||
|
||||
===============================================================================
|
||||
##### How to configure Interrupts using driver #####
|
||||
===============================================================================
|
||||
[..] This section provide functions allowing to configure the NVIC interrupts
|
||||
(IRQ). The Cortex-M4 exceptions are managed by CMSIS functions.
|
||||
(#) Configure the NVIC Priority Grouping using NVIC_PriorityGroupConfig()
|
||||
function according to the following table.
|
||||
The table below gives the allowed values of the pre-emption priority
|
||||
and subpriority according to the Priority Grouping configuration
|
||||
performed by NVIC_PriorityGroupConfig function.
|
||||
|
||||
(#) Enable and Configure the priority of the selected IRQ Channels.
|
||||
[..]
|
||||
(@) When the NVIC_PriorityGroup_0 is selected, it will no any nested interrupt,
|
||||
the IRQ priority will be managed only by subpriority.
|
||||
The sub-priority is only used to sort pending exception priorities,
|
||||
and does not affect active exceptions.
|
||||
(@) Lower priority values gives higher priority.
|
||||
(@) Priority Order:
|
||||
(#@) Lowest Preemption priority.
|
||||
(#@) Lowest Subpriority.
|
||||
(#@) Lowest hardware priority (IRQn position).
|
||||
|
||||
@endverbatim
|
||||
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© 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_misc.h"
|
||||
|
||||
/** @addtogroup STM32F30x_StdPeriph_Driver
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @defgroup MISC
|
||||
* @brief MISC driver modules
|
||||
* @{
|
||||
*/
|
||||
|
||||
/* Private typedef -----------------------------------------------------------*/
|
||||
/* Private define ------------------------------------------------------------*/
|
||||
#define AIRCR_VECTKEY_MASK ((uint32_t)0x05FA0000)
|
||||
|
||||
/* Private macro -------------------------------------------------------------*/
|
||||
/* Private variables ---------------------------------------------------------*/
|
||||
/* Private function prototypes -----------------------------------------------*/
|
||||
/* Private functions ---------------------------------------------------------*/
|
||||
|
||||
/** @defgroup MISC_Private_Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief Configures the priority grouping: pre-emption priority and subpriority.
|
||||
* @param NVIC_PriorityGroup: specifies the priority grouping bits length.
|
||||
* This parameter can be one of the following values:
|
||||
* @arg NVIC_PriorityGroup_0: 0 bits for pre-emption priority.
|
||||
* 4 bits for subpriority.
|
||||
* @arg NVIC_PriorityGroup_1: 1 bits for pre-emption priority.
|
||||
* 3 bits for subpriority.
|
||||
* @arg NVIC_PriorityGroup_2: 2 bits for pre-emption priority.
|
||||
* 2 bits for subpriority.
|
||||
* @arg NVIC_PriorityGroup_3: 3 bits for pre-emption priority.
|
||||
* 1 bits for subpriority.
|
||||
* @arg 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.
|
||||
* @retval None
|
||||
*/
|
||||
void NVIC_PriorityGroupConfig(uint32_t NVIC_PriorityGroup)
|
||||
{
|
||||
/* Check the parameters */
|
||||
assert_param(IS_NVIC_PRIORITY_GROUP(NVIC_PriorityGroup));
|
||||
|
||||
/* Set the PRIGROUP[10:8] bits according to NVIC_PriorityGroup value */
|
||||
SCB->AIRCR = AIRCR_VECTKEY_MASK | NVIC_PriorityGroup;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief 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.
|
||||
* @param NVIC_InitStruct: pointer to a NVIC_InitTypeDef structure that contains
|
||||
* the configuration information for the specified NVIC peripheral.
|
||||
* @retval None
|
||||
*/
|
||||
void NVIC_Init(NVIC_InitTypeDef* NVIC_InitStruct)
|
||||
{
|
||||
uint32_t tmppriority = 0x00, tmppre = 0x00, tmpsub = 0x0F;
|
||||
|
||||
/* Check the parameters */
|
||||
assert_param(IS_FUNCTIONAL_STATE(NVIC_InitStruct->NVIC_IRQChannelCmd));
|
||||
assert_param(IS_NVIC_PREEMPTION_PRIORITY(NVIC_InitStruct->NVIC_IRQChannelPreemptionPriority));
|
||||
assert_param(IS_NVIC_SUB_PRIORITY(NVIC_InitStruct->NVIC_IRQChannelSubPriority));
|
||||
|
||||
if (NVIC_InitStruct->NVIC_IRQChannelCmd != DISABLE)
|
||||
{
|
||||
/* Compute the Corresponding IRQ Priority --------------------------------*/
|
||||
tmppriority = (0x700 - ((SCB->AIRCR) & (uint32_t)0x700))>> 0x08;
|
||||
tmppre = (0x4 - tmppriority);
|
||||
tmpsub = tmpsub >> tmppriority;
|
||||
|
||||
tmppriority = (uint32_t)NVIC_InitStruct->NVIC_IRQChannelPreemptionPriority << tmppre;
|
||||
tmppriority |= NVIC_InitStruct->NVIC_IRQChannelSubPriority & tmpsub;
|
||||
tmppriority = tmppriority << 0x04;
|
||||
|
||||
NVIC->IP[NVIC_InitStruct->NVIC_IRQChannel] = tmppriority;
|
||||
|
||||
/* Enable the Selected IRQ Channels --------------------------------------*/
|
||||
NVIC->ISER[NVIC_InitStruct->NVIC_IRQChannel >> 0x05] =
|
||||
(uint32_t)0x01 << (NVIC_InitStruct->NVIC_IRQChannel & (uint8_t)0x1F);
|
||||
}
|
||||
else
|
||||
{
|
||||
/* Disable the Selected IRQ Channels -------------------------------------*/
|
||||
NVIC->ICER[NVIC_InitStruct->NVIC_IRQChannel >> 0x05] =
|
||||
(uint32_t)0x01 << (NVIC_InitStruct->NVIC_IRQChannel & (uint8_t)0x1F);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Sets the vector table location and Offset.
|
||||
* @param NVIC_VectTab: specifies if the vector table is in RAM or FLASH memory.
|
||||
* This parameter can be one of the following values:
|
||||
* @arg NVIC_VectTab_RAM
|
||||
* @arg NVIC_VectTab_FLASH
|
||||
* @param Offset: Vector Table base offset field. This value must be a multiple of 0x200.
|
||||
* @retval None
|
||||
*/
|
||||
void NVIC_SetVectorTable(uint32_t NVIC_VectTab, uint32_t Offset)
|
||||
{
|
||||
/* Check the parameters */
|
||||
assert_param(IS_NVIC_VECTTAB(NVIC_VectTab));
|
||||
assert_param(IS_NVIC_OFFSET(Offset));
|
||||
|
||||
SCB->VTOR = NVIC_VectTab | (Offset & (uint32_t)0x1FFFFF80);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Selects the condition for the system to enter low power mode.
|
||||
* @param LowPowerMode: Specifies the new mode for the system to enter low power mode.
|
||||
* This parameter can be one of the following values:
|
||||
* @arg NVIC_LP_SEVONPEND
|
||||
* @arg NVIC_LP_SLEEPDEEP
|
||||
* @arg NVIC_LP_SLEEPONEXIT
|
||||
* @param NewState: new state of LP condition. This parameter can be: ENABLE or DISABLE.
|
||||
* @retval None
|
||||
*/
|
||||
void NVIC_SystemLPConfig(uint8_t LowPowerMode, FunctionalState NewState)
|
||||
{
|
||||
/* Check the parameters */
|
||||
assert_param(IS_NVIC_LP(LowPowerMode));
|
||||
assert_param(IS_FUNCTIONAL_STATE(NewState));
|
||||
|
||||
if (NewState != DISABLE)
|
||||
{
|
||||
SCB->SCR |= LowPowerMode;
|
||||
}
|
||||
else
|
||||
{
|
||||
SCB->SCR &= (uint32_t)(~(uint32_t)LowPowerMode);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Configures the SysTick clock source.
|
||||
* @param SysTick_CLKSource: specifies the SysTick clock source.
|
||||
* This parameter can be one of the following values:
|
||||
* @arg SysTick_CLKSource_HCLK_Div8: AHB clock divided by 8 selected as SysTick clock source.
|
||||
* @arg SysTick_CLKSource_HCLK: AHB clock selected as SysTick clock source.
|
||||
* @retval None
|
||||
*/
|
||||
void SysTick_CLKSourceConfig(uint32_t SysTick_CLKSource)
|
||||
{
|
||||
/* Check the parameters */
|
||||
assert_param(IS_SYSTICK_CLK_SOURCE(SysTick_CLKSource));
|
||||
if (SysTick_CLKSource == SysTick_CLKSource_HCLK)
|
||||
{
|
||||
SysTick->CTRL |= SysTick_CLKSource_HCLK;
|
||||
}
|
||||
else
|
||||
{
|
||||
SysTick->CTRL &= SysTick_CLKSource_HCLK_Div8;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
|
@ -0,0 +1,575 @@
|
|||
/**
|
||||
******************************************************************************
|
||||
* @file stm32f30x_opamp.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 operational amplifiers (OPAMP1,...OPAMP4) peripheral:
|
||||
* + OPAMP Configuration
|
||||
* + OPAMP calibration
|
||||
*
|
||||
@verbatim
|
||||
|
||||
==============================================================================
|
||||
##### OPAMP Peripheral Features #####
|
||||
==============================================================================
|
||||
|
||||
[..]
|
||||
The device integrates 4 operational amplifiers OPAMP1, OPAMP2, OPAMP3 and OPAMP4:
|
||||
|
||||
(+) The OPAMPs non inverting input can be selected among the list shown by
|
||||
table below.
|
||||
|
||||
(+) The OPAMPs inverting input can be selected among the list shown by
|
||||
table below.
|
||||
|
||||
(+) The OPAMPs outputs can be internally connected to the inverting input
|
||||
(follower mode)
|
||||
(+) The OPAMPs outputs can be internally connected to resistor feedback
|
||||
output (Programmable Gain Amplifier mode)
|
||||
|
||||
(+) The OPAMPs outputs can be internally connected to ADC
|
||||
|
||||
(+) The OPAMPs can be calibrated to compensate the offset compensation
|
||||
|
||||
(+) Timer-controlled Mux for automatic switch of inverting and
|
||||
non-inverting input
|
||||
|
||||
OPAMPs inverting/non-inverting inputs:
|
||||
+--------------------------------------------------------------+
|
||||
| | | OPAMP1 | OPAMP2 | OPAMP3 | OPAMP4 |
|
||||
|-----------------|--------|--------|--------|--------|--------|
|
||||
| | PGA | OK | OK | OK | OK |
|
||||
| Inverting Input | Vout | OK | OK | OK | OK |
|
||||
| | IO1 | PC5 | PC5 | PB10 | PB10 |
|
||||
| | IO2 | PA3 | PA5 | PB2 | PD8 |
|
||||
|-----------------|--------|--------|--------|--------|--------|
|
||||
| | IO1 | PA7 | PD14 | PB13 | PD11 |
|
||||
| Non Inverting | IO2 | PA5 | PB14 | PA5 | PB11 |
|
||||
| Input | IO3 | PA3 | PB0 | PA1 | PA4 |
|
||||
| | IO4 | PA1 | PA7 | PB0 | PB13 |
|
||||
+--------------------------------------------------------------+
|
||||
|
||||
##### How to use this driver #####
|
||||
==============================================================================
|
||||
[..]
|
||||
This driver provides functions to configure and program the OPAMP
|
||||
of all STM32F30x devices.
|
||||
|
||||
To use the OPAMP, perform the following steps:
|
||||
|
||||
(#) Enable the SYSCFG APB clock to get write access to OPAMP
|
||||
register using RCC_APB2PeriphClockCmd(RCC_APB2Periph_SYSCFG, ENABLE);
|
||||
|
||||
(#) Configure the OPAMP input in analog mode using GPIO_Init()
|
||||
|
||||
(#) Configure the OPAMP using OPAMP_Init() function:
|
||||
(++) Select the inverting input
|
||||
(++) Select the non-inverting inverting input
|
||||
|
||||
(#) Enable the OPAMP using OPAMP_Cmd() function
|
||||
|
||||
@endverbatim
|
||||
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© 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_opamp.h"
|
||||
|
||||
/** @addtogroup STM32F30x_StdPeriph_Driver
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @defgroup OPAMP
|
||||
* @brief OPAMP driver modules
|
||||
* @{
|
||||
*/
|
||||
|
||||
/* Private typedef -----------------------------------------------------------*/
|
||||
/* Private define ------------------------------------------------------------*/
|
||||
#define OPAMP_CSR_DEFAULT_MASK ((uint32_t)0xFFFFFF93)
|
||||
#define OPAMP_CSR_TIMERMUX_MASK ((uint32_t)0xFFFFF8FF)
|
||||
#define OPAMP_CSR_TRIMMING_MASK ((uint32_t)0x0000001F)
|
||||
|
||||
/* Private macro -------------------------------------------------------------*/
|
||||
/* Private variables ---------------------------------------------------------*/
|
||||
/* Private function prototypes -----------------------------------------------*/
|
||||
/* Private functions ---------------------------------------------------------*/
|
||||
|
||||
/** @defgroup OPAMP_Private_Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @defgroup OPAMP_Group1 Initialization and Configuration functions
|
||||
* @brief Initialization and Configuration functions
|
||||
*
|
||||
@verbatim
|
||||
===============================================================================
|
||||
##### Initialization and Configuration functions #####
|
||||
===============================================================================
|
||||
|
||||
@endverbatim
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief Deinitializes OPAMP peripheral registers to their default reset values.
|
||||
* @note Deinitialization can't be performed if the OPAMP configuration is locked.
|
||||
* To unlock the configuration, perform a system reset.
|
||||
* @param OPAMP_Selection: the selected OPAMP.
|
||||
* This parameter can be OPAMP_Selection_OPAMPx where x can be 1 to 4
|
||||
* to select the OPAMP peripheral.
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
void OPAMP_DeInit(uint32_t OPAMP_Selection)
|
||||
{
|
||||
/*!< Set OPAMP_CSR register to reset value */
|
||||
*(__IO uint32_t *) (OPAMP_BASE + OPAMP_Selection) = ((uint32_t)0x00000000);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Initializes the OPAMP peripheral according to the specified parameters
|
||||
* in OPAMP_InitStruct
|
||||
* @note If the selected OPAMP is locked, initialization can't be performed.
|
||||
* To unlock the configuration, perform a system reset.
|
||||
* @param OPAMP_Selection: the selected OPAMP.
|
||||
* This parameter can be OPAMP_Selection_OPAMPx where x can be 1 to 4
|
||||
* to select the OPAMP peripheral.
|
||||
* @param OPAMP_InitStruct: pointer to an OPAMP_InitTypeDef structure that contains
|
||||
* the configuration information for the specified OPAMP peripheral.
|
||||
* - OPAMP_InvertingInput specifies the inverting input of OPAMP
|
||||
* - OPAMP_NonInvertingInput specifies the non inverting input of OPAMP
|
||||
* @retval None
|
||||
*/
|
||||
void OPAMP_Init(uint32_t OPAMP_Selection, OPAMP_InitTypeDef* OPAMP_InitStruct)
|
||||
{
|
||||
uint32_t tmpreg = 0;
|
||||
|
||||
/* Check the parameters */
|
||||
assert_param(IS_OPAMP_ALL_PERIPH(OPAMP_Selection));
|
||||
assert_param(IS_OPAMP_INVERTING_INPUT(OPAMP_InitStruct->OPAMP_InvertingInput));
|
||||
assert_param(IS_OPAMP_NONINVERTING_INPUT(OPAMP_InitStruct->OPAMP_NonInvertingInput));
|
||||
|
||||
/*!< Get the OPAMPx_CSR register value */
|
||||
tmpreg = *(__IO uint32_t *) (OPAMP_BASE + OPAMP_Selection);
|
||||
|
||||
/*!< Clear the inverting and non inverting bits selection bits */
|
||||
tmpreg &= (uint32_t) (OPAMP_CSR_DEFAULT_MASK);
|
||||
|
||||
/*!< Configure OPAMP: inverting and non inverting inputs */
|
||||
tmpreg |= (uint32_t)(OPAMP_InitStruct->OPAMP_InvertingInput | OPAMP_InitStruct->OPAMP_NonInvertingInput);
|
||||
|
||||
/*!< Write to OPAMPx_CSR register */
|
||||
*(__IO uint32_t *) (OPAMP_BASE + OPAMP_Selection) = tmpreg;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Fills each OPAMP_InitStruct member with its default value.
|
||||
* @param OPAMP_InitStruct: pointer to an OPAMP_InitTypeDef structure which will
|
||||
* be initialized.
|
||||
* @retval None
|
||||
*/
|
||||
void OPAMP_StructInit(OPAMP_InitTypeDef* OPAMP_InitStruct)
|
||||
{
|
||||
OPAMP_InitStruct->OPAMP_NonInvertingInput = OPAMP_NonInvertingInput_IO1;
|
||||
OPAMP_InitStruct->OPAMP_InvertingInput = OPAMP_InvertingInput_IO1;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Configure the feedback resistor gain.
|
||||
* @note If the selected OPAMP is locked, gain configuration can't be performed.
|
||||
* To unlock the configuration, perform a system reset.
|
||||
* @param OPAMP_Selection: the selected OPAMP.
|
||||
* This parameter can be OPAMP_Selection_OPAMPx where x can be 1 to 4
|
||||
* to select the OPAMP peripheral.
|
||||
* @param NewState: new state of the OPAMP peripheral.
|
||||
* This parameter can be: ENABLE or DISABLE.
|
||||
* @retval None
|
||||
*/
|
||||
void OPAMP_PGAConfig(uint32_t OPAMP_Selection, uint32_t OPAMP_PGAGain, uint32_t OPAMP_PGAConnect)
|
||||
{
|
||||
/* Check the parameters */
|
||||
assert_param(IS_OPAMP_ALL_PERIPH(OPAMP_Selection));
|
||||
assert_param(IS_OPAMP_PGAGAIN(OPAMP_PGAGain));
|
||||
assert_param(IS_OPAMP_PGACONNECT(OPAMP_PGAConnect));
|
||||
|
||||
/* Reset the configuration bits */
|
||||
*(__IO uint32_t *) (OPAMP_BASE + OPAMP_Selection) &= (uint32_t)(~OPAMP_CSR_PGGAIN);
|
||||
|
||||
/* Set the new configuration */
|
||||
*(__IO uint32_t *) (OPAMP_BASE + OPAMP_Selection) |= (uint32_t) (OPAMP_PGAGain | OPAMP_PGAConnect);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Configure the OPAMP's internal reference.
|
||||
* @note This feature is used when calibration enabled or OPAMP's reference
|
||||
* connected to the non inverting input.
|
||||
* @note If the selected OPAMP is locked, Vref configuration can't be performed.
|
||||
* To unlock the configuration, perform a system reset.
|
||||
* @param OPAMP_Selection: the selected OPAMP.
|
||||
* This parameter can be OPAMP_Selection_OPAMPx where x can be 1 to 4
|
||||
* to select the OPAMP peripheral.
|
||||
* @param OPAMP_Vref: This parameter can be:
|
||||
* OPAMP_Vref_3VDDA: OPMAP Vref = 3.3% VDDA
|
||||
* OPAMP_Vref_10VDDA: OPMAP Vref = 10% VDDA
|
||||
* OPAMP_Vref_50VDDA: OPMAP Vref = 50% VDDA
|
||||
* OPAMP_Vref_90VDDA: OPMAP Vref = 90% VDDA
|
||||
* @retval None
|
||||
*/
|
||||
void OPAMP_VrefConfig(uint32_t OPAMP_Selection, uint32_t OPAMP_Vref)
|
||||
{
|
||||
uint32_t tmpreg = 0;
|
||||
|
||||
/* Check the parameters */
|
||||
assert_param(IS_OPAMP_ALL_PERIPH(OPAMP_Selection));
|
||||
assert_param(IS_OPAMP_VREF(OPAMP_Vref));
|
||||
|
||||
/*!< Get the OPAMPx_CSR register value */
|
||||
tmpreg = *(__IO uint32_t *) (OPAMP_BASE + OPAMP_Selection);
|
||||
|
||||
/*!< Clear the CALSEL bits */
|
||||
tmpreg &= (uint32_t) (~OPAMP_CSR_CALSEL);
|
||||
|
||||
/*!< Configure OPAMP reference */
|
||||
tmpreg |= (uint32_t)(OPAMP_Vref);
|
||||
|
||||
/*!< Write to OPAMPx_CSR register */
|
||||
*(__IO uint32_t *) (OPAMP_BASE + OPAMP_Selection) = tmpreg;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Connnect the internal reference to the OPAMP's non inverting input.
|
||||
* @note If the selected OPAMP is locked, Vref configuration can't be performed.
|
||||
* To unlock the configuration, perform a system reset.
|
||||
* @param OPAMP_Selection: the selected OPAMP.
|
||||
* This parameter can be OPAMP_Selection_OPAMPx where x can be 1 to 4
|
||||
* to select the OPAMP peripheral.
|
||||
* @param NewState: new state of the OPAMP peripheral.
|
||||
* This parameter can be: ENABLE or DISABLE.
|
||||
* @retval None
|
||||
*/
|
||||
void OPAMP_VrefConnectNonInvertingInput(uint32_t OPAMP_Selection, FunctionalState NewState)
|
||||
{
|
||||
/* Check the parameters */
|
||||
assert_param(IS_OPAMP_ALL_PERIPH(OPAMP_Selection));
|
||||
assert_param(IS_FUNCTIONAL_STATE(NewState));
|
||||
|
||||
if (NewState != DISABLE)
|
||||
{
|
||||
/* Connnect the internal reference to the OPAMP's non inverting input */
|
||||
*(__IO uint32_t *) (OPAMP_BASE + OPAMP_Selection) |= (uint32_t) (OPAMP_CSR_FORCEVP);
|
||||
}
|
||||
else
|
||||
{
|
||||
/* Disconnnect the internal reference to the OPAMP's non inverting input */
|
||||
*(__IO uint32_t *) (OPAMP_BASE + OPAMP_Selection) &= (uint32_t)(~OPAMP_CSR_FORCEVP);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Enables or disables connecting the OPAMP's internal reference to ADC.
|
||||
* @note If the selected OPAMP is locked, Vref connection can't be performed.
|
||||
* To unlock the configuration, perform a system reset.
|
||||
* @param NewState: new state of the Vrefint output.
|
||||
* This parameter can be: ENABLE or DISABLE.
|
||||
* @retval None
|
||||
*/
|
||||
void OPAMP_VrefConnectADCCmd(uint32_t OPAMP_Selection, FunctionalState NewState)
|
||||
{
|
||||
/* Check the parameters */
|
||||
assert_param(IS_OPAMP_ALL_PERIPH(OPAMP_Selection));
|
||||
assert_param(IS_FUNCTIONAL_STATE(NewState));
|
||||
|
||||
if (NewState != DISABLE)
|
||||
{
|
||||
/* Enable output internal reference */
|
||||
*(__IO uint32_t *) (OPAMP_BASE + OPAMP_Selection) |= (uint32_t) (OPAMP_CSR_TSTREF);
|
||||
}
|
||||
else
|
||||
{
|
||||
/* Disable output internal reference */
|
||||
*(__IO uint32_t *) (OPAMP_BASE + OPAMP_Selection) &= (uint32_t)(~OPAMP_CSR_TSTREF);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Configure the OPAMP peripheral (secondary inputs) for timer-controlled
|
||||
* mux mode according to the specified parameters in OPAMP_InitStruct.
|
||||
* @note If the selected OPAMP is locked, timer-controlled mux configuration
|
||||
* can't be performed.
|
||||
* To unlock the configuration, perform a system reset.
|
||||
* @param OPAMP_Selection: the selected OPAMP.
|
||||
* This parameter can be OPAMP_Selection_OPAMPx where x can be 1 to 4
|
||||
* to select the OPAMP peripheral.
|
||||
* @param OPAMP_InitStruct: pointer to an OPAMP_InitTypeDef structure that contains
|
||||
* the configuration information for the specified OPAMP peripheral.
|
||||
* - OPAMP_InvertingInput specifies the inverting input of OPAMP
|
||||
* - OPAMP_NonInvertingInput specifies the non inverting input of OPAMP
|
||||
* @note PGA and Vout can't be selected as seconadry inverting input.
|
||||
* @retval None
|
||||
*/
|
||||
void OPAMP_TimerControlledMuxConfig(uint32_t OPAMP_Selection, OPAMP_InitTypeDef* OPAMP_InitStruct)
|
||||
{
|
||||
uint32_t tmpreg = 0;
|
||||
|
||||
/* Check the parameters */
|
||||
assert_param(IS_OPAMP_ALL_PERIPH(OPAMP_Selection));
|
||||
assert_param(IS_OPAMP_SECONDARY_INVINPUT(OPAMP_InitStruct->OPAMP_InvertingInput));
|
||||
assert_param(IS_OPAMP_NONINVERTING_INPUT(OPAMP_InitStruct->OPAMP_NonInvertingInput));
|
||||
|
||||
/*!< Get the OPAMPx_CSR register value */
|
||||
tmpreg = *(__IO uint32_t *) (OPAMP_BASE + OPAMP_Selection);
|
||||
|
||||
/*!< Clear the secondary inverting bit, secondary non inverting bit and TCMEN bits */
|
||||
tmpreg &= (uint32_t) (OPAMP_CSR_TIMERMUX_MASK);
|
||||
|
||||
/*!< Configure OPAMP: secondary inverting and non inverting inputs */
|
||||
tmpreg |= (uint32_t)((uint32_t)(OPAMP_InitStruct->OPAMP_InvertingInput<<3) | (uint32_t)(OPAMP_InitStruct->OPAMP_NonInvertingInput<<7));
|
||||
|
||||
/*!< Write to OPAMPx_CSR register */
|
||||
*(__IO uint32_t *) (OPAMP_BASE + OPAMP_Selection) = tmpreg;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Enable or disable the timer-controlled mux mode.
|
||||
* @note If the selected OPAMP is locked, enable/disable can't be performed.
|
||||
* To unlock the configuration, perform a system reset.
|
||||
* @param OPAMP_Selection: the selected OPAMP.
|
||||
* This parameter can be OPAMP_Selection_OPAMPx where x can be 1 to 4
|
||||
* to select the OPAMP peripheral.
|
||||
* @param NewState: new state of the OPAMP peripheral.
|
||||
* This parameter can be: ENABLE or DISABLE.
|
||||
* @retval None
|
||||
*/
|
||||
void OPAMP_TimerControlledMuxCmd(uint32_t OPAMP_Selection, FunctionalState NewState)
|
||||
{
|
||||
/* Check the parameters */
|
||||
assert_param(IS_OPAMP_ALL_PERIPH(OPAMP_Selection));
|
||||
assert_param(IS_FUNCTIONAL_STATE(NewState));
|
||||
|
||||
if (NewState != DISABLE)
|
||||
{
|
||||
/* Enable the timer-controlled Mux mode */
|
||||
*(__IO uint32_t *) (OPAMP_BASE + OPAMP_Selection) |= (uint32_t) (OPAMP_CSR_TCMEN);
|
||||
}
|
||||
else
|
||||
{
|
||||
/* Disable the timer-controlled Mux mode */
|
||||
*(__IO uint32_t *) (OPAMP_BASE + OPAMP_Selection) &= (uint32_t)(~OPAMP_CSR_TCMEN);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Enable or disable the OPAMP peripheral.
|
||||
* @note If the selected OPAMP is locked, enable/disable can't be performed.
|
||||
* To unlock the configuration, perform a system reset.
|
||||
* @param OPAMP_Selection: the selected OPAMP.
|
||||
* This parameter can be OPAMP_Selection_OPAMPx where x can be 1 to 4
|
||||
* to select the OPAMP peripheral.
|
||||
* @param NewState: new state of the OPAMP peripheral.
|
||||
* This parameter can be: ENABLE or DISABLE.
|
||||
* @retval None
|
||||
*/
|
||||
void OPAMP_Cmd(uint32_t OPAMP_Selection, FunctionalState NewState)
|
||||
{
|
||||
/* Check the parameters */
|
||||
assert_param(IS_OPAMP_ALL_PERIPH(OPAMP_Selection));
|
||||
assert_param(IS_FUNCTIONAL_STATE(NewState));
|
||||
|
||||
if (NewState != DISABLE)
|
||||
{
|
||||
/* Enable the selected OPAMPx peripheral */
|
||||
*(__IO uint32_t *) (OPAMP_BASE + OPAMP_Selection) |= (uint32_t) (OPAMP_CSR_OPAMPxEN);
|
||||
}
|
||||
else
|
||||
{
|
||||
/* Disable the selected OPAMPx peripheral */
|
||||
*(__IO uint32_t *) (OPAMP_BASE + OPAMP_Selection) &= (uint32_t)(~OPAMP_CSR_OPAMPxEN);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Return the output level (high or low) during calibration of the selected OPAMP.
|
||||
* @param OPAMP_Selection: the selected OPAMP.
|
||||
* This parameter can be OPAMP_Selection_OPAMPx where x can be 1 to 4
|
||||
* to select the OPAMP peripheral.
|
||||
* - OPAMP output is low when the non-inverting input is at a lower
|
||||
* voltage than the inverting input
|
||||
* - OPAMP output is high when the non-inverting input is at a higher
|
||||
* voltage than the inverting input
|
||||
* @note OPAMP ouput level is provided only during calibration phase.
|
||||
* @retval Returns the selected OPAMP output level: low or high.
|
||||
*
|
||||
*/
|
||||
uint32_t OPAMP_GetOutputLevel(uint32_t OPAMP_Selection)
|
||||
{
|
||||
uint32_t opampout = 0x0;
|
||||
|
||||
/* Check the parameters */
|
||||
assert_param(IS_OPAMP_ALL_PERIPH(OPAMP_Selection));
|
||||
|
||||
/* Check if selected OPAMP output is high */
|
||||
if ((*(__IO uint32_t *) (OPAMP_BASE + OPAMP_Selection) & (OPAMP_CSR_OUTCAL)) != 0)
|
||||
{
|
||||
opampout = OPAMP_OutputLevel_High;
|
||||
}
|
||||
else
|
||||
{
|
||||
opampout = OPAMP_OutputLevel_Low;
|
||||
}
|
||||
|
||||
/* Return the OPAMP output level */
|
||||
return (uint32_t)(opampout);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Select the trimming mode.
|
||||
* @param OffsetTrimming: the selected offset trimming mode.
|
||||
* This parameter can be one of the following values:
|
||||
* @arg OPAMP_Trimming_Factory: factory trimming values are used for offset
|
||||
* calibration
|
||||
* @arg OPAMP_Trimming_User: user trimming values are used for offset
|
||||
* calibration
|
||||
* @note When OffsetTrimming_User is selected, use OPAMP_OffsetTrimConfig()
|
||||
* function or OPAMP_OffsetTrimLowPowerConfig() function to adjust
|
||||
* trimming value.
|
||||
* @retval None
|
||||
*/
|
||||
void OPAMP_OffsetTrimModeSelect(uint32_t OPAMP_Selection, uint32_t OPAMP_Trimming)
|
||||
{
|
||||
/* Check the parameters */
|
||||
assert_param(IS_OPAMP_ALL_PERIPH(OPAMP_Selection));
|
||||
assert_param(IS_OPAMP_TRIMMING(OPAMP_Trimming));
|
||||
|
||||
/* Reset USERTRIM bit */
|
||||
*(__IO uint32_t *) (OPAMP_BASE + OPAMP_Selection) &= (~(uint32_t) (OPAMP_CSR_USERTRIM));
|
||||
|
||||
/* Select trimming mode */
|
||||
*(__IO uint32_t *) (OPAMP_BASE + OPAMP_Selection) |= OPAMP_Trimming;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Configure the trimming value of the OPAMP.
|
||||
* @param OPAMP_Selection: the selected OPAMP.
|
||||
* This parameter can be OPAMP_Selection_OPAMPx where x can be 1 to 4
|
||||
* to select the OPAMP peripheral.
|
||||
* @param OPAMP_Input: the selected OPAMP input.
|
||||
* This parameter can be one of the following values:
|
||||
* @arg OPAMP_Input_Inverting: Inverting input is selected to configure the trimming value
|
||||
* @arg OPAMP_Input_NonInverting: Non inverting input is selected to configure the trimming value
|
||||
* @param OPAMP_TrimValue: the trimming value. This parameter can be any value lower
|
||||
* or equal to 0x0000001F.
|
||||
* @retval None
|
||||
*/
|
||||
void OPAMP_OffsetTrimConfig(uint32_t OPAMP_Selection, uint32_t OPAMP_Input, uint32_t OPAMP_TrimValue)
|
||||
{
|
||||
uint32_t tmpreg = 0;
|
||||
|
||||
/* Check the parameters */
|
||||
assert_param(IS_OPAMP_ALL_PERIPH(OPAMP_Selection));
|
||||
assert_param(IS_OPAMP_INPUT(OPAMP_Input));
|
||||
assert_param(IS_OPAMP_TRIMMINGVALUE(OPAMP_TrimValue));
|
||||
|
||||
/*!< Get the OPAMPx_CSR register value */
|
||||
tmpreg = *(__IO uint32_t *) (OPAMP_BASE + OPAMP_Selection);
|
||||
|
||||
/*!< Clear the trimming bits */
|
||||
tmpreg &= ((uint32_t)~(OPAMP_CSR_TRIMMING_MASK<<OPAMP_Input));
|
||||
|
||||
/*!< Configure the new trimming value */
|
||||
tmpreg |= (uint32_t)(OPAMP_TrimValue<<OPAMP_Input);
|
||||
|
||||
/*!< Write to OPAMPx_CSR register */
|
||||
*(__IO uint32_t *) (OPAMP_BASE + OPAMP_Selection) = tmpreg;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Start or stop the calibration of selected OPAMP peripheral.
|
||||
* @note If the selected OPAMP is locked, start/stop can't be performed.
|
||||
* To unlock the configuration, perform a system reset.
|
||||
* @param OPAMP_Selection: the selected OPAMP.
|
||||
* This parameter can be OPAMP_Selection_OPAMPx where x can be 1 to 4
|
||||
* to select the OPAMP peripheral.
|
||||
* @param NewState: new state of the OPAMP peripheral.
|
||||
* This parameter can be: ENABLE or DISABLE.
|
||||
* @retval None
|
||||
*/
|
||||
void OPAMP_StartCalibration(uint32_t OPAMP_Selection, FunctionalState NewState)
|
||||
{
|
||||
/* Check the parameters */
|
||||
assert_param(IS_OPAMP_ALL_PERIPH(OPAMP_Selection));
|
||||
assert_param(IS_FUNCTIONAL_STATE(NewState));
|
||||
|
||||
if (NewState != DISABLE)
|
||||
{
|
||||
/* Start the OPAMPx calibration */
|
||||
*(__IO uint32_t *) (OPAMP_BASE + OPAMP_Selection) |= (uint32_t) (OPAMP_CSR_CALON);
|
||||
}
|
||||
else
|
||||
{
|
||||
/* Stop the OPAMPx calibration */
|
||||
*(__IO uint32_t *) (OPAMP_BASE + OPAMP_Selection) &= (uint32_t)(~OPAMP_CSR_CALON);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/** @defgroup OPAMP_Group2 OPAMP configuration locking function
|
||||
* @brief OPAMP1,...OPAMP4 configuration locking function
|
||||
* OPAMP1,...OPAMP4 configuration can be locked each separately.
|
||||
* Unlocking is performed by system reset.
|
||||
*
|
||||
@verbatim
|
||||
===============================================================================
|
||||
##### Configuration Lock function #####
|
||||
===============================================================================
|
||||
|
||||
@endverbatim
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief Lock the selected OPAMP configuration.
|
||||
* @note Locking the configuration means that all control bits are read-only.
|
||||
* To unlock the OPAMP configuration, perform a system reset.
|
||||
* @param OPAMP_Selection: the selected OPAMP.
|
||||
* This parameter can be OPAMP_Selection_OPAMPx where x can be 1 to 4
|
||||
* to select the OPAMP peripheral.
|
||||
* @retval None
|
||||
*/
|
||||
void OPAMP_LockConfig(uint32_t OPAMP_Selection)
|
||||
{
|
||||
/* Check the parameter */
|
||||
assert_param(IS_OPAMP_ALL_PERIPH(OPAMP_Selection));
|
||||
|
||||
/* Set the lock bit corresponding to selected OPAMP */
|
||||
*(__IO uint32_t *) (OPAMP_BASE + OPAMP_Selection) |= (uint32_t) (OPAMP_CSR_LOCK);
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
|
@ -0,0 +1,538 @@
|
|||
/**
|
||||
******************************************************************************
|
||||
* @file stm32f30x_pwr.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 Power Controller (PWR) peripheral:
|
||||
* + Backup Domain Access
|
||||
* + PVD configuration
|
||||
* + WakeUp pins configuration
|
||||
* + Low Power modes configuration
|
||||
* + Flags management
|
||||
*
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© 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_pwr.h"
|
||||
#include "stm32f30x_rcc.h"
|
||||
|
||||
/** @addtogroup STM32F30x_StdPeriph_Driver
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @defgroup PWR
|
||||
* @brief PWR driver modules
|
||||
* @{
|
||||
*/
|
||||
|
||||
/* Private typedef -----------------------------------------------------------*/
|
||||
/* Private define ------------------------------------------------------------*/
|
||||
/* --------- PWR registers bit address in the alias region ---------- */
|
||||
#define PWR_OFFSET (PWR_BASE - PERIPH_BASE)
|
||||
|
||||
/* --- CR Register ---*/
|
||||
|
||||
/* Alias word address of DBP bit */
|
||||
#define CR_OFFSET (PWR_OFFSET + 0x00)
|
||||
#define DBP_BitNumber 0x08
|
||||
#define CR_DBP_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (DBP_BitNumber * 4))
|
||||
|
||||
/* Alias word address of PVDE bit */
|
||||
#define PVDE_BitNumber 0x04
|
||||
#define CR_PVDE_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (PVDE_BitNumber * 4))
|
||||
|
||||
/* ------------------ PWR registers bit mask ------------------------ */
|
||||
|
||||
/* CR register bit mask */
|
||||
#define CR_DS_MASK ((uint32_t)0xFFFFFFFC)
|
||||
#define CR_PLS_MASK ((uint32_t)0xFFFFFF1F)
|
||||
|
||||
/* Private macro -------------------------------------------------------------*/
|
||||
/* Private variables ---------------------------------------------------------*/
|
||||
/* Private function prototypes -----------------------------------------------*/
|
||||
/* Private functions ---------------------------------------------------------*/
|
||||
|
||||
/** @defgroup PWR_Private_Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @defgroup PWR_Group1 Backup Domain Access function
|
||||
* @brief Backup Domain Access function
|
||||
*
|
||||
@verbatim
|
||||
==============================================================================
|
||||
##### Backup Domain Access function #####
|
||||
==============================================================================
|
||||
|
||||
[..] After reset, the Backup Domain Registers (RCC BDCR Register, RTC registers
|
||||
and RTC backup registers) are protected against possible stray write accesses.
|
||||
[..] To enable access to Backup domain use the PWR_BackupAccessCmd(ENABLE) function.
|
||||
|
||||
@endverbatim
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief Deinitializes the PWR peripheral registers to their default reset values.
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
void PWR_DeInit(void)
|
||||
{
|
||||
RCC_APB1PeriphResetCmd(RCC_APB1Periph_PWR, ENABLE);
|
||||
RCC_APB1PeriphResetCmd(RCC_APB1Periph_PWR, DISABLE);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Enables or disables access to the RTC and backup registers.
|
||||
* @note If the HSE divided by 32 is used as the RTC clock, the
|
||||
* Backup Domain Access should be kept enabled.
|
||||
* @param NewState: new state of the access to the RTC and backup registers.
|
||||
* This parameter can be: ENABLE or DISABLE.
|
||||
* @retval None
|
||||
*/
|
||||
void PWR_BackupAccessCmd(FunctionalState NewState)
|
||||
{
|
||||
/* Check the parameters */
|
||||
assert_param(IS_FUNCTIONAL_STATE(NewState));
|
||||
*(__IO uint32_t *) CR_DBP_BB = (uint32_t)NewState;
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/** @defgroup PWR_Group2 PVD configuration functions
|
||||
* @brief PVD configuration functions
|
||||
*
|
||||
@verbatim
|
||||
===============================================================================
|
||||
##### PVD configuration functions #####
|
||||
==============================================================================
|
||||
[..]
|
||||
(+) The PVD is used to monitor the VDD power supply by comparing it to a threshold
|
||||
selected by the PVD Level (PLS[2:0] bits in the PWR_CR).
|
||||
(+) A PVDO flag is available to indicate if VDD/VDDA is higher or lower than the
|
||||
PVD threshold. This event is internally connected to the EXTI line16
|
||||
and can generate an interrupt if enabled through the EXTI registers.
|
||||
(+) The PVD is stopped in Standby mode.
|
||||
|
||||
@endverbatim
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief Configures the voltage threshold detected by the Power Voltage Detector(PVD).
|
||||
* @param PWR_PVDLevel: specifies the PVD detection level
|
||||
* This parameter can be one of the following values:
|
||||
* @arg PWR_PVDLevel_0: PVD detection level set to 2.18V
|
||||
* @arg PWR_PVDLevel_1: PVD detection level set to 2.28V
|
||||
* @arg PWR_PVDLevel_2: PVD detection level set to 2.38V
|
||||
* @arg PWR_PVDLevel_3: PVD detection level set to 2.48V
|
||||
* @arg PWR_PVDLevel_4: PVD detection level set to 2.58V
|
||||
* @arg PWR_PVDLevel_5: PVD detection level set to 2.68V
|
||||
* @arg PWR_PVDLevel_6: PVD detection level set to 2.78V
|
||||
* @arg PWR_PVDLevel_7: PVD detection level set to 2.88V
|
||||
* @retval None
|
||||
*/
|
||||
void PWR_PVDLevelConfig(uint32_t PWR_PVDLevel)
|
||||
{
|
||||
uint32_t tmpreg = 0;
|
||||
|
||||
/* Check the parameters */
|
||||
assert_param(IS_PWR_PVD_LEVEL(PWR_PVDLevel));
|
||||
|
||||
tmpreg = PWR->CR;
|
||||
|
||||
/* Clear PLS[7:5] bits */
|
||||
tmpreg &= CR_PLS_MASK;
|
||||
|
||||
/* Set PLS[7:5] bits according to PWR_PVDLevel value */
|
||||
tmpreg |= PWR_PVDLevel;
|
||||
|
||||
/* Store the new value */
|
||||
PWR->CR = tmpreg;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Enables or disables the Power Voltage Detector(PVD).
|
||||
* @param NewState: new state of the PVD.
|
||||
* This parameter can be: ENABLE or DISABLE.
|
||||
* @retval None
|
||||
*/
|
||||
void PWR_PVDCmd(FunctionalState NewState)
|
||||
{
|
||||
/* Check the parameters */
|
||||
assert_param(IS_FUNCTIONAL_STATE(NewState));
|
||||
*(__IO uint32_t *) CR_PVDE_BB = (uint32_t)NewState;
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/** @defgroup PWR_Group3 WakeUp pins configuration functions
|
||||
* @brief WakeUp pins configuration functions
|
||||
*
|
||||
@verbatim
|
||||
===============================================================================
|
||||
##### WakeUp pins configuration functions #####
|
||||
===============================================================================
|
||||
[..]
|
||||
(+) WakeUp pins are used to wakeup the system from Standby mode. These pins are
|
||||
forced in input pull down configuration and are active on rising edges.
|
||||
(+) There are three WakeUp pins: WakeUp Pin 1 on PA.00, WakeUp Pin 2 on PC.13 and
|
||||
WakeUp Pin 3 on PE.06.
|
||||
|
||||
@endverbatim
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief Enables or disables the WakeUp Pin functionality.
|
||||
* @param PWR_WakeUpPin: specifies the WakeUpPin.
|
||||
* This parameter can be: PWR_WakeUpPin_1, PWR_WakeUpPin_2 or PWR_WakeUpPin_3.
|
||||
* @param NewState: new state of the WakeUp Pin functionality.
|
||||
* This parameter can be: ENABLE or DISABLE.
|
||||
* @retval None
|
||||
*/
|
||||
void PWR_WakeUpPinCmd(uint32_t PWR_WakeUpPin, FunctionalState NewState)
|
||||
{
|
||||
/* Check the parameters */
|
||||
assert_param(IS_PWR_WAKEUP_PIN(PWR_WakeUpPin));
|
||||
assert_param(IS_FUNCTIONAL_STATE(NewState));
|
||||
|
||||
if (NewState != DISABLE)
|
||||
{
|
||||
/* Enable the EWUPx pin */
|
||||
PWR->CSR |= PWR_WakeUpPin;
|
||||
}
|
||||
else
|
||||
{
|
||||
/* Disable the EWUPx pin */
|
||||
PWR->CSR &= ~PWR_WakeUpPin;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
/** @defgroup PWR_Group4 Low Power modes configuration functions
|
||||
* @brief Low Power modes configuration functions
|
||||
*
|
||||
@verbatim
|
||||
===============================================================================
|
||||
##### Low Power modes configuration functions #####
|
||||
==============================================================================
|
||||
|
||||
[..] The devices feature three low-power modes:
|
||||
(+) Sleep mode: Cortex-M4 core stopped, peripherals kept running.
|
||||
(+) Stop mode: all clocks are stopped, regulator running, regulator in low power mode
|
||||
(+) Standby mode: VCORE domain powered off
|
||||
|
||||
*** Sleep mode ***
|
||||
==================
|
||||
[..]
|
||||
(+) Entry:
|
||||
(++) The Sleep mode is entered by executing the WFE() or WFI() instructions.
|
||||
(+) Exit:
|
||||
(++) Any peripheral interrupt acknowledged by the nested vectored interrupt
|
||||
controller (NVIC) can wake up the device from Sleep mode.
|
||||
|
||||
*** Stop mode ***
|
||||
=================
|
||||
[..] In Stop mode, all clocks in the VCORE domain are stopped, the PLL, the HSI,
|
||||
and the HSE RC oscillators are disabled. Internal SRAM and register
|
||||
contents are preserved.
|
||||
The voltage regulator can be configured either in normal or low-power mode.
|
||||
|
||||
(+) Entry:
|
||||
(++) The Stop mode is entered using the PWR_EnterSTOPMode(PWR_Regulator_LowPower,)
|
||||
function with regulator in LowPower or with Regulator ON.
|
||||
(+) Exit:
|
||||
(++) Any EXTI Line (Internal or External) configured in Interrupt/Event mode
|
||||
or any internal IPs (I2C or UASRT) wakeup event.
|
||||
|
||||
*** Standby mode ***
|
||||
====================
|
||||
[..] The Standby mode allows to achieve the lowest power consumption. It is based
|
||||
on the Cortex-M4 deepsleep mode, with the voltage regulator disabled.
|
||||
The VCORE domain is consequently powered off. The PLL, the HSI, and the HSE
|
||||
oscillator are also switched off. SRAM and register
|
||||
contents are lost except for the Backup domain (RTC registers, RTC backup
|
||||
registers and Standby circuitry).
|
||||
|
||||
[..] The voltage regulator is OFF.
|
||||
|
||||
(+) Entry:
|
||||
(++) The Standby mode is entered using the PWR_EnterSTANDBYMode() function.
|
||||
(+) Exit:
|
||||
(++) WKUP pin rising edge, RTC alarm (Alarm A and Alarm B), RTC wakeup,
|
||||
tamper event, time-stamp event, external reset in NRST pin, IWDG reset.
|
||||
|
||||
*** Auto-wakeup (AWU) from low-power mode ***
|
||||
=============================================
|
||||
[..] The MCU can be woken up from low-power mode by an RTC Alarm event, a tamper
|
||||
event, a time-stamp event, or a comparator event, without depending on an
|
||||
external interrupt (Auto-wakeup mode).
|
||||
|
||||
(+) RTC auto-wakeup (AWU) from the Stop mode
|
||||
(++) To wake up from the Stop mode with an RTC alarm event, it is necessary to:
|
||||
(+++) Configure the EXTI Line 17 to be sensitive to rising edges (Interrupt
|
||||
or Event modes) using the EXTI_Init() function.
|
||||
(+++) Enable the RTC Alarm Interrupt using the RTC_ITConfig() function
|
||||
(+++) Configure the RTC to generate the RTC alarm using the RTC_SetAlarm()
|
||||
and RTC_AlarmCmd() functions.
|
||||
(++) To wake up from the Stop mode with an RTC Tamper or time stamp event, it
|
||||
is necessary to:
|
||||
(+++) Configure the EXTI Line 19 to be sensitive to rising edges (Interrupt
|
||||
or Event modes) using the EXTI_Init() function.
|
||||
(+++) Enable the RTC Tamper or time stamp Interrupt using the RTC_ITConfig()
|
||||
function.
|
||||
(+++) Configure the RTC to detect the tamper or time stamp event using the
|
||||
RTC_TimeStampConfig(), RTC_TamperTriggerConfig() and RTC_TamperCmd()
|
||||
functions.
|
||||
|
||||
(+) RTC auto-wakeup (AWU) from the Standby mode
|
||||
(++) To wake up from the Standby mode with an RTC alarm event, it is necessary to:
|
||||
(+++) Enable the RTC Alarm Interrupt using the RTC_ITConfig() function.
|
||||
(+++) Configure the RTC to generate the RTC alarm using the RTC_SetAlarm()
|
||||
and RTC_AlarmCmd() functions.
|
||||
(++) To wake up from the Standby mode with an RTC Tamper or time stamp event, it
|
||||
is necessary to:
|
||||
(+++) Enable the RTC Tamper or time stamp Interrupt using the RTC_ITConfig()
|
||||
function.
|
||||
(+++) Configure the RTC to detect the tamper or time stamp event using the
|
||||
RTC_TimeStampConfig(), RTC_TamperTriggerConfig() and RTC_TamperCmd()
|
||||
functions.
|
||||
|
||||
(+) Comparator auto-wakeup (AWU) from the Stop mode
|
||||
(++) To wake up from the Stop mode with a comparator wakeup event, it is necessary to:
|
||||
(+++) Configure the correspondant comparator EXTI Line to be sensitive to
|
||||
the selected edges (falling, rising or falling and rising)
|
||||
(Interrupt or Event modes) using the EXTI_Init() function.
|
||||
(+++) Configure the comparator to generate the event.
|
||||
|
||||
@endverbatim
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief Enters Sleep mode.
|
||||
* @note In Sleep mode, all I/O pins keep the same state as in Run mode.
|
||||
* @param PWR_SLEEPEntry: specifies if SLEEP mode in entered with WFI or WFE instruction.
|
||||
* This parameter can be one of the following values:
|
||||
* @arg PWR_SLEEPEntry_WFI: enter SLEEP mode with WFI instruction
|
||||
* @arg PWR_SLEEPEntry_WFE: enter SLEEP mode with WFE instruction
|
||||
* @retval None
|
||||
*/
|
||||
void PWR_EnterSleepMode(uint8_t PWR_SLEEPEntry)
|
||||
{
|
||||
/* Check the parameters */
|
||||
assert_param(IS_PWR_SLEEP_ENTRY(PWR_SLEEPEntry));
|
||||
|
||||
/* Clear SLEEPDEEP bit of Cortex System Control Register */
|
||||
SCB->SCR &= (uint32_t)~((uint32_t)SCB_SCR_SLEEPDEEP_Msk);
|
||||
|
||||
/* Select SLEEP mode entry -------------------------------------------------*/
|
||||
if(PWR_SLEEPEntry == PWR_SLEEPEntry_WFI)
|
||||
{
|
||||
/* Request Wait For Interrupt */
|
||||
__WFI();
|
||||
}
|
||||
else
|
||||
{
|
||||
/* Request Wait For Event */
|
||||
__WFE();
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Enters STOP mode.
|
||||
* @note In Stop mode, all I/O pins keep the same state as in Run mode.
|
||||
* @note When exiting Stop mode by issuing an interrupt or a wakeup event,
|
||||
* the HSI RC oscillator is selected as system clock.
|
||||
* @note When the voltage regulator operates in low power mode, an additional
|
||||
* startup delay is incurred when waking up from Stop mode.
|
||||
* By keeping the internal regulator ON during Stop mode, the consumption
|
||||
* is higher although the startup time is reduced.
|
||||
* @param PWR_Regulator: specifies the regulator state in STOP mode.
|
||||
* This parameter can be one of the following values:
|
||||
* @arg PWR_Regulator_ON: STOP mode with regulator ON
|
||||
* @arg PWR_Regulator_LowPower: STOP mode with regulator in low power mode
|
||||
* @param PWR_STOPEntry: specifies if STOP mode in entered with WFI or WFE instruction.
|
||||
* This parameter can be one of the following values:
|
||||
* @arg PWR_STOPEntry_WFI: enter STOP mode with WFI instruction
|
||||
* @arg PWR_STOPEntry_WFE: enter STOP mode with WFE instruction
|
||||
* @retval None
|
||||
*/
|
||||
void PWR_EnterSTOPMode(uint32_t PWR_Regulator, uint8_t PWR_STOPEntry)
|
||||
{
|
||||
uint32_t tmpreg = 0;
|
||||
|
||||
/* Check the parameters */
|
||||
assert_param(IS_PWR_REGULATOR(PWR_Regulator));
|
||||
assert_param(IS_PWR_STOP_ENTRY(PWR_STOPEntry));
|
||||
|
||||
/* Select the regulator state in STOP mode ---------------------------------*/
|
||||
tmpreg = PWR->CR;
|
||||
/* Clear PDDS and LPDSR bits */
|
||||
tmpreg &= CR_DS_MASK;
|
||||
|
||||
/* Set LPDSR bit according to PWR_Regulator value */
|
||||
tmpreg |= PWR_Regulator;
|
||||
|
||||
/* Store the new value */
|
||||
PWR->CR = tmpreg;
|
||||
|
||||
/* Set SLEEPDEEP bit of Cortex System Control Register */
|
||||
SCB->SCR |= SCB_SCR_SLEEPDEEP_Msk;
|
||||
|
||||
/* Select STOP mode entry --------------------------------------------------*/
|
||||
if(PWR_STOPEntry == PWR_STOPEntry_WFI)
|
||||
{
|
||||
/* Request Wait For Interrupt */
|
||||
__WFI();
|
||||
}
|
||||
else
|
||||
{
|
||||
/* Request Wait For Event */
|
||||
__WFE();
|
||||
}
|
||||
/* Reset SLEEPDEEP bit of Cortex System Control Register */
|
||||
SCB->SCR &= (uint32_t)~((uint32_t)SCB_SCR_SLEEPDEEP_Msk);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Enters STANDBY mode.
|
||||
* @note In Standby mode, all I/O pins are high impedance except for:
|
||||
* @note Reset pad (still available)
|
||||
* @note RTC_AF1 pin (PC13) if configured for Wakeup pin 2 (WKUP2), tamper,
|
||||
* time-stamp, RTC Alarm out, or RTC clock calibration out.
|
||||
* @note WKUP pin 1 (PA0) and WKUP pin 3 (PE6), if enabled.
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
void PWR_EnterSTANDBYMode(void)
|
||||
{
|
||||
/* Clear Wakeup flag */
|
||||
PWR->CR |= PWR_CR_CWUF;
|
||||
|
||||
/* Select STANDBY mode */
|
||||
PWR->CR |= PWR_CR_PDDS;
|
||||
|
||||
/* Set SLEEPDEEP bit of Cortex System Control Register */
|
||||
SCB->SCR |= SCB_SCR_SLEEPDEEP_Msk;
|
||||
|
||||
/* This option is used to ensure that store operations are completed */
|
||||
#if defined ( __CC_ARM )
|
||||
__force_stores();
|
||||
#endif
|
||||
/* Request Wait For Interrupt */
|
||||
__WFI();
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/** @defgroup PWR_Group5 Flags management functions
|
||||
* @brief Flags management functions
|
||||
*
|
||||
@verbatim
|
||||
===============================================================================
|
||||
##### Flags management functions #####
|
||||
===============================================================================
|
||||
|
||||
@endverbatim
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief Checks whether the specified PWR flag is set or not.
|
||||
* @param PWR_FLAG: specifies the flag to check.
|
||||
* This parameter can be one of the following values:
|
||||
* @arg PWR_FLAG_WU: Wake Up flag. This flag indicates that a wakeup event
|
||||
* was received from the WKUP pin or from the RTC alarm (Alarm A or Alarm B),
|
||||
* RTC Tamper event, RTC TimeStamp event or RTC Wakeup.
|
||||
* @arg PWR_FLAG_SB: StandBy flag. This flag indicates that the system was
|
||||
* resumed from StandBy mode.
|
||||
* @arg PWR_FLAG_PVDO: PVD Output. This flag is valid only if PVD is enabled
|
||||
* by the PWR_PVDCmd() function.
|
||||
* @arg PWR_FLAG_VREFINTRDY: Internal Voltage Reference Ready flag. This
|
||||
* flag indicates the state of the internal voltage reference, VREFINT.
|
||||
* @retval The new state of PWR_FLAG (SET or RESET).
|
||||
*/
|
||||
FlagStatus PWR_GetFlagStatus(uint32_t PWR_FLAG)
|
||||
{
|
||||
FlagStatus bitstatus = RESET;
|
||||
/* Check the parameters */
|
||||
assert_param(IS_PWR_GET_FLAG(PWR_FLAG));
|
||||
|
||||
if ((PWR->CSR & PWR_FLAG) != (uint32_t)RESET)
|
||||
{
|
||||
bitstatus = SET;
|
||||
}
|
||||
else
|
||||
{
|
||||
bitstatus = RESET;
|
||||
}
|
||||
/* Return the flag status */
|
||||
return bitstatus;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Clears the PWR's pending flags.
|
||||
* @param PWR_FLAG: specifies the flag to clear.
|
||||
* This parameter can be one of the following values:
|
||||
* @arg PWR_FLAG_WU: Wake Up flag
|
||||
* @arg PWR_FLAG_SB: StandBy flag
|
||||
* @retval None
|
||||
*/
|
||||
void PWR_ClearFlag(uint32_t PWR_FLAG)
|
||||
{
|
||||
/* Check the parameters */
|
||||
assert_param(IS_PWR_CLEAR_FLAG(PWR_FLAG));
|
||||
|
||||
PWR->CR |= PWR_FLAG << 2;
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
File diff suppressed because it is too large
Load diff
File diff suppressed because it is too large
Load diff
File diff suppressed because it is too large
Load diff
|
@ -0,0 +1,524 @@
|
|||
/**
|
||||
******************************************************************************
|
||||
* @file stm32f30x_syscfg.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 SYSCFG peripheral:
|
||||
* + Remapping the memory mapped at 0x00000000
|
||||
* + Remapping the DMA channels
|
||||
* + Enabling I2C fast mode plus driving capability for I2C plus
|
||||
* + Remapping USB interrupt line
|
||||
* + Configuring the EXTI lines connection to the GPIO port
|
||||
* + Configuring the CLASSB requirements
|
||||
*
|
||||
@verbatim
|
||||
|
||||
===============================================================================
|
||||
##### How to use this driver #####
|
||||
===============================================================================
|
||||
[..] The SYSCFG registers can be accessed only when the SYSCFG
|
||||
interface APB clock is enabled.
|
||||
[..] To enable SYSCFG APB clock use:
|
||||
RCC_APBPeriphClockCmd(RCC_APBPeriph_SYSCFG, ENABLE);
|
||||
|
||||
@endverbatim
|
||||
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© 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_syscfg.h"
|
||||
|
||||
/** @addtogroup STM32F30x_StdPeriph_Driver
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @defgroup SYSCFG
|
||||
* @brief SYSCFG driver modules
|
||||
* @{
|
||||
*/
|
||||
|
||||
/* Private typedef -----------------------------------------------------------*/
|
||||
/* Private define ------------------------------------------------------------*/
|
||||
/* Reset value od SYSCFG_CFGR1 register */
|
||||
#define CFGR1_CLEAR_MASK ((uint32_t)0x7C000000)
|
||||
|
||||
/* ------------ SYSCFG registers bit address in the alias region -------------*/
|
||||
#define SYSCFG_OFFSET (SYSCFG_BASE - PERIPH_BASE)
|
||||
|
||||
/* --- CFGR1 Register ---*/
|
||||
/* Alias word address of USB_IT_RMP bit */
|
||||
#define CFGR1_OFFSET (SYSCFG_OFFSET + 0x00)
|
||||
#define USBITRMP_BitNumber 0x05
|
||||
#define CFGR1_USBITRMP_BB (PERIPH_BB_BASE + (CFGR1_OFFSET * 32) + (USBITRMP_BitNumber * 4))
|
||||
|
||||
/* --- CFGR2 Register ---*/
|
||||
/* Alias word address of BYP_ADDR_PAR bit */
|
||||
#define CFGR2_OFFSET (SYSCFG_OFFSET + 0x18)
|
||||
#define BYPADDRPAR_BitNumber 0x04
|
||||
#define CFGR1_BYPADDRPAR_BB (PERIPH_BB_BASE + (CFGR2_OFFSET * 32) + (BYPADDRPAR_BitNumber * 4))
|
||||
|
||||
/* Private macro -------------------------------------------------------------*/
|
||||
/* Private variables ---------------------------------------------------------*/
|
||||
/* Private function prototypes -----------------------------------------------*/
|
||||
/* Private functions ---------------------------------------------------------*/
|
||||
|
||||
/** @defgroup SYSCFG_Private_Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @defgroup SYSCFG_Group1 SYSCFG Initialization and Configuration functions
|
||||
* @brief SYSCFG Initialization and Configuration functions
|
||||
*
|
||||
@verbatim
|
||||
===============================================================================
|
||||
##### SYSCFG Initialization and Configuration functions #####
|
||||
===============================================================================
|
||||
|
||||
@endverbatim
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief Deinitializes the SYSCFG registers to their default reset values.
|
||||
* @param None
|
||||
* @retval None
|
||||
* @note MEM_MODE bits are not affected by APB reset.
|
||||
* MEM_MODE bits took the value from the user option bytes.
|
||||
*/
|
||||
void SYSCFG_DeInit(void)
|
||||
{
|
||||
/* Reset SYSCFG_CFGR1 register to reset value without affecting MEM_MODE bits */
|
||||
SYSCFG->CFGR1 &= SYSCFG_CFGR1_MEM_MODE;
|
||||
/* Set FPU Interrupt Enable bits to default value */
|
||||
SYSCFG->CFGR1 |= 0x7C000000;
|
||||
/* Reset RAM Write protection bits to default value */
|
||||
SYSCFG->RCR = 0x00000000;
|
||||
/* Set EXTICRx registers to reset value */
|
||||
SYSCFG->EXTICR[0] = 0;
|
||||
SYSCFG->EXTICR[1] = 0;
|
||||
SYSCFG->EXTICR[2] = 0;
|
||||
SYSCFG->EXTICR[3] = 0;
|
||||
/* Set CFGR2 register to reset value */
|
||||
SYSCFG->CFGR2 = 0;
|
||||
/* Set CFGR3 register to reset value */
|
||||
SYSCFG->CFGR3 = 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Configures the memory mapping at address 0x00000000.
|
||||
* @param SYSCFG_MemoryRemap: selects the memory remapping.
|
||||
* This parameter can be one of the following values:
|
||||
* @arg SYSCFG_MemoryRemap_Flash: Main Flash memory mapped at 0x00000000
|
||||
* @arg SYSCFG_MemoryRemap_SystemMemory: System Flash memory mapped at 0x00000000
|
||||
* @arg SYSCFG_MemoryRemap_SRAM: Embedded SRAM mapped at 0x00000000
|
||||
* @retval None
|
||||
*/
|
||||
void SYSCFG_MemoryRemapConfig(uint32_t SYSCFG_MemoryRemap)
|
||||
{
|
||||
uint32_t tmpcfgr1 = 0;
|
||||
|
||||
/* Check the parameter */
|
||||
assert_param(IS_SYSCFG_MEMORY_REMAP(SYSCFG_MemoryRemap));
|
||||
|
||||
/* Get CFGR1 register value */
|
||||
tmpcfgr1 = SYSCFG->CFGR1;
|
||||
|
||||
/* Clear MEM_MODE bits */
|
||||
tmpcfgr1 &= (uint32_t) (~SYSCFG_CFGR1_MEM_MODE);
|
||||
|
||||
/* Set the new MEM_MODE bits value */
|
||||
tmpcfgr1 |= (uint32_t) SYSCFG_MemoryRemap;
|
||||
|
||||
/* Set CFGR1 register with the new memory remap configuration */
|
||||
SYSCFG->CFGR1 = tmpcfgr1;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Configures the DMA channels remapping.
|
||||
* @param SYSCFG_DMARemap: selects the DMA channels remap.
|
||||
* This parameter can be one of the following values:
|
||||
* @arg SYSCFG_DMARemap_TIM17: Remap TIM17 DMA requests from DMA1 channel1 to channel2
|
||||
* @arg SYSCFG_DMARemap_TIM16: Remap TIM16 DMA requests from DMA1 channel3 to channel4
|
||||
* @arg SYSCFG_DMARemap_TIM6DAC1Ch1: Remap TIM6/DAC1 DMA requests from DMA2 channel 3 to DMA1 channel 3
|
||||
* @arg SYSCFG_DMARemap_TIM7DAC1Ch2: Remap TIM7/DAC2 DMA requests from DMA2 channel 4 to DMA1 channel 4
|
||||
* @arg SYSCFG_DMARemap_ADC2ADC4: Remap ADC2 and ADC4 DMA requests from DMA2 channel1/channel3 to channel3/channel4
|
||||
* @arg SYSCFG_DMARemap_DAC2Ch1: Remap DAC2 DMA requests to DMA1 channel5
|
||||
* @arg SYSCFG_DMARemapCh2_SPI1_RX: Remap SPI1 RX DMA1 CH2 requests
|
||||
* @arg SYSCFG_DMARemapCh4_SPI1_RX: Remap SPI1 RX DMA CH4 requests
|
||||
* @arg SYSCFG_DMARemapCh6_SPI1_RX: Remap SPI1 RX DMA CH6 requests
|
||||
* @arg SYSCFG_DMARemapCh3_SPI1_TX: Remap SPI1 TX DMA CH2 requests
|
||||
* @arg SYSCFG_DMARemapCh5_SPI1_TX: Remap SPI1 TX DMA CH5 requests
|
||||
* @arg SYSCFG_DMARemapCh7_SPI1_TX: Remap SPI1 TX DMA CH7 requests
|
||||
* @arg SYSCFG_DMARemapCh7_I2C1_RX: Remap I2C1 RX DMA CH7 requests
|
||||
* @arg SYSCFG_DMARemapCh3_I2C1_RX: Remap I2C1 RX DMA CH3 requests
|
||||
* @arg SYSCFG_DMARemapCh5_I2C1_RX: Remap I2C1 RX DMA CH5 requests
|
||||
* @arg SYSCFG_DMARemapCh6_I2C1_TX: Remap I2C1 TX DMA CH6 requests
|
||||
* @arg SYSCFG_DMARemapCh2_I2C1_TX: Remap I2C1 TX DMA CH2 requests
|
||||
* @arg SYSCFG_DMARemapCh4_I2C1_TX: Remap I2C1 TX DMA CH4 requests
|
||||
* @arg SYSCFG_DMARemapCh4_ADC2: Remap ADC2 DMA1 Ch4 requests
|
||||
* @arg SYSCFG_DMARemapCh2_ADC2: Remap ADC2 DMA1 Ch2 requests
|
||||
* @param NewState: new state of the DMA channel remapping.
|
||||
* This parameter can be: Enable or Disable.
|
||||
* @note When enabled, DMA channel of the selected peripheral is remapped
|
||||
* @note When disabled, Default DMA channel is mapped to the selected peripheral
|
||||
* @note
|
||||
* By default TIM17 DMA requests is mapped to channel 1
|
||||
* use SYSCFG_DMAChannelRemapConfig(SYSCFG_DMARemap_TIM17, Enable)
|
||||
* to remap TIM17 DMA requests to DMA1 channel 2
|
||||
* use SYSCFG_DMAChannelRemapConfig(SYSCFG_DMARemap_TIM17, Disable)
|
||||
* to map TIM17 DMA requests to DMA1 channel 1 (default mapping)
|
||||
* @retval None
|
||||
*/
|
||||
void SYSCFG_DMAChannelRemapConfig(uint32_t SYSCFG_DMARemap, FunctionalState NewState)
|
||||
{
|
||||
/* Check the parameters */
|
||||
assert_param(IS_SYSCFG_DMA_REMAP(SYSCFG_DMARemap));
|
||||
assert_param(IS_FUNCTIONAL_STATE(NewState));
|
||||
|
||||
if ((SYSCFG_DMARemap & 0x80000000)!= 0x80000000)
|
||||
{
|
||||
if (NewState != DISABLE)
|
||||
{
|
||||
/* Remap the DMA channel */
|
||||
SYSCFG->CFGR1 |= (uint32_t)SYSCFG_DMARemap;
|
||||
}
|
||||
else
|
||||
{
|
||||
/* use the default DMA channel mapping */
|
||||
SYSCFG->CFGR1 &= (uint32_t)(~SYSCFG_DMARemap);
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
if (NewState != DISABLE)
|
||||
{
|
||||
/* Remap the DMA channel */
|
||||
SYSCFG->CFGR3 |= (uint32_t)SYSCFG_DMARemap;
|
||||
}
|
||||
else
|
||||
{
|
||||
/* use the default DMA channel mapping */
|
||||
SYSCFG->CFGR3 &= (uint32_t)(~SYSCFG_DMARemap);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Configures the remapping capabilities of DAC/TIM triggers.
|
||||
* @param SYSCFG_TriggerRemap: selects the trigger to be remapped.
|
||||
* This parameter can be one of the following values:
|
||||
* @arg SYSCFG_TriggerRemap_DACTIM3: Remap DAC trigger from TIM8 to TIM3
|
||||
* @arg SYSCFG_TriggerRemap_TIM1TIM17: Remap TIM1 ITR3 from TIM4 TRGO to TIM17 OC
|
||||
* @arg SYSCFG_TriggerRemap_DACHRTIM1_TRIG1: Remap DAC trigger to HRTIM1 TRIG1
|
||||
* @arg SYSCFG_TriggerRemap_DACHRTIM1_TRIG2: Remap DAC trigger to HRTIM1 TRIG2
|
||||
* @param NewState: new state of the trigger mapping.
|
||||
* This parameter can be: ENABLE or DISABLE.
|
||||
* @note ENABLE: Enable fast mode plus driving capability for selected pin
|
||||
* @note DISABLE: Disable fast mode plus driving capability for selected pin
|
||||
* @retval None
|
||||
*/
|
||||
void SYSCFG_TriggerRemapConfig(uint32_t SYSCFG_TriggerRemap, FunctionalState NewState)
|
||||
{
|
||||
/* Check the parameters */
|
||||
assert_param(IS_SYSCFG_TRIGGER_REMAP(SYSCFG_TriggerRemap));
|
||||
assert_param(IS_FUNCTIONAL_STATE(NewState));
|
||||
|
||||
if ((SYSCFG_TriggerRemap & 0x80000000)!= 0x80000000)
|
||||
{
|
||||
if (NewState != DISABLE)
|
||||
{
|
||||
/* Remap the trigger */
|
||||
SYSCFG->CFGR1 |= (uint32_t)SYSCFG_TriggerRemap;
|
||||
}
|
||||
else
|
||||
{
|
||||
/* Use the default trigger mapping */
|
||||
SYSCFG->CFGR1 &= (uint32_t)(~SYSCFG_TriggerRemap);
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
if (NewState != DISABLE)
|
||||
{
|
||||
/* Remap the trigger */
|
||||
SYSCFG->CFGR3 |= (uint32_t)SYSCFG_TriggerRemap;
|
||||
}
|
||||
else
|
||||
{
|
||||
/* Use the default trigger mapping */
|
||||
SYSCFG->CFGR3 &= (uint32_t)(~SYSCFG_TriggerRemap);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Configures the remapping capabilities of encoder mode.
|
||||
* @ note This feature implement the so-called M/T method for measuring speed
|
||||
* and position using quadrature encoders.
|
||||
* @param SYSCFG_EncoderRemap: selects the remap option for encoder mode.
|
||||
* This parameter can be one of the following values:
|
||||
* @arg SYSCFG_EncoderRemap_No: No remap
|
||||
* @arg SYSCFG_EncoderRemap_TIM2: Timer 2 IC1 and IC2 connected to TIM15 IC1 and IC2
|
||||
* @arg SYSCFG_EncoderRemap_TIM3: Timer 3 IC1 and IC2 connected to TIM15 IC1 and IC2
|
||||
* @arg SYSCFG_EncoderRemap_TIM4: Timer 4 IC1 and IC2 connected to TIM15 IC1 and IC2
|
||||
* @retval None
|
||||
*/
|
||||
void SYSCFG_EncoderRemapConfig(uint32_t SYSCFG_EncoderRemap)
|
||||
{
|
||||
/* Check the parameter */
|
||||
assert_param(IS_SYSCFG_ENCODER_REMAP(SYSCFG_EncoderRemap));
|
||||
|
||||
/* Reset the encoder mode remapping bits */
|
||||
SYSCFG->CFGR1 &= (uint32_t)(~SYSCFG_CFGR1_ENCODER_MODE);
|
||||
|
||||
/* Set the selected configuration */
|
||||
SYSCFG->CFGR1 |= (uint32_t)(SYSCFG_EncoderRemap);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Remaps the USB interrupt lines.
|
||||
* @param NewState: new state of the mapping of USB interrupt lines.
|
||||
* This parameter can be:
|
||||
* @param ENABLE: Remap the USB interrupt line as following:
|
||||
* @arg USB Device High Priority (USB_HP) interrupt mapped to line 74.
|
||||
* @arg USB Device Low Priority (USB_LP) interrupt mapped to line 75.
|
||||
* @arg USB Wakeup Interrupt (USB_WKUP) interrupt mapped to line 76.
|
||||
* @param DISABLE: Use the default USB interrupt line:
|
||||
* @arg USB Device High Priority (USB_HP) interrupt mapped to line 19.
|
||||
* @arg USB Device Low Priority (USB_LP) interrupt mapped to line 20.
|
||||
* @arg USB Wakeup Interrupt (USB_WKUP) interrupt mapped to line 42.
|
||||
* @retval None
|
||||
*/
|
||||
void SYSCFG_USBInterruptLineRemapCmd(FunctionalState NewState)
|
||||
{
|
||||
/* Check the parameter */
|
||||
assert_param(IS_FUNCTIONAL_STATE(NewState));
|
||||
|
||||
/* Remap the USB interupt lines */
|
||||
*(__IO uint32_t *) CFGR1_USBITRMP_BB = (uint32_t)NewState;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Configures the I2C fast mode plus driving capability.
|
||||
* @param SYSCFG_I2CFastModePlus: selects the pin.
|
||||
* This parameter can be one of the following values:
|
||||
* @arg SYSCFG_I2CFastModePlus_PB6: Configure fast mode plus driving capability for PB6
|
||||
* @arg SYSCFG_I2CFastModePlus_PB7: Configure fast mode plus driving capability for PB7
|
||||
* @arg SYSCFG_I2CFastModePlus_PB8: Configure fast mode plus driving capability for PB8
|
||||
* @arg SYSCFG_I2CFastModePlus_PB9: Configure fast mode plus driving capability for PB9
|
||||
* @arg SYSCFG_I2CFastModePlus_I2C1: Configure fast mode plus driving capability for I2C1 pins
|
||||
* @arg SYSCFG_I2CFastModePlus_I2C2: Configure fast mode plus driving capability for I2C2 pins
|
||||
* @param NewState: new state of the DMA channel remapping.
|
||||
* This parameter can be:
|
||||
* @arg ENABLE: Enable fast mode plus driving capability for selected I2C pin
|
||||
* @arg DISABLE: Disable fast mode plus driving capability for selected I2C pin
|
||||
* @note For I2C1, fast mode plus driving capability can be enabled on all selected
|
||||
* I2C1 pins using SYSCFG_I2CFastModePlus_I2C1 parameter or independently
|
||||
* on each one of the following pins PB6, PB7, PB8 and PB9.
|
||||
* @note For remaing I2C1 pins (PA14, PA15...) fast mode plus driving capability
|
||||
* can be enabled only by using SYSCFG_I2CFastModePlus_I2C1 parameter.
|
||||
* @note For all I2C2 pins fast mode plus driving capability can be enabled
|
||||
* only by using SYSCFG_I2CFastModePlus_I2C2 parameter.
|
||||
* @retval None
|
||||
*/
|
||||
void SYSCFG_I2CFastModePlusConfig(uint32_t SYSCFG_I2CFastModePlus, FunctionalState NewState)
|
||||
{
|
||||
/* Check the parameters */
|
||||
assert_param(IS_SYSCFG_I2C_FMP(SYSCFG_I2CFastModePlus));
|
||||
assert_param(IS_FUNCTIONAL_STATE(NewState));
|
||||
|
||||
if (NewState != DISABLE)
|
||||
{
|
||||
/* Enable fast mode plus driving capability for selected I2C pin */
|
||||
SYSCFG->CFGR1 |= (uint32_t)SYSCFG_I2CFastModePlus;
|
||||
}
|
||||
else
|
||||
{
|
||||
/* Disable fast mode plus driving capability for selected I2C pin */
|
||||
SYSCFG->CFGR1 &= (uint32_t)(~SYSCFG_I2CFastModePlus);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Enables or disables the selected SYSCFG interrupts.
|
||||
* @param SYSCFG_IT: specifies the SYSCFG interrupt sources to be enabled or disabled.
|
||||
* This parameter can be one of the following values:
|
||||
* @arg SYSCFG_IT_IXC: Inexact Interrupt
|
||||
* @arg SYSCFG_IT_IDC: Input denormal Interrupt
|
||||
* @arg SYSCFG_IT_OFC: Overflow Interrupt
|
||||
* @arg SYSCFG_IT_UFC: Underflow Interrupt
|
||||
* @arg SYSCFG_IT_DZC: Divide-by-zero Interrupt
|
||||
* @arg SYSCFG_IT_IOC: Invalid operation Interrupt
|
||||
* @param NewState: new state of the specified SYSCFG interrupts.
|
||||
* This parameter can be: ENABLE or DISABLE.
|
||||
* @retval None
|
||||
*/
|
||||
void SYSCFG_ITConfig(uint32_t SYSCFG_IT, FunctionalState NewState)
|
||||
{
|
||||
/* Check the parameters */
|
||||
assert_param(IS_FUNCTIONAL_STATE(NewState));
|
||||
assert_param(IS_SYSCFG_IT(SYSCFG_IT));
|
||||
|
||||
if (NewState != DISABLE)
|
||||
{
|
||||
/* Enable the selected SYSCFG interrupts */
|
||||
SYSCFG->CFGR1 |= SYSCFG_IT;
|
||||
}
|
||||
else
|
||||
{
|
||||
/* Disable the selected SYSCFG interrupts */
|
||||
SYSCFG->CFGR1 &= ((uint32_t)~SYSCFG_IT);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Selects the GPIO pin used as EXTI Line.
|
||||
* @param EXTI_PortSourceGPIOx : selects the GPIO port to be used as source
|
||||
* for EXTI lines where x can be (A, B, C, D, E or F).
|
||||
* @param EXTI_PinSourcex: specifies the EXTI line to be configured.
|
||||
* This parameter can be EXTI_PinSourcex where x can be (0..15)
|
||||
* @retval None
|
||||
*/
|
||||
void SYSCFG_EXTILineConfig(uint8_t EXTI_PortSourceGPIOx, uint8_t EXTI_PinSourcex)
|
||||
{
|
||||
uint32_t tmp = 0x00;
|
||||
|
||||
/* Check the parameters */
|
||||
assert_param(IS_EXTI_PORT_SOURCE(EXTI_PortSourceGPIOx));
|
||||
assert_param(IS_EXTI_PIN_SOURCE(EXTI_PinSourcex));
|
||||
|
||||
tmp = ((uint32_t)0x0F) << (0x04 * (EXTI_PinSourcex & (uint8_t)0x03));
|
||||
SYSCFG->EXTICR[EXTI_PinSourcex >> 0x02] &= ~tmp;
|
||||
SYSCFG->EXTICR[EXTI_PinSourcex >> 0x02] |= (((uint32_t)EXTI_PortSourceGPIOx) << (0x04 * (EXTI_PinSourcex & (uint8_t)0x03)));
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Connects the selected parameter to the break input of TIM1.
|
||||
* @note The selected configuration is locked and can be unlocked by system reset
|
||||
* @param SYSCFG_Break: selects the configuration to be connected to break
|
||||
* input of TIM1
|
||||
* This parameter can be any combination of the following values:
|
||||
* @arg SYSCFG_Break_PVD: PVD interrupt is connected to the break input of TIM1.
|
||||
* @arg SYSCFG_Break_SRAMParity: SRAM Parity error is connected to the break input of TIM1.
|
||||
* @arg SYSCFG_Break_HardFault: Lockup output of CortexM4 is connected to the break input of TIM1.
|
||||
* @retval None
|
||||
*/
|
||||
void SYSCFG_BreakConfig(uint32_t SYSCFG_Break)
|
||||
{
|
||||
/* Check the parameter */
|
||||
assert_param(IS_SYSCFG_LOCK_CONFIG(SYSCFG_Break));
|
||||
|
||||
SYSCFG->CFGR2 |= (uint32_t) SYSCFG_Break;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Disables the parity check on RAM.
|
||||
* @note Disabling the parity check on RAM locks the configuration bit.
|
||||
* To re-enable the parity check on RAM perform a system reset.
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
void SYSCFG_BypassParityCheckDisable(void)
|
||||
{
|
||||
/* Disable the adddress parity check on RAM */
|
||||
*(__IO uint32_t *) CFGR1_BYPADDRPAR_BB = (uint32_t)0x00000001;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Enables the ICODE SRAM write protection.
|
||||
* @note Enabling the ICODE SRAM write protection locks the configuration bit.
|
||||
* To disable the ICODE SRAM write protection perform a system reset.
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
void SYSCFG_SRAMWRPEnable(uint32_t SYSCFG_SRAMWRP)
|
||||
{
|
||||
/* Check the parameter */
|
||||
assert_param(IS_SYSCFG_PAGE(SYSCFG_SRAMWRP));
|
||||
|
||||
/* Enable the write-protection on the selected ICODE SRAM page */
|
||||
SYSCFG->RCR |= (uint32_t)SYSCFG_SRAMWRP;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Checks whether the specified SYSCFG flag is set or not.
|
||||
* @param SYSCFG_Flag: specifies the SYSCFG flag to check.
|
||||
* This parameter can be one of the following values:
|
||||
* @arg SYSCFG_FLAG_PE: SRAM parity error flag.
|
||||
* @retval The new state of SYSCFG_Flag (SET or RESET).
|
||||
*/
|
||||
FlagStatus SYSCFG_GetFlagStatus(uint32_t SYSCFG_Flag)
|
||||
{
|
||||
(void)SYSCFG_Flag;
|
||||
FlagStatus bitstatus = RESET;
|
||||
|
||||
/* Check the parameter */
|
||||
assert_param(IS_SYSCFG_FLAG(SYSCFG_Flag));
|
||||
|
||||
/* Check the status of the specified SPI flag */
|
||||
if ((SYSCFG->CFGR2 & SYSCFG_CFGR2_SRAM_PE) != (uint32_t)RESET)
|
||||
{
|
||||
/* SYSCFG_Flag is set */
|
||||
bitstatus = SET;
|
||||
}
|
||||
else
|
||||
{
|
||||
/* SYSCFG_Flag is reset */
|
||||
bitstatus = RESET;
|
||||
}
|
||||
/* Return the SYSCFG_Flag status */
|
||||
return bitstatus;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Clears the selected SYSCFG flag.
|
||||
* @param SYSCFG_Flag: selects the flag to be cleared.
|
||||
* This parameter can be any combination of the following values:
|
||||
* @arg SYSCFG_FLAG_PE: SRAM parity error flag.
|
||||
* @retval None
|
||||
*/
|
||||
void SYSCFG_ClearFlag(uint32_t SYSCFG_Flag)
|
||||
{
|
||||
/* Check the parameter */
|
||||
assert_param(IS_SYSCFG_FLAG(SYSCFG_Flag));
|
||||
|
||||
SYSCFG->CFGR2 |= (uint32_t) SYSCFG_Flag;
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
||||
|
File diff suppressed because it is too large
Load diff
File diff suppressed because it is too large
Load diff
|
@ -0,0 +1,304 @@
|
|||
/**
|
||||
******************************************************************************
|
||||
* @file stm32f30x_wwdg.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 Window watchdog (WWDG) peripheral:
|
||||
* + Prescaler, Refresh window and Counter configuration
|
||||
* + WWDG activation
|
||||
* + Interrupts and flags management
|
||||
*
|
||||
* @verbatim
|
||||
*
|
||||
==============================================================================
|
||||
##### WWDG features #####
|
||||
==============================================================================
|
||||
|
||||
[..] Once enabled the WWDG generates a system reset on expiry of a programmed
|
||||
time period, unless the program refreshes the counter (downcounter)
|
||||
before to reach 0x3F value (i.e. a reset is generated when the counter
|
||||
value rolls over from 0x40 to 0x3F).
|
||||
[..] An MCU reset is also generated if the counter value is refreshed
|
||||
before the counter has reached the refresh window value. This
|
||||
implies that the counter must be refreshed in a limited window.
|
||||
|
||||
[..] Once enabled the WWDG cannot be disabled except by a system reset.
|
||||
|
||||
[..] WWDGRST flag in RCC_CSR register can be used to inform when a WWDG
|
||||
reset occurs.
|
||||
|
||||
[..] The WWDG counter input clock is derived from the APB clock divided
|
||||
by a programmable prescaler.
|
||||
|
||||
[..] WWDG counter clock = PCLK1 / Prescaler.
|
||||
[..] WWDG timeout = (WWDG counter clock) * (counter value).
|
||||
|
||||
[..] Min-max timeout value @36MHz (PCLK1): ~114us / ~58.3ms.
|
||||
|
||||
##### How to use this driver #####
|
||||
==============================================================================
|
||||
[..]
|
||||
(#) Enable WWDG clock using RCC_APB1PeriphClockCmd(RCC_APB1Periph_WWDG, ENABLE)
|
||||
function.
|
||||
|
||||
(#) Configure the WWDG prescaler using WWDG_SetPrescaler() function.
|
||||
|
||||
(#) Configure the WWDG refresh window using WWDG_SetWindowValue() function.
|
||||
|
||||
(#) Set the WWDG counter value and start it using WWDG_Enable() function.
|
||||
When the WWDG is enabled the counter value should be configured to
|
||||
a value greater than 0x40 to prevent generating an immediate reset.
|
||||
|
||||
(#) Optionally you can enable the Early wakeup interrupt which is
|
||||
generated when the counter reach 0x40.
|
||||
Once enabled this interrupt cannot be disabled except by a system reset.
|
||||
|
||||
(#) Then the application program must refresh the WWDG counter at regular
|
||||
intervals during normal operation to prevent an MCU reset, using
|
||||
WWDG_SetCounter() function. This operation must occur only when
|
||||
the counter value is lower than the refresh window value,
|
||||
programmed using WWDG_SetWindowValue().
|
||||
|
||||
@endverbatim
|
||||
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© 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_wwdg.h"
|
||||
#include "stm32f30x_rcc.h"
|
||||
|
||||
/** @addtogroup STM32F30x_StdPeriph_Driver
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @defgroup WWDG
|
||||
* @brief WWDG driver modules
|
||||
* @{
|
||||
*/
|
||||
|
||||
/* Private typedef -----------------------------------------------------------*/
|
||||
/* Private define ------------------------------------------------------------*/
|
||||
/* --------------------- WWDG registers bit mask ---------------------------- */
|
||||
/* CFR register bit mask */
|
||||
#define CFR_WDGTB_MASK ((uint32_t)0xFFFFFE7F)
|
||||
#define CFR_W_MASK ((uint32_t)0xFFFFFF80)
|
||||
#define BIT_MASK ((uint8_t)0x7F)
|
||||
|
||||
/* Private macro -------------------------------------------------------------*/
|
||||
/* Private variables ---------------------------------------------------------*/
|
||||
/* Private function prototypes -----------------------------------------------*/
|
||||
/* Private functions ---------------------------------------------------------*/
|
||||
|
||||
/** @defgroup WWDG_Private_Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @defgroup WWDG_Group1 Prescaler, Refresh window and Counter configuration functions
|
||||
* @brief Prescaler, Refresh window and Counter configuration functions
|
||||
*
|
||||
@verbatim
|
||||
==============================================================================
|
||||
##### Prescaler, Refresh window and Counter configuration functions #####
|
||||
==============================================================================
|
||||
|
||||
@endverbatim
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief Deinitializes the WWDG peripheral registers to their default reset values.
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
void WWDG_DeInit(void)
|
||||
{
|
||||
RCC_APB1PeriphResetCmd(RCC_APB1Periph_WWDG, ENABLE);
|
||||
RCC_APB1PeriphResetCmd(RCC_APB1Periph_WWDG, DISABLE);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Sets the WWDG Prescaler.
|
||||
* @param WWDG_Prescaler: specifies the WWDG Prescaler.
|
||||
* This parameter can be one of the following values:
|
||||
* @arg WWDG_Prescaler_1: WWDG counter clock = (PCLK1/4096)/1
|
||||
* @arg WWDG_Prescaler_2: WWDG counter clock = (PCLK1/4096)/2
|
||||
* @arg WWDG_Prescaler_4: WWDG counter clock = (PCLK1/4096)/4
|
||||
* @arg WWDG_Prescaler_8: WWDG counter clock = (PCLK1/4096)/8
|
||||
* @retval None
|
||||
*/
|
||||
void WWDG_SetPrescaler(uint32_t WWDG_Prescaler)
|
||||
{
|
||||
uint32_t tmpreg = 0;
|
||||
/* Check the parameters */
|
||||
assert_param(IS_WWDG_PRESCALER(WWDG_Prescaler));
|
||||
/* Clear WDGTB[1:0] bits */
|
||||
tmpreg = WWDG->CFR & CFR_WDGTB_MASK;
|
||||
/* Set WDGTB[1:0] bits according to WWDG_Prescaler value */
|
||||
tmpreg |= WWDG_Prescaler;
|
||||
/* Store the new value */
|
||||
WWDG->CFR = tmpreg;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Sets the WWDG window value.
|
||||
* @param WindowValue: specifies the window value to be compared to the downcounter.
|
||||
* This parameter value must be lower than 0x80.
|
||||
* @retval None
|
||||
*/
|
||||
void WWDG_SetWindowValue(uint8_t WindowValue)
|
||||
{
|
||||
__IO uint32_t tmpreg = 0;
|
||||
|
||||
/* Check the parameters */
|
||||
assert_param(IS_WWDG_WINDOW_VALUE(WindowValue));
|
||||
/* Clear W[6:0] bits */
|
||||
|
||||
tmpreg = WWDG->CFR & CFR_W_MASK;
|
||||
|
||||
/* Set W[6:0] bits according to WindowValue value */
|
||||
tmpreg |= WindowValue & (uint32_t) BIT_MASK;
|
||||
|
||||
/* Store the new value */
|
||||
WWDG->CFR = tmpreg;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Enables the WWDG Early Wakeup interrupt(EWI).
|
||||
* @note Once enabled this interrupt cannot be disabled except by a system reset.
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
void WWDG_EnableIT(void)
|
||||
{
|
||||
WWDG->CFR |= WWDG_CFR_EWI;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Sets the WWDG counter value.
|
||||
* @param Counter: specifies the watchdog counter value.
|
||||
* This parameter must be a number between 0x40 and 0x7F (to prevent generating
|
||||
* an immediate reset).
|
||||
* @retval None
|
||||
*/
|
||||
void WWDG_SetCounter(uint8_t Counter)
|
||||
{
|
||||
/* Check the parameters */
|
||||
assert_param(IS_WWDG_COUNTER(Counter));
|
||||
/* Write to T[6:0] bits to configure the counter value, no need to do
|
||||
a read-modify-write; writing a 0 to WDGA bit does nothing */
|
||||
WWDG->CR = Counter & BIT_MASK;
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/** @defgroup WWDG_Group2 WWDG activation functions
|
||||
* @brief WWDG activation functions
|
||||
*
|
||||
@verbatim
|
||||
==============================================================================
|
||||
##### WWDG activation function #####
|
||||
==============================================================================
|
||||
|
||||
@endverbatim
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief Enables WWDG and load the counter value.
|
||||
* @param Counter: specifies the watchdog counter value.
|
||||
* This parameter must be a number between 0x40 and 0x7F (to prevent generating
|
||||
* an immediate reset).
|
||||
* @retval None
|
||||
*/
|
||||
void WWDG_Enable(uint8_t Counter)
|
||||
{
|
||||
/* Check the parameters */
|
||||
assert_param(IS_WWDG_COUNTER(Counter));
|
||||
WWDG->CR = WWDG_CR_WDGA | Counter;
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/** @defgroup WWDG_Group3 Interrupts and flags management functions
|
||||
* @brief Interrupts and flags management functions
|
||||
*
|
||||
@verbatim
|
||||
==============================================================================
|
||||
##### Interrupts and flags management functions #####
|
||||
==============================================================================
|
||||
|
||||
@endverbatim
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief Checks whether the Early Wakeup interrupt flag is set or not.
|
||||
* @param None
|
||||
* @retval The new state of the Early Wakeup interrupt flag (SET or RESET).
|
||||
*/
|
||||
FlagStatus WWDG_GetFlagStatus(void)
|
||||
{
|
||||
FlagStatus bitstatus = RESET;
|
||||
|
||||
if ((WWDG->SR) != (uint32_t)RESET)
|
||||
{
|
||||
bitstatus = SET;
|
||||
}
|
||||
else
|
||||
{
|
||||
bitstatus = RESET;
|
||||
}
|
||||
return bitstatus;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Clears Early Wakeup interrupt flag.
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
void WWDG_ClearFlag(void)
|
||||
{
|
||||
WWDG->SR = (uint32_t)RESET;
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
Loading…
Add table
Add a link
Reference in a new issue