1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-20 14:55:21 +03:00

STM32F4: Libraries

This commit is contained in:
blckmn 2016-06-08 05:32:31 +10:00
parent 55d8eb57be
commit d4e96ba8e7
206 changed files with 141406 additions and 0 deletions

View file

@ -0,0 +1,249 @@
/**
******************************************************************************
* @file misc.c
* @author MCD Application Team
* @version V1.6.1
* @date 21-October-2015
* @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.
*
* 1. 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
* ==========================================================================================================================
* NVIC_PriorityGroup | NVIC_IRQChannelPreemptionPriority | NVIC_IRQChannelSubPriority | Description
* ==========================================================================================================================
* NVIC_PriorityGroup_0 | 0 | 0-15 | 0 bits for pre-emption priority
* | | | 4 bits for subpriority
* --------------------------------------------------------------------------------------------------------------------------
* NVIC_PriorityGroup_1 | 0-1 | 0-7 | 1 bits for pre-emption priority
* | | | 3 bits for subpriority
* --------------------------------------------------------------------------------------------------------------------------
* NVIC_PriorityGroup_2 | 0-3 | 0-3 | 2 bits for pre-emption priority
* | | | 2 bits for subpriority
* --------------------------------------------------------------------------------------------------------------------------
* NVIC_PriorityGroup_3 | 0-7 | 0-1 | 3 bits for pre-emption priority
* | | | 1 bits for subpriority
* --------------------------------------------------------------------------------------------------------------------------
* NVIC_PriorityGroup_4 | 0-15 | 0 | 4 bits for pre-emption priority
* | | | 0 bits for subpriority
* ==========================================================================================================================
*
* 2. Enable and Configure the priority of the selected IRQ Channels using NVIC_Init()
*
* @note When the NVIC_PriorityGroup_0 is selected, IRQ pre-emption is no more possible.
* The pending IRQ priority will be managed only by the subpriority.
*
* @note IRQ priority order (sorted by highest to lowest priority):
* - Lowest pre-emption priority
* - Lowest subpriority
* - Lowest hardware priority (IRQ number)
*
* @endverbatim
*
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2015 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 "misc.h"
/** @addtogroup STM32F4xx_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 the NVIC_PriorityGroup_0 is selected, IRQ pre-emption is no more possible.
* The pending IRQ priority will be managed only by the 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)
{
uint8_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 = NVIC_InitStruct->NVIC_IRQChannelPreemptionPriority << tmppre;
tmppriority |= (uint8_t)(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: Vector Table in internal SRAM.
* @arg NVIC_VectTab_FLASH: Vector Table in internal 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: Low Power SEV on Pend.
* @arg NVIC_LP_SLEEPDEEP: Low Power DEEPSLEEP request.
* @arg NVIC_LP_SLEEPONEXIT: Low Power Sleep on Exit.
* @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****/

File diff suppressed because it is too large Load diff

File diff suppressed because it is too large Load diff

View file

@ -0,0 +1,608 @@
/**
******************************************************************************
* @file stm32f4xx_cec.c
* @author MCD Application Team
* @version V1.6.1
* @date 21-October-2015
* @brief This file provides firmware functions to manage the following
* functionalities of the Consumer Electronics Control (CEC) peripheral
* applicable only on STM32F446xx devices:
* + Initialization and Configuration
* + Data transfers functions
* + Interrupts and flags management
*
* @verbatim
==============================================================================
##### CEC features #####
==============================================================================
[..] This device provides some features:
(#) Supports HDMI-CEC specification 1.4.
(#) Supports two source clocks(HSI/244 or LSE).
(#) Works in stop mode(without APB clock, but with CEC clock 32KHz).
It can genarate an interrupt in the CEC clock domain that the CPU
wakes up from the low power mode.
(#) Configurable Signal Free Time before of transmission start. The
number of nominal data bit periods waited before transmission can be
ruled by Hardware or Software.
(#) Configurable Peripheral Address (multi-addressing configuration).
(#) Supports listen mode.The CEC Messages addressed to different destination
can be received without interfering with CEC bus when Listen mode option is enabled.
(#) Configurable Rx-Tolerance(Standard and Extended tolerance margin).
(#) Error detection with configurable error bit generation.
(#) Arbitration lost error in the case of two CEC devices starting at the same time.
##### How to use this driver #####
==============================================================================
[..] This driver provides functions to configure and program the CEC device,
follow steps below:
(#) The source clock can be configured using:
(++) RCC_CECCLKConfig(RCC_CECCLK_HSI_Div244) for HSI(Default)
(++) RCC_CECCLKConfig(RCC_CECCLK_LSE) for LSE.
(#) Enable CEC peripheral clock using RCC_APBPeriphClockCmd(RCC_APBPeriph_CEC, ENABLE).
(#) Peripherals alternate function.
(++) Connect the pin to the desired peripherals' Alternate Function (AF) using
GPIO_PinAFConfig() function.
(++) Configure the desired pin in alternate function by:
GPIO_InitStruct->GPIO_Mode = GPIO_Mode_AF.
(++) Select the type open-drain and output speed via GPIO_OType
and GPIO_Speed members.
(++) Call GPIO_Init() function.
(#) Configure the Signal Free Time, Rx Tolerance, Stop reception generation
and Bit error generation using the CEC_Init() function.
The function CEC_Init() must be called when the CEC peripheral is disabled.
(#) Configure the CEC own address by calling the fuction CEC_OwnAddressConfig().
(#) Optionally, you can configure the Listen mode using the function CEC_ListenModeCmd().
(#) Enable the NVIC and the corresponding interrupt using the function
CEC_ITConfig() if you need to use interrupt mode.
CEC_ITConfig() must be called before enabling the CEC peripheral.
(#) Enable the CEC using the CEC_Cmd() function.
(#) Charge the first data byte in the TXDR register using CEC_SendDataByte().
(#) Enable the transmission of the Byte of a CEC message using CEC_StartOfMessage()
(#) Transmit single data through the CEC peripheral using CEC_SendDataByte()
and Receive the last transmitted byte using CEC_ReceiveDataByte().
(#) Enable the CEC_EndOfMessage() in order to indicate the last byte of the message.
[..]
(@) If the listen mode is enabled, Stop reception generation and Bit error generation
must be in reset state.
(@) If the CEC message consists of only 1 byte, the function CEC_EndOfMessage()
must be called before CEC_StartOfMessage().
@endverbatim
*
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2015 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 "stm32f4xx_cec.h"
#include "stm32f4xx_rcc.h"
/** @addtogroup STM32F4xx_StdPeriph_Driver
* @{
*/
/** @defgroup CEC
* @brief CEC driver modules
* @{
*/
#if defined(STM32F446xx)
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
#define BROADCAST_ADDRESS ((uint32_t)0x0000F)
#define CFGR_CLEAR_MASK ((uint32_t)0x7000FE00) /* CFGR register Mask */
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/** @defgroup CEC_Private_Functions
* @{
*/
/** @defgroup CEC_Group1 Initialization and Configuration functions
* @brief Initialization and Configuration functions
*
@verbatim
===============================================================================
##### Initialization and Configuration functions #####
===============================================================================
[..] This section provides functions allowing to initialize:
(+) CEC own addresses
(+) CEC Signal Free Time
(+) CEC Rx Tolerance
(+) CEC Stop Reception
(+) CEC Bit Rising Error
(+) CEC Long Bit Period Error
[..] This section provides also a function to configure the CEC peripheral in Listen Mode.
Messages addressed to different destination can be received when Listen mode is
enabled without interfering with CEC bus.
@endverbatim
* @{
*/
/**
* @brief Deinitializes the CEC peripheral registers to their default reset values.
* @param None
* @retval None
*/
void CEC_DeInit(void)
{
RCC_APB1PeriphResetCmd(RCC_APB1Periph_CEC, ENABLE);
RCC_APB1PeriphResetCmd(RCC_APB1Periph_CEC, DISABLE);
}
/**
* @brief Initializes the CEC peripheral according to the specified parameters
* in the CEC_InitStruct.
* @note The CEC parameters must be configured before enabling the CEC peripheral.
* @param CEC_InitStruct: pointer to an CEC_InitTypeDef structure that contains
* the configuration information for the specified CEC peripheral.
* @retval None
*/
void CEC_Init(CEC_InitTypeDef* CEC_InitStruct)
{
uint32_t tmpreg = 0;
/* Check the parameters */
assert_param(IS_CEC_SIGNAL_FREE_TIME(CEC_InitStruct->CEC_SignalFreeTime));
assert_param(IS_CEC_RX_TOLERANCE(CEC_InitStruct->CEC_RxTolerance));
assert_param(IS_CEC_STOP_RECEPTION(CEC_InitStruct->CEC_StopReception));
assert_param(IS_CEC_BIT_RISING_ERROR(CEC_InitStruct->CEC_BitRisingError));
assert_param(IS_CEC_LONG_BIT_PERIOD_ERROR(CEC_InitStruct->CEC_LongBitPeriodError));
assert_param(IS_CEC_BDR_NO_GEN_ERROR(CEC_InitStruct->CEC_BRDNoGen));
assert_param(IS_CEC_SFT_OPTION(CEC_InitStruct->CEC_SFTOption));
/* Get the CEC CFGR value */
tmpreg = CEC->CFGR;
/* Clear CFGR bits */
tmpreg &= CFGR_CLEAR_MASK;
/* Configure the CEC peripheral */
tmpreg |= (CEC_InitStruct->CEC_SignalFreeTime | CEC_InitStruct->CEC_RxTolerance |
CEC_InitStruct->CEC_StopReception | CEC_InitStruct->CEC_BitRisingError |
CEC_InitStruct->CEC_LongBitPeriodError| CEC_InitStruct->CEC_BRDNoGen |
CEC_InitStruct->CEC_SFTOption);
/* Write to CEC CFGR register */
CEC->CFGR = tmpreg;
}
/**
* @brief Fills each CEC_InitStruct member with its default value.
* @param CEC_InitStruct: pointer to a CEC_InitTypeDef structure which will
* be initialized.
* @retval None
*/
void CEC_StructInit(CEC_InitTypeDef* CEC_InitStruct)
{
CEC_InitStruct->CEC_SignalFreeTime = CEC_SignalFreeTime_Standard;
CEC_InitStruct->CEC_RxTolerance = CEC_RxTolerance_Standard;
CEC_InitStruct->CEC_StopReception = CEC_StopReception_Off;
CEC_InitStruct->CEC_BitRisingError = CEC_BitRisingError_Off;
CEC_InitStruct->CEC_LongBitPeriodError = CEC_LongBitPeriodError_Off;
CEC_InitStruct->CEC_BRDNoGen = CEC_BRDNoGen_Off;
CEC_InitStruct->CEC_SFTOption = CEC_SFTOption_Off;
}
/**
* @brief Enables or disables the CEC peripheral.
* @param NewState: new state of the CEC peripheral.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void CEC_Cmd(FunctionalState NewState)
{
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
/* Enable the CEC peripheral */
CEC->CR |= CEC_CR_CECEN;
}
else
{
/* Disable the CEC peripheral */
CEC->CR &= ~CEC_CR_CECEN;
}
}
/**
* @brief Enables or disables the CEC Listen Mode.
* @param NewState: new state of the Listen Mode.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void CEC_ListenModeCmd(FunctionalState NewState)
{
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
/* Enable the Listen Mode */
CEC->CFGR |= CEC_CFGR_LSTN;
}
else
{
/* Disable the Listen Mode */
CEC->CFGR &= ~CEC_CFGR_LSTN;
}
}
/**
* @brief Defines the Own Address of the CEC device.
* @param CEC_OwnAddress: The CEC own address.
* @retval None
*/
void CEC_OwnAddressConfig(uint8_t CEC_OwnAddress)
{
uint32_t tmp =0x00;
/* Check the parameters */
assert_param(IS_CEC_ADDRESS(CEC_OwnAddress));
tmp = 1 <<(CEC_OwnAddress + 16);
/* Set the CEC own address */
CEC->CFGR |= tmp;
}
/**
* @brief Clears the Own Address of the CEC device.
* @param CEC_OwnAddress: The CEC own address.
* @retval None
*/
void CEC_OwnAddressClear(void)
{
/* Set the CEC own address */
CEC->CFGR = 0x0;
}
/**
* @}
*/
/** @defgroup CEC_Group2 Data transfers functions
* @brief Data transfers functions
*
@verbatim
===============================================================================
##### Data transfers functions #####
===============================================================================
[..] This section provides functions allowing the CEC data transfers.The read
access of the CEC_RXDR register can be done using the CEC_ReceiveData()function
and returns the Rx buffered value. Whereas a write access to the CEC_TXDR can be
done using CEC_SendData() function.
@endverbatim
* @{
*/
/**
* @brief Transmits single data through the CEC peripheral.
* @param Data: the data to transmit.
* @retval None
*/
void CEC_SendData(uint8_t Data)
{
/* Transmit Data */
CEC->TXDR = Data;
}
/**
* @brief Returns the most recent received data by the CEC peripheral.
* @param None
* @retval The received data.
*/
uint8_t CEC_ReceiveData(void)
{
/* Receive Data */
return (uint8_t)(CEC->RXDR);
}
/**
* @brief Starts a new message.
* @param None
* @retval None
*/
void CEC_StartOfMessage(void)
{
/* Starts of new message */
CEC->CR |= CEC_CR_TXSOM;
}
/**
* @brief Transmits message with an EOM bit.
* @param None
* @retval None
*/
void CEC_EndOfMessage(void)
{
/* The data byte will be transmitted with an EOM bit */
CEC->CR |= CEC_CR_TXEOM;
}
/**
* @}
*/
/** @defgroup CEC_Group3 Interrupts and flags management functions
* @brief Interrupts and flags management functions
*
@verbatim
===============================================================================
##### Interrupts and flags management functions #####
===============================================================================
[..] This section provides functions allowing to configure the CEC Interrupts
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 communication: Polling mode or Interrupt mode.
[..] In polling mode, the CEC can be managed by the following flags:
(+) CEC_FLAG_TXACKE : to indicate a missing acknowledge in transmission mode.
(+) CEC_FLAG_TXERR : to indicate an error occurs during transmission mode.
The initiator detects low impedance in the CEC line.
(+) CEC_FLAG_TXUDR : to indicate if an underrun error occurs in transmission mode.
The transmission is enabled while the software has not yet
loaded any value into the TXDR register.
(+) CEC_FLAG_TXEND : to indicate the end of successful transmission.
(+) CEC_FLAG_TXBR : to indicate the next transmission data has to be written to TXDR.
(+) CEC_FLAG_ARBLST : to indicate arbitration lost in the case of two CEC devices
starting at the same time.
(+) CEC_FLAG_RXACKE : to indicate a missing acknowledge in receive mode.
(+) CEC_FLAG_LBPE : to indicate a long bit period error generated during receive mode.
(+) CEC_FLAG_SBPE : to indicate a short bit period error generated during receive mode.
(+) CEC_FLAG_BRE : to indicate a bit rising error generated during receive mode.
(+) CEC_FLAG_RXOVR : to indicate if an overrun error occur while receiving a CEC message.
A byte is not yet received while a new byte is stored in the RXDR register.
(+) CEC_FLAG_RXEND : to indicate the end Of reception
(+) CEC_FLAG_RXBR : to indicate a new byte has been received from the CEC line and
stored into the RXDR buffer.
[..]
(@)In this Mode, it is advised to use the following functions:
FlagStatus CEC_GetFlagStatus(uint16_t CEC_FLAG);
void CEC_ClearFlag(uint16_t CEC_FLAG);
[..] In Interrupt mode, the CEC can be managed by the following interrupt sources:
(+) CEC_IT_TXACKE : to indicate a TX Missing acknowledge
(+) CEC_IT_TXACKE : to indicate a missing acknowledge in transmission mode.
(+) CEC_IT_TXERR : to indicate an error occurs during transmission mode.
The initiator detects low impedance in the CEC line.
(+) CEC_IT_TXUDR : to indicate if an underrun error occurs in transmission mode.
The transmission is enabled while the software has not yet
loaded any value into the TXDR register.
(+) CEC_IT_TXEND : to indicate the end of successful transmission.
(+) CEC_IT_TXBR : to indicate the next transmission data has to be written to TXDR register.
(+) CEC_IT_ARBLST : to indicate arbitration lost in the case of two CEC devices
starting at the same time.
(+) CEC_IT_RXACKE : to indicate a missing acknowledge in receive mode.
(+) CEC_IT_LBPE : to indicate a long bit period error generated during receive mode.
(+) CEC_IT_SBPE : to indicate a short bit period error generated during receive mode.
(+) CEC_IT_BRE : to indicate a bit rising error generated during receive mode.
(+) CEC_IT_RXOVR : to indicate if an overrun error occur while receiving a CEC message.
A byte is not yet received while a new byte is stored in the RXDR register.
(+) CEC_IT_RXEND : to indicate the end Of reception
(+) CEC_IT_RXBR : to indicate a new byte has been received from the CEC line and
stored into the RXDR buffer.
[..]
(@)In this Mode it is advised to use the following functions:
void CEC_ITConfig( uint16_t CEC_IT, FunctionalState NewState);
ITStatus CEC_GetITStatus(uint16_t CEC_IT);
void CEC_ClearITPendingBit(uint16_t CEC_IT);
@endverbatim
* @{
*/
/**
* @brief Enables or disables the selected CEC interrupts.
* @param CEC_IT: specifies the CEC interrupt source to be enabled.
* This parameter can be any combination of the following values:
* @arg CEC_IT_TXACKE: Tx Missing acknowledge Error
* @arg CEC_IT_TXERR: Tx Error.
* @arg CEC_IT_TXUDR: Tx-Buffer Underrun.
* @arg CEC_IT_TXEND: End of Transmission (successful transmission of the last byte).
* @arg CEC_IT_TXBR: Tx-Byte Request.
* @arg CEC_IT_ARBLST: Arbitration Lost
* @arg CEC_IT_RXACKE: Rx-Missing Acknowledge
* @arg CEC_IT_LBPE: Rx Long period Error
* @arg CEC_IT_SBPE: Rx Short period Error
* @arg CEC_IT_BRE: Rx Bit Rising Error
* @arg CEC_IT_RXOVR: Rx Overrun.
* @arg CEC_IT_RXEND: End Of Reception
* @arg CEC_IT_RXBR: Rx-Byte Received
* @param NewState: new state of the selected CEC interrupts.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void CEC_ITConfig(uint16_t CEC_IT, FunctionalState NewState)
{
assert_param(IS_FUNCTIONAL_STATE(NewState));
assert_param(IS_CEC_IT(CEC_IT));
if (NewState != DISABLE)
{
/* Enable the selected CEC interrupt */
CEC->IER |= CEC_IT;
}
else
{
CEC_IT =~CEC_IT;
/* Disable the selected CEC interrupt */
CEC->IER &= CEC_IT;
}
}
/**
* @brief Gets the CEC flag status.
* @param CEC_FLAG: specifies the CEC flag to check.
* This parameter can be one of the following values:
* @arg CEC_FLAG_TXACKE: Tx Missing acknowledge Error
* @arg CEC_FLAG_TXERR: Tx Error.
* @arg CEC_FLAG_TXUDR: Tx-Buffer Underrun.
* @arg CEC_FLAG_TXEND: End of transmission (successful transmission of the last byte).
* @arg CEC_FLAG_TXBR: Tx-Byte Request.
* @arg CEC_FLAG_ARBLST: Arbitration Lost
* @arg CEC_FLAG_RXACKE: Rx-Missing Acknowledge
* @arg CEC_FLAG_LBPE: Rx Long period Error
* @arg CEC_FLAG_SBPE: Rx Short period Error
* @arg CEC_FLAG_BRE: Rx Bit Rissing Error
* @arg CEC_FLAG_RXOVR: Rx Overrun.
* @arg CEC_FLAG_RXEND: End Of Reception.
* @arg CEC_FLAG_RXBR: Rx-Byte Received.
* @retval The new state of CEC_FLAG (SET or RESET)
*/
FlagStatus CEC_GetFlagStatus(uint16_t CEC_FLAG)
{
FlagStatus bitstatus = RESET;
assert_param(IS_CEC_GET_FLAG(CEC_FLAG));
/* Check the status of the specified CEC flag */
if ((CEC->ISR & CEC_FLAG) != (uint16_t)RESET)
{
/* CEC flag is set */
bitstatus = SET;
}
else
{
/* CEC flag is reset */
bitstatus = RESET;
}
/* Return the CEC flag status */
return bitstatus;
}
/**
* @brief Clears the CEC's pending flags.
* @param CEC_FLAG: specifies the flag to clear.
* This parameter can be any combination of the following values:
* @arg CEC_FLAG_TXACKE: Tx Missing acknowledge Error
* @arg CEC_FLAG_TXERR: Tx Error
* @arg CEC_FLAG_TXUDR: Tx-Buffer Underrun
* @arg CEC_FLAG_TXEND: End of transmission (successful transmission of the last byte).
* @arg CEC_FLAG_TXBR: Tx-Byte Request
* @arg CEC_FLAG_ARBLST: Arbitration Lost
* @arg CEC_FLAG_RXACKE: Rx Missing Acknowledge
* @arg CEC_FLAG_LBPE: Rx Long period Error
* @arg CEC_FLAG_SBPE: Rx Short period Error
* @arg CEC_FLAG_BRE: Rx Bit Rising Error
* @arg CEC_FLAG_RXOVR: Rx Overrun
* @arg CEC_FLAG_RXEND: End Of Reception
* @arg CEC_FLAG_RXBR: Rx-Byte Received
* @retval None
*/
void CEC_ClearFlag(uint32_t CEC_FLAG)
{
assert_param(IS_CEC_CLEAR_FLAG(CEC_FLAG));
/* Clear the selected CEC flag */
CEC->ISR = CEC_FLAG;
}
/**
* @brief Checks whether the specified CEC interrupt has occurred or not.
* @param CEC_IT: specifies the CEC interrupt source to check.
* This parameter can be one of the following values:
* @arg CEC_IT_TXACKE: Tx Missing acknowledge Error
* @arg CEC_IT_TXERR: Tx Error.
* @arg CEC_IT_TXUDR: Tx-Buffer Underrun.
* @arg CEC_IT_TXEND: End of transmission (successful transmission of the last byte).
* @arg CEC_IT_TXBR: Tx-Byte Request.
* @arg CEC_IT_ARBLST: Arbitration Lost.
* @arg CEC_IT_RXACKE: Rx-Missing Acknowledge.
* @arg CEC_IT_LBPE: Rx Long period Error.
* @arg CEC_IT_SBPE: Rx Short period Error.
* @arg CEC_IT_BRE: Rx Bit Rising Error.
* @arg CEC_IT_RXOVR: Rx Overrun.
* @arg CEC_IT_RXEND: End Of Reception.
* @arg CEC_IT_RXBR: Rx-Byte Received
* @retval The new state of CEC_IT (SET or RESET).
*/
ITStatus CEC_GetITStatus(uint16_t CEC_IT)
{
ITStatus bitstatus = RESET;
uint32_t enablestatus = 0;
/* Check the parameters */
assert_param(IS_CEC_GET_IT(CEC_IT));
/* Get the CEC IT enable bit status */
enablestatus = (CEC->IER & CEC_IT);
/* Check the status of the specified CEC interrupt */
if (((CEC->ISR & CEC_IT) != (uint32_t)RESET) && enablestatus)
{
/* CEC interrupt is set */
bitstatus = SET;
}
else
{
/* CEC interrupt is reset */
bitstatus = RESET;
}
/* Return the CEC interrupt status */
return bitstatus;
}
/**
* @brief Clears the CEC's interrupt pending bits.
* @param CEC_IT: specifies the CEC interrupt pending bit to clear.
* This parameter can be any combination of the following values:
* @arg CEC_IT_TXACKE: Tx Missing acknowledge Error
* @arg CEC_IT_TXERR: Tx Error
* @arg CEC_IT_TXUDR: Tx-Buffer Underrun
* @arg CEC_IT_TXEND: End of Transmission
* @arg CEC_IT_TXBR: Tx-Byte Request
* @arg CEC_IT_ARBLST: Arbitration Lost
* @arg CEC_IT_RXACKE: Rx-Missing Acknowledge
* @arg CEC_IT_LBPE: Rx Long period Error
* @arg CEC_IT_SBPE: Rx Short period Error
* @arg CEC_IT_BRE: Rx Bit Rising Error
* @arg CEC_IT_RXOVR: Rx Overrun
* @arg CEC_IT_RXEND: End Of Reception
* @arg CEC_IT_RXBR: Rx-Byte Received
* @retval None
*/
void CEC_ClearITPendingBit(uint16_t CEC_IT)
{
assert_param(IS_CEC_IT(CEC_IT));
/* Clear the selected CEC interrupt pending bits */
CEC->ISR = CEC_IT;
}
/**
* @}
*/
/**
* @}
*/
#endif /* STM32F446xx */
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View file

@ -0,0 +1,133 @@
/**
******************************************************************************
* @file stm32f4xx_crc.c
* @author MCD Application Team
* @version V1.6.1
* @date 21-October-2015
* @brief This file provides all the CRC firmware functions.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2015 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 "stm32f4xx_crc.h"
/** @addtogroup STM32F4xx_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
* @{
*/
/**
* @brief Resets the CRC Data register (DR).
* @param None
* @retval None
*/
void CRC_ResetDR(void)
{
/* Reset CRC generator */
CRC->CR = CRC_CR_RESET;
}
/**
* @brief Computes the 32-bit CRC of a given data word(32-bit).
* @param Data: data word(32-bit) to compute its CRC
* @retval 32-bit CRC
*/
uint32_t CRC_CalcCRC(uint32_t Data)
{
CRC->DR = 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);
}
/**
* @brief Stores a 8-bit data in the Independent Data(ID) register.
* @param IDValue: 8-bit value to be stored in the ID register
* @retval None
*/
void CRC_SetIDRegister(uint8_t IDValue)
{
CRC->IDR = 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****/

View file

@ -0,0 +1,934 @@
/**
******************************************************************************
* @file stm32f4xx_cryp.c
* @author MCD Application Team
* @version V1.6.1
* @date 21-October-2015
* @brief This file provides firmware functions to manage the following
* functionalities of the Cryptographic processor (CRYP) peripheral:
* + Initialization and Configuration functions
* + Data treatment functions
* + Context swapping functions
* + DMA interface function
* + Interrupts and flags management
*
@verbatim
===================================================================
##### How to use this driver #####
===================================================================
[..]
(#) Enable the CRYP controller clock using
RCC_AHB2PeriphClockCmd(RCC_AHB2Periph_CRYP, ENABLE); function.
(#) Initialize the CRYP using CRYP_Init(), CRYP_KeyInit() and if needed
CRYP_IVInit().
(#) Flush the IN and OUT FIFOs by using CRYP_FIFOFlush() function.
(#) Enable the CRYP controller using the CRYP_Cmd() function.
(#) If using DMA for Data input and output transfer, activate the needed DMA
Requests using CRYP_DMACmd() function
(#) If DMA is not used for data transfer, use CRYP_DataIn() and CRYP_DataOut()
functions to enter data to IN FIFO and get result from OUT FIFO.
(#) To control CRYP events you can use one of the following two methods:
(++) Check on CRYP flags using the CRYP_GetFlagStatus() function.
(++) Use CRYP interrupts through the function CRYP_ITConfig() at
initialization phase and CRYP_GetITStatus() function into interrupt
routines in processing phase.
(#) Save and restore Cryptographic processor context using CRYP_SaveContext()
and CRYP_RestoreContext() functions.
*** Procedure to perform an encryption or a decryption ***
==========================================================
*** Initialization ***
======================
[..]
(#) Initialize the peripheral using CRYP_Init(), CRYP_KeyInit() and CRYP_IVInit
functions:
(++) Configure the key size (128-, 192- or 256-bit, in the AES only)
(++) Enter the symmetric key
(++) Configure the data type
(++) In case of decryption in AES-ECB or AES-CBC, you must prepare
the key: configure the key preparation mode. Then Enable the CRYP
peripheral using CRYP_Cmd() function: the BUSY flag is set.
Wait until BUSY flag is reset : the key is prepared for decryption
(++) Configure the algorithm and chaining (the DES/TDES in ECB/CBC, the
AES in ECB/CBC/CTR)
(++) Configure the direction (encryption/decryption).
(++) Write the initialization vectors (in CBC or CTR modes only)
(#) Flush the IN and OUT FIFOs using the CRYP_FIFOFlush() function
*** Basic Processing mode (polling mode) ***
============================================
[..]
(#) Enable the cryptographic processor using CRYP_Cmd() function.
(#) Write the first blocks in the input FIFO (2 to 8 words) using
CRYP_DataIn() function.
(#) Repeat the following sequence until the complete message has been
processed:
(++) Wait for flag CRYP_FLAG_OFNE occurs (using CRYP_GetFlagStatus()
function), then read the OUT-FIFO using CRYP_DataOut() function
(1 block or until the FIFO is empty)
(++) Wait for flag CRYP_FLAG_IFNF occurs, (using CRYP_GetFlagStatus()
function then write the IN FIFO using CRYP_DataIn() function
(1 block or until the FIFO is full)
(#) At the end of the processing, CRYP_FLAG_BUSY flag will be reset and
both FIFOs are empty (CRYP_FLAG_IFEM is set and CRYP_FLAG_OFNE is
reset). You can disable the peripheral using CRYP_Cmd() function.
*** Interrupts Processing mode ***
==================================
[..] In this mode, Processing is done when the data are transferred by the
CPU during interrupts.
(#) Enable the interrupts CRYP_IT_INI and CRYP_IT_OUTI using CRYP_ITConfig()
function.
(#) Enable the cryptographic processor using CRYP_Cmd() function.
(#) In the CRYP_IT_INI interrupt handler : load the input message into the
IN FIFO using CRYP_DataIn() function . You can load 2 or 4 words at a
time, or load data until the IN FIFO is full. When the last word of
the message has been entered into the IN FIFO, disable the CRYP_IT_INI
interrupt (using CRYP_ITConfig() function).
(#) In the CRYP_IT_OUTI interrupt handler : read the output message from
the OUT FIFO using CRYP_DataOut() function. You can read 1 block (2 or
4 words) at a time or read data until the FIFO is empty.
When the last word has been read, INIM=0, BUSY=0 and both FIFOs are
empty (CRYP_FLAG_IFEM is set and CRYP_FLAG_OFNE is reset).
You can disable the CRYP_IT_OUTI interrupt (using CRYP_ITConfig()
function) and you can disable the peripheral using CRYP_Cmd() function.
*** DMA Processing mode ***
===========================
[..] In this mode, Processing is done when the DMA is used to transfer the
data from/to the memory.
(#) Configure the DMA controller to transfer the input data from the
memory using DMA_Init() function.
The transfer length is the length of the message.
As message padding is not managed by the peripheral, the message
length must be an entire number of blocks. The data are transferred
in burst mode. The burst length is 4 words in the AES and 2 or 4
words in the DES/TDES. The DMA should be configured to set an
interrupt on transfer completion of the output data to indicate that
the processing is finished.
Refer to DMA peripheral driver for more details.
(#) Enable the cryptographic processor using CRYP_Cmd() function.
Enable the DMA requests CRYP_DMAReq_DataIN and CRYP_DMAReq_DataOUT
using CRYP_DMACmd() function.
(#) All the transfers and processing are managed by the DMA and the
cryptographic processor. The DMA transfer complete interrupt indicates
that the processing is complete. Both FIFOs are normally empty and
CRYP_FLAG_BUSY flag is reset.
@endverbatim
*
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2015 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 "stm32f4xx_cryp.h"
#include "stm32f4xx_rcc.h"
/** @addtogroup STM32F4xx_StdPeriph_Driver
* @{
*/
/** @defgroup CRYP
* @brief CRYP driver modules
* @{
*/
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
#define FLAG_MASK ((uint8_t)0x20)
#define MAX_TIMEOUT ((uint16_t)0xFFFF)
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/** @defgroup CRYP_Private_Functions
* @{
*/
/** @defgroup CRYP_Group1 Initialization and Configuration functions
* @brief Initialization and Configuration functions
*
@verbatim
===============================================================================
##### Initialization and Configuration functions #####
===============================================================================
[..] This section provides functions allowing to
(+) Initialize the cryptographic Processor using CRYP_Init() function
(++) Encrypt or Decrypt
(++) mode : TDES-ECB, TDES-CBC,
DES-ECB, DES-CBC,
AES-ECB, AES-CBC, AES-CTR, AES-Key, AES-GCM, AES-CCM
(++) DataType : 32-bit data, 16-bit data, bit data or bit-string
(++) Key Size (only in AES modes)
(+) Configure the Encrypt or Decrypt Key using CRYP_KeyInit() function
(+) Configure the Initialization Vectors(IV) for CBC and CTR modes using
CRYP_IVInit() function.
(+) Flushes the IN and OUT FIFOs : using CRYP_FIFOFlush() function.
(+) Enable or disable the CRYP Processor using CRYP_Cmd() function
@endverbatim
* @{
*/
/**
* @brief Deinitializes the CRYP peripheral registers to their default reset values
* @param None
* @retval None
*/
void CRYP_DeInit(void)
{
/* Enable CRYP reset state */
RCC_AHB2PeriphResetCmd(RCC_AHB2Periph_CRYP, ENABLE);
/* Release CRYP from reset state */
RCC_AHB2PeriphResetCmd(RCC_AHB2Periph_CRYP, DISABLE);
}
/**
* @brief Initializes the CRYP peripheral according to the specified parameters
* in the CRYP_InitStruct.
* @param CRYP_InitStruct: pointer to a CRYP_InitTypeDef structure that contains
* the configuration information for the CRYP peripheral.
* @retval None
*/
void CRYP_Init(CRYP_InitTypeDef* CRYP_InitStruct)
{
/* Check the parameters */
assert_param(IS_CRYP_ALGOMODE(CRYP_InitStruct->CRYP_AlgoMode));
assert_param(IS_CRYP_DATATYPE(CRYP_InitStruct->CRYP_DataType));
assert_param(IS_CRYP_ALGODIR(CRYP_InitStruct->CRYP_AlgoDir));
/* Select Algorithm mode*/
CRYP->CR &= ~CRYP_CR_ALGOMODE;
CRYP->CR |= CRYP_InitStruct->CRYP_AlgoMode;
/* Select dataType */
CRYP->CR &= ~CRYP_CR_DATATYPE;
CRYP->CR |= CRYP_InitStruct->CRYP_DataType;
/* select Key size (used only with AES algorithm) */
if ((CRYP_InitStruct->CRYP_AlgoMode != CRYP_AlgoMode_TDES_ECB) &&
(CRYP_InitStruct->CRYP_AlgoMode != CRYP_AlgoMode_TDES_CBC) &&
(CRYP_InitStruct->CRYP_AlgoMode != CRYP_AlgoMode_DES_ECB) &&
(CRYP_InitStruct->CRYP_AlgoMode != CRYP_AlgoMode_DES_CBC))
{
assert_param(IS_CRYP_KEYSIZE(CRYP_InitStruct->CRYP_KeySize));
CRYP->CR &= ~CRYP_CR_KEYSIZE;
CRYP->CR |= CRYP_InitStruct->CRYP_KeySize; /* Key size and value must be
configured once the key has
been prepared */
}
/* Select data Direction */
CRYP->CR &= ~CRYP_CR_ALGODIR;
CRYP->CR |= CRYP_InitStruct->CRYP_AlgoDir;
}
/**
* @brief Fills each CRYP_InitStruct member with its default value.
* @param CRYP_InitStruct: pointer to a CRYP_InitTypeDef structure which will
* be initialized.
* @retval None
*/
void CRYP_StructInit(CRYP_InitTypeDef* CRYP_InitStruct)
{
/* Initialize the CRYP_AlgoDir member */
CRYP_InitStruct->CRYP_AlgoDir = CRYP_AlgoDir_Encrypt;
/* initialize the CRYP_AlgoMode member */
CRYP_InitStruct->CRYP_AlgoMode = CRYP_AlgoMode_TDES_ECB;
/* initialize the CRYP_DataType member */
CRYP_InitStruct->CRYP_DataType = CRYP_DataType_32b;
/* Initialize the CRYP_KeySize member */
CRYP_InitStruct->CRYP_KeySize = CRYP_KeySize_128b;
}
/**
* @brief Initializes the CRYP Keys according to the specified parameters in
* the CRYP_KeyInitStruct.
* @param CRYP_KeyInitStruct: pointer to a CRYP_KeyInitTypeDef structure that
* contains the configuration information for the CRYP Keys.
* @retval None
*/
void CRYP_KeyInit(CRYP_KeyInitTypeDef* CRYP_KeyInitStruct)
{
/* Key Initialisation */
CRYP->K0LR = CRYP_KeyInitStruct->CRYP_Key0Left;
CRYP->K0RR = CRYP_KeyInitStruct->CRYP_Key0Right;
CRYP->K1LR = CRYP_KeyInitStruct->CRYP_Key1Left;
CRYP->K1RR = CRYP_KeyInitStruct->CRYP_Key1Right;
CRYP->K2LR = CRYP_KeyInitStruct->CRYP_Key2Left;
CRYP->K2RR = CRYP_KeyInitStruct->CRYP_Key2Right;
CRYP->K3LR = CRYP_KeyInitStruct->CRYP_Key3Left;
CRYP->K3RR = CRYP_KeyInitStruct->CRYP_Key3Right;
}
/**
* @brief Fills each CRYP_KeyInitStruct member with its default value.
* @param CRYP_KeyInitStruct: pointer to a CRYP_KeyInitTypeDef structure
* which will be initialized.
* @retval None
*/
void CRYP_KeyStructInit(CRYP_KeyInitTypeDef* CRYP_KeyInitStruct)
{
CRYP_KeyInitStruct->CRYP_Key0Left = 0;
CRYP_KeyInitStruct->CRYP_Key0Right = 0;
CRYP_KeyInitStruct->CRYP_Key1Left = 0;
CRYP_KeyInitStruct->CRYP_Key1Right = 0;
CRYP_KeyInitStruct->CRYP_Key2Left = 0;
CRYP_KeyInitStruct->CRYP_Key2Right = 0;
CRYP_KeyInitStruct->CRYP_Key3Left = 0;
CRYP_KeyInitStruct->CRYP_Key3Right = 0;
}
/**
* @brief Initializes the CRYP Initialization Vectors(IV) according to the
* specified parameters in the CRYP_IVInitStruct.
* @param CRYP_IVInitStruct: pointer to a CRYP_IVInitTypeDef structure that contains
* the configuration information for the CRYP Initialization Vectors(IV).
* @retval None
*/
void CRYP_IVInit(CRYP_IVInitTypeDef* CRYP_IVInitStruct)
{
CRYP->IV0LR = CRYP_IVInitStruct->CRYP_IV0Left;
CRYP->IV0RR = CRYP_IVInitStruct->CRYP_IV0Right;
CRYP->IV1LR = CRYP_IVInitStruct->CRYP_IV1Left;
CRYP->IV1RR = CRYP_IVInitStruct->CRYP_IV1Right;
}
/**
* @brief Fills each CRYP_IVInitStruct member with its default value.
* @param CRYP_IVInitStruct: pointer to a CRYP_IVInitTypeDef Initialization
* Vectors(IV) structure which will be initialized.
* @retval None
*/
void CRYP_IVStructInit(CRYP_IVInitTypeDef* CRYP_IVInitStruct)
{
CRYP_IVInitStruct->CRYP_IV0Left = 0;
CRYP_IVInitStruct->CRYP_IV0Right = 0;
CRYP_IVInitStruct->CRYP_IV1Left = 0;
CRYP_IVInitStruct->CRYP_IV1Right = 0;
}
/**
* @brief Configures the AES-CCM and AES-GCM phases
* @note This function is used only with AES-CCM or AES-GCM Algorithms
* @param CRYP_Phase: specifies the CRYP AES-CCM and AES-GCM phase to be configured.
* This parameter can be one of the following values:
* @arg CRYP_Phase_Init: Initialization phase
* @arg CRYP_Phase_Header: Header phase
* @arg CRYP_Phase_Payload: Payload phase
* @arg CRYP_Phase_Final: Final phase
* @retval None
*/
void CRYP_PhaseConfig(uint32_t CRYP_Phase)
{ uint32_t tempcr = 0;
/* Check the parameter */
assert_param(IS_CRYP_PHASE(CRYP_Phase));
/* Get the CR register */
tempcr = CRYP->CR;
/* Reset the phase configuration bits: GCMP_CCMPH */
tempcr &= (uint32_t)(~CRYP_CR_GCM_CCMPH);
/* Set the selected phase */
tempcr |= (uint32_t)CRYP_Phase;
/* Set the CR register */
CRYP->CR = tempcr;
}
/**
* @brief Flushes the IN and OUT FIFOs (that is read and write pointers of the
* FIFOs are reset)
* @note The FIFOs must be flushed only when BUSY flag is reset.
* @param None
* @retval None
*/
void CRYP_FIFOFlush(void)
{
/* Reset the read and write pointers of the FIFOs */
CRYP->CR |= CRYP_CR_FFLUSH;
}
/**
* @brief Enables or disables the CRYP peripheral.
* @param NewState: new state of the CRYP peripheral.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void CRYP_Cmd(FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
/* Enable the Cryptographic processor */
CRYP->CR |= CRYP_CR_CRYPEN;
}
else
{
/* Disable the Cryptographic processor */
CRYP->CR &= ~CRYP_CR_CRYPEN;
}
}
/**
* @}
*/
/** @defgroup CRYP_Group2 CRYP Data processing functions
* @brief CRYP Data processing functions
*
@verbatim
===============================================================================
##### CRYP Data processing functions #####
===============================================================================
[..] This section provides functions allowing the encryption and decryption
operations:
(+) Enter data to be treated in the IN FIFO : using CRYP_DataIn() function.
(+) Get the data result from the OUT FIFO : using CRYP_DataOut() function.
@endverbatim
* @{
*/
/**
* @brief Writes data in the Data Input register (DIN).
* @note After the DIN register has been read once or several times,
* the FIFO must be flushed (using CRYP_FIFOFlush() function).
* @param Data: data to write in Data Input register
* @retval None
*/
void CRYP_DataIn(uint32_t Data)
{
CRYP->DR = Data;
}
/**
* @brief Returns the last data entered into the output FIFO.
* @param None
* @retval Last data entered into the output FIFO.
*/
uint32_t CRYP_DataOut(void)
{
return CRYP->DOUT;
}
/**
* @}
*/
/** @defgroup CRYP_Group3 Context swapping functions
* @brief Context swapping functions
*
@verbatim
===============================================================================
##### Context swapping functions #####
===============================================================================
[..] This section provides functions allowing to save and store CRYP Context
[..] It is possible to interrupt an encryption/ decryption/ key generation process
to perform another processing with a higher priority, and to complete the
interrupted process later on, when the higher-priority task is complete. To do
so, the context of the interrupted task must be saved from the CRYP registers
to memory, and then be restored from memory to the CRYP registers.
(#) To save the current context, use CRYP_SaveContext() function
(#) To restore the saved context, use CRYP_RestoreContext() function
@endverbatim
* @{
*/
/**
* @brief Saves the CRYP peripheral Context.
* @note This function stops DMA transfer before to save the context. After
* restoring the context, you have to enable the DMA again (if the DMA
* was previously used).
* @param CRYP_ContextSave: pointer to a CRYP_Context structure that contains
* the repository for current context.
* @param CRYP_KeyInitStruct: pointer to a CRYP_KeyInitTypeDef structure that
* contains the configuration information for the CRYP Keys.
* @retval None
*/
ErrorStatus CRYP_SaveContext(CRYP_Context* CRYP_ContextSave,
CRYP_KeyInitTypeDef* CRYP_KeyInitStruct)
{
__IO uint32_t timeout = 0;
uint32_t ckeckmask = 0, bitstatus;
ErrorStatus status = ERROR;
/* Stop DMA transfers on the IN FIFO by clearing the DIEN bit in the CRYP_DMACR */
CRYP->DMACR &= ~(uint32_t)CRYP_DMACR_DIEN;
/* Wait until both the IN and OUT FIFOs are empty
(IFEM=1 and OFNE=0 in the CRYP_SR register) and the
BUSY bit is cleared. */
if ((CRYP->CR & (uint32_t)(CRYP_CR_ALGOMODE_TDES_ECB | CRYP_CR_ALGOMODE_TDES_CBC)) != (uint32_t)0 )/* TDES */
{
ckeckmask = CRYP_SR_IFEM | CRYP_SR_BUSY ;
}
else /* AES or DES */
{
ckeckmask = CRYP_SR_IFEM | CRYP_SR_BUSY | CRYP_SR_OFNE;
}
do
{
bitstatus = CRYP->SR & ckeckmask;
timeout++;
}
while ((timeout != MAX_TIMEOUT) && (bitstatus != CRYP_SR_IFEM));
if ((CRYP->SR & ckeckmask) != CRYP_SR_IFEM)
{
status = ERROR;
}
else
{
/* Stop DMA transfers on the OUT FIFO by
- writing the DOEN bit to 0 in the CRYP_DMACR register
- and clear the CRYPEN bit. */
CRYP->DMACR &= ~(uint32_t)CRYP_DMACR_DOEN;
CRYP->CR &= ~(uint32_t)CRYP_CR_CRYPEN;
/* Save the current configuration (bit 19, bit[17:16] and bits [9:2] in the CRYP_CR register) */
CRYP_ContextSave->CR_CurrentConfig = CRYP->CR & (CRYP_CR_GCM_CCMPH |
CRYP_CR_KEYSIZE |
CRYP_CR_DATATYPE |
CRYP_CR_ALGOMODE |
CRYP_CR_ALGODIR);
/* and, if not in ECB mode, the initialization vectors. */
CRYP_ContextSave->CRYP_IV0LR = CRYP->IV0LR;
CRYP_ContextSave->CRYP_IV0RR = CRYP->IV0RR;
CRYP_ContextSave->CRYP_IV1LR = CRYP->IV1LR;
CRYP_ContextSave->CRYP_IV1RR = CRYP->IV1RR;
/* save The key value */
CRYP_ContextSave->CRYP_K0LR = CRYP_KeyInitStruct->CRYP_Key0Left;
CRYP_ContextSave->CRYP_K0RR = CRYP_KeyInitStruct->CRYP_Key0Right;
CRYP_ContextSave->CRYP_K1LR = CRYP_KeyInitStruct->CRYP_Key1Left;
CRYP_ContextSave->CRYP_K1RR = CRYP_KeyInitStruct->CRYP_Key1Right;
CRYP_ContextSave->CRYP_K2LR = CRYP_KeyInitStruct->CRYP_Key2Left;
CRYP_ContextSave->CRYP_K2RR = CRYP_KeyInitStruct->CRYP_Key2Right;
CRYP_ContextSave->CRYP_K3LR = CRYP_KeyInitStruct->CRYP_Key3Left;
CRYP_ContextSave->CRYP_K3RR = CRYP_KeyInitStruct->CRYP_Key3Right;
/* Save the content of context swap registers */
CRYP_ContextSave->CRYP_CSGCMCCMR[0] = CRYP->CSGCMCCM0R;
CRYP_ContextSave->CRYP_CSGCMCCMR[1] = CRYP->CSGCMCCM1R;
CRYP_ContextSave->CRYP_CSGCMCCMR[2] = CRYP->CSGCMCCM2R;
CRYP_ContextSave->CRYP_CSGCMCCMR[3] = CRYP->CSGCMCCM3R;
CRYP_ContextSave->CRYP_CSGCMCCMR[4] = CRYP->CSGCMCCM4R;
CRYP_ContextSave->CRYP_CSGCMCCMR[5] = CRYP->CSGCMCCM5R;
CRYP_ContextSave->CRYP_CSGCMCCMR[6] = CRYP->CSGCMCCM6R;
CRYP_ContextSave->CRYP_CSGCMCCMR[7] = CRYP->CSGCMCCM7R;
CRYP_ContextSave->CRYP_CSGCMR[0] = CRYP->CSGCM0R;
CRYP_ContextSave->CRYP_CSGCMR[1] = CRYP->CSGCM1R;
CRYP_ContextSave->CRYP_CSGCMR[2] = CRYP->CSGCM2R;
CRYP_ContextSave->CRYP_CSGCMR[3] = CRYP->CSGCM3R;
CRYP_ContextSave->CRYP_CSGCMR[4] = CRYP->CSGCM4R;
CRYP_ContextSave->CRYP_CSGCMR[5] = CRYP->CSGCM5R;
CRYP_ContextSave->CRYP_CSGCMR[6] = CRYP->CSGCM6R;
CRYP_ContextSave->CRYP_CSGCMR[7] = CRYP->CSGCM7R;
/* When needed, save the DMA status (pointers for IN and OUT messages,
number of remaining bytes, etc.) */
status = SUCCESS;
}
return status;
}
/**
* @brief Restores the CRYP peripheral Context.
* @note Since the DMA transfer is stopped in CRYP_SaveContext() function,
* after restoring the context, you have to enable the DMA again (if the
* DMA was previously used).
* @param CRYP_ContextRestore: pointer to a CRYP_Context structure that contains
* the repository for saved context.
* @note The data that were saved during context saving must be rewritten into
* the IN FIFO.
* @retval None
*/
void CRYP_RestoreContext(CRYP_Context* CRYP_ContextRestore)
{
/* Configure the processor with the saved configuration */
CRYP->CR = CRYP_ContextRestore->CR_CurrentConfig;
/* restore The key value */
CRYP->K0LR = CRYP_ContextRestore->CRYP_K0LR;
CRYP->K0RR = CRYP_ContextRestore->CRYP_K0RR;
CRYP->K1LR = CRYP_ContextRestore->CRYP_K1LR;
CRYP->K1RR = CRYP_ContextRestore->CRYP_K1RR;
CRYP->K2LR = CRYP_ContextRestore->CRYP_K2LR;
CRYP->K2RR = CRYP_ContextRestore->CRYP_K2RR;
CRYP->K3LR = CRYP_ContextRestore->CRYP_K3LR;
CRYP->K3RR = CRYP_ContextRestore->CRYP_K3RR;
/* and the initialization vectors. */
CRYP->IV0LR = CRYP_ContextRestore->CRYP_IV0LR;
CRYP->IV0RR = CRYP_ContextRestore->CRYP_IV0RR;
CRYP->IV1LR = CRYP_ContextRestore->CRYP_IV1LR;
CRYP->IV1RR = CRYP_ContextRestore->CRYP_IV1RR;
/* Restore the content of context swap registers */
CRYP->CSGCMCCM0R = CRYP_ContextRestore->CRYP_CSGCMCCMR[0];
CRYP->CSGCMCCM1R = CRYP_ContextRestore->CRYP_CSGCMCCMR[1];
CRYP->CSGCMCCM2R = CRYP_ContextRestore->CRYP_CSGCMCCMR[2];
CRYP->CSGCMCCM3R = CRYP_ContextRestore->CRYP_CSGCMCCMR[3];
CRYP->CSGCMCCM4R = CRYP_ContextRestore->CRYP_CSGCMCCMR[4];
CRYP->CSGCMCCM5R = CRYP_ContextRestore->CRYP_CSGCMCCMR[5];
CRYP->CSGCMCCM6R = CRYP_ContextRestore->CRYP_CSGCMCCMR[6];
CRYP->CSGCMCCM7R = CRYP_ContextRestore->CRYP_CSGCMCCMR[7];
CRYP->CSGCM0R = CRYP_ContextRestore->CRYP_CSGCMR[0];
CRYP->CSGCM1R = CRYP_ContextRestore->CRYP_CSGCMR[1];
CRYP->CSGCM2R = CRYP_ContextRestore->CRYP_CSGCMR[2];
CRYP->CSGCM3R = CRYP_ContextRestore->CRYP_CSGCMR[3];
CRYP->CSGCM4R = CRYP_ContextRestore->CRYP_CSGCMR[4];
CRYP->CSGCM5R = CRYP_ContextRestore->CRYP_CSGCMR[5];
CRYP->CSGCM6R = CRYP_ContextRestore->CRYP_CSGCMR[6];
CRYP->CSGCM7R = CRYP_ContextRestore->CRYP_CSGCMR[7];
/* Enable the cryptographic processor */
CRYP->CR |= CRYP_CR_CRYPEN;
}
/**
* @}
*/
/** @defgroup CRYP_Group4 CRYP's DMA interface Configuration function
* @brief CRYP's DMA interface Configuration function
*
@verbatim
===============================================================================
##### CRYP's DMA interface Configuration function #####
===============================================================================
[..] This section provides functions allowing to configure the DMA interface for
CRYP data input and output transfer.
[..] When the DMA mode is enabled (using the CRYP_DMACmd() function), data can be
transferred:
(+) From memory to the CRYP IN FIFO using the DMA peripheral by enabling
the CRYP_DMAReq_DataIN request.
(+) From the CRYP OUT FIFO to the memory using the DMA peripheral by enabling
the CRYP_DMAReq_DataOUT request.
@endverbatim
* @{
*/
/**
* @brief Enables or disables the CRYP DMA interface.
* @param CRYP_DMAReq: specifies the CRYP DMA transfer request to be enabled or disabled.
* This parameter can be any combination of the following values:
* @arg CRYP_DMAReq_DataOUT: DMA for outgoing(Tx) data transfer
* @arg CRYP_DMAReq_DataIN: DMA for incoming(Rx) data transfer
* @param NewState: new state of the selected CRYP DMA transfer request.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void CRYP_DMACmd(uint8_t CRYP_DMAReq, FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_CRYP_DMAREQ(CRYP_DMAReq));
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
/* Enable the selected CRYP DMA request */
CRYP->DMACR |= CRYP_DMAReq;
}
else
{
/* Disable the selected CRYP DMA request */
CRYP->DMACR &= (uint8_t)~CRYP_DMAReq;
}
}
/**
* @}
*/
/** @defgroup CRYP_Group5 Interrupts and flags management functions
* @brief Interrupts and flags management functions
*
@verbatim
===============================================================================
##### Interrupts and flags management functions #####
===============================================================================
[..] This section provides functions allowing to configure the CRYP Interrupts and
to get the status and Interrupts pending bits.
[..] The CRYP provides 2 Interrupts sources and 7 Flags:
*** Flags : ***
===============
[..]
(#) CRYP_FLAG_IFEM : Set when Input FIFO is empty. This Flag is cleared only
by hardware.
(#) CRYP_FLAG_IFNF : Set when Input FIFO is not full. This Flag is cleared
only by hardware.
(#) CRYP_FLAG_INRIS : Set when Input FIFO Raw interrupt is pending it gives
the raw interrupt state prior to masking of the input FIFO service interrupt.
This Flag is cleared only by hardware.
(#) CRYP_FLAG_OFNE : Set when Output FIFO not empty. This Flag is cleared
only by hardware.
(#) CRYP_FLAG_OFFU : Set when Output FIFO is full. This Flag is cleared only
by hardware.
(#) CRYP_FLAG_OUTRIS : Set when Output FIFO Raw interrupt is pending it gives
the raw interrupt state prior to masking of the output FIFO service interrupt.
This Flag is cleared only by hardware.
(#) CRYP_FLAG_BUSY : Set when the CRYP core is currently processing a block
of data or a key preparation (for AES decryption). This Flag is cleared
only by hardware. To clear it, the CRYP core must be disabled and the last
processing has completed.
*** Interrupts : ***
====================
[..]
(#) CRYP_IT_INI : The input FIFO service interrupt is asserted when there
are less than 4 words in the input FIFO. This interrupt is associated to
CRYP_FLAG_INRIS flag.
-@- This interrupt is cleared by performing write operations to the input FIFO
until it holds 4 or more words. The input FIFO service interrupt INMIS is
enabled with the CRYP enable bit. Consequently, when CRYP is disabled, the
INMIS signal is low even if the input FIFO is empty.
(#) CRYP_IT_OUTI : The output FIFO service interrupt is asserted when there
is one or more (32-bit word) data items in the output FIFO. This interrupt
is associated to CRYP_FLAG_OUTRIS flag.
-@- This interrupt is cleared by reading data from the output FIFO until there
is no valid (32-bit) word left (that is, the interrupt follows the state
of the OFNE (output FIFO not empty) flag).
*** Managing the CRYP controller events : ***
=============================================
[..] The user should identify which mode will be used in his application to manage
the CRYP controller events: Polling mode or Interrupt mode.
(#) In the Polling Mode it is advised to use the following functions:
(++) CRYP_GetFlagStatus() : to check if flags events occur.
-@@- The CRYPT flags do not need to be cleared since they are cleared as
soon as the associated event are reset.
(#) In the Interrupt Mode it is advised to use the following functions:
(++) CRYP_ITConfig() : to enable or disable the interrupt source.
(++) CRYP_GetITStatus() : to check if Interrupt occurs.
-@@- The CRYPT interrupts have no pending bits, the interrupt is cleared as
soon as the associated event is reset.
@endverbatim
* @{
*/
/**
* @brief Enables or disables the specified CRYP interrupts.
* @param CRYP_IT: specifies the CRYP interrupt source to be enabled or disabled.
* This parameter can be any combination of the following values:
* @arg CRYP_IT_INI: Input FIFO interrupt
* @arg CRYP_IT_OUTI: Output FIFO interrupt
* @param NewState: new state of the specified CRYP interrupt.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void CRYP_ITConfig(uint8_t CRYP_IT, FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_CRYP_CONFIG_IT(CRYP_IT));
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
/* Enable the selected CRYP interrupt */
CRYP->IMSCR |= CRYP_IT;
}
else
{
/* Disable the selected CRYP interrupt */
CRYP->IMSCR &= (uint8_t)~CRYP_IT;
}
}
/**
* @brief Checks whether the specified CRYP interrupt has occurred or not.
* @note This function checks the status of the masked interrupt (i.e the
* interrupt should be previously enabled).
* @param CRYP_IT: specifies the CRYP (masked) interrupt source to check.
* This parameter can be one of the following values:
* @arg CRYP_IT_INI: Input FIFO interrupt
* @arg CRYP_IT_OUTI: Output FIFO interrupt
* @retval The new state of CRYP_IT (SET or RESET).
*/
ITStatus CRYP_GetITStatus(uint8_t CRYP_IT)
{
ITStatus bitstatus = RESET;
/* Check the parameters */
assert_param(IS_CRYP_GET_IT(CRYP_IT));
/* Check the status of the specified CRYP interrupt */
if ((CRYP->MISR & CRYP_IT) != (uint8_t)RESET)
{
/* CRYP_IT is set */
bitstatus = SET;
}
else
{
/* CRYP_IT is reset */
bitstatus = RESET;
}
/* Return the CRYP_IT status */
return bitstatus;
}
/**
* @brief Returns whether CRYP peripheral is enabled or disabled.
* @param none.
* @retval Current state of the CRYP peripheral (ENABLE or DISABLE).
*/
FunctionalState CRYP_GetCmdStatus(void)
{
FunctionalState state = DISABLE;
if ((CRYP->CR & CRYP_CR_CRYPEN) != 0)
{
/* CRYPEN bit is set */
state = ENABLE;
}
else
{
/* CRYPEN bit is reset */
state = DISABLE;
}
return state;
}
/**
* @brief Checks whether the specified CRYP flag is set or not.
* @param CRYP_FLAG: specifies the CRYP flag to check.
* This parameter can be one of the following values:
* @arg CRYP_FLAG_IFEM: Input FIFO Empty flag.
* @arg CRYP_FLAG_IFNF: Input FIFO Not Full flag.
* @arg CRYP_FLAG_OFNE: Output FIFO Not Empty flag.
* @arg CRYP_FLAG_OFFU: Output FIFO Full flag.
* @arg CRYP_FLAG_BUSY: Busy flag.
* @arg CRYP_FLAG_OUTRIS: Output FIFO raw interrupt flag.
* @arg CRYP_FLAG_INRIS: Input FIFO raw interrupt flag.
* @retval The new state of CRYP_FLAG (SET or RESET).
*/
FlagStatus CRYP_GetFlagStatus(uint8_t CRYP_FLAG)
{
FlagStatus bitstatus = RESET;
uint32_t tempreg = 0;
/* Check the parameters */
assert_param(IS_CRYP_GET_FLAG(CRYP_FLAG));
/* check if the FLAG is in RISR register */
if ((CRYP_FLAG & FLAG_MASK) != 0x00)
{
tempreg = CRYP->RISR;
}
else /* The FLAG is in SR register */
{
tempreg = CRYP->SR;
}
/* Check the status of the specified CRYP flag */
if ((tempreg & CRYP_FLAG ) != (uint8_t)RESET)
{
/* CRYP_FLAG is set */
bitstatus = SET;
}
else
{
/* CRYP_FLAG is reset */
bitstatus = RESET;
}
/* Return the CRYP_FLAG status */
return bitstatus;
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

File diff suppressed because it is too large Load diff

View file

@ -0,0 +1,308 @@
/**
******************************************************************************
* @file stm32f4xx_cryp_des.c
* @author MCD Application Team
* @version V1.6.1
* @date 21-October-2015
* @brief This file provides high level functions to encrypt and decrypt an
* input message using DES in ECB/CBC modes.
* It uses the stm32f4xx_cryp.c/.h drivers to access the STM32F4xx CRYP
* peripheral.
*
@verbatim
===================================================================
##### How to use this driver #####
===================================================================
[..]
(#) Enable The CRYP controller clock using
RCC_AHB2PeriphClockCmd(RCC_AHB2Periph_CRYP, ENABLE); function.
(#) Encrypt and decrypt using DES in ECB Mode using CRYP_DES_ECB() function.
(#) Encrypt and decrypt using DES in CBC Mode using CRYP_DES_CBC() function.
@endverbatim
*
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2015 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 "stm32f4xx_cryp.h"
/** @addtogroup STM32F4xx_StdPeriph_Driver
* @{
*/
/** @defgroup CRYP
* @brief CRYP driver modules
* @{
*/
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
#define DESBUSY_TIMEOUT ((uint32_t) 0x00010000)
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/** @defgroup CRYP_Private_Functions
* @{
*/
/** @defgroup CRYP_Group8 High Level DES functions
* @brief High Level DES functions
*
@verbatim
===============================================================================
##### High Level DES functions #####
===============================================================================
@endverbatim
* @{
*/
/**
* @brief Encrypt and decrypt using DES in ECB Mode
* @param Mode: encryption or decryption Mode.
* This parameter can be one of the following values:
* @arg MODE_ENCRYPT: Encryption
* @arg MODE_DECRYPT: Decryption
* @param Key: Key used for DES algorithm.
* @param Ilength: length of the Input buffer, must be a multiple of 8.
* @param Input: pointer to the Input buffer.
* @param Output: pointer to the returned buffer.
* @retval An ErrorStatus enumeration value:
* - SUCCESS: Operation done
* - ERROR: Operation failed
*/
ErrorStatus CRYP_DES_ECB(uint8_t Mode, uint8_t Key[8], uint8_t *Input,
uint32_t Ilength, uint8_t *Output)
{
CRYP_InitTypeDef DES_CRYP_InitStructure;
CRYP_KeyInitTypeDef DES_CRYP_KeyInitStructure;
__IO uint32_t counter = 0;
uint32_t busystatus = 0;
ErrorStatus status = SUCCESS;
uint32_t keyaddr = (uint32_t)Key;
uint32_t inputaddr = (uint32_t)Input;
uint32_t outputaddr = (uint32_t)Output;
uint32_t i = 0;
/* Crypto structures initialisation*/
CRYP_KeyStructInit(&DES_CRYP_KeyInitStructure);
/* Crypto Init for Encryption process */
if( Mode == MODE_ENCRYPT ) /* DES encryption */
{
DES_CRYP_InitStructure.CRYP_AlgoDir = CRYP_AlgoDir_Encrypt;
}
else/* if( Mode == MODE_DECRYPT )*/ /* DES decryption */
{
DES_CRYP_InitStructure.CRYP_AlgoDir = CRYP_AlgoDir_Decrypt;
}
DES_CRYP_InitStructure.CRYP_AlgoMode = CRYP_AlgoMode_DES_ECB;
DES_CRYP_InitStructure.CRYP_DataType = CRYP_DataType_8b;
CRYP_Init(&DES_CRYP_InitStructure);
/* Key Initialisation */
DES_CRYP_KeyInitStructure.CRYP_Key1Left = __REV(*(uint32_t*)(keyaddr));
keyaddr+=4;
DES_CRYP_KeyInitStructure.CRYP_Key1Right= __REV(*(uint32_t*)(keyaddr));
CRYP_KeyInit(& DES_CRYP_KeyInitStructure);
/* Flush IN/OUT FIFO */
CRYP_FIFOFlush();
/* Enable Crypto processor */
CRYP_Cmd(ENABLE);
if(CRYP_GetCmdStatus() == DISABLE)
{
/* The CRYP peripheral clock is not enabled or the device doesn't embed
the CRYP peripheral (please check the device sales type. */
return(ERROR);
}
for(i=0; ((i<Ilength) && (status != ERROR)); i+=8)
{
/* Write the Input block in the Input FIFO */
CRYP_DataIn(*(uint32_t*)(inputaddr));
inputaddr+=4;
CRYP_DataIn(*(uint32_t*)(inputaddr));
inputaddr+=4;
/* Wait until the complete message has been processed */
counter = 0;
do
{
busystatus = CRYP_GetFlagStatus(CRYP_FLAG_BUSY);
counter++;
}while ((counter != DESBUSY_TIMEOUT) && (busystatus != RESET));
if (busystatus != RESET)
{
status = ERROR;
}
else
{
/* Read the Output block from the Output FIFO */
*(uint32_t*)(outputaddr) = CRYP_DataOut();
outputaddr+=4;
*(uint32_t*)(outputaddr) = CRYP_DataOut();
outputaddr+=4;
}
}
/* Disable Crypto */
CRYP_Cmd(DISABLE);
return status;
}
/**
* @brief Encrypt and decrypt using DES in CBC Mode
* @param Mode: encryption or decryption Mode.
* This parameter can be one of the following values:
* @arg MODE_ENCRYPT: Encryption
* @arg MODE_DECRYPT: Decryption
* @param Key: Key used for DES algorithm.
* @param InitVectors: Initialisation Vectors used for DES algorithm.
* @param Ilength: length of the Input buffer, must be a multiple of 8.
* @param Input: pointer to the Input buffer.
* @param Output: pointer to the returned buffer.
* @retval An ErrorStatus enumeration value:
* - SUCCESS: Operation done
* - ERROR: Operation failed
*/
ErrorStatus CRYP_DES_CBC(uint8_t Mode, uint8_t Key[8], uint8_t InitVectors[8],
uint8_t *Input, uint32_t Ilength, uint8_t *Output)
{
CRYP_InitTypeDef DES_CRYP_InitStructure;
CRYP_KeyInitTypeDef DES_CRYP_KeyInitStructure;
CRYP_IVInitTypeDef DES_CRYP_IVInitStructure;
__IO uint32_t counter = 0;
uint32_t busystatus = 0;
ErrorStatus status = SUCCESS;
uint32_t keyaddr = (uint32_t)Key;
uint32_t inputaddr = (uint32_t)Input;
uint32_t outputaddr = (uint32_t)Output;
uint32_t ivaddr = (uint32_t)InitVectors;
uint32_t i = 0;
/* Crypto structures initialisation*/
CRYP_KeyStructInit(&DES_CRYP_KeyInitStructure);
/* Crypto Init for Encryption process */
if(Mode == MODE_ENCRYPT) /* DES encryption */
{
DES_CRYP_InitStructure.CRYP_AlgoDir = CRYP_AlgoDir_Encrypt;
}
else /*if(Mode == MODE_DECRYPT)*/ /* DES decryption */
{
DES_CRYP_InitStructure.CRYP_AlgoDir = CRYP_AlgoDir_Decrypt;
}
DES_CRYP_InitStructure.CRYP_AlgoMode = CRYP_AlgoMode_DES_CBC;
DES_CRYP_InitStructure.CRYP_DataType = CRYP_DataType_8b;
CRYP_Init(&DES_CRYP_InitStructure);
/* Key Initialisation */
DES_CRYP_KeyInitStructure.CRYP_Key1Left = __REV(*(uint32_t*)(keyaddr));
keyaddr+=4;
DES_CRYP_KeyInitStructure.CRYP_Key1Right= __REV(*(uint32_t*)(keyaddr));
CRYP_KeyInit(& DES_CRYP_KeyInitStructure);
/* Initialization Vectors */
DES_CRYP_IVInitStructure.CRYP_IV0Left = __REV(*(uint32_t*)(ivaddr));
ivaddr+=4;
DES_CRYP_IVInitStructure.CRYP_IV0Right= __REV(*(uint32_t*)(ivaddr));
CRYP_IVInit(&DES_CRYP_IVInitStructure);
/* Flush IN/OUT FIFO */
CRYP_FIFOFlush();
/* Enable Crypto processor */
CRYP_Cmd(ENABLE);
if(CRYP_GetCmdStatus() == DISABLE)
{
/* The CRYP peripheral clock is not enabled or the device doesn't embed
the CRYP peripheral (please check the device sales type. */
return(ERROR);
}
for(i=0; ((i<Ilength) && (status != ERROR)); i+=8)
{
/* Write the Input block in the Input FIFO */
CRYP_DataIn(*(uint32_t*)(inputaddr));
inputaddr+=4;
CRYP_DataIn(*(uint32_t*)(inputaddr));
inputaddr+=4;
/* Wait until the complete message has been processed */
counter = 0;
do
{
busystatus = CRYP_GetFlagStatus(CRYP_FLAG_BUSY);
counter++;
}while ((counter != DESBUSY_TIMEOUT) && (busystatus != RESET));
if (busystatus != RESET)
{
status = ERROR;
}
else
{
/* Read the Output block from the Output FIFO */
*(uint32_t*)(outputaddr) = CRYP_DataOut();
outputaddr+=4;
*(uint32_t*)(outputaddr) = CRYP_DataOut();
outputaddr+=4;
}
}
/* Disable Crypto */
CRYP_Cmd(DISABLE);
return status;
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View file

@ -0,0 +1,325 @@
/**
******************************************************************************
* @file stm32f4xx_cryp_tdes.c
* @author MCD Application Team
* @version V1.6.1
* @date 21-October-2015
* @brief This file provides high level functions to encrypt and decrypt an
* input message using TDES in ECB/CBC modes .
* It uses the stm32f4xx_cryp.c/.h drivers to access the STM32F4xx CRYP
* peripheral.
*
@verbatim
===============================================================================
##### How to use this driver #####
===============================================================================
[..]
(#) Enable The CRYP controller clock using
RCC_AHB2PeriphClockCmd(RCC_AHB2Periph_CRYP, ENABLE); function.
(#) Encrypt and decrypt using TDES in ECB Mode using CRYP_TDES_ECB() function.
(#) Encrypt and decrypt using TDES in CBC Mode using CRYP_TDES_CBC() function.
@endverbatim
*
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2015 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 "stm32f4xx_cryp.h"
/** @addtogroup STM32F4xx_StdPeriph_Driver
* @{
*/
/** @defgroup CRYP
* @brief CRYP driver modules
* @{
*/
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
#define TDESBUSY_TIMEOUT ((uint32_t) 0x00010000)
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/** @defgroup CRYP_Private_Functions
* @{
*/
/** @defgroup CRYP_Group7 High Level TDES functions
* @brief High Level TDES functions
*
@verbatim
===============================================================================
##### High Level TDES functions #####
===============================================================================
@endverbatim
* @{
*/
/**
* @brief Encrypt and decrypt using TDES in ECB Mode
* @param Mode: encryption or decryption Mode.
* This parameter can be one of the following values:
* @arg MODE_ENCRYPT: Encryption
* @arg MODE_DECRYPT: Decryption
* @param Key: Key used for TDES algorithm.
* @param Ilength: length of the Input buffer, must be a multiple of 8.
* @param Input: pointer to the Input buffer.
* @param Output: pointer to the returned buffer.
* @retval An ErrorStatus enumeration value:
* - SUCCESS: Operation done
* - ERROR: Operation failed
*/
ErrorStatus CRYP_TDES_ECB(uint8_t Mode, uint8_t Key[24], uint8_t *Input,
uint32_t Ilength, uint8_t *Output)
{
CRYP_InitTypeDef TDES_CRYP_InitStructure;
CRYP_KeyInitTypeDef TDES_CRYP_KeyInitStructure;
__IO uint32_t counter = 0;
uint32_t busystatus = 0;
ErrorStatus status = SUCCESS;
uint32_t keyaddr = (uint32_t)Key;
uint32_t inputaddr = (uint32_t)Input;
uint32_t outputaddr = (uint32_t)Output;
uint32_t i = 0;
/* Crypto structures initialisation*/
CRYP_KeyStructInit(&TDES_CRYP_KeyInitStructure);
/* Crypto Init for Encryption process */
if(Mode == MODE_ENCRYPT) /* TDES encryption */
{
TDES_CRYP_InitStructure.CRYP_AlgoDir = CRYP_AlgoDir_Encrypt;
}
else /*if(Mode == MODE_DECRYPT)*/ /* TDES decryption */
{
TDES_CRYP_InitStructure.CRYP_AlgoDir = CRYP_AlgoDir_Decrypt;
}
TDES_CRYP_InitStructure.CRYP_AlgoMode = CRYP_AlgoMode_TDES_ECB;
TDES_CRYP_InitStructure.CRYP_DataType = CRYP_DataType_8b;
CRYP_Init(&TDES_CRYP_InitStructure);
/* Key Initialisation */
TDES_CRYP_KeyInitStructure.CRYP_Key1Left = __REV(*(uint32_t*)(keyaddr));
keyaddr+=4;
TDES_CRYP_KeyInitStructure.CRYP_Key1Right= __REV(*(uint32_t*)(keyaddr));
keyaddr+=4;
TDES_CRYP_KeyInitStructure.CRYP_Key2Left = __REV(*(uint32_t*)(keyaddr));
keyaddr+=4;
TDES_CRYP_KeyInitStructure.CRYP_Key2Right= __REV(*(uint32_t*)(keyaddr));
keyaddr+=4;
TDES_CRYP_KeyInitStructure.CRYP_Key3Left = __REV(*(uint32_t*)(keyaddr));
keyaddr+=4;
TDES_CRYP_KeyInitStructure.CRYP_Key3Right= __REV(*(uint32_t*)(keyaddr));
CRYP_KeyInit(& TDES_CRYP_KeyInitStructure);
/* Flush IN/OUT FIFO */
CRYP_FIFOFlush();
/* Enable Crypto processor */
CRYP_Cmd(ENABLE);
if(CRYP_GetCmdStatus() == DISABLE)
{
/* The CRYP peripheral clock is not enabled or the device doesn't embed
the CRYP peripheral (please check the device sales type. */
return(ERROR);
}
for(i=0; ((i<Ilength) && (status != ERROR)); i+=8)
{
/* Write the Input block in the Input FIFO */
CRYP_DataIn(*(uint32_t*)(inputaddr));
inputaddr+=4;
CRYP_DataIn(*(uint32_t*)(inputaddr));
inputaddr+=4;
/* Wait until the complete message has been processed */
counter = 0;
do
{
busystatus = CRYP_GetFlagStatus(CRYP_FLAG_BUSY);
counter++;
}while ((counter != TDESBUSY_TIMEOUT) && (busystatus != RESET));
if (busystatus != RESET)
{
status = ERROR;
}
else
{
/* Read the Output block from the Output FIFO */
*(uint32_t*)(outputaddr) = CRYP_DataOut();
outputaddr+=4;
*(uint32_t*)(outputaddr) = CRYP_DataOut();
outputaddr+=4;
}
}
/* Disable Crypto */
CRYP_Cmd(DISABLE);
return status;
}
/**
* @brief Encrypt and decrypt using TDES in CBC Mode
* @param Mode: encryption or decryption Mode.
* This parameter can be one of the following values:
* @arg MODE_ENCRYPT: Encryption
* @arg MODE_DECRYPT: Decryption
* @param Key: Key used for TDES algorithm.
* @param InitVectors: Initialisation Vectors used for TDES algorithm.
* @param Input: pointer to the Input buffer.
* @param Ilength: length of the Input buffer, must be a multiple of 8.
* @param Output: pointer to the returned buffer.
* @retval An ErrorStatus enumeration value:
* - SUCCESS: Operation done
* - ERROR: Operation failed
*/
ErrorStatus CRYP_TDES_CBC(uint8_t Mode, uint8_t Key[24], uint8_t InitVectors[8],
uint8_t *Input, uint32_t Ilength, uint8_t *Output)
{
CRYP_InitTypeDef TDES_CRYP_InitStructure;
CRYP_KeyInitTypeDef TDES_CRYP_KeyInitStructure;
CRYP_IVInitTypeDef TDES_CRYP_IVInitStructure;
__IO uint32_t counter = 0;
uint32_t busystatus = 0;
ErrorStatus status = SUCCESS;
uint32_t keyaddr = (uint32_t)Key;
uint32_t inputaddr = (uint32_t)Input;
uint32_t outputaddr = (uint32_t)Output;
uint32_t ivaddr = (uint32_t)InitVectors;
uint32_t i = 0;
/* Crypto structures initialisation*/
CRYP_KeyStructInit(&TDES_CRYP_KeyInitStructure);
/* Crypto Init for Encryption process */
if(Mode == MODE_ENCRYPT) /* TDES encryption */
{
TDES_CRYP_InitStructure.CRYP_AlgoDir = CRYP_AlgoDir_Encrypt;
}
else
{
TDES_CRYP_InitStructure.CRYP_AlgoDir = CRYP_AlgoDir_Decrypt;
}
TDES_CRYP_InitStructure.CRYP_AlgoMode = CRYP_AlgoMode_TDES_CBC;
TDES_CRYP_InitStructure.CRYP_DataType = CRYP_DataType_8b;
CRYP_Init(&TDES_CRYP_InitStructure);
/* Key Initialisation */
TDES_CRYP_KeyInitStructure.CRYP_Key1Left = __REV(*(uint32_t*)(keyaddr));
keyaddr+=4;
TDES_CRYP_KeyInitStructure.CRYP_Key1Right= __REV(*(uint32_t*)(keyaddr));
keyaddr+=4;
TDES_CRYP_KeyInitStructure.CRYP_Key2Left = __REV(*(uint32_t*)(keyaddr));
keyaddr+=4;
TDES_CRYP_KeyInitStructure.CRYP_Key2Right= __REV(*(uint32_t*)(keyaddr));
keyaddr+=4;
TDES_CRYP_KeyInitStructure.CRYP_Key3Left = __REV(*(uint32_t*)(keyaddr));
keyaddr+=4;
TDES_CRYP_KeyInitStructure.CRYP_Key3Right= __REV(*(uint32_t*)(keyaddr));
CRYP_KeyInit(& TDES_CRYP_KeyInitStructure);
/* Initialization Vectors */
TDES_CRYP_IVInitStructure.CRYP_IV0Left = __REV(*(uint32_t*)(ivaddr));
ivaddr+=4;
TDES_CRYP_IVInitStructure.CRYP_IV0Right= __REV(*(uint32_t*)(ivaddr));
CRYP_IVInit(&TDES_CRYP_IVInitStructure);
/* Flush IN/OUT FIFO */
CRYP_FIFOFlush();
/* Enable Crypto processor */
CRYP_Cmd(ENABLE);
if(CRYP_GetCmdStatus() == DISABLE)
{
/* The CRYP peripheral clock is not enabled or the device doesn't embed
the CRYP peripheral (please check the device sales type. */
return(ERROR);
}
for(i=0; ((i<Ilength) && (status != ERROR)); i+=8)
{
/* Write the Input block in the Input FIFO */
CRYP_DataIn(*(uint32_t*)(inputaddr));
inputaddr+=4;
CRYP_DataIn(*(uint32_t*)(inputaddr));
inputaddr+=4;
/* Wait until the complete message has been processed */
counter = 0;
do
{
busystatus = CRYP_GetFlagStatus(CRYP_FLAG_BUSY);
counter++;
}while ((counter != TDESBUSY_TIMEOUT) && (busystatus != RESET));
if (busystatus != RESET)
{
status = ERROR;
}
else
{
/* Read the Output block from the Output FIFO */
*(uint32_t*)(outputaddr) = CRYP_DataOut();
outputaddr+=4;
*(uint32_t*)(outputaddr) = CRYP_DataOut();
outputaddr+=4;
}
}
/* Disable Crypto */
CRYP_Cmd(DISABLE);
return status;
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View file

@ -0,0 +1,714 @@
/**
******************************************************************************
* @file stm32f4xx_dac.c
* @author MCD Application Team
* @version V1.6.1
* @date 21-October-2015
* @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 #####
===============================================================================
[..]
*** DAC Channels ***
====================
[..]
The device integrates two 12-bit Digital Analog Converters that can
be used independently or simultaneously (dual mode):
(#) DAC channel1 with DAC_OUT1 (PA4) as output
(#) DAC channel2 with DAC_OUT2 (PA5) as output
*** DAC Triggers ***
====================
[..]
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() functions.
[..]
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, TIM4, TIM5, TIM6, TIM7 and TIM8
(DAC_Trigger_T2_TRGO, DAC_Trigger_T4_TRGO...)
The timer TRGO event should be selected using TIM_SelectOutputTrigger()
(#) Software using DAC_Trigger_Software
*** DAC Buffer mode feature ***
===============================
[..]
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.
*** DAC wave generation feature ***
===================================
[..]
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
*** DAC data format ***
=======================
[..]
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
*** DAC data value to voltage correspondence ***
================================================
[..]
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
VEF+ 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.3V, DAC_OUT1 = (3.3 * 868) / 4095 = 0.7V
*** DMA requests ***
=====================
[..]
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 : mapped on DMA1 Stream5 channel7 which must be
already configured
(#) DAC channel2 : mapped on DMA1 Stream6 channel7 which must be
already configured
##### How to use this driver #####
===============================================================================
[..]
(+) DAC APB clock must be enabled to get write access to DAC
registers using
RCC_APB1PeriphClockCmd(RCC_APB1Periph_DAC, ENABLE)
(+) Configure DAC_OUTx (DAC_OUT1: PA4, DAC_OUT2: PA5) in analog mode.
(+) Configure the DAC channel using DAC_Init() function
(+) Enable the DAC channel using DAC_Cmd() function
@endverbatim
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2015 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 "stm32f4xx_dac.h"
#include "stm32f4xx_rcc.h"
/** @addtogroup STM32F4xx_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 None
* @retval None
*/
void DAC_DeInit(void)
{
/* Enable DAC reset state */
RCC_APB1PeriphResetCmd(RCC_APB1Periph_DAC, ENABLE);
/* Release DAC from reset state */
RCC_APB1PeriphResetCmd(RCC_APB1Periph_DAC, DISABLE);
}
/**
* @brief Initializes the DAC peripheral according to the specified parameters
* in the DAC_InitStruct.
* @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(uint32_t DAC_Channel, DAC_InitTypeDef* DAC_InitStruct)
{
uint32_t tmpreg1 = 0, tmpreg2 = 0;
/* Check the DAC parameters */
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_OUTPUT_BUFFER_STATE(DAC_InitStruct->DAC_OutputBuffer));
/*---------------------------- DAC CR Configuration --------------------------*/
/* Get the DAC CR value */
tmpreg1 = DAC->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 bit according to DAC_OutputBuffer value */
tmpreg2 = (DAC_InitStruct->DAC_Trigger | DAC_InitStruct->DAC_WaveGeneration |
DAC_InitStruct->DAC_LFSRUnmask_TriangleAmplitude | \
DAC_InitStruct->DAC_OutputBuffer);
/* Calculate CR register value depending on DAC_Channel */
tmpreg1 |= tmpreg2 << DAC_Channel;
/* Write to DAC CR */
DAC->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_OutputBuffer member */
DAC_InitStruct->DAC_OutputBuffer = DAC_OutputBuffer_Enable;
}
/**
* @brief Enables or disables the specified DAC channel.
* @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(uint32_t DAC_Channel, FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_DAC_CHANNEL(DAC_Channel));
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
/* Enable the selected DAC channel */
DAC->CR |= (DAC_CR_EN1 << DAC_Channel);
}
else
{
/* Disable the selected DAC channel */
DAC->CR &= (~(DAC_CR_EN1 << DAC_Channel));
}
}
/**
* @brief Enables or disables the selected DAC channel software trigger.
* @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(uint32_t DAC_Channel, FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_DAC_CHANNEL(DAC_Channel));
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
/* Enable software trigger for the selected DAC channel */
DAC->SWTRIGR |= (uint32_t)DAC_SWTRIGR_SWTRIG1 << (DAC_Channel >> 4);
}
else
{
/* Disable software trigger for the selected DAC channel */
DAC->SWTRIGR &= ~((uint32_t)DAC_SWTRIGR_SWTRIG1 << (DAC_Channel >> 4));
}
}
/**
* @brief Enables or disables simultaneously the two DAC channels software triggers.
* @param NewState: new state of the DAC channels software triggers.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void DAC_DualSoftwareTriggerCmd(FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
/* Enable software trigger for both DAC channels */
DAC->SWTRIGR |= DUAL_SWTRIG_SET;
}
else
{
/* Disable software trigger for both DAC channels */
DAC->SWTRIGR &= DUAL_SWTRIG_RESET;
}
}
/**
* @brief Enables or disables the selected DAC channel wave generation.
* @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.
* @retval None
*/
void DAC_WaveGenerationCmd(uint32_t DAC_Channel, uint32_t DAC_Wave, FunctionalState NewState)
{
/* Check the parameters */
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 */
DAC->CR |= DAC_Wave << DAC_Channel;
}
else
{
/* Disable the selected wave generation for the selected DAC channel */
DAC->CR &= ~(DAC_Wave << DAC_Channel);
}
}
/**
* @brief Set the specified data holding register value for DAC channel1.
* @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(uint32_t DAC_Align, uint16_t Data)
{
__IO uint32_t tmp = 0;
/* Check the parameters */
assert_param(IS_DAC_ALIGN(DAC_Align));
assert_param(IS_DAC_DATA(Data));
tmp = (uint32_t)DAC_BASE;
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 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(uint32_t DAC_Align, uint16_t Data)
{
__IO uint32_t tmp = 0;
/* Check the parameters */
assert_param(IS_DAC_ALIGN(DAC_Align));
assert_param(IS_DAC_DATA(Data));
tmp = (uint32_t)DAC_BASE;
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 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(uint32_t DAC_Align, uint16_t Data2, uint16_t Data1)
{
uint32_t data = 0, tmp = 0;
/* Check the parameters */
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)DAC_BASE;
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 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(uint32_t DAC_Channel)
{
__IO uint32_t tmp = 0;
/* Check the parameters */
assert_param(IS_DAC_CHANNEL(DAC_Channel));
tmp = (uint32_t) DAC_BASE ;
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.
* @note When enabled DMA1 is generated when an external trigger (EXTI Line9,
* TIM2, TIM4, TIM5, TIM6, TIM7 or TIM8 but not a software trigger) occurs.
* @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 is mapped on DMA1 Stream 5 channel7 which must be
* already configured.
* @note The DAC channel2 is mapped on DMA1 Stream 6 channel7 which must be
* already configured.
* @retval None
*/
void DAC_DMACmd(uint32_t DAC_Channel, FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_DAC_CHANNEL(DAC_Channel));
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
/* Enable the selected DAC channel DMA request */
DAC->CR |= (DAC_CR_DMAEN1 << DAC_Channel);
}
else
{
/* Disable the selected DAC channel DMA request */
DAC->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 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 the following values:
* @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(uint32_t DAC_Channel, uint32_t DAC_IT, FunctionalState NewState)
{
/* Check the parameters */
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 */
DAC->CR |= (DAC_IT << DAC_Channel);
}
else
{
/* Disable the selected DAC interrupts */
DAC->CR &= (~(uint32_t)(DAC_IT << DAC_Channel));
}
}
/**
* @brief Checks whether the specified DAC flag is set or not.
* @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 check.
* This parameter can be only of the following value:
* @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(uint32_t DAC_Channel, uint32_t DAC_FLAG)
{
FlagStatus bitstatus = RESET;
/* Check the parameters */
assert_param(IS_DAC_CHANNEL(DAC_Channel));
assert_param(IS_DAC_FLAG(DAC_FLAG));
/* Check the status of the specified DAC flag */
if ((DAC->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 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 of the following value:
* @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 None
*/
void DAC_ClearFlag(uint32_t DAC_Channel, uint32_t DAC_FLAG)
{
/* Check the parameters */
assert_param(IS_DAC_CHANNEL(DAC_Channel));
assert_param(IS_DAC_FLAG(DAC_FLAG));
/* Clear the selected DAC flags */
DAC->SR = (DAC_FLAG << DAC_Channel);
}
/**
* @brief Checks whether the specified DAC interrupt has occurred or not.
* @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 the following values:
* @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(uint32_t DAC_Channel, uint32_t DAC_IT)
{
ITStatus bitstatus = RESET;
uint32_t enablestatus = 0;
/* Check the parameters */
assert_param(IS_DAC_CHANNEL(DAC_Channel));
assert_param(IS_DAC_IT(DAC_IT));
/* Get the DAC_IT enable bit status */
enablestatus = (DAC->CR & (DAC_IT << DAC_Channel)) ;
/* Check the status of the specified DAC interrupt */
if (((DAC->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 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
* @note The DMA underrun occurs when a second external trigger arrives before the
* acknowledgement for the first external trigger is received (first request).
* @retval None
*/
void DAC_ClearITPendingBit(uint32_t DAC_Channel, uint32_t DAC_IT)
{
/* Check the parameters */
assert_param(IS_DAC_CHANNEL(DAC_Channel));
assert_param(IS_DAC_IT(DAC_IT));
/* Clear the selected DAC interrupt pending bits */
DAC->SR = (DAC_IT << DAC_Channel);
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View file

@ -0,0 +1,180 @@
/**
******************************************************************************
* @file stm32f4xx_dbgmcu.c
* @author MCD Application Team
* @version V1.6.1
* @date 21-October-2015
* @brief This file provides all the DBGMCU firmware functions.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2015 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 "stm32f4xx_dbgmcu.h"
/** @addtogroup STM32F4xx_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
* @{
*/
/**
* @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);
}
/**
* @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_TIM5_STOP: TIM5 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_TIM12_STOP: TIM12 counter stopped when Core is halted
* @arg DBGMCU_TIM13_STOP: TIM13 counter stopped when Core is halted
* @arg DBGMCU_TIM14_STOP: TIM14 counter stopped when Core is halted
* @arg DBGMCU_RTC_STOP: RTC Calendar and Wakeup counter 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_I2C3_SMBUS_TIMEOUT: I2C3 SMBUS timeout mode stopped when Core is halted
* @arg DBGMCU_CAN2_STOP: Debug CAN1 stopped when Core is halted
* @arg DBGMCU_CAN1_STOP: Debug CAN2 stopped when Core is halted
* 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_TIM9_STOP: TIM9 counter stopped when Core is halted
* @arg DBGMCU_TIM10_STOP: TIM10 counter stopped when Core is halted
* @arg DBGMCU_TIM11_STOP: TIM11 counter stopped when Core is halted
* @param NewState: new state of the specified 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****/

View file

@ -0,0 +1,538 @@
/**
******************************************************************************
* @file stm32f4xx_dcmi.c
* @author MCD Application Team
* @version V1.6.1
* @date 21-October-2015
* @brief This file provides firmware functions to manage the following
* functionalities of the DCMI peripheral:
* + Initialization and Configuration
* + Image capture functions
* + Interrupts and flags management
*
@verbatim
===============================================================================
##### How to use this driver #####
===============================================================================
[..]
The sequence below describes how to use this driver to capture image
from a camera module connected to the DCMI Interface.
This sequence does not take into account the configuration of the
camera module, which should be made before to configure and enable
the DCMI to capture images.
(#) Enable the clock for the DCMI and associated GPIOs using the following
functions:
RCC_AHB2PeriphClockCmd(RCC_AHB2Periph_DCMI, ENABLE);
RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOx, ENABLE);
(#) DCMI pins configuration
(++) Connect the involved DCMI pins to AF13 using the following function
GPIO_PinAFConfig(GPIOx, GPIO_PinSourcex, GPIO_AF_DCMI);
(++) Configure these DCMI pins in alternate function mode by calling
the function GPIO_Init();
(#) Declare a DCMI_InitTypeDef structure, for example:
DCMI_InitTypeDef DCMI_InitStructure;
and fill the DCMI_InitStructure variable with the allowed values
of the structure member.
(#) Initialize the DCMI interface by calling the function
DCMI_Init(&DCMI_InitStructure);
(#) Configure the DMA2_Stream1 channel1 to transfer Data from DCMI DR
register to the destination memory buffer.
(#) Enable DCMI interface using the function
DCMI_Cmd(ENABLE);
(#) Start the image capture using the function
DCMI_CaptureCmd(ENABLE);
(#) At this stage the DCMI interface waits for the first start of frame,
then a DMA request is generated continuously/once (depending on the
mode used, Continuous/Snapshot) to transfer the received data into
the destination memory.
-@- If you need to capture only a rectangular window from the received
image, you have to use the DCMI_CROPConfig() function to configure
the coordinates and size of the window to be captured, then enable
the Crop feature using DCMI_CROPCmd(ENABLE);
In this case, the Crop configuration should be made before to enable
and start the DCMI interface.
@endverbatim
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2015 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 "stm32f4xx_dcmi.h"
#include "stm32f4xx_rcc.h"
/** @addtogroup STM32F4xx_StdPeriph_Driver
* @{
*/
/** @defgroup DCMI
* @brief DCMI driver modules
* @{
*/
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/** @defgroup DCMI_Private_Functions
* @{
*/
/** @defgroup DCMI_Group1 Initialization and Configuration functions
* @brief Initialization and Configuration functions
*
@verbatim
===============================================================================
##### Initialization and Configuration functions #####
===============================================================================
@endverbatim
* @{
*/
/**
* @brief Deinitializes the DCMI registers to their default reset values.
* @param None
* @retval None
*/
void DCMI_DeInit(void)
{
DCMI->CR = 0x0;
DCMI->IER = 0x0;
DCMI->ICR = 0x1F;
DCMI->ESCR = 0x0;
DCMI->ESUR = 0x0;
DCMI->CWSTRTR = 0x0;
DCMI->CWSIZER = 0x0;
}
/**
* @brief Initializes the DCMI according to the specified parameters in the DCMI_InitStruct.
* @param DCMI_InitStruct: pointer to a DCMI_InitTypeDef structure that contains
* the configuration information for the DCMI.
* @retval None
*/
void DCMI_Init(DCMI_InitTypeDef* DCMI_InitStruct)
{
uint32_t temp = 0x0;
/* Check the parameters */
assert_param(IS_DCMI_CAPTURE_MODE(DCMI_InitStruct->DCMI_CaptureMode));
assert_param(IS_DCMI_SYNCHRO(DCMI_InitStruct->DCMI_SynchroMode));
assert_param(IS_DCMI_PCKPOLARITY(DCMI_InitStruct->DCMI_PCKPolarity));
assert_param(IS_DCMI_VSPOLARITY(DCMI_InitStruct->DCMI_VSPolarity));
assert_param(IS_DCMI_HSPOLARITY(DCMI_InitStruct->DCMI_HSPolarity));
assert_param(IS_DCMI_CAPTURE_RATE(DCMI_InitStruct->DCMI_CaptureRate));
assert_param(IS_DCMI_EXTENDED_DATA(DCMI_InitStruct->DCMI_ExtendedDataMode));
/* The DCMI configuration registers should be programmed correctly before
enabling the CR_ENABLE Bit and the CR_CAPTURE Bit */
DCMI->CR &= ~(DCMI_CR_ENABLE | DCMI_CR_CAPTURE);
/* Reset the old DCMI configuration */
temp = DCMI->CR;
temp &= ~((uint32_t)DCMI_CR_CM | DCMI_CR_ESS | DCMI_CR_PCKPOL |
DCMI_CR_HSPOL | DCMI_CR_VSPOL | DCMI_CR_FCRC_0 |
DCMI_CR_FCRC_1 | DCMI_CR_EDM_0 | DCMI_CR_EDM_1);
/* Sets the new configuration of the DCMI peripheral */
temp |= ((uint32_t)DCMI_InitStruct->DCMI_CaptureMode |
DCMI_InitStruct->DCMI_SynchroMode |
DCMI_InitStruct->DCMI_PCKPolarity |
DCMI_InitStruct->DCMI_VSPolarity |
DCMI_InitStruct->DCMI_HSPolarity |
DCMI_InitStruct->DCMI_CaptureRate |
DCMI_InitStruct->DCMI_ExtendedDataMode);
DCMI->CR = temp;
}
/**
* @brief Fills each DCMI_InitStruct member with its default value.
* @param DCMI_InitStruct : pointer to a DCMI_InitTypeDef structure which will
* be initialized.
* @retval None
*/
void DCMI_StructInit(DCMI_InitTypeDef* DCMI_InitStruct)
{
/* Set the default configuration */
DCMI_InitStruct->DCMI_CaptureMode = DCMI_CaptureMode_Continuous;
DCMI_InitStruct->DCMI_SynchroMode = DCMI_SynchroMode_Hardware;
DCMI_InitStruct->DCMI_PCKPolarity = DCMI_PCKPolarity_Falling;
DCMI_InitStruct->DCMI_VSPolarity = DCMI_VSPolarity_Low;
DCMI_InitStruct->DCMI_HSPolarity = DCMI_HSPolarity_Low;
DCMI_InitStruct->DCMI_CaptureRate = DCMI_CaptureRate_All_Frame;
DCMI_InitStruct->DCMI_ExtendedDataMode = DCMI_ExtendedDataMode_8b;
}
/**
* @brief Initializes the DCMI peripheral CROP mode according to the specified
* parameters in the DCMI_CROPInitStruct.
* @note This function should be called before to enable and start the DCMI interface.
* @param DCMI_CROPInitStruct: pointer to a DCMI_CROPInitTypeDef structure that
* contains the configuration information for the DCMI peripheral CROP mode.
* @retval None
*/
void DCMI_CROPConfig(DCMI_CROPInitTypeDef* DCMI_CROPInitStruct)
{
/* Sets the CROP window coordinates */
DCMI->CWSTRTR = (uint32_t)((uint32_t)DCMI_CROPInitStruct->DCMI_HorizontalOffsetCount |
((uint32_t)DCMI_CROPInitStruct->DCMI_VerticalStartLine << 16));
/* Sets the CROP window size */
DCMI->CWSIZER = (uint32_t)(DCMI_CROPInitStruct->DCMI_CaptureCount |
((uint32_t)DCMI_CROPInitStruct->DCMI_VerticalLineCount << 16));
}
/**
* @brief Enables or disables the DCMI Crop feature.
* @note This function should be called before to enable and start the DCMI interface.
* @param NewState: new state of the DCMI Crop feature.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void DCMI_CROPCmd(FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
/* Enable the DCMI Crop feature */
DCMI->CR |= (uint32_t)DCMI_CR_CROP;
}
else
{
/* Disable the DCMI Crop feature */
DCMI->CR &= ~(uint32_t)DCMI_CR_CROP;
}
}
/**
* @brief Sets the embedded synchronization codes
* @param DCMI_CodesInitTypeDef: pointer to a DCMI_CodesInitTypeDef structure that
* contains the embedded synchronization codes for the DCMI peripheral.
* @retval None
*/
void DCMI_SetEmbeddedSynchroCodes(DCMI_CodesInitTypeDef* DCMI_CodesInitStruct)
{
DCMI->ESCR = (uint32_t)(DCMI_CodesInitStruct->DCMI_FrameStartCode |
((uint32_t)DCMI_CodesInitStruct->DCMI_LineStartCode << 8)|
((uint32_t)DCMI_CodesInitStruct->DCMI_LineEndCode << 16)|
((uint32_t)DCMI_CodesInitStruct->DCMI_FrameEndCode << 24));
}
/**
* @brief Enables or disables the DCMI JPEG format.
* @note The Crop and Embedded Synchronization features cannot be used in this mode.
* @param NewState: new state of the DCMI JPEG format.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void DCMI_JPEGCmd(FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
/* Enable the DCMI JPEG format */
DCMI->CR |= (uint32_t)DCMI_CR_JPEG;
}
else
{
/* Disable the DCMI JPEG format */
DCMI->CR &= ~(uint32_t)DCMI_CR_JPEG;
}
}
/**
* @}
*/
/** @defgroup DCMI_Group2 Image capture functions
* @brief Image capture functions
*
@verbatim
===============================================================================
##### Image capture functions #####
===============================================================================
@endverbatim
* @{
*/
/**
* @brief Enables or disables the DCMI interface.
* @param NewState: new state of the DCMI interface.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void DCMI_Cmd(FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
/* Enable the DCMI by setting ENABLE bit */
DCMI->CR |= (uint32_t)DCMI_CR_ENABLE;
}
else
{
/* Disable the DCMI by clearing ENABLE bit */
DCMI->CR &= ~(uint32_t)DCMI_CR_ENABLE;
}
}
/**
* @brief Enables or disables the DCMI Capture.
* @param NewState: new state of the DCMI capture.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void DCMI_CaptureCmd(FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
/* Enable the DCMI Capture */
DCMI->CR |= (uint32_t)DCMI_CR_CAPTURE;
}
else
{
/* Disable the DCMI Capture */
DCMI->CR &= ~(uint32_t)DCMI_CR_CAPTURE;
}
}
/**
* @brief Reads the data stored in the DR register.
* @param None
* @retval Data register value
*/
uint32_t DCMI_ReadData(void)
{
return DCMI->DR;
}
/**
* @}
*/
/** @defgroup DCMI_Group3 Interrupts and flags management functions
* @brief Interrupts and flags management functions
*
@verbatim
===============================================================================
##### Interrupts and flags management functions #####
===============================================================================
@endverbatim
* @{
*/
/**
* @brief Enables or disables the DCMI interface interrupts.
* @param DCMI_IT: specifies the DCMI interrupt sources to be enabled or disabled.
* This parameter can be any combination of the following values:
* @arg DCMI_IT_FRAME: Frame capture complete interrupt mask
* @arg DCMI_IT_OVF: Overflow interrupt mask
* @arg DCMI_IT_ERR: Synchronization error interrupt mask
* @arg DCMI_IT_VSYNC: VSYNC interrupt mask
* @arg DCMI_IT_LINE: Line interrupt mask
* @param NewState: new state of the specified DCMI interrupts.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void DCMI_ITConfig(uint16_t DCMI_IT, FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_DCMI_CONFIG_IT(DCMI_IT));
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
/* Enable the Interrupt sources */
DCMI->IER |= DCMI_IT;
}
else
{
/* Disable the Interrupt sources */
DCMI->IER &= (uint16_t)(~DCMI_IT);
}
}
/**
* @brief Checks whether the DCMI interface flag is set or not.
* @param DCMI_FLAG: specifies the flag to check.
* This parameter can be one of the following values:
* @arg DCMI_FLAG_FRAMERI: Frame capture complete Raw flag mask
* @arg DCMI_FLAG_OVFRI: Overflow Raw flag mask
* @arg DCMI_FLAG_ERRRI: Synchronization error Raw flag mask
* @arg DCMI_FLAG_VSYNCRI: VSYNC Raw flag mask
* @arg DCMI_FLAG_LINERI: Line Raw flag mask
* @arg DCMI_FLAG_FRAMEMI: Frame capture complete Masked flag mask
* @arg DCMI_FLAG_OVFMI: Overflow Masked flag mask
* @arg DCMI_FLAG_ERRMI: Synchronization error Masked flag mask
* @arg DCMI_FLAG_VSYNCMI: VSYNC Masked flag mask
* @arg DCMI_FLAG_LINEMI: Line Masked flag mask
* @arg DCMI_FLAG_HSYNC: HSYNC flag mask
* @arg DCMI_FLAG_VSYNC: VSYNC flag mask
* @arg DCMI_FLAG_FNE: Fifo not empty flag mask
* @retval The new state of DCMI_FLAG (SET or RESET).
*/
FlagStatus DCMI_GetFlagStatus(uint16_t DCMI_FLAG)
{
FlagStatus bitstatus = RESET;
uint32_t dcmireg, tempreg = 0;
/* Check the parameters */
assert_param(IS_DCMI_GET_FLAG(DCMI_FLAG));
/* Get the DCMI register index */
dcmireg = (((uint16_t)DCMI_FLAG) >> 12);
if (dcmireg == 0x00) /* The FLAG is in RISR register */
{
tempreg= DCMI->RISR;
}
else if (dcmireg == 0x02) /* The FLAG is in SR register */
{
tempreg = DCMI->SR;
}
else /* The FLAG is in MISR register */
{
tempreg = DCMI->MISR;
}
if ((tempreg & DCMI_FLAG) != (uint16_t)RESET )
{
bitstatus = SET;
}
else
{
bitstatus = RESET;
}
/* Return the DCMI_FLAG status */
return bitstatus;
}
/**
* @brief Clears the DCMI's pending flags.
* @param DCMI_FLAG: specifies the flag to clear.
* This parameter can be any combination of the following values:
* @arg DCMI_FLAG_FRAMERI: Frame capture complete Raw flag mask
* @arg DCMI_FLAG_OVFRI: Overflow Raw flag mask
* @arg DCMI_FLAG_ERRRI: Synchronization error Raw flag mask
* @arg DCMI_FLAG_VSYNCRI: VSYNC Raw flag mask
* @arg DCMI_FLAG_LINERI: Line Raw flag mask
* @retval None
*/
void DCMI_ClearFlag(uint16_t DCMI_FLAG)
{
/* Check the parameters */
assert_param(IS_DCMI_CLEAR_FLAG(DCMI_FLAG));
/* Clear the flag by writing in the ICR register 1 in the corresponding
Flag position*/
DCMI->ICR = DCMI_FLAG;
}
/**
* @brief Checks whether the DCMI interrupt has occurred or not.
* @param DCMI_IT: specifies the DCMI interrupt source to check.
* This parameter can be one of the following values:
* @arg DCMI_IT_FRAME: Frame capture complete interrupt mask
* @arg DCMI_IT_OVF: Overflow interrupt mask
* @arg DCMI_IT_ERR: Synchronization error interrupt mask
* @arg DCMI_IT_VSYNC: VSYNC interrupt mask
* @arg DCMI_IT_LINE: Line interrupt mask
* @retval The new state of DCMI_IT (SET or RESET).
*/
ITStatus DCMI_GetITStatus(uint16_t DCMI_IT)
{
ITStatus bitstatus = RESET;
uint32_t itstatus = 0;
/* Check the parameters */
assert_param(IS_DCMI_GET_IT(DCMI_IT));
itstatus = DCMI->MISR & DCMI_IT; /* Only masked interrupts are checked */
if ((itstatus != (uint16_t)RESET))
{
bitstatus = SET;
}
else
{
bitstatus = RESET;
}
return bitstatus;
}
/**
* @brief Clears the DCMI's interrupt pending bits.
* @param DCMI_IT: specifies the DCMI interrupt pending bit to clear.
* This parameter can be any combination of the following values:
* @arg DCMI_IT_FRAME: Frame capture complete interrupt mask
* @arg DCMI_IT_OVF: Overflow interrupt mask
* @arg DCMI_IT_ERR: Synchronization error interrupt mask
* @arg DCMI_IT_VSYNC: VSYNC interrupt mask
* @arg DCMI_IT_LINE: Line interrupt mask
* @retval None
*/
void DCMI_ClearITPendingBit(uint16_t DCMI_IT)
{
/* Clear the interrupt pending Bit by writing in the ICR register 1 in the
corresponding pending Bit position*/
DCMI->ICR = DCMI_IT;
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

File diff suppressed because it is too large Load diff

View file

@ -0,0 +1,784 @@
/**
******************************************************************************
* @file stm32f4xx_dma2d.c
* @author MCD Application Team
* @version V1.6.1
* @date 21-October-2015
* @brief This file provides firmware functions to manage the following
* functionalities of the DMA2D controller (DMA2D) peripheral:
* + Initialization and configuration
* + Interrupts and flags management
*
@verbatim
===============================================================================
##### How to use this driver #####
===============================================================================
[..]
(#) Enable DMA2D clock using
RCC_APB2PeriphResetCmd(RCC_APB2Periph_DMA2D, ENABLE) function.
(#) Configures DMA2D
(++) transfer mode
(++) pixel format, line_number, pixel_per_line
(++) output memory address
(++) alpha value
(++) output offset
(++) Default color (RGB)
(#) Configures Foreground or/and background
(++) memory address
(++) alpha value
(++) offset and default color
(#) Call the DMA2D_Start() to enable the DMA2D controller.
@endverbatim
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2015 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 "stm32f4xx_dma2d.h"
#include "stm32f4xx_rcc.h"
/** @addtogroup STM32F4xx_StdPeriph_Driver
* @{
*/
/** @defgroup DMA2D
* @brief DMA2D driver modules
* @{
*/
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
#define CR_MASK ((uint32_t)0xFFFCE0FC) /* DMA2D CR Mask */
#define PFCCR_MASK ((uint32_t)0x00FC00C0) /* DMA2D FGPFCCR Mask */
#define DEAD_MASK ((uint32_t)0xFFFF00FE) /* DMA2D DEAD Mask */
/** @defgroup DMA2D_Private_Functions
* @{
*/
/** @defgroup DMA2D_Group1 Initialization and Configuration functions
* @brief Initialization and Configuration functions
*
@verbatim
===============================================================================
##### Initialization and Configuration functions #####
===============================================================================
[..] This section provides functions allowing to:
(+) Initialize and configure the DMA2D
(+) Start/Abort/Suspend Transfer
(+) Initialize, configure and set Foreground and background
(+) configure and enable DeadTime
(+) configure lineWatermark
@endverbatim
* @{
*/
/**
* @brief Deinitializes the DMA2D peripheral registers to their default reset
* values.
* @param None
* @retval None
*/
void DMA2D_DeInit(void)
{
/* Enable DMA2D reset state */
RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_DMA2D, ENABLE);
/* Release DMA2D from reset state */
RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_DMA2D, DISABLE);
}
/**
* @brief Initializes the DMA2D peripheral according to the specified parameters
* in the DMA2D_InitStruct.
* @note This function can be used only when the DMA2D is disabled.
* @param DMA2D_InitStruct: pointer to a DMA2D_InitTypeDef structure that contains
* the configuration information for the specified DMA2D peripheral.
* @retval None
*/
void DMA2D_Init(DMA2D_InitTypeDef* DMA2D_InitStruct)
{
uint32_t outgreen = 0;
uint32_t outred = 0;
uint32_t outalpha = 0;
uint32_t pixline = 0;
/* Check the parameters */
assert_param(IS_DMA2D_MODE(DMA2D_InitStruct->DMA2D_Mode));
assert_param(IS_DMA2D_CMODE(DMA2D_InitStruct->DMA2D_CMode));
assert_param(IS_DMA2D_OGREEN(DMA2D_InitStruct->DMA2D_OutputGreen));
assert_param(IS_DMA2D_ORED(DMA2D_InitStruct->DMA2D_OutputRed));
assert_param(IS_DMA2D_OBLUE(DMA2D_InitStruct->DMA2D_OutputBlue));
assert_param(IS_DMA2D_OALPHA(DMA2D_InitStruct->DMA2D_OutputAlpha));
assert_param(IS_DMA2D_OUTPUT_OFFSET(DMA2D_InitStruct->DMA2D_OutputOffset));
assert_param(IS_DMA2D_LINE(DMA2D_InitStruct->DMA2D_NumberOfLine));
assert_param(IS_DMA2D_PIXEL(DMA2D_InitStruct->DMA2D_PixelPerLine));
/* Configures the DMA2D operation mode */
DMA2D->CR &= (uint32_t)CR_MASK;
DMA2D->CR |= (DMA2D_InitStruct->DMA2D_Mode);
/* Configures the color mode of the output image */
DMA2D->OPFCCR &= ~(uint32_t)DMA2D_OPFCCR_CM;
DMA2D->OPFCCR |= (DMA2D_InitStruct->DMA2D_CMode);
/* Configures the output color */
if (DMA2D_InitStruct->DMA2D_CMode == DMA2D_ARGB8888)
{
outgreen = DMA2D_InitStruct->DMA2D_OutputGreen << 8;
outred = DMA2D_InitStruct->DMA2D_OutputRed << 16;
outalpha = DMA2D_InitStruct->DMA2D_OutputAlpha << 24;
}
else
if (DMA2D_InitStruct->DMA2D_CMode == DMA2D_RGB888)
{
outgreen = DMA2D_InitStruct->DMA2D_OutputGreen << 8;
outred = DMA2D_InitStruct->DMA2D_OutputRed << 16;
outalpha = (uint32_t)0x00000000;
}
else
if (DMA2D_InitStruct->DMA2D_CMode == DMA2D_RGB565)
{
outgreen = DMA2D_InitStruct->DMA2D_OutputGreen << 5;
outred = DMA2D_InitStruct->DMA2D_OutputRed << 11;
outalpha = (uint32_t)0x00000000;
}
else
if (DMA2D_InitStruct->DMA2D_CMode == DMA2D_ARGB1555)
{
outgreen = DMA2D_InitStruct->DMA2D_OutputGreen << 5;
outred = DMA2D_InitStruct->DMA2D_OutputRed << 10;
outalpha = DMA2D_InitStruct->DMA2D_OutputAlpha << 15;
}
else /* DMA2D_CMode = DMA2D_ARGB4444 */
{
outgreen = DMA2D_InitStruct->DMA2D_OutputGreen << 4;
outred = DMA2D_InitStruct->DMA2D_OutputRed << 8;
outalpha = DMA2D_InitStruct->DMA2D_OutputAlpha << 12;
}
DMA2D->OCOLR |= ((outgreen) | (outred) | (DMA2D_InitStruct->DMA2D_OutputBlue) | (outalpha));
/* Configures the output memory address */
DMA2D->OMAR = (DMA2D_InitStruct->DMA2D_OutputMemoryAdd);
/* Configure the line Offset */
DMA2D->OOR &= ~(uint32_t)DMA2D_OOR_LO;
DMA2D->OOR |= (DMA2D_InitStruct->DMA2D_OutputOffset);
/* Configure the number of line and pixel per line */
pixline = DMA2D_InitStruct->DMA2D_PixelPerLine << 16;
DMA2D->NLR &= ~(DMA2D_NLR_NL | DMA2D_NLR_PL);
DMA2D->NLR |= ((DMA2D_InitStruct->DMA2D_NumberOfLine) | (pixline));
/**
* @brief Fills each DMA2D_InitStruct member with its default value.
* @param DMA2D_InitStruct: pointer to a DMA2D_InitTypeDef structure which will
* be initialized.
* @retval None
*/
}
void DMA2D_StructInit(DMA2D_InitTypeDef* DMA2D_InitStruct)
{
/* Initialize the transfer mode member */
DMA2D_InitStruct->DMA2D_Mode = DMA2D_M2M;
/* Initialize the output color mode members */
DMA2D_InitStruct->DMA2D_CMode = DMA2D_ARGB8888;
/* Initialize the alpha and RGB values */
DMA2D_InitStruct->DMA2D_OutputGreen = 0x00;
DMA2D_InitStruct->DMA2D_OutputBlue = 0x00;
DMA2D_InitStruct->DMA2D_OutputRed = 0x00;
DMA2D_InitStruct->DMA2D_OutputAlpha = 0x00;
/* Initialize the output memory address */
DMA2D_InitStruct->DMA2D_OutputMemoryAdd = 0x00;
/* Initialize the output offset */
DMA2D_InitStruct->DMA2D_OutputOffset = 0x00;
/* Initialize the number of line and the number of pixel per line */
DMA2D_InitStruct->DMA2D_NumberOfLine = 0x00;
DMA2D_InitStruct->DMA2D_PixelPerLine = 0x00;
}
/**
* @brief Start the DMA2D transfer.
* @param
* @retval None
*/
void DMA2D_StartTransfer(void)
{
/* Start DMA2D transfer by setting START bit */
DMA2D->CR |= (uint32_t)DMA2D_CR_START;
}
/**
* @brief Abort the DMA2D transfer.
* @param
* @retval None
*/
void DMA2D_AbortTransfer(void)
{
/* Start DMA2D transfer by setting START bit */
DMA2D->CR |= (uint32_t)DMA2D_CR_ABORT;
}
/**
* @brief Stop or continue the DMA2D transfer.
* @param NewState: new state of the DMA2D peripheral.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void DMA2D_Suspend(FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
/* Suspend DMA2D transfer by setting STOP bit */
DMA2D->CR |= (uint32_t)DMA2D_CR_SUSP;
}
else
{
/* Continue DMA2D transfer by clearing STOP bit */
DMA2D->CR &= ~(uint32_t)DMA2D_CR_SUSP;
}
}
/**
* @brief Configures the Foreground according to the specified parameters
* in the DMA2D_FGStruct.
* @note This function can be used only when the transfer is disabled.
* @param DMA2D_FGStruct: pointer to a DMA2D_FGTypeDef structure that contains
* the configuration information for the specified Background.
* @retval None
*/
void DMA2D_FGConfig(DMA2D_FG_InitTypeDef* DMA2D_FG_InitStruct)
{
uint32_t fg_clutcolormode = 0;
uint32_t fg_clutsize = 0;
uint32_t fg_alpha_mode = 0;
uint32_t fg_alphavalue = 0;
uint32_t fg_colorgreen = 0;
uint32_t fg_colorred = 0;
assert_param(IS_DMA2D_FGO(DMA2D_FG_InitStruct->DMA2D_FGO));
assert_param(IS_DMA2D_FGCM(DMA2D_FG_InitStruct->DMA2D_FGCM));
assert_param(IS_DMA2D_FG_CLUT_CM(DMA2D_FG_InitStruct->DMA2D_FG_CLUT_CM));
assert_param(IS_DMA2D_FG_CLUT_SIZE(DMA2D_FG_InitStruct->DMA2D_FG_CLUT_SIZE));
assert_param(IS_DMA2D_FG_ALPHA_MODE(DMA2D_FG_InitStruct->DMA2D_FGPFC_ALPHA_MODE));
assert_param(IS_DMA2D_FG_ALPHA_VALUE(DMA2D_FG_InitStruct->DMA2D_FGPFC_ALPHA_VALUE));
assert_param(IS_DMA2D_FGC_BLUE(DMA2D_FG_InitStruct->DMA2D_FGC_BLUE));
assert_param(IS_DMA2D_FGC_GREEN(DMA2D_FG_InitStruct->DMA2D_FGC_GREEN));
assert_param(IS_DMA2D_FGC_RED(DMA2D_FG_InitStruct->DMA2D_FGC_RED));
/* Configures the FG memory address */
DMA2D->FGMAR = (DMA2D_FG_InitStruct->DMA2D_FGMA);
/* Configures the FG offset */
DMA2D->FGOR &= ~(uint32_t)DMA2D_FGOR_LO;
DMA2D->FGOR |= (DMA2D_FG_InitStruct->DMA2D_FGO);
/* Configures foreground Pixel Format Convertor */
DMA2D->FGPFCCR &= (uint32_t)PFCCR_MASK;
fg_clutcolormode = DMA2D_FG_InitStruct->DMA2D_FG_CLUT_CM << 4;
fg_clutsize = DMA2D_FG_InitStruct->DMA2D_FG_CLUT_SIZE << 8;
fg_alpha_mode = DMA2D_FG_InitStruct->DMA2D_FGPFC_ALPHA_MODE << 16;
fg_alphavalue = DMA2D_FG_InitStruct->DMA2D_FGPFC_ALPHA_VALUE << 24;
DMA2D->FGPFCCR |= (DMA2D_FG_InitStruct->DMA2D_FGCM | fg_clutcolormode | fg_clutsize | \
fg_alpha_mode | fg_alphavalue);
/* Configures foreground color */
DMA2D->FGCOLR &= ~(DMA2D_FGCOLR_BLUE | DMA2D_FGCOLR_GREEN | DMA2D_FGCOLR_RED);
fg_colorgreen = DMA2D_FG_InitStruct->DMA2D_FGC_GREEN << 8;
fg_colorred = DMA2D_FG_InitStruct->DMA2D_FGC_RED << 16;
DMA2D->FGCOLR |= (DMA2D_FG_InitStruct->DMA2D_FGC_BLUE | fg_colorgreen | fg_colorred);
/* Configures foreground CLUT memory address */
DMA2D->FGCMAR = DMA2D_FG_InitStruct->DMA2D_FGCMAR;
}
/**
* @brief Fills each DMA2D_FGStruct member with its default value.
* @param DMA2D_FGStruct: pointer to a DMA2D_FGTypeDef structure which will
* be initialized.
* @retval None
*/
void DMA2D_FG_StructInit(DMA2D_FG_InitTypeDef* DMA2D_FG_InitStruct)
{
/*!< Initialize the DMA2D foreground memory address */
DMA2D_FG_InitStruct->DMA2D_FGMA = 0x00;
/*!< Initialize the DMA2D foreground offset */
DMA2D_FG_InitStruct->DMA2D_FGO = 0x00;
/*!< Initialize the DMA2D foreground color mode */
DMA2D_FG_InitStruct->DMA2D_FGCM = CM_ARGB8888;
/*!< Initialize the DMA2D foreground CLUT color mode */
DMA2D_FG_InitStruct->DMA2D_FG_CLUT_CM = CLUT_CM_ARGB8888;
/*!< Initialize the DMA2D foreground CLUT size */
DMA2D_FG_InitStruct->DMA2D_FG_CLUT_SIZE = 0x00;
/*!< Initialize the DMA2D foreground alpha mode */
DMA2D_FG_InitStruct->DMA2D_FGPFC_ALPHA_MODE = NO_MODIF_ALPHA_VALUE;
/*!< Initialize the DMA2D foreground alpha value */
DMA2D_FG_InitStruct->DMA2D_FGPFC_ALPHA_VALUE = 0x00;
/*!< Initialize the DMA2D foreground blue value */
DMA2D_FG_InitStruct->DMA2D_FGC_BLUE = 0x00;
/*!< Initialize the DMA2D foreground green value */
DMA2D_FG_InitStruct->DMA2D_FGC_GREEN = 0x00;
/*!< Initialize the DMA2D foreground red value */
DMA2D_FG_InitStruct->DMA2D_FGC_RED = 0x00;
/*!< Initialize the DMA2D foreground CLUT memory address */
DMA2D_FG_InitStruct->DMA2D_FGCMAR = 0x00;
}
/**
* @brief Configures the Background according to the specified parameters
* in the DMA2D_BGStruct.
* @note This function can be used only when the transfer is disabled.
* @param DMA2D_BGStruct: pointer to a DMA2D_BGTypeDef structure that contains
* the configuration information for the specified Background.
* @retval None
*/
void DMA2D_BGConfig(DMA2D_BG_InitTypeDef* DMA2D_BG_InitStruct)
{
uint32_t bg_clutcolormode = 0;
uint32_t bg_clutsize = 0;
uint32_t bg_alpha_mode = 0;
uint32_t bg_alphavalue = 0;
uint32_t bg_colorgreen = 0;
uint32_t bg_colorred = 0;
assert_param(IS_DMA2D_BGO(DMA2D_BG_InitStruct->DMA2D_BGO));
assert_param(IS_DMA2D_BGCM(DMA2D_BG_InitStruct->DMA2D_BGCM));
assert_param(IS_DMA2D_BG_CLUT_CM(DMA2D_BG_InitStruct->DMA2D_BG_CLUT_CM));
assert_param(IS_DMA2D_BG_CLUT_SIZE(DMA2D_BG_InitStruct->DMA2D_BG_CLUT_SIZE));
assert_param(IS_DMA2D_BG_ALPHA_MODE(DMA2D_BG_InitStruct->DMA2D_BGPFC_ALPHA_MODE));
assert_param(IS_DMA2D_BG_ALPHA_VALUE(DMA2D_BG_InitStruct->DMA2D_BGPFC_ALPHA_VALUE));
assert_param(IS_DMA2D_BGC_BLUE(DMA2D_BG_InitStruct->DMA2D_BGC_BLUE));
assert_param(IS_DMA2D_BGC_GREEN(DMA2D_BG_InitStruct->DMA2D_BGC_GREEN));
assert_param(IS_DMA2D_BGC_RED(DMA2D_BG_InitStruct->DMA2D_BGC_RED));
/* Configures the BG memory address */
DMA2D->BGMAR = (DMA2D_BG_InitStruct->DMA2D_BGMA);
/* Configures the BG offset */
DMA2D->BGOR &= ~(uint32_t)DMA2D_BGOR_LO;
DMA2D->BGOR |= (DMA2D_BG_InitStruct->DMA2D_BGO);
/* Configures background Pixel Format Convertor */
DMA2D->BGPFCCR &= (uint32_t)PFCCR_MASK;
bg_clutcolormode = DMA2D_BG_InitStruct->DMA2D_BG_CLUT_CM << 4;
bg_clutsize = DMA2D_BG_InitStruct->DMA2D_BG_CLUT_SIZE << 8;
bg_alpha_mode = DMA2D_BG_InitStruct->DMA2D_BGPFC_ALPHA_MODE << 16;
bg_alphavalue = DMA2D_BG_InitStruct->DMA2D_BGPFC_ALPHA_VALUE << 24;
DMA2D->BGPFCCR |= (DMA2D_BG_InitStruct->DMA2D_BGCM | bg_clutcolormode | bg_clutsize | \
bg_alpha_mode | bg_alphavalue);
/* Configures background color */
DMA2D->BGCOLR &= ~(DMA2D_BGCOLR_BLUE | DMA2D_BGCOLR_GREEN | DMA2D_BGCOLR_RED);
bg_colorgreen = DMA2D_BG_InitStruct->DMA2D_BGC_GREEN << 8;
bg_colorred = DMA2D_BG_InitStruct->DMA2D_BGC_RED << 16;
DMA2D->BGCOLR |= (DMA2D_BG_InitStruct->DMA2D_BGC_BLUE | bg_colorgreen | bg_colorred);
/* Configures background CLUT memory address */
DMA2D->BGCMAR = DMA2D_BG_InitStruct->DMA2D_BGCMAR;
}
/**
* @brief Fills each DMA2D_BGStruct member with its default value.
* @param DMA2D_BGStruct: pointer to a DMA2D_BGTypeDef structure which will
* be initialized.
* @retval None
*/
void DMA2D_BG_StructInit(DMA2D_BG_InitTypeDef* DMA2D_BG_InitStruct)
{
/*!< Initialize the DMA2D background memory address */
DMA2D_BG_InitStruct->DMA2D_BGMA = 0x00;
/*!< Initialize the DMA2D background offset */
DMA2D_BG_InitStruct->DMA2D_BGO = 0x00;
/*!< Initialize the DMA2D background color mode */
DMA2D_BG_InitStruct->DMA2D_BGCM = CM_ARGB8888;
/*!< Initialize the DMA2D background CLUT color mode */
DMA2D_BG_InitStruct->DMA2D_BG_CLUT_CM = CLUT_CM_ARGB8888;
/*!< Initialize the DMA2D background CLUT size */
DMA2D_BG_InitStruct->DMA2D_BG_CLUT_SIZE = 0x00;
/*!< Initialize the DMA2D background alpha mode */
DMA2D_BG_InitStruct->DMA2D_BGPFC_ALPHA_MODE = NO_MODIF_ALPHA_VALUE;
/*!< Initialize the DMA2D background alpha value */
DMA2D_BG_InitStruct->DMA2D_BGPFC_ALPHA_VALUE = 0x00;
/*!< Initialize the DMA2D background blue value */
DMA2D_BG_InitStruct->DMA2D_BGC_BLUE = 0x00;
/*!< Initialize the DMA2D background green value */
DMA2D_BG_InitStruct->DMA2D_BGC_GREEN = 0x00;
/*!< Initialize the DMA2D background red value */
DMA2D_BG_InitStruct->DMA2D_BGC_RED = 0x00;
/*!< Initialize the DMA2D background CLUT memory address */
DMA2D_BG_InitStruct->DMA2D_BGCMAR = 0x00;
}
/**
* @brief Start the automatic loading of the CLUT or abort the transfer.
* @param NewState: new state of the DMA2D peripheral.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void DMA2D_FGStart(FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
/* Start the automatic loading of the CLUT */
DMA2D->FGPFCCR |= DMA2D_FGPFCCR_START;
}
else
{
/* abort the transfer */
DMA2D->FGPFCCR &= (uint32_t)~DMA2D_FGPFCCR_START;
}
}
/**
* @brief Start the automatic loading of the CLUT or abort the transfer.
* @param NewState: new state of the DMA2D peripheral.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void DMA2D_BGStart(FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
/* Start the automatic loading of the CLUT */
DMA2D->BGPFCCR |= DMA2D_BGPFCCR_START;
}
else
{
/* abort the transfer */
DMA2D->BGPFCCR &= (uint32_t)~DMA2D_BGPFCCR_START;
}
}
/**
* @brief Configures the DMA2D dead time.
* @param DMA2D_DeadTime: specifies the DMA2D dead time.
* This parameter can be one of the following values:
* @retval None
*/
void DMA2D_DeadTimeConfig(uint32_t DMA2D_DeadTime, FunctionalState NewState)
{
uint32_t DeadTime;
/* Check the parameters */
assert_param(IS_DMA2D_DEAD_TIME(DMA2D_DeadTime));
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
/* Enable and Configures the dead time */
DMA2D->AMTCR &= (uint32_t)DEAD_MASK;
DeadTime = DMA2D_DeadTime << 8;
DMA2D->AMTCR |= (DeadTime | DMA2D_AMTCR_EN);
}
else
{
DMA2D->AMTCR &= ~(uint32_t)DMA2D_AMTCR_EN;
}
}
/**
* @brief Define the configuration of the line watermark .
* @param DMA2D_LWatermarkConfig: Line Watermark configuration.
* @retval None
*/
void DMA2D_LineWatermarkConfig(uint32_t DMA2D_LWatermarkConfig)
{
/* Check the parameters */
assert_param(IS_DMA2D_LineWatermark(DMA2D_LWatermarkConfig));
/* Sets the Line watermark configuration */
DMA2D->LWR = (uint32_t)DMA2D_LWatermarkConfig;
}
/**
* @}
*/
/** @defgroup DMA2D_Group2 Interrupts and flags management functions
* @brief Interrupts and flags management functions
*
@verbatim
===============================================================================
##### Interrupts and flags management functions #####
===============================================================================
[..] This section provides functions allowing to configure the DMA2D
Interrupts and to get the status and clear flags and Interrupts
pending bits.
[..] The DMA2D provides 6 Interrupts sources and 6 Flags
*** Flags ***
=============
[..]
(+) DMA2D_FLAG_CE : Configuration Error Interrupt flag
(+) DMA2D_FLAG_CAE: CLUT Access Error Interrupt flag
(+) DMA2D_FLAG_TW: Transfer Watermark Interrupt flag
(+) DMA2D_FLAG_TC: Transfer Complete interrupt flag
(+) DMA2D_FLAG_TE: Transfer Error interrupt flag
(+) DMA2D_FLAG_CTC: CLUT Transfer Complete Interrupt flag
*** Interrupts ***
==================
[..]
(+) DMA2D_IT_CE: Configuration Error Interrupt is generated when a wrong
configuration is detected
(+) DMA2D_IT_CAE: CLUT Access Error Interrupt
(+) DMA2D_IT_TW: Transfer Watermark Interrupt is generated when
the programmed watermark is reached
(+) DMA2D_IT_TE: Transfer Error interrupt is generated when the CPU trying
to access the CLUT while a CLUT loading or a DMA2D1 transfer
is on going
(+) DMA2D_IT_CTC: CLUT Transfer Complete Interrupt
(+) DMA2D_IT_TC: Transfer Complete interrupt
@endverbatim
* @{
*/
/**
* @brief Enables or disables the specified DMA2D's interrupts.
* @param DMA2D_IT: specifies the DMA2D interrupts sources to be enabled or disabled.
* This parameter can be any combination of the following values:
* @arg DMA2D_IT_CE: Configuration Error Interrupt Enable.
* @arg DMA2D_IT_CTC: CLUT Transfer Complete Interrupt Enable.
* @arg DMA2D_IT_CAE: CLUT Access Error Interrupt Enable.
* @arg DMA2D_IT_TW: Transfer Watermark Interrupt Enable.
* @arg DMA2D_IT_TC: Transfer Complete interrupt enable.
* @arg DMA2D_IT_TE: Transfer Error interrupt enable.
* @param NewState: new state of the specified DMA2D interrupts.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void DMA2D_ITConfig(uint32_t DMA2D_IT, FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_DMA2D_IT(DMA2D_IT));
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
/* Enable the selected DMA2D interrupts */
DMA2D->CR |= DMA2D_IT;
}
else
{
/* Disable the selected DMA2D interrupts */
DMA2D->CR &= (uint32_t)~DMA2D_IT;
}
}
/**
* @brief Checks whether the specified DMA2D's flag is set or not.
* @param DMA2D_FLAG: specifies the flag to check.
* This parameter can be one of the following values:
* @arg DMA2D_FLAG_CE: Configuration Error Interrupt flag.
* @arg DMA2D_FLAG_CTC: CLUT Transfer Complete Interrupt flag.
* @arg DMA2D_FLAG_CAE: CLUT Access Error Interrupt flag.
* @arg DMA2D_FLAG_TW: Transfer Watermark Interrupt flag.
* @arg DMA2D_FLAG_TC: Transfer Complete interrupt flag.
* @arg DMA2D_FLAG_TE: Transfer Error interrupt flag.
* @retval The new state of DMA2D_FLAG (SET or RESET).
*/
FlagStatus DMA2D_GetFlagStatus(uint32_t DMA2D_FLAG)
{
FlagStatus bitstatus = RESET;
/* Check the parameters */
assert_param(IS_DMA2D_GET_FLAG(DMA2D_FLAG));
/* Check the status of the specified DMA2D flag */
if (((DMA2D->ISR) & DMA2D_FLAG) != (uint32_t)RESET)
{
/* DMA2D_FLAG is set */
bitstatus = SET;
}
else
{
/* DMA2D_FLAG is reset */
bitstatus = RESET;
}
/* Return the DMA2D_FLAG status */
return bitstatus;
}
/**
* @brief Clears the DMA2D's pending flags.
* @param DMA2D_FLAG: specifies the flag to clear.
* This parameter can be any combination of the following values:
* @arg DMA2D_FLAG_CE: Configuration Error Interrupt flag.
* @arg DMA2D_FLAG_CTC: CLUT Transfer Complete Interrupt flag.
* @arg DMA2D_FLAG_CAE: CLUT Access Error Interrupt flag.
* @arg DMA2D_FLAG_TW: Transfer Watermark Interrupt flag.
* @arg DMA2D_FLAG_TC: Transfer Complete interrupt flag.
* @arg DMA2D_FLAG_TE: Transfer Error interrupt flag.
* @retval None
*/
void DMA2D_ClearFlag(uint32_t DMA2D_FLAG)
{
/* Check the parameters */
assert_param(IS_DMA2D_GET_FLAG(DMA2D_FLAG));
/* Clear the corresponding DMA2D flag */
DMA2D->IFCR = (uint32_t)DMA2D_FLAG;
}
/**
* @brief Checks whether the specified DMA2D's interrupt has occurred or not.
* @param DMA2D_IT: specifies the DMA2D interrupts sources to check.
* This parameter can be one of the following values:
* @arg DMA2D_IT_CE: Configuration Error Interrupt Enable.
* @arg DMA2D_IT_CTC: CLUT Transfer Complete Interrupt Enable.
* @arg DMA2D_IT_CAE: CLUT Access Error Interrupt Enable.
* @arg DMA2D_IT_TW: Transfer Watermark Interrupt Enable.
* @arg DMA2D_IT_TC: Transfer Complete interrupt enable.
* @arg DMA2D_IT_TE: Transfer Error interrupt enable.
* @retval The new state of the DMA2D_IT (SET or RESET).
*/
ITStatus DMA2D_GetITStatus(uint32_t DMA2D_IT)
{
ITStatus bitstatus = RESET;
uint32_t DMA2D_IT_FLAG = DMA2D_IT >> 8;
/* Check the parameters */
assert_param(IS_DMA2D_IT(DMA2D_IT));
if ((DMA2D->ISR & DMA2D_IT_FLAG) != (uint32_t)RESET)
{
bitstatus = SET;
}
else
{
bitstatus = RESET;
}
if (((DMA2D->CR & DMA2D_IT) != (uint32_t)RESET) && (bitstatus != (uint32_t)RESET))
{
bitstatus = SET;
}
else
{
bitstatus = RESET;
}
return bitstatus;
}
/**
* @brief Clears the DMA2D's interrupt pending bits.
* @param DMA2D_IT: specifies the interrupt pending bit to clear.
* This parameter can be any combination of the following values:
* @arg DMA2D_IT_CE: Configuration Error Interrupt.
* @arg DMA2D_IT_CTC: CLUT Transfer Complete Interrupt.
* @arg DMA2D_IT_CAE: CLUT Access Error Interrupt.
* @arg DMA2D_IT_TW: Transfer Watermark Interrupt.
* @arg DMA2D_IT_TC: Transfer Complete interrupt.
* @arg DMA2D_IT_TE: Transfer Error interrupt.
* @retval None
*/
void DMA2D_ClearITPendingBit(uint32_t DMA2D_IT)
{
/* Check the parameters */
assert_param(IS_DMA2D_IT(DMA2D_IT));
DMA2D_IT = DMA2D_IT >> 8;
/* Clear the corresponding DMA2D Interrupt */
DMA2D->IFCR = (uint32_t)DMA2D_IT;
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

File diff suppressed because it is too large Load diff

View file

@ -0,0 +1,312 @@
/**
******************************************************************************
* @file stm32f4xx_exti.c
* @author MCD Application Team
* @version V1.6.1
* @date 21-October-2015
* @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 the USB OTG FS Wakeup from suspend event
(#) EXTI line 19 is connected to the Ethernet Wakeup event
(#) EXTI line 20 is connected to the USB OTG HS (configured in FS) Wakeup event
(#) EXTI line 21 is connected to the RTC Tamper and Time Stamp events
(#) EXTI line 22 is connected to the RTC Wakeup event
(#) EXTI line 23 is connected to the LPTIM 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()
(#) Configure NVIC IRQ channel mapped to the EXTI line using NVIC_Init()
[..]
(@) 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>&copy; COPYRIGHT 2015 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 "stm32f4xx_exti.h"
/** @addtogroup STM32F4xx_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 = 0x00000000;
EXTI->EMR = 0x00000000;
EXTI->RTSR = 0x00000000;
EXTI->FTSR = 0x00000000;
EXTI->PR = 0x007FFFFF;
}
/**
* @brief Initializes the EXTI peripheral according to the specified
* parameters in the EXTI_InitStruct.
* @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(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 */
EXTI->IMR &= ~EXTI_InitStruct->EXTI_Line;
EXTI->EMR &= ~EXTI_InitStruct->EXTI_Line;
tmp += EXTI_InitStruct->EXTI_Mode;
*(__IO uint32_t *) tmp |= EXTI_InitStruct->EXTI_Line;
/* Clear Rising Falling edge configuration */
EXTI->RTSR &= ~EXTI_InitStruct->EXTI_Line;
EXTI->FTSR &= ~EXTI_InitStruct->EXTI_Line;
/* Select the trigger for the selected external interrupts */
if (EXTI_InitStruct->EXTI_Trigger == EXTI_Trigger_Rising_Falling)
{
/* Rising Falling edge */
EXTI->RTSR |= EXTI_InitStruct->EXTI_Line;
EXTI->FTSR |= EXTI_InitStruct->EXTI_Line;
}
else
{
tmp = (uint32_t)EXTI_BASE;
tmp += EXTI_InitStruct->EXTI_Trigger;
*(__IO uint32_t *) tmp |= EXTI_InitStruct->EXTI_Line;
}
}
else
{
tmp += EXTI_InitStruct->EXTI_Mode;
/* Disable the selected external lines */
*(__IO uint32_t *) tmp &= ~EXTI_InitStruct->EXTI_Line;
}
}
/**
* @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_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..22)
* @retval None
*/
void EXTI_GenerateSWInterrupt(uint32_t EXTI_Line)
{
/* Check the parameters */
assert_param(IS_EXTI_LINE(EXTI_Line));
EXTI->SWIER |= EXTI_Line;
}
/**
* @}
*/
/** @defgroup EXTI_Group2 Interrupts and flags management functions
* @brief Interrupts and flags management functions
*
@verbatim
===============================================================================
##### Interrupts and flags management functions #####
===============================================================================
@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 EXTI_Linex where x can be(0..22)
* @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 ((EXTI->PR & EXTI_Line) != (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..22)
* @retval None
*/
void EXTI_ClearFlag(uint32_t EXTI_Line)
{
/* Check the parameters */
assert_param(IS_EXTI_LINE(EXTI_Line));
EXTI->PR = EXTI_Line;
}
/**
* @brief Checks whether the specified EXTI line is asserted or not.
* @param EXTI_Line: specifies the EXTI line to check.
* This parameter can be EXTI_Linex where x can be(0..22)
* @retval The new state of EXTI_Line (SET or RESET).
*/
ITStatus EXTI_GetITStatus(uint32_t EXTI_Line)
{
FlagStatus bitstatus = RESET;
/* Check the parameters */
assert_param(IS_GET_EXTI_LINE(EXTI_Line));
if ((EXTI->PR & EXTI_Line) != (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..22)
* @retval None
*/
void EXTI_ClearITPendingBit(uint32_t EXTI_Line)
{
/* Check the parameters */
assert_param(IS_EXTI_LINE(EXTI_Line));
EXTI->PR = EXTI_Line;
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

File diff suppressed because it is too large Load diff

View file

@ -0,0 +1,158 @@
/**
******************************************************************************
* @file stm32f4xx_flash_ramfunc.c
* @author MCD Application Team
* @version V1.6.1
* @date 21-October-2015
* @brief FLASH RAMFUNC module driver.
* This file provides a FLASH firmware functions which should be
* executed from internal SRAM
* + Stop/Start the flash interface while System Run
* + Enable/Disable the flash sleep while System Run
*
@verbatim
==============================================================================
##### APIs executed from Internal RAM #####
==============================================================================
[..]
*** ARM Compiler ***
--------------------
[..] RAM functions are defined using the toolchain options.
Functions that are be executed in RAM should reside in a separate
source module. Using the 'Options for File' dialog you can simply change
the 'Code / Const' area of a module to a memory space in physical RAM.
Available memory areas are declared in the 'Target' tab of the
Options for Target' dialog.
*** ICCARM Compiler ***
-----------------------
[..] RAM functions are defined using a specific toolchain keyword "__ramfunc".
*** GNU Compiler ***
--------------------
[..] RAM functions are defined using a specific toolchain attribute
"__attribute__((section(".RamFunc")))".
@endverbatim
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2015 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 "stm32f4xx_flash_ramfunc.h"
/** @addtogroup STM32F4xx_StdPeriph_Driver
* @{
*/
/** @defgroup FLASH RAMFUNC
* @brief FLASH RAMFUNC driver modules
* @{
*/
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/** @defgroup FLASH_RAMFUNC_Private_Functions
* @{
*/
/** @defgroup FLASH_RAMFUNC_Group1 Peripheral features functions executed from internal RAM
* @brief Peripheral Extended features functions
*
@verbatim
===============================================================================
##### ramfunc functions #####
===============================================================================
[..]
This subsection provides a set of functions that should be executed from RAM
transfers.
@endverbatim
* @{
*/
/**
* @brief Start/Stop the flash interface while System Run
* @note This mode is only available for STM32F411xx devices.
* @note This mode could n't be set while executing with the flash itself.
* It should be done with specific routine executed from RAM.
* @param NewState: new state of the Smart Card mode.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
__RAM_FUNC FLASH_FlashInterfaceCmd(FunctionalState NewState)
{
if (NewState != DISABLE)
{
/* Start the flash interface while System Run */
CLEAR_BIT(PWR->CR, PWR_CR_FISSR);
}
else
{
/* Stop the flash interface while System Run */
SET_BIT(PWR->CR, PWR_CR_FISSR);
}
}
/**
* @brief Enable/Disable the flash sleep while System Run
* @note This mode is only available for STM32F411xx devices.
* @note This mode could n't be set while executing with the flash itself.
* It should be done with specific routine executed from RAM.
* @param NewState: new state of the Smart Card mode.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
__RAM_FUNC FLASH_FlashSleepModeCmd(FunctionalState NewState)
{
if (NewState != DISABLE)
{
/* Enable the flash sleep while System Run */
SET_BIT(PWR->CR, PWR_CR_FMSSR);
}
else
{
/* Disable the flash sleep while System Run */
CLEAR_BIT(PWR->CR, PWR_CR_FMSSR);
}
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/************************ (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

View file

@ -0,0 +1,611 @@
/**
******************************************************************************
* @file stm32f4xx_gpio.c
* @author MCD Application Team
* @version V1.6.1
* @date 21-October-2015
* @brief This file provides firmware functions to manage the following
* functionalities of the GPIO peripheral:
* + Initialization and Configuration
* + GPIO Read and Write
* + GPIO Alternate functions configuration
*
@verbatim
===============================================================================
##### How to use this driver #####
===============================================================================
[..]
(#) Enable the GPIO AHB clock using the following function
RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOx, ENABLE);
(#) 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: 2 MHz, 25 MHz, 50 MHz or 100 MHz.
(++) 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 or DAC
output.
(#) Peripherals alternate function:
(++) For ADC and DAC, 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 PH0 and PH1, respectively, when the HSE oscillator is off.
The HSE has priority over the GPIO function.
@endverbatim
*
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2015 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 "stm32f4xx_gpio.h"
#include "stm32f4xx_rcc.h"
/** @addtogroup STM32F4xx_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 De-initializes the GPIOx peripheral registers to their default reset values.
* @note By default, The GPIO pins are configured in input floating mode (except JTAG pins).
* @param GPIOx: where x can be (A..K) to select the GPIO peripheral for STM32F405xx/407xx and STM32F415xx/417xx devices
* x can be (A..I) to select the GPIO peripheral for STM32F42xxx/43xxx devices.
* x can be (A, B, C, D and H) to select the GPIO peripheral for STM32F401xx devices.
* @retval None
*/
void GPIO_DeInit(GPIO_TypeDef* GPIOx)
{
/* Check the parameters */
assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
if (GPIOx == GPIOA)
{
RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOA, ENABLE);
RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOA, DISABLE);
}
else if (GPIOx == GPIOB)
{
RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOB, ENABLE);
RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOB, DISABLE);
}
else if (GPIOx == GPIOC)
{
RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOC, ENABLE);
RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOC, DISABLE);
}
else if (GPIOx == GPIOD)
{
RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOD, ENABLE);
RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOD, DISABLE);
}
else if (GPIOx == GPIOE)
{
RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOE, ENABLE);
RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOE, DISABLE);
}
else if (GPIOx == GPIOF)
{
RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOF, ENABLE);
RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOF, DISABLE);
}
else if (GPIOx == GPIOG)
{
RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOG, ENABLE);
RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOG, DISABLE);
}
else if (GPIOx == GPIOH)
{
RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOH, ENABLE);
RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOH, DISABLE);
}
else if (GPIOx == GPIOI)
{
RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOI, ENABLE);
RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOI, DISABLE);
}
else if (GPIOx == GPIOJ)
{
RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOJ, ENABLE);
RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOJ, DISABLE);
}
else
{
if (GPIOx == GPIOK)
{
RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOK, ENABLE);
RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOK, DISABLE);
}
}
}
/**
* @brief Initializes the GPIOx peripheral according to the specified parameters in the GPIO_InitStruct.
* @param GPIOx: where x can be (A..K) to select the GPIO peripheral for STM32F405xx/407xx and STM32F415xx/417xx devices
* x can be (A..I) to select the GPIO peripheral for STM32F42xxx/43xxx devices.
* x can be (A, B, C, D and H) to select the GPIO peripheral for STM32F401xx devices.
* @param GPIO_InitStruct: pointer to a GPIO_InitTypeDef structure that contains
* the configuration information for the specified GPIO peripheral.
* @retval None
*/
void GPIO_Init(GPIO_TypeDef* GPIOx, GPIO_InitTypeDef* GPIO_InitStruct)
{
uint32_t pinpos = 0x00, pos = 0x00 , currentpin = 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)
{
GPIOx->MODER &= ~(GPIO_MODER_MODER0 << (pinpos * 2));
GPIOx->MODER |= (((uint32_t)GPIO_InitStruct->GPIO_Mode) << (pinpos * 2));
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));
}
/* Pull-up Pull down resistor configuration*/
GPIOx->PUPDR &= ~(GPIO_PUPDR_PUPDR0 << ((uint16_t)pinpos * 2));
GPIOx->PUPDR |= (((uint32_t)GPIO_InitStruct->GPIO_PuPd) << (pinpos * 2));
}
}
}
/**
* @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.
* @note 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..K) to select the GPIO peripheral for STM32F405xx/407xx and STM32F415xx/417xx devices
* x can be (A..I) to select the GPIO peripheral for STM32F42xxx/43xxx devices.
* x can be (A, B, C, D and H) to select the GPIO peripheral for STM32F401xx devices.
* @param GPIO_Pin: specifies the port bit to be locked.
* 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)
{
__IO uint32_t tmp = 0x00010000;
/* Check the parameters */
assert_param(IS_GPIO_ALL_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..K) to select the GPIO peripheral for STM32F405xx/407xx and STM32F415xx/417xx devices
* x can be (A..I) to select the GPIO peripheral for STM32F42xxx/43xxx devices.
* x can be (A, B, C, D and H) to select the GPIO peripheral for STM32F401xx devices.
* @param GPIO_Pin: specifies the port bit to read.
* This parameter can be GPIO_Pin_x where x can be (0..15).
* @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 GPIO input data port.
* @param GPIOx: where x can be (A..K) to select the GPIO peripheral for STM32F405xx/407xx and STM32F415xx/417xx devices
* x can be (A..I) to select the GPIO peripheral for STM32F42xxx/43xxx devices.
* x can be (A, B, C, D and H) to select the GPIO peripheral for STM32F401xx devices.
* @retval GPIO input data port 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..K) to select the GPIO peripheral for STM32F405xx/407xx and STM32F415xx/417xx devices
* x can be (A..I) to select the GPIO peripheral for STM32F42xxx/43xxx devices.
* x can be (A, B, C, D and H) to select the GPIO peripheral for STM32F401xx devices.
* @param GPIO_Pin: specifies the port bit to read.
* This parameter can be GPIO_Pin_x where x can be (0..15).
* @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..K) to select the GPIO peripheral for STM32F405xx/407xx and STM32F415xx/417xx devices
* x can be (A..I) to select the GPIO peripheral for STM32F42xxx/43xxx devices.
* x can be (A, B, C, D and H) to select the GPIO peripheral for STM32F401xx devices.
* @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.
* @note This functions uses GPIOx_BSRR register to allow atomic read/modify
* accesses. In this way, there is no risk of an IRQ occurring between
* the read and the modify access.
* @param GPIOx: where x can be (A..K) to select the GPIO peripheral for STM32F405xx/407xx and STM32F415xx/417xx devices
* x can be (A..I) to select the GPIO peripheral for STM32F42xxx/43xxx devices.
* x can be (A, B, C, D and H) to select the GPIO peripheral for STM32F401xx devices.
* @param GPIO_Pin: specifies the port bits to be written.
* This parameter can be any combination of GPIO_Pin_x where x can be (0..15).
* @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->BSRRL = GPIO_Pin;
}
/**
* @brief Clears the selected data port bits.
* @note This functions uses GPIOx_BSRR register to allow atomic read/modify
* accesses. In this way, there is no risk of an IRQ occurring between
* the read and the modify access.
* @param GPIOx: where x can be (A..K) to select the GPIO peripheral for STM32F405xx/407xx and STM32F415xx/417xx devices
* x can be (A..I) to select the GPIO peripheral for STM32F42xxx/43xxx devices.
* x can be (A, B, C, D and H) to select the GPIO peripheral for STM32F401xx devices.
* @param GPIO_Pin: specifies the port bits to be written.
* This parameter can be any combination of GPIO_Pin_x where x can be (0..15).
* @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->BSRRH = GPIO_Pin;
}
/**
* @brief Sets or clears the selected data port bit.
* @param GPIOx: where x can be (A..K) to select the GPIO peripheral for STM32F405xx/407xx and STM32F415xx/417xx devices
* x can be (A..I) to select the GPIO peripheral for STM32F42xxx/43xxx devices.
* x can be (A, B, C, D and H) to select the GPIO peripheral for STM32F401xx devices.
* @param GPIO_Pin: specifies the port bit to be written.
* This parameter can be one of GPIO_Pin_x where x can be (0..15).
* @param BitVal: specifies the value to be written to the selected bit.
* This parameter can be one of the BitAction enum 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->BSRRL = GPIO_Pin;
}
else
{
GPIOx->BSRRH = GPIO_Pin ;
}
}
/**
* @brief Writes data to the specified GPIO data port.
* @param GPIOx: where x can be (A..K) to select the GPIO peripheral for STM32F405xx/407xx and STM32F415xx/417xx devices
* x can be (A..I) to select the GPIO peripheral for STM32F42xxx/43xxx devices.
* x can be (A, B, C, D and H) to select the GPIO peripheral for STM32F401xx devices.
* @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;
}
/**
* @brief Toggles the specified GPIO pins..
* @param GPIOx: where x can be (A..K) to select the GPIO peripheral for STM32F405xx/407xx and STM32F415xx/417xx devices
* x can be (A..I) to select the GPIO peripheral for STM32F42xxx/43xxx devices.
* x can be (A, B, C, D and H) to select the GPIO peripheral for STM32F401xx devices.
* @param GPIO_Pin: Specifies the pins to be toggled.
* @retval None
*/
void GPIO_ToggleBits(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin)
{
/* Check the parameters */
assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
GPIOx->ODR ^= GPIO_Pin;
}
/**
* @}
*/
/** @defgroup GPIO_Group3 GPIO Alternate functions configuration function
* @brief GPIO Alternate functions configuration function
*
@verbatim
===============================================================================
##### GPIO Alternate functions configuration function #####
===============================================================================
@endverbatim
* @{
*/
/**
* @brief Changes the mapping of the specified pin.
* @param GPIOx: where x can be (A..K) to select the GPIO peripheral for STM32F405xx/407xx and STM32F415xx/417xx devices
* x can be (A..I) to select the GPIO peripheral for STM32F42xxx/43xxx devices.
* x can be (A, B, C, D and H) to select the GPIO peripheral for STM32F401xx devices.
* @param GPIO_PinSource: specifies the pin for the Alternate function.
* This parameter can be GPIO_PinSourcex where x can be (0..15).
* @param GPIO_AFSelection: selects the pin to used as Alternate function.
* This parameter can be one of the following values:
* @arg GPIO_AF_RTC_50Hz: Connect RTC_50Hz pin to AF0 (default after reset)
* @arg GPIO_AF_MCO: Connect MCO pin (MCO1 and MCO2) to AF0 (default after reset)
* @arg GPIO_AF_TAMPER: Connect TAMPER pins (TAMPER_1 and TAMPER_2) to AF0 (default after reset)
* @arg GPIO_AF_SWJ: Connect SWJ pins (SWD and JTAG)to AF0 (default after reset)
* @arg GPIO_AF_TRACE: Connect TRACE pins to AF0 (default after reset)
* @arg GPIO_AF_TIM1: Connect TIM1 pins to AF1
* @arg GPIO_AF_TIM2: Connect TIM2 pins to AF1
* @arg GPIO_AF_TIM3: Connect TIM3 pins to AF2
* @arg GPIO_AF_TIM4: Connect TIM4 pins to AF2
* @arg GPIO_AF_TIM5: Connect TIM5 pins to AF2
* @arg GPIO_AF_TIM8: Connect TIM8 pins to AF3
* @arg GPIO_AF_TIM9: Connect TIM9 pins to AF3
* @arg GPIO_AF_TIM10: Connect TIM10 pins to AF3
* @arg GPIO_AF_TIM11: Connect TIM11 pins to AF3
* @arg GPIO_AF_I2C1: Connect I2C1 pins to AF4
* @arg GPIO_AF_I2C2: Connect I2C2 pins to AF4
* @arg GPIO_AF_I2C3: Connect I2C3 pins to AF4
* @arg GPIO_AF_SPI1: Connect SPI1 pins to AF5
* @arg GPIO_AF_SPI2: Connect SPI2/I2S2 pins to AF5
* @arg GPIO_AF_SPI4: Connect SPI4 pins to AF5
* @arg GPIO_AF_SPI5: Connect SPI5 pins to AF5
* @arg GPIO_AF_SPI6: Connect SPI6 pins to AF5
* @arg GPIO_AF_SAI1: Connect SAI1 pins to AF6 for STM32F42xxx/43xxx devices.
* @arg GPIO_AF_SPI3: Connect SPI3/I2S3 pins to AF6
* @arg GPIO_AF_I2S3ext: Connect I2S3ext pins to AF7
* @arg GPIO_AF_USART1: Connect USART1 pins to AF7
* @arg GPIO_AF_USART2: Connect USART2 pins to AF7
* @arg GPIO_AF_USART3: Connect USART3 pins to AF7
* @arg GPIO_AF_UART4: Connect UART4 pins to AF8
* @arg GPIO_AF_UART5: Connect UART5 pins to AF8
* @arg GPIO_AF_USART6: Connect USART6 pins to AF8
* @arg GPIO_AF_UART7: Connect UART7 pins to AF8
* @arg GPIO_AF_UART8: Connect UART8 pins to AF8
* @arg GPIO_AF_CAN1: Connect CAN1 pins to AF9
* @arg GPIO_AF_CAN2: Connect CAN2 pins to AF9
* @arg GPIO_AF_TIM12: Connect TIM12 pins to AF9
* @arg GPIO_AF_TIM13: Connect TIM13 pins to AF9
* @arg GPIO_AF_TIM14: Connect TIM14 pins to AF9
* @arg GPIO_AF_OTG_FS: Connect OTG_FS pins to AF10
* @arg GPIO_AF_OTG_HS: Connect OTG_HS pins to AF10
* @arg GPIO_AF_ETH: Connect ETHERNET pins to AF11
* @arg GPIO_AF_FSMC: Connect FSMC pins to AF12
* @arg GPIO_AF_FMC: Connect FMC pins to AF12 for STM32F42xxx/43xxx devices.
* @arg GPIO_AF_OTG_HS_FS: Connect OTG HS (configured in FS) pins to AF12
* @arg GPIO_AF_SDIO: Connect SDIO pins to AF12
* @arg GPIO_AF_DCMI: Connect DCMI pins to AF13
* @arg GPIO_AF_LTDC: Connect LTDC pins to AF14 for STM32F429xx/439xx devices.
* @arg GPIO_AF_EVENTOUT: Connect EVENTOUT pins to AF15
* @retval None
*/
void GPIO_PinAFConfig(GPIO_TypeDef* GPIOx, uint16_t GPIO_PinSource, uint8_t GPIO_AF)
{
uint32_t temp = 0x00;
uint32_t temp_2 = 0x00;
/* Check the parameters */
assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
assert_param(IS_GPIO_PIN_SOURCE(GPIO_PinSource));
assert_param(IS_GPIO_AF(GPIO_AF));
temp = ((uint32_t)(GPIO_AF) << ((uint32_t)((uint32_t)GPIO_PinSource & (uint32_t)0x07) * 4)) ;
GPIOx->AFR[GPIO_PinSource >> 0x03] &= ~((uint32_t)0xF << ((uint32_t)((uint32_t)GPIO_PinSource & (uint32_t)0x07) * 4)) ;
temp_2 = GPIOx->AFR[GPIO_PinSource >> 0x03] | temp;
GPIOx->AFR[GPIO_PinSource >> 0x03] = temp_2;
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View file

@ -0,0 +1,726 @@
/**
******************************************************************************
* @file stm32f4xx_hash.c
* @author MCD Application Team
* @version V1.6.1
* @date 21-October-2015
* @brief This file provides firmware functions to manage the following
* functionalities of the HASH / HMAC Processor (HASH) peripheral:
* - Initialization and Configuration functions
* - Message Digest generation functions
* - context swapping functions
* - DMA interface function
* - Interrupts and flags management
*
@verbatim
===================================================================
##### How to use this driver #####
===================================================================
*** HASH operation : ***
========================
[..]
(#) Enable the HASH controller clock using
RCC_AHB2PeriphClockCmd(RCC_AHB2Periph_HASH, ENABLE) function.
(#) Initialize the HASH using HASH_Init() function.
(#) Reset the HASH processor core, so that the HASH will be ready
to compute he message digest of a new message by using HASH_Reset() function.
(#) Enable the HASH controller using the HASH_Cmd() function.
(#) if using DMA for Data input transfer, Activate the DMA Request
using HASH_DMACmd() function
(#) if DMA is not used for data transfer, use HASH_DataIn() function
to enter data to IN FIFO.
(#) Configure the Number of valid bits in last word of the message
using HASH_SetLastWordValidBitsNbr() function.
(#) if the message length is not an exact multiple of 512 bits,
then the function HASH_StartDigest() must be called to launch the computation
of the final digest.
(#) Once computed, the digest can be read using HASH_GetDigest() function.
(#) To control HASH events you can use one of the following wo methods:
(++) Check on HASH flags using the HASH_GetFlagStatus() function.
(++) Use HASH interrupts through the function HASH_ITConfig() at
initialization phase and HASH_GetITStatus() function into
interrupt routines in hashing phase.
After checking on a flag you should clear it using HASH_ClearFlag()
function. And after checking on an interrupt event you should
clear it using HASH_ClearITPendingBit() function.
(#) Save and restore hash processor context using
HASH_SaveContext() and HASH_RestoreContext() functions.
*** HMAC operation : ***
========================
[..] The HMAC algorithm is used for message authentication, by
irreversibly binding the message being processed to a key chosen
by the user.
For HMAC specifications, refer to "HMAC: keyed-hashing for message
authentication, H. Krawczyk, M. Bellare, R. Canetti, February 1997"
[..] Basically, the HMAC algorithm consists of two nested hash operations:
HMAC(message) = Hash[((key | pad) XOR 0x5C) | Hash(((key | pad) XOR 0x36) | message)]
where:
(+) "pad" is a sequence of zeroes needed to extend the key to the
length of the underlying hash function data block (that is
512 bits for both the SHA-1 and MD5 hash algorithms)
(+) "|" represents the concatenation operator
[..]To compute the HMAC, four different phases are required:
(#) Initialize the HASH using HASH_Init() function to do HMAC
operation.
(#) The key (to be used for the inner hash function) is then given to the core.
This operation follows the same mechanism as the one used to send the
message in the hash operation (that is, by HASH_DataIn() function and,
finally, HASH_StartDigest() function.
(#) Once the last word has been entered and computation has started,
the hash processor elaborates the key. It is then ready to accept the message
text using the same mechanism as the one used to send the message in the
hash operation.
(#) After the first hash round, the hash processor returns "ready" to indicate
that it is ready to receive the key to be used for the outer hash function
(normally, this key is the same as the one used for the inner hash function).
When the last word of the key is entered and computation starts, the HMAC
result is made available using HASH_GetDigest() function.
@endverbatim
*
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2015 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 "stm32f4xx_hash.h"
#include "stm32f4xx_rcc.h"
/** @addtogroup STM32F4xx_StdPeriph_Driver
* @{
*/
/** @defgroup HASH
* @brief HASH driver modules
* @{
*/
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/** @defgroup HASH_Private_Functions
* @{
*/
/** @defgroup HASH_Group1 Initialization and Configuration functions
* @brief Initialization and Configuration functions
*
@verbatim
===============================================================================
##### Initialization and Configuration functions #####
===============================================================================
[..] This section provides functions allowing to
(+) Initialize the HASH peripheral
(+) Configure the HASH Processor
(+) MD5/SHA1,
(+) HASH/HMAC,
(+) datatype
(+) HMAC Key (if mode = HMAC)
(+) Reset the HASH Processor
@endverbatim
* @{
*/
/**
* @brief De-initializes the HASH peripheral registers to their default reset values
* @param None
* @retval None
*/
void HASH_DeInit(void)
{
/* Enable HASH reset state */
RCC_AHB2PeriphResetCmd(RCC_AHB2Periph_HASH, ENABLE);
/* Release HASH from reset state */
RCC_AHB2PeriphResetCmd(RCC_AHB2Periph_HASH, DISABLE);
}
/**
* @brief Initializes the HASH peripheral according to the specified parameters
* in the HASH_InitStruct structure.
* @note the hash processor is reset when calling this function so that the
* HASH will be ready to compute the message digest of a new message.
* There is no need to call HASH_Reset() function.
* @param HASH_InitStruct: pointer to a HASH_InitTypeDef structure that contains
* the configuration information for the HASH peripheral.
* @note The field HASH_HMACKeyType in HASH_InitTypeDef must be filled only
* if the algorithm mode is HMAC.
* @retval None
*/
void HASH_Init(HASH_InitTypeDef* HASH_InitStruct)
{
/* Check the parameters */
assert_param(IS_HASH_ALGOSELECTION(HASH_InitStruct->HASH_AlgoSelection));
assert_param(IS_HASH_DATATYPE(HASH_InitStruct->HASH_DataType));
assert_param(IS_HASH_ALGOMODE(HASH_InitStruct->HASH_AlgoMode));
/* Configure the Algorithm used, algorithm mode and the datatype */
HASH->CR &= ~ (HASH_CR_ALGO | HASH_CR_DATATYPE | HASH_CR_MODE);
HASH->CR |= (HASH_InitStruct->HASH_AlgoSelection | \
HASH_InitStruct->HASH_DataType | \
HASH_InitStruct->HASH_AlgoMode);
/* if algorithm mode is HMAC, set the Key */
if(HASH_InitStruct->HASH_AlgoMode == HASH_AlgoMode_HMAC)
{
assert_param(IS_HASH_HMAC_KEYTYPE(HASH_InitStruct->HASH_HMACKeyType));
HASH->CR &= ~HASH_CR_LKEY;
HASH->CR |= HASH_InitStruct->HASH_HMACKeyType;
}
/* Reset the HASH processor core, so that the HASH will be ready to compute
the message digest of a new message */
HASH->CR |= HASH_CR_INIT;
}
/**
* @brief Fills each HASH_InitStruct member with its default value.
* @param HASH_InitStruct : pointer to a HASH_InitTypeDef structure which will
* be initialized.
* @note The default values set are : Processor mode is HASH, Algorithm selected is SHA1,
* Data type selected is 32b and HMAC Key Type is short key.
* @retval None
*/
void HASH_StructInit(HASH_InitTypeDef* HASH_InitStruct)
{
/* Initialize the HASH_AlgoSelection member */
HASH_InitStruct->HASH_AlgoSelection = HASH_AlgoSelection_SHA1;
/* Initialize the HASH_AlgoMode member */
HASH_InitStruct->HASH_AlgoMode = HASH_AlgoMode_HASH;
/* Initialize the HASH_DataType member */
HASH_InitStruct->HASH_DataType = HASH_DataType_32b;
/* Initialize the HASH_HMACKeyType member */
HASH_InitStruct->HASH_HMACKeyType = HASH_HMACKeyType_ShortKey;
}
/**
* @brief Resets the HASH processor core, so that the HASH will be ready
* to compute the message digest of a new message.
* @note Calling this function will clear the HASH_SR_DCIS (Digest calculation
* completion interrupt status) bit corresponding to HASH_IT_DCI
* interrupt and HASH_FLAG_DCIS flag.
* @param None
* @retval None
*/
void HASH_Reset(void)
{
/* Reset the HASH processor core */
HASH->CR |= HASH_CR_INIT;
}
/**
* @}
*/
/** @defgroup HASH_Group2 Message Digest generation functions
* @brief Message Digest generation functions
*
@verbatim
===============================================================================
##### Message Digest generation functions #####
===============================================================================
[..] This section provides functions allowing the generation of message digest:
(+) Push data in the IN FIFO : using HASH_DataIn()
(+) Get the number of words set in IN FIFO, use HASH_GetInFIFOWordsNbr()
(+) set the last word valid bits number using HASH_SetLastWordValidBitsNbr()
(+) start digest calculation : using HASH_StartDigest()
(+) Get the Digest message : using HASH_GetDigest()
@endverbatim
* @{
*/
/**
* @brief Configure the Number of valid bits in last word of the message
* @param ValidNumber: Number of valid bits in last word of the message.
* This parameter must be a number between 0 and 0x1F.
* - 0x00: All 32 bits of the last data written are valid
* - 0x01: Only bit [0] of the last data written is valid
* - 0x02: Only bits[1:0] of the last data written are valid
* - 0x03: Only bits[2:0] of the last data written are valid
* - ...
* - 0x1F: Only bits[30:0] of the last data written are valid
* @note The Number of valid bits must be set before to start the message
* digest competition (in Hash and HMAC) and key treatment(in HMAC).
* @retval None
*/
void HASH_SetLastWordValidBitsNbr(uint16_t ValidNumber)
{
/* Check the parameters */
assert_param(IS_HASH_VALIDBITSNUMBER(ValidNumber));
/* Configure the Number of valid bits in last word of the message */
HASH->STR &= ~(HASH_STR_NBW);
HASH->STR |= ValidNumber;
}
/**
* @brief Writes data in the Data Input FIFO
* @param Data: new data of the message to be processed.
* @retval None
*/
void HASH_DataIn(uint32_t Data)
{
/* Write in the DIN register a new data */
HASH->DIN = Data;
}
/**
* @brief Returns the number of words already pushed into the IN FIFO.
* @param None
* @retval The value of words already pushed into the IN FIFO.
*/
uint8_t HASH_GetInFIFOWordsNbr(void)
{
/* Return the value of NBW bits */
return ((HASH->CR & HASH_CR_NBW) >> 8);
}
/**
* @brief Provides the message digest result.
* @note In MD5 mode, Data[7] to Data[4] filed of HASH_MsgDigest structure is not used
* and is read as zero.
* In SHA-1 mode, Data[7] to Data[5] filed of HASH_MsgDigest structure is not used
* and is read as zero.
* In SHA-224 mode, Data[7] filed of HASH_MsgDigest structure is not used
* and is read as zero.
* @param HASH_MessageDigest: pointer to a HASH_MsgDigest structure which will
* hold the message digest result
* @retval None
*/
void HASH_GetDigest(HASH_MsgDigest* HASH_MessageDigest)
{
/* Get the data field */
HASH_MessageDigest->Data[0] = HASH->HR[0];
HASH_MessageDigest->Data[1] = HASH->HR[1];
HASH_MessageDigest->Data[2] = HASH->HR[2];
HASH_MessageDigest->Data[3] = HASH->HR[3];
HASH_MessageDigest->Data[4] = HASH->HR[4];
HASH_MessageDigest->Data[5] = HASH_DIGEST->HR[5];
HASH_MessageDigest->Data[6] = HASH_DIGEST->HR[6];
HASH_MessageDigest->Data[7] = HASH_DIGEST->HR[7];
}
/**
* @brief Starts the message padding and calculation of the final message
* @param None
* @retval None
*/
void HASH_StartDigest(void)
{
/* Start the Digest calculation */
HASH->STR |= HASH_STR_DCAL;
}
/**
* @}
*/
/** @defgroup HASH_Group3 Context swapping functions
* @brief Context swapping functions
*
@verbatim
===============================================================================
##### Context swapping functions #####
===============================================================================
[..] This section provides functions allowing to save and store HASH Context
[..] It is possible to interrupt a HASH/HMAC process to perform another processing
with a higher priority, and to complete the interrupted process later on, when
the higher priority task is complete. To do so, the context of the interrupted
task must be saved from the HASH registers to memory, and then be restored
from memory to the HASH registers.
(#) To save the current context, use HASH_SaveContext() function
(#) To restore the saved context, use HASH_RestoreContext() function
@endverbatim
* @{
*/
/**
* @brief Save the Hash peripheral Context.
* @note The context can be saved only when no block is currently being
* processed. So user must wait for DINIS = 1 (the last block has been
* processed and the input FIFO is empty) or NBW != 0 (the FIFO is not
* full and no processing is ongoing).
* @param HASH_ContextSave: pointer to a HASH_Context structure that contains
* the repository for current context.
* @retval None
*/
void HASH_SaveContext(HASH_Context* HASH_ContextSave)
{
uint8_t i = 0;
/* save context registers */
HASH_ContextSave->HASH_IMR = HASH->IMR;
HASH_ContextSave->HASH_STR = HASH->STR;
HASH_ContextSave->HASH_CR = HASH->CR;
for(i=0; i<=53;i++)
{
HASH_ContextSave->HASH_CSR[i] = HASH->CSR[i];
}
}
/**
* @brief Restore the Hash peripheral Context.
* @note After calling this function, user can restart the processing from the
* point where it has been interrupted.
* @param HASH_ContextRestore: pointer to a HASH_Context structure that contains
* the repository for saved context.
* @retval None
*/
void HASH_RestoreContext(HASH_Context* HASH_ContextRestore)
{
uint8_t i = 0;
/* restore context registers */
HASH->IMR = HASH_ContextRestore->HASH_IMR;
HASH->STR = HASH_ContextRestore->HASH_STR;
HASH->CR = HASH_ContextRestore->HASH_CR;
/* Initialize the hash processor */
HASH->CR |= HASH_CR_INIT;
/* continue restoring context registers */
for(i=0; i<=53;i++)
{
HASH->CSR[i] = HASH_ContextRestore->HASH_CSR[i];
}
}
/**
* @}
*/
/** @defgroup HASH_Group4 HASH's DMA interface Configuration function
* @brief HASH's DMA interface Configuration function
*
@verbatim
===============================================================================
##### HASH's DMA interface Configuration function #####
===============================================================================
[..] This section provides functions allowing to configure the DMA interface for
HASH/ HMAC data input transfer.
[..] When the DMA mode is enabled (using the HASH_DMACmd() function), data can be
sent to the IN FIFO using the DMA peripheral.
@endverbatim
* @{
*/
/**
* @brief Enables or disables auto-start message padding and
* calculation of the final message digest at the end of DMA transfer.
* @param NewState: new state of the selected HASH DMA transfer request.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void HASH_AutoStartDigest(FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
/* Enable the auto start of the final message digest at the end of DMA transfer */
HASH->CR &= ~HASH_CR_MDMAT;
}
else
{
/* Disable the auto start of the final message digest at the end of DMA transfer */
HASH->CR |= HASH_CR_MDMAT;
}
}
/**
* @brief Enables or disables the HASH DMA interface.
* @note The DMA is disabled by hardware after the end of transfer.
* @param NewState: new state of the selected HASH DMA transfer request.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void HASH_DMACmd(FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
/* Enable the HASH DMA request */
HASH->CR |= HASH_CR_DMAE;
}
else
{
/* Disable the HASH DMA request */
HASH->CR &= ~HASH_CR_DMAE;
}
}
/**
* @}
*/
/** @defgroup HASH_Group5 Interrupts and flags management functions
* @brief Interrupts and flags management functions
*
@verbatim
===============================================================================
##### Interrupts and flags management functions #####
===============================================================================
[..] This section provides functions allowing to configure the HASH Interrupts and
to get the status and clear flags and Interrupts pending bits.
[..] The HASH provides 2 Interrupts sources and 5 Flags:
*** Flags : ***
===============
[..]
(#) HASH_FLAG_DINIS : set when 16 locations are free in the Data IN FIFO
which means that a new block (512 bit) can be entered into the input buffer.
(#) HASH_FLAG_DCIS : set when Digest calculation is complete
(#) HASH_FLAG_DMAS : set when HASH's DMA interface is enabled (DMAE=1) or
a transfer is ongoing. This Flag is cleared only by hardware.
(#) HASH_FLAG_BUSY : set when The hash core is processing a block of data
This Flag is cleared only by hardware.
(#) HASH_FLAG_DINNE : set when Data IN FIFO is not empty which means that
the Data IN FIFO contains at least one word of data. This Flag is cleared
only by hardware.
*** Interrupts : ***
====================
[..]
(#) HASH_IT_DINI : if enabled, this interrupt source is pending when 16
locations are free in the Data IN FIFO which means that a new block (512 bit)
can be entered into the input buffer. This interrupt source is cleared using
HASH_ClearITPendingBit(HASH_IT_DINI) function.
(#) HASH_IT_DCI : if enabled, this interrupt source is pending when Digest
calculation is complete. This interrupt source is cleared using
HASH_ClearITPendingBit(HASH_IT_DCI) function.
*** Managing the HASH controller events : ***
=============================================
[..] The user should identify which mode will be used in his application to manage
the HASH controller events: Polling mode or Interrupt mode.
(#) In the Polling Mode it is advised to use the following functions:
(++) HASH_GetFlagStatus() : to check if flags events occur.
(++) HASH_ClearFlag() : to clear the flags events.
(#) In the Interrupt Mode it is advised to use the following functions:
(++) HASH_ITConfig() : to enable or disable the interrupt source.
(++) HASH_GetITStatus() : to check if Interrupt occurs.
(++) HASH_ClearITPendingBit() : to clear the Interrupt pending Bit
(corresponding Flag).
@endverbatim
* @{
*/
/**
* @brief Enables or disables the specified HASH interrupts.
* @param HASH_IT: specifies the HASH interrupt source to be enabled or disabled.
* This parameter can be any combination of the following values:
* @arg HASH_IT_DINI: Data Input interrupt
* @arg HASH_IT_DCI: Digest Calculation Completion Interrupt
* @param NewState: new state of the specified HASH interrupt.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void HASH_ITConfig(uint32_t HASH_IT, FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_HASH_IT(HASH_IT));
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
/* Enable the selected HASH interrupt */
HASH->IMR |= HASH_IT;
}
else
{
/* Disable the selected HASH interrupt */
HASH->IMR &= (uint32_t)(~HASH_IT);
}
}
/**
* @brief Checks whether the specified HASH flag is set or not.
* @param HASH_FLAG: specifies the HASH flag to check.
* This parameter can be one of the following values:
* @arg HASH_FLAG_DINIS: Data input interrupt status flag
* @arg HASH_FLAG_DCIS: Digest calculation completion interrupt status flag
* @arg HASH_FLAG_BUSY: Busy flag
* @arg HASH_FLAG_DMAS: DMAS Status flag
* @arg HASH_FLAG_DINNE: Data Input register (DIN) not empty status flag
* @retval The new state of HASH_FLAG (SET or RESET)
*/
FlagStatus HASH_GetFlagStatus(uint32_t HASH_FLAG)
{
FlagStatus bitstatus = RESET;
uint32_t tempreg = 0;
/* Check the parameters */
assert_param(IS_HASH_GET_FLAG(HASH_FLAG));
/* check if the FLAG is in CR register */
if ((HASH_FLAG & HASH_FLAG_DINNE) != (uint32_t)RESET )
{
tempreg = HASH->CR;
}
else /* The FLAG is in SR register */
{
tempreg = HASH->SR;
}
/* Check the status of the specified HASH flag */
if ((tempreg & HASH_FLAG) != (uint32_t)RESET)
{
/* HASH is set */
bitstatus = SET;
}
else
{
/* HASH_FLAG is reset */
bitstatus = RESET;
}
/* Return the HASH_FLAG status */
return bitstatus;
}
/**
* @brief Clears the HASH flags.
* @param HASH_FLAG: specifies the flag to clear.
* This parameter can be any combination of the following values:
* @arg HASH_FLAG_DINIS: Data Input Flag
* @arg HASH_FLAG_DCIS: Digest Calculation Completion Flag
* @retval None
*/
void HASH_ClearFlag(uint32_t HASH_FLAG)
{
/* Check the parameters */
assert_param(IS_HASH_CLEAR_FLAG(HASH_FLAG));
/* Clear the selected HASH flags */
HASH->SR = ~(uint32_t)HASH_FLAG;
}
/**
* @brief Checks whether the specified HASH interrupt has occurred or not.
* @param HASH_IT: specifies the HASH interrupt source to check.
* This parameter can be one of the following values:
* @arg HASH_IT_DINI: Data Input interrupt
* @arg HASH_IT_DCI: Digest Calculation Completion Interrupt
* @retval The new state of HASH_IT (SET or RESET).
*/
ITStatus HASH_GetITStatus(uint32_t HASH_IT)
{
ITStatus bitstatus = RESET;
uint32_t tmpreg = 0;
/* Check the parameters */
assert_param(IS_HASH_GET_IT(HASH_IT));
/* Check the status of the specified HASH interrupt */
tmpreg = HASH->SR;
if (((HASH->IMR & tmpreg) & HASH_IT) != RESET)
{
/* HASH_IT is set */
bitstatus = SET;
}
else
{
/* HASH_IT is reset */
bitstatus = RESET;
}
/* Return the HASH_IT status */
return bitstatus;
}
/**
* @brief Clears the HASH interrupt pending bit(s).
* @param HASH_IT: specifies the HASH interrupt pending bit(s) to clear.
* This parameter can be any combination of the following values:
* @arg HASH_IT_DINI: Data Input interrupt
* @arg HASH_IT_DCI: Digest Calculation Completion Interrupt
* @retval None
*/
void HASH_ClearITPendingBit(uint32_t HASH_IT)
{
/* Check the parameters */
assert_param(IS_HASH_IT(HASH_IT));
/* Clear the selected HASH interrupt pending bit */
HASH->SR = (uint32_t)(~HASH_IT);
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View file

@ -0,0 +1,320 @@
/**
******************************************************************************
* @file stm32f4xx_hash_md5.c
* @author MCD Application Team
* @version V1.6.1
* @date 21-October-2015
* @brief This file provides high level functions to compute the HASH MD5 and
* HMAC MD5 Digest of an input message.
* It uses the stm32f4xx_hash.c/.h drivers to access the STM32F4xx HASH
* peripheral.
*
@verbatim
===================================================================
##### How to use this driver #####
===================================================================
[..]
(#) Enable The HASH controller clock using
RCC_AHB2PeriphClockCmd(RCC_AHB2Periph_HASH, ENABLE); function.
(#) Calculate the HASH MD5 Digest using HASH_MD5() function.
(#) Calculate the HMAC MD5 Digest using HMAC_MD5() function.
@endverbatim
*
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2015 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 "stm32f4xx_hash.h"
/** @addtogroup STM32F4xx_StdPeriph_Driver
* @{
*/
/** @defgroup HASH
* @brief HASH driver modules
* @{
*/
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
#define MD5BUSY_TIMEOUT ((uint32_t) 0x00010000)
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/** @defgroup HASH_Private_Functions
* @{
*/
/** @defgroup HASH_Group7 High Level MD5 functions
* @brief High Level MD5 Hash and HMAC functions
*
@verbatim
===============================================================================
##### High Level MD5 Hash and HMAC functions #####
===============================================================================
@endverbatim
* @{
*/
/**
* @brief Compute the HASH MD5 digest.
* @param Input: pointer to the Input buffer to be treated.
* @param Ilen: length of the Input buffer.
* @param Output: the returned digest
* @retval An ErrorStatus enumeration value:
* - SUCCESS: digest computation done
* - ERROR: digest computation failed
*/
ErrorStatus HASH_MD5(uint8_t *Input, uint32_t Ilen, uint8_t Output[16])
{
HASH_InitTypeDef MD5_HASH_InitStructure;
HASH_MsgDigest MD5_MessageDigest;
__IO uint16_t nbvalidbitsdata = 0;
uint32_t i = 0;
__IO uint32_t counter = 0;
uint32_t busystatus = 0;
ErrorStatus status = SUCCESS;
uint32_t inputaddr = (uint32_t)Input;
uint32_t outputaddr = (uint32_t)Output;
/* Number of valid bits in last word of the Input data */
nbvalidbitsdata = 8 * (Ilen % 4);
/* HASH peripheral initialization */
HASH_DeInit();
/* HASH Configuration */
MD5_HASH_InitStructure.HASH_AlgoSelection = HASH_AlgoSelection_MD5;
MD5_HASH_InitStructure.HASH_AlgoMode = HASH_AlgoMode_HASH;
MD5_HASH_InitStructure.HASH_DataType = HASH_DataType_8b;
HASH_Init(&MD5_HASH_InitStructure);
/* Configure the number of valid bits in last word of the data */
HASH_SetLastWordValidBitsNbr(nbvalidbitsdata);
/* Write the Input block in the IN FIFO */
for(i=0; i<Ilen; i+=4)
{
HASH_DataIn(*(uint32_t*)inputaddr);
inputaddr+=4;
}
/* Start the HASH processor */
HASH_StartDigest();
/* wait until the Busy flag is RESET */
do
{
busystatus = HASH_GetFlagStatus(HASH_FLAG_BUSY);
counter++;
}while ((counter != MD5BUSY_TIMEOUT) && (busystatus != RESET));
if (busystatus != RESET)
{
status = ERROR;
}
else
{
/* Read the message digest */
HASH_GetDigest(&MD5_MessageDigest);
*(uint32_t*)(outputaddr) = __REV(MD5_MessageDigest.Data[0]);
outputaddr+=4;
*(uint32_t*)(outputaddr) = __REV(MD5_MessageDigest.Data[1]);
outputaddr+=4;
*(uint32_t*)(outputaddr) = __REV(MD5_MessageDigest.Data[2]);
outputaddr+=4;
*(uint32_t*)(outputaddr) = __REV(MD5_MessageDigest.Data[3]);
}
return status;
}
/**
* @brief Compute the HMAC MD5 digest.
* @param Key: pointer to the Key used for HMAC.
* @param Keylen: length of the Key used for HMAC.
* @param Input: pointer to the Input buffer to be treated.
* @param Ilen: length of the Input buffer.
* @param Output: the returned digest
* @retval An ErrorStatus enumeration value:
* - SUCCESS: digest computation done
* - ERROR: digest computation failed
*/
ErrorStatus HMAC_MD5(uint8_t *Key, uint32_t Keylen, uint8_t *Input,
uint32_t Ilen, uint8_t Output[16])
{
HASH_InitTypeDef MD5_HASH_InitStructure;
HASH_MsgDigest MD5_MessageDigest;
__IO uint16_t nbvalidbitsdata = 0;
__IO uint16_t nbvalidbitskey = 0;
uint32_t i = 0;
__IO uint32_t counter = 0;
uint32_t busystatus = 0;
ErrorStatus status = SUCCESS;
uint32_t keyaddr = (uint32_t)Key;
uint32_t inputaddr = (uint32_t)Input;
uint32_t outputaddr = (uint32_t)Output;
/* Number of valid bits in last word of the Input data */
nbvalidbitsdata = 8 * (Ilen % 4);
/* Number of valid bits in last word of the Key */
nbvalidbitskey = 8 * (Keylen % 4);
/* HASH peripheral initialization */
HASH_DeInit();
/* HASH Configuration */
MD5_HASH_InitStructure.HASH_AlgoSelection = HASH_AlgoSelection_MD5;
MD5_HASH_InitStructure.HASH_AlgoMode = HASH_AlgoMode_HMAC;
MD5_HASH_InitStructure.HASH_DataType = HASH_DataType_8b;
if(Keylen > 64)
{
/* HMAC long Key */
MD5_HASH_InitStructure.HASH_HMACKeyType = HASH_HMACKeyType_LongKey;
}
else
{
/* HMAC short Key */
MD5_HASH_InitStructure.HASH_HMACKeyType = HASH_HMACKeyType_ShortKey;
}
HASH_Init(&MD5_HASH_InitStructure);
/* Configure the number of valid bits in last word of the Key */
HASH_SetLastWordValidBitsNbr(nbvalidbitskey);
/* Write the Key */
for(i=0; i<Keylen; i+=4)
{
HASH_DataIn(*(uint32_t*)keyaddr);
keyaddr+=4;
}
/* Start the HASH processor */
HASH_StartDigest();
/* wait until the Busy flag is RESET */
do
{
busystatus = HASH_GetFlagStatus(HASH_FLAG_BUSY);
counter++;
}while ((counter != MD5BUSY_TIMEOUT) && (busystatus != RESET));
if (busystatus != RESET)
{
status = ERROR;
}
else
{
/* Configure the number of valid bits in last word of the Input data */
HASH_SetLastWordValidBitsNbr(nbvalidbitsdata);
/* Write the Input block in the IN FIFO */
for(i=0; i<Ilen; i+=4)
{
HASH_DataIn(*(uint32_t*)inputaddr);
inputaddr+=4;
}
/* Start the HASH processor */
HASH_StartDigest();
/* wait until the Busy flag is RESET */
counter =0;
do
{
busystatus = HASH_GetFlagStatus(HASH_FLAG_BUSY);
counter++;
}while ((counter != MD5BUSY_TIMEOUT) && (busystatus != RESET));
if (busystatus != RESET)
{
status = ERROR;
}
else
{
/* Configure the number of valid bits in last word of the Key */
HASH_SetLastWordValidBitsNbr(nbvalidbitskey);
/* Write the Key */
keyaddr = (uint32_t)Key;
for(i=0; i<Keylen; i+=4)
{
HASH_DataIn(*(uint32_t*)keyaddr);
keyaddr+=4;
}
/* Start the HASH processor */
HASH_StartDigest();
/* wait until the Busy flag is RESET */
counter =0;
do
{
busystatus = HASH_GetFlagStatus(HASH_FLAG_BUSY);
counter++;
}while ((counter != MD5BUSY_TIMEOUT) && (busystatus != RESET));
if (busystatus != RESET)
{
status = ERROR;
}
else
{
/* Read the message digest */
HASH_GetDigest(&MD5_MessageDigest);
*(uint32_t*)(outputaddr) = __REV(MD5_MessageDigest.Data[0]);
outputaddr+=4;
*(uint32_t*)(outputaddr) = __REV(MD5_MessageDigest.Data[1]);
outputaddr+=4;
*(uint32_t*)(outputaddr) = __REV(MD5_MessageDigest.Data[2]);
outputaddr+=4;
*(uint32_t*)(outputaddr) = __REV(MD5_MessageDigest.Data[3]);
}
}
}
return status;
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View file

@ -0,0 +1,323 @@
/**
******************************************************************************
* @file stm32f4xx_hash_sha1.c
* @author MCD Application Team
* @version V1.6.1
* @date 21-October-2015
* @brief This file provides high level functions to compute the HASH SHA1 and
* HMAC SHA1 Digest of an input message.
* It uses the stm32f4xx_hash.c/.h drivers to access the STM32F4xx HASH
* peripheral.
*
@verbatim
===================================================================
##### How to use this driver #####
===================================================================
[..]
(#) Enable The HASH controller clock using
RCC_AHB2PeriphClockCmd(RCC_AHB2Periph_HASH, ENABLE); function.
(#) Calculate the HASH SHA1 Digest using HASH_SHA1() function.
(#) Calculate the HMAC SHA1 Digest using HMAC_SHA1() function.
@endverbatim
*
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2015 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 "stm32f4xx_hash.h"
/** @addtogroup STM32F4xx_StdPeriph_Driver
* @{
*/
/** @defgroup HASH
* @brief HASH driver modules
* @{
*/
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
#define SHA1BUSY_TIMEOUT ((uint32_t) 0x00010000)
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/** @defgroup HASH_Private_Functions
* @{
*/
/** @defgroup HASH_Group6 High Level SHA1 functions
* @brief High Level SHA1 Hash and HMAC functions
*
@verbatim
===============================================================================
##### High Level SHA1 Hash and HMAC functions #####
===============================================================================
@endverbatim
* @{
*/
/**
* @brief Compute the HASH SHA1 digest.
* @param Input: pointer to the Input buffer to be treated.
* @param Ilen: length of the Input buffer.
* @param Output: the returned digest
* @retval An ErrorStatus enumeration value:
* - SUCCESS: digest computation done
* - ERROR: digest computation failed
*/
ErrorStatus HASH_SHA1(uint8_t *Input, uint32_t Ilen, uint8_t Output[20])
{
HASH_InitTypeDef SHA1_HASH_InitStructure;
HASH_MsgDigest SHA1_MessageDigest;
__IO uint16_t nbvalidbitsdata = 0;
uint32_t i = 0;
__IO uint32_t counter = 0;
uint32_t busystatus = 0;
ErrorStatus status = SUCCESS;
uint32_t inputaddr = (uint32_t)Input;
uint32_t outputaddr = (uint32_t)Output;
/* Number of valid bits in last word of the Input data */
nbvalidbitsdata = 8 * (Ilen % 4);
/* HASH peripheral initialization */
HASH_DeInit();
/* HASH Configuration */
SHA1_HASH_InitStructure.HASH_AlgoSelection = HASH_AlgoSelection_SHA1;
SHA1_HASH_InitStructure.HASH_AlgoMode = HASH_AlgoMode_HASH;
SHA1_HASH_InitStructure.HASH_DataType = HASH_DataType_8b;
HASH_Init(&SHA1_HASH_InitStructure);
/* Configure the number of valid bits in last word of the data */
HASH_SetLastWordValidBitsNbr(nbvalidbitsdata);
/* Write the Input block in the IN FIFO */
for(i=0; i<Ilen; i+=4)
{
HASH_DataIn(*(uint32_t*)inputaddr);
inputaddr+=4;
}
/* Start the HASH processor */
HASH_StartDigest();
/* wait until the Busy flag is RESET */
do
{
busystatus = HASH_GetFlagStatus(HASH_FLAG_BUSY);
counter++;
}while ((counter != SHA1BUSY_TIMEOUT) && (busystatus != RESET));
if (busystatus != RESET)
{
status = ERROR;
}
else
{
/* Read the message digest */
HASH_GetDigest(&SHA1_MessageDigest);
*(uint32_t*)(outputaddr) = __REV(SHA1_MessageDigest.Data[0]);
outputaddr+=4;
*(uint32_t*)(outputaddr) = __REV(SHA1_MessageDigest.Data[1]);
outputaddr+=4;
*(uint32_t*)(outputaddr) = __REV(SHA1_MessageDigest.Data[2]);
outputaddr+=4;
*(uint32_t*)(outputaddr) = __REV(SHA1_MessageDigest.Data[3]);
outputaddr+=4;
*(uint32_t*)(outputaddr) = __REV(SHA1_MessageDigest.Data[4]);
}
return status;
}
/**
* @brief Compute the HMAC SHA1 digest.
* @param Key: pointer to the Key used for HMAC.
* @param Keylen: length of the Key used for HMAC.
* @param Input: pointer to the Input buffer to be treated.
* @param Ilen: length of the Input buffer.
* @param Output: the returned digest
* @retval An ErrorStatus enumeration value:
* - SUCCESS: digest computation done
* - ERROR: digest computation failed
*/
ErrorStatus HMAC_SHA1(uint8_t *Key, uint32_t Keylen, uint8_t *Input,
uint32_t Ilen, uint8_t Output[20])
{
HASH_InitTypeDef SHA1_HASH_InitStructure;
HASH_MsgDigest SHA1_MessageDigest;
__IO uint16_t nbvalidbitsdata = 0;
__IO uint16_t nbvalidbitskey = 0;
uint32_t i = 0;
__IO uint32_t counter = 0;
uint32_t busystatus = 0;
ErrorStatus status = SUCCESS;
uint32_t keyaddr = (uint32_t)Key;
uint32_t inputaddr = (uint32_t)Input;
uint32_t outputaddr = (uint32_t)Output;
/* Number of valid bits in last word of the Input data */
nbvalidbitsdata = 8 * (Ilen % 4);
/* Number of valid bits in last word of the Key */
nbvalidbitskey = 8 * (Keylen % 4);
/* HASH peripheral initialization */
HASH_DeInit();
/* HASH Configuration */
SHA1_HASH_InitStructure.HASH_AlgoSelection = HASH_AlgoSelection_SHA1;
SHA1_HASH_InitStructure.HASH_AlgoMode = HASH_AlgoMode_HMAC;
SHA1_HASH_InitStructure.HASH_DataType = HASH_DataType_8b;
if(Keylen > 64)
{
/* HMAC long Key */
SHA1_HASH_InitStructure.HASH_HMACKeyType = HASH_HMACKeyType_LongKey;
}
else
{
/* HMAC short Key */
SHA1_HASH_InitStructure.HASH_HMACKeyType = HASH_HMACKeyType_ShortKey;
}
HASH_Init(&SHA1_HASH_InitStructure);
/* Configure the number of valid bits in last word of the Key */
HASH_SetLastWordValidBitsNbr(nbvalidbitskey);
/* Write the Key */
for(i=0; i<Keylen; i+=4)
{
HASH_DataIn(*(uint32_t*)keyaddr);
keyaddr+=4;
}
/* Start the HASH processor */
HASH_StartDigest();
/* wait until the Busy flag is RESET */
do
{
busystatus = HASH_GetFlagStatus(HASH_FLAG_BUSY);
counter++;
}while ((counter != SHA1BUSY_TIMEOUT) && (busystatus != RESET));
if (busystatus != RESET)
{
status = ERROR;
}
else
{
/* Configure the number of valid bits in last word of the Input data */
HASH_SetLastWordValidBitsNbr(nbvalidbitsdata);
/* Write the Input block in the IN FIFO */
for(i=0; i<Ilen; i+=4)
{
HASH_DataIn(*(uint32_t*)inputaddr);
inputaddr+=4;
}
/* Start the HASH processor */
HASH_StartDigest();
/* wait until the Busy flag is RESET */
counter =0;
do
{
busystatus = HASH_GetFlagStatus(HASH_FLAG_BUSY);
counter++;
}while ((counter != SHA1BUSY_TIMEOUT) && (busystatus != RESET));
if (busystatus != RESET)
{
status = ERROR;
}
else
{
/* Configure the number of valid bits in last word of the Key */
HASH_SetLastWordValidBitsNbr(nbvalidbitskey);
/* Write the Key */
keyaddr = (uint32_t)Key;
for(i=0; i<Keylen; i+=4)
{
HASH_DataIn(*(uint32_t*)keyaddr);
keyaddr+=4;
}
/* Start the HASH processor */
HASH_StartDigest();
/* wait until the Busy flag is RESET */
counter =0;
do
{
busystatus = HASH_GetFlagStatus(HASH_FLAG_BUSY);
counter++;
}while ((counter != SHA1BUSY_TIMEOUT) && (busystatus != RESET));
if (busystatus != RESET)
{
status = ERROR;
}
else
{
/* Read the message digest */
HASH_GetDigest(&SHA1_MessageDigest);
*(uint32_t*)(outputaddr) = __REV(SHA1_MessageDigest.Data[0]);
outputaddr+=4;
*(uint32_t*)(outputaddr) = __REV(SHA1_MessageDigest.Data[1]);
outputaddr+=4;
*(uint32_t*)(outputaddr) = __REV(SHA1_MessageDigest.Data[2]);
outputaddr+=4;
*(uint32_t*)(outputaddr) = __REV(SHA1_MessageDigest.Data[3]);
outputaddr+=4;
*(uint32_t*)(outputaddr) = __REV(SHA1_MessageDigest.Data[4]);
}
}
}
return status;
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

File diff suppressed because it is too large Load diff

View file

@ -0,0 +1,266 @@
/**
******************************************************************************
* @file stm32f4xx_iwdg.c
* @author MCD Application Team
* @version V1.6.1
* @date 21-October-2015
* @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 @32KHz (LSI): ~125us / ~32.7s
The IWDG timeout may vary due to LSI frequency dispersion. STM32F4xx
devices provide the capability to measure the LSI frequency (LSI clock
connected internally to TIM5 CH4 input capture). The measured value
can be used to have an IWDG timeout with an acceptable accuracy.
For more information, please refer to the STM32F4xx Reference manual
##### How to use this driver #####
===============================================================================
[..]
(#) 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.
(#) 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)
(#) Then the application program must reload the IWDG counter at regular
intervals during normal operation to prevent an MCU reset, using
IWDG_ReloadCounter() function.
@endverbatim
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2015 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 "stm32f4xx_iwdg.h"
/** @addtogroup STM32F4xx_StdPeriph_Driver
* @{
*/
/** @defgroup IWDG
* @brief IWDG driver modules
* @{
*/
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* 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;
}
/**
* @}
*/
/** @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
* @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****/

View file

@ -0,0 +1,951 @@
/**
******************************************************************************
* @file stm32f4xx_lptim.c
* @author MCD Application Team
* @version V1.6.1
* @date 21-October-2015
* @brief This file provides firmware functions to manage the following
* functionalities of the Low Power Timer (LPT) peripheral:
* + Initialization functions.
* + Configuration functions.
* + Interrupts and flags management functions.
*
* @verbatim
*
================================================================================
##### How to use this driver #####
================================================================================
Basic configuration:
--------------------
- Configure the clock source, the prescaler, the waveform shape and
the output polarity by filling the "LPTIM_InitTypeDef" structure and
calling LPTIM_Init.
- If the ULPTIM source is selected as clock source, configure the digital
Glitch filter by setting the number of consecutive samples
to be detected by using LPTIM_ConfigClockGlitchFilter.
- To select a software start use LPTIM_SelectSoftwareStart.
- To select an external trigger for the start of the counter, configure
the source and its active edge polarity by calling
LPTIM_ConfigExternalTrigger. Configure the Digital Glitch filter for
the external triggers by setting the number of consecutive samples
to be detected by using LPTIM_ConfigTriggerGlitchFilter.
- Select the operating mode of the peripheral by using
LPTIM_SelectOperatingMode, 2 modes can be selected:
+ Continuous mode: the timer is free running, the timer is started
from a trigger event and never stops until the timer is disabled
+ One shot mode: the timer is started from a trigger event and
stops when reaching the auto-reload value.
- Use LPTIM_SetAutoreloadValue to set the auto-reload value and
LPTIM_SetCompareValue to set the compare value.
- Configure the preload mode by using LPTIM_ConfigUpdate function. 2 modes
are available:
+ The Autoreload and compare registers are updated immediately after
APB write.
+ The Autoreload and compare registers are updated at the end of
counter period.
- Enable the peripheral by calling LPTIM_Cmd.
Encoder mode:
-------------
- To select the encoder feature, use the function: LPTIM_SelectEncoderMode.
- To select on which edge (Rising edge, falling edge or both edges)
the counter is incremented, use LPTIM_SelectClockPolarity.
Counter mode:
-------------
- Use LPTIM_SelectCounterMode to select the counting mode. In this mode
the counter is incremented on each valid event on ULPTIM.
Timeout function:
-----------------
In this case, the trigger will reset the timer. The first trigger event
will start the timer, any successive trigger event will reset the counter
and the timer restarts.
- To active this feature use LPTIM_TimoutCmd.
Interrupt configuration:
------------------------
- Use LPTIM_ITConfig to configure an interruption.
- Call LPTIM_GetFlagStatus to get a flag status.
- Call LPTIM_GetITStatus to get an interrupt status.
- Use LPTIM_ClearFlag to clear a flag.
@endverbatim
*
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2015 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 "stm32f4xx_lptim.h"
/** @addtogroup STM32F4xx_StdPeriph_Driver
* @{
*/
/** @defgroup LPTIM
* @brief LPTIM driver modules
* @{
*/
#if defined(STM32F410xx)
/* External variables --------------------------------------------------------*/
/* Private typedef -----------------------------------------------------------*/
/* Private defines -----------------------------------------------------------*/
#define CFGR_INIT_CLEAR_MASK ((uint32_t) 0xFFCFF1FE)
#define CFGR_TRIG_AND_POL_CLEAR_MASK ((uint32_t) 0xFFF91FFF)
/* Private macros ------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/** @defgroup LPTIM_Private_Functions
* @{
*/
/** @defgroup LPTIM_Group1 Initialization functions
* @brief Initialization functions
*
@verbatim
===============================================================================
Initialization functions
===============================================================================
This section provides functions allowing to:
- Deinitialize the LPTimer
- Initialize the Clock source, the Prescaler, the Ouput Waveform shape and Polarity
- Initialize the member of LPTIM_InitStruct structer with default value
@endverbatim
* @{
*/
/**
* @brief Deinitializes the LPTIMx peripheral registers to their default reset values.
* @param LPTIMx: where x can be 1.
* @retval None
*
*/
void LPTIM_DeInit(LPTIM_TypeDef* LPTIMx)
{
/* Check the parameters */
assert_param(IS_LPTIM_ALL_PERIPH(LPTIMx));
/* Deinitializes the LPTIM1 peripheral */
if(LPTIMx == LPTIM1)
{
RCC_APB1PeriphResetCmd(RCC_APB1Periph_LPTIM1, ENABLE);
RCC_APB1PeriphResetCmd(RCC_APB1Periph_LPTIM1, DISABLE);
}
}
/**
* @brief Initializes the LPTIMx peripheral according to the specified parameters
* in the LPTIM_InitStruct.
* @param LPTIMx: where x can be 1.
* @param LPTIM_InitStruct: pointer to an LPTIM_InitTypeDef structure that contains
* the configuration information for the specified LPTIM peripheral.
* @retval None
*
* @note It is mandatory to disable the peripheral to use this function.
*/
void LPTIM_Init(LPTIM_TypeDef* LPTIMx, LPTIM_InitTypeDef* LPTIM_InitStruct)
{
uint32_t tmpreg1 = 0;
/* Check the parameters */
assert_param(IS_LPTIM_ALL_PERIPH(LPTIMx));
assert_param(IS_LPTIM_CLOCK_SOURCE(LPTIM_InitStruct->LPTIM_ClockSource));
assert_param(IS_LPTIM_CLOCK_PRESCALER(LPTIM_InitStruct->LPTIM_Prescaler));
assert_param(IS_LPTIM_WAVEFORM(LPTIM_InitStruct->LPTIM_Waveform));
assert_param(IS_LPTIM_OUTPUT_POLARITY(LPTIM_InitStruct->LPTIM_OutputPolarity));
/* Get the LPTIMx CFGR value */
tmpreg1 = LPTIMx->CFGR;
/* Clear CKSEL, PRESC, WAVE and WAVEPOL bits */
tmpreg1 &= CFGR_INIT_CLEAR_MASK;
/* Set or Reset CKSEL bit according to LPTIM_ClockSource value */
/* Set or Reset PRESC bits according to LPTIM_Prescaler value */
/* Set or Reset WAVE bit according to LPTIM_Waveform value */
/* Set or Reset WAVEPOL bit according to LPTIM_OutputPolarity value */
tmpreg1 |= (LPTIM_InitStruct->LPTIM_ClockSource | LPTIM_InitStruct->LPTIM_Prescaler
|LPTIM_InitStruct->LPTIM_Waveform | LPTIM_InitStruct->LPTIM_OutputPolarity);
/* Write to LPTIMx CFGR */
LPTIMx->CFGR = tmpreg1;
}
/**
* @brief Fills each LPTIM_InitStruct member with its default value.
* @param LPTIM_InitStruct : pointer to a LPTIM_InitTypeDef structure which will be initialized.
* @retval None
*/
void LPTIM_StructInit(LPTIM_InitTypeDef* LPTIM_InitStruct)
{
/* APB Clock/Low Power oscillators is selected as default Clock source*/
LPTIM_InitStruct->LPTIM_ClockSource = LPTIM_ClockSource_APBClock_LPosc;
/* High Polarity is selected as default polarity */
LPTIM_InitStruct->LPTIM_OutputPolarity = LPTIM_OutputPolarity_High;
/* DIV=1 is selected as default prescaler */
LPTIM_InitStruct->LPTIM_Prescaler = LPTIM_Prescaler_DIV1;
/* PWM/One pulse mode is selected as default Waveform shape */
LPTIM_InitStruct->LPTIM_Waveform = LPTIM_Waveform_PWM_OnePulse;
}
/**
* @}
*/
/** @defgroup LPTIM_Group2 Configuration functions
* @brief Configuration functions
*
@verbatim
===============================================================================
Configuration functions
===============================================================================
This section provides functions allowing to configure the Low Power Timer:
- Select the Clock source.
- Configure the Glitch filter for the external clock and the external clock.
- Configure the prescaler of the counter.
- Select the Trigger source of the counter.
- Configure the operating mode (Single or Continuous mode).
- Select the Waveform shape (PWM/One Pulse or Set once) and polarity.
- Enable or disable the Encoder mode and the Timeout function.
- Write on the Autoreload and the Compare registers and configure the
preload mode.
- Get the Counter value.
- Enable or disable the peripheral.
@endverbatim
* @{
*/
/**
* @brief Enables or disables the specified LPTIM peripheral.
* @param LPTIMx: where x can be 1.
* @param NewState: new state of the LPTIMx peripheral.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void LPTIM_Cmd(LPTIM_TypeDef* LPTIMx, FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_LPTIM_ALL_PERIPH(LPTIMx));
assert_param(IS_FUNCTIONAL_STATE(NewState));
if(NewState != DISABLE)
{
/* Set the ENABLE bit */
LPTIMx->CR |= LPTIM_CR_ENABLE;
}
else
{
/* Reset the ENABLE bit */
LPTIMx->CR &= ~(LPTIM_CR_ENABLE);
}
}
/**
* @brief Selects the Clock source of the LPTIM counter.
* @param LPTIMx: where x can be 1.
* @param LPTIM_ClockSource: the selected clock source.
* This parameter can be:
* @arg LPTIM_ClockSource_APBClock_LPosc : APB clock/LP oscillators selected
* @arg LPTIM_ClockSource_ULPTIM: ULPTIM (external input) selected
* @retval None
*
* @note It is mandatory to disable the peripheral to use this function.
*/
void LPTIM_SelectClockSource(LPTIM_TypeDef* LPTIMx, uint32_t LPTIM_ClockSource)
{
/* Check the parameters */
assert_param(IS_LPTIM_ALL_PERIPH(LPTIMx));
assert_param(IS_LPTIM_CLOCK_SOURCE(LPTIM_ClockSource));
/* Clear the CKSEL bit */
LPTIMx->CFGR &= ~(LPTIM_CFGR_CKSEL);
/* Set or Reset the CKSEL bit */
LPTIMx->CFGR |= LPTIM_ClockSource;
}
/**
* @brief Configures the polarity of the edge to be used to count
* if the ULPTIM input is selected.
* @param LPTIMx: where x can be 1.
* @param LPTIM_ClockPolarity: the selected clock polarity.
* This parameter can be:
* @arg LPTIM_ClockPolarity_RisingEdge : Counter Clock = LPTIM Clock / 1
* @arg LPTIM_ClockPolarity_FallingEdge : Counter Clock = LPTIM Clock / 2
* @arg LPTIM_ClockPolarity_BothEdges : Counter Clock = LPTIM Clock / 4
* @retval None
*
* @note It is mandatory to disable the peripheral to use this function.
*/
void LPTIM_SelectULPTIMClockPolarity(LPTIM_TypeDef* LPTIMx, uint32_t LPTIM_ClockPolarity)
{
uint32_t tmpreg1 = 0;
/* Check the parameters */
assert_param(IS_LPTIM_ALL_PERIPH(LPTIMx));
assert_param(IS_LPTIM_CLOCK_POLARITY(LPTIM_ClockPolarity));
/* Get the LPTIMx CFGR value */
tmpreg1 = LPTIMx->CFGR;
/* Clear the CKPOL bits */
tmpreg1 &= ~(LPTIM_CFGR_CKPOL);
/* Set or Reset the PRESC bits */
tmpreg1 |= LPTIM_ClockPolarity;
/* Write to LPTIMx CFGR */
LPTIMx->CFGR = tmpreg1;
}
/**
* @brief Configures the Clock Prescaler.
* @param LPTIMx: where x can be 1.
* @param LPTIM_Prescaler: the selected clock prescaler.
* This parameter can be:
* @arg LPTIM_Prescaler_DIV1 : Counter Clock = LPTIM Clock / 1
* @arg LPTIM_Prescaler_DIV2 : Counter Clock = LPTIM Clock / 2
* @arg LPTIM_Prescaler_DIV4 : Counter Clock = LPTIM Clock / 4
* @arg LPTIM_Prescaler_DIV8 : Counter Clock = LPTIM Clock / 8
* @arg LPTIM_Prescaler_DIV16 : Counter Clock = LPTIM Clock / 16
* @arg LPTIM_Prescaler_DIV32 : Counter Clock = LPTIM Clock / 32
* @arg LPTIM_Prescaler_DIV64 : Counter Clock = LPTIM Clock / 64
* @arg LPTIM_Prescaler_DIV128 : Counter Clock = LPTIM Clock / 128
* @retval None
*
* @note It is mandatory to disable the peripheral to use this function.
*/
void LPTIM_ConfigPrescaler(LPTIM_TypeDef* LPTIMx, uint32_t LPTIM_Prescaler)
{
uint32_t tmpreg1 = 0;
/* Check the parameters */
assert_param(IS_LPTIM_ALL_PERIPH(LPTIMx));
assert_param(IS_LPTIM_CLOCK_PRESCALER(LPTIM_Prescaler));
/* Get the LPTIMx CFGR value */
tmpreg1 = LPTIMx->CFGR;
/* Clear the PRESC bits */
tmpreg1 &= ~(LPTIM_CFGR_PRESC);
/* Set or Reset the PRESC bits */
tmpreg1 |= LPTIM_Prescaler;
/* Write to LPTIMx CFGR */
LPTIMx->CFGR = tmpreg1;
}
/**
* @brief Selects the trigger source for the counter and its polarity.
* @param LPTIMx: where x can be 1.
* @param LPTIM_ExtTRGSource: the selected external trigger.
* This parameter can be:
* @arg LPTIM_ExtTRGSource_Trig0 : ext_trig0
* @arg LPTIM_ExtTRGSource_Trig1 : ext_trig1
* @arg LPTIM_ExtTRGSource_Trig2 : ext_trig2
* @arg LPTIM_ExtTRGSource_Trig3 : ext_trig3
* @arg LPTIM_ExtTRGSource_Trig4 : ext_trig4
* @arg LPTIM_ExtTRGSource_Trig5 : ext_trig5
* @arg LPTIM_ExtTRGSource_Trig6 : ext_trig6
* @arg LPTIM_ExtTRGSource_Trig7 : ext_trig7
* @param LPTIM_ExtTRGPolarity: the selected external trigger.
* This parameter can be:
* @arg LPTIM_ExtTRGPolarity_RisingEdge : Rising edge polarity selected
* @arg LPTIM_ExtTRGPolarity_FallingEdge : Falling edge polarity selected
* @arg LPTIM_ExtTRGPolarity_BothEdges : Both edges polarity selected
* @retval None
*
* @note It is mandatory to disable the peripheral to use this function.
*/
void LPTIM_ConfigExternalTrigger(LPTIM_TypeDef* LPTIMx, uint32_t LPTIM_ExtTRGSource, uint32_t LPTIM_ExtTRGPolarity)
{
uint32_t tmpreg1 = 0;
/* Check the parameters */
assert_param(IS_LPTIM_ALL_PERIPH(LPTIMx));
assert_param(IS_LPTIM_EXT_TRG_SOURCE(LPTIM_ExtTRGSource));
assert_param(IS_LPTIM_EXT_TRG_POLARITY(LPTIM_ExtTRGPolarity));
/* Get the LPTIMx CFGR value */
tmpreg1 = LPTIMx->CFGR;
/* Clear the TRIGEN and TRIGSEL bits */
tmpreg1 &= CFGR_TRIG_AND_POL_CLEAR_MASK;
/* Set or Reset the TRIGEN and TRIGSEL bits */
tmpreg1 |= (LPTIM_ExtTRGSource | LPTIM_ExtTRGPolarity);
/* Write to LPTIMx CFGR */
LPTIMx->CFGR = tmpreg1;
}
/**
* @brief Selects a software start of the counter.
* @param LPTIMx: where x can be 1.
* @retval None
*
* @note It is mandatory to disable the peripheral to use this function.
*/
void LPTIM_SelectSoftwareStart(LPTIM_TypeDef* LPTIMx)
{
/* Check the parameters */
assert_param(IS_LPTIM_ALL_PERIPH(LPTIMx));
/* Reset the TRIGEN bits to allow a software start */
LPTIMx->CFGR &= ~(LPTIM_CFGR_TRIGEN);
}
/**
* @brief Configures the digital filter for trigger by determining the number of consecutive
* samples at the specified level to detect a correct transition.
* @param LPTIMx: where x can be 1.
* @param LPTIM_TrigSampleTime: the number of samples to detect a valid transition.
* This parameter can be:
* @arg LPTIM_TrigSampleTime_DirectTransistion : Event is detected on input transitions
* @arg LPTIM_TrigSampleTime_2Transistions : Event is detected after 2 consecutive samples at the active level
* @arg LPTIM_TrigSampleTime_4Transistions : Event is detected after 4 consecutive samples at the active level
* @arg LPTIM_TrigSampleTime_8Transistions : Event is detected after 8 consecutive samples at the active level
* @retval None
*
* @note It is mandatory to disable the peripheral to use this function.
* @note An auxiliary clock must be present to use this feature.
*/
void LPTIM_ConfigTriggerGlitchFilter(LPTIM_TypeDef* LPTIMx, uint32_t LPTIM_TrigSampleTime)
{
uint32_t tmpreg1 = 0;
/* Check the parameters */
assert_param(IS_LPTIM_ALL_PERIPH(LPTIMx));
assert_param(IS_LPTIM_TRIG_SAMPLE_TIME(LPTIM_TrigSampleTime));
/* Get the LPTIMx CFGR value */
tmpreg1 = LPTIMx->CFGR;
/* Clear the TRGFLT bits */
tmpreg1 &= ~(LPTIM_CFGR_TRGFLT);
/* Set or Reset the TRGFLT bits according to LPTIM_TrigSampleTime */
tmpreg1 |= (LPTIM_TrigSampleTime);
/* Write to LPTIMx CFGR */
LPTIMx->CFGR = tmpreg1;
}
/**
* @brief Configures the digital filter for the external clock by determining the number
of consecutive samples at the specified level to detect a correct transition.
* @param LPTIMx: where x can be 1.
* @param LPTIM_ClockSampleTime: the number of samples to detect a valid transition.
* This parameter can be:
* @arg LPTIM_ClockSampleTime_DirectTransistion : Event is detected on input transitions
* @arg LPTIM_ClockSampleTime_2Transistions : Event is detected after 2 consecutive samples at the active level
* @arg LPTIM_ClockSampleTime_4Transistions : Event is detected after 4 consecutive samples at the active level
* @arg LPTIM_ClockSampleTime_8Transistions : Event is detected after 8 consecutive samples at the active level
* @retval None
*
* @note It is mandatory to disable the peripheral to use this function.
* @note An auxiliary clock must be present to use this feature.
*/
void LPTIM_ConfigClockGlitchFilter(LPTIM_TypeDef* LPTIMx, uint32_t LPTIM_ClockSampleTime)
{
uint32_t tmpreg1 = 0;
/* Check the parameters */
assert_param(IS_LPTIM_ALL_PERIPH(LPTIMx));
assert_param(IS_LPTIM_CLOCK_SAMPLE_TIME(LPTIM_ClockSampleTime));
/* Get the LPTIMx CFGR value */
tmpreg1 = LPTIMx->CFGR;
/* Clear the CKFLT bits */
tmpreg1 &= ~(LPTIM_CFGR_CKFLT);
/* Set or Reset the CKFLT bits according to LPTIM_ClockSampleTime */
tmpreg1 |= LPTIM_ClockSampleTime;
/* Write to LPTIMx CFGR */
LPTIMx->CFGR = tmpreg1;
}
/**
* @brief Selects an operating mode.
* @param LPTIMx: where x can be 1.
* @param LPTIM_Mode: the selected mode.
* This parameter can be:
* @arg LPTIM_Mode_Continuous : Timer starts in Continuous mode
* @arg LPTIM_Mode_Single : Timer will starts in Single mode
* @retval None
*/
void LPTIM_SelectOperatingMode(LPTIM_TypeDef* LPTIMx, uint32_t LPTIM_Mode)
{
/* Check the parameters */
assert_param(IS_LPTIM_ALL_PERIPH(LPTIMx));
assert_param(IS_LPTIM_MODE(LPTIM_Mode));
if(LPTIM_Mode == LPTIM_Mode_Continuous)
{
/* Set the CNTSTRT to select the continuous start*/
LPTIMx->CR |= LPTIM_Mode_Continuous;
}
else if(LPTIM_Mode == LPTIM_Mode_Single)
{
/* Set the SNGSTRT to select the continuous start*/
LPTIMx->CR |= LPTIM_Mode_Single;
}
}
/**
* @brief Enables or disables the Timeout function.
* @param LPTIMx: where x can be 1.
* @param NewState: new state of the Timeout function.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*
* @note It is mandatory to disable the peripheral to use this function.
*/
void LPTIM_TimoutCmd(LPTIM_TypeDef* LPTIMx, FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_LPTIM_ALL_PERIPH(LPTIMx));
assert_param(IS_FUNCTIONAL_STATE(NewState));
if(NewState != DISABLE)
{
/* Set the TIMOUT bit */
LPTIMx->CFGR |= LPTIM_CFGR_TIMOUT;
}
else
{
/* Reset the TIMOUT bit */
LPTIMx->CFGR &= ~(LPTIM_CFGR_TIMOUT);
}
}
/**
* @brief Configures the Waveform shape.
* @param LPTIMx: where x can be 1.
* @param LPTIM_Waveform: the selected waveform shape.
* This parameter can be:
* @arg LPTIM_Waveform_PWM_OnePulse : PWM/One Pulse is selected
* @arg LPTIM_Waveform_SetOnce : Set once is selected
* @retval None
*
* @note It is mandatory to disable the peripheral to use this function.
*/
void LPTIM_ConfigWaveform(LPTIM_TypeDef* LPTIMx, uint32_t LPTIM_Waveform)
{
/* Check the parameters */
assert_param(IS_LPTIM_ALL_PERIPH(LPTIMx));
assert_param(IS_LPTIM_WAVEFORM(LPTIM_Waveform));
/* Clear the WAVE bit */
LPTIMx->CFGR &= ~(LPTIM_CFGR_CKFLT);
/* Set or Reset the WAVE bit according to LPTIM_Waveform */
LPTIMx->CFGR |= (LPTIM_Waveform);
}
/**
* @brief Configures the Autoreload and Compare registers update mode.
* @param LPTIMx: where x can be 1.
* @param LPTIM_Update: The selected update mode.
* This parameter can be:
* @arg LPTIM_Update_Immediate : Registers updated after APB write
* @arg LPTIM_Update_EndOfPeriod : Registers updated at the end of current timer preload
* @retval None
*
* @note It is mandatory to disable the peripheral to use this function.
*/
void LPTIM_ConfigUpdate(LPTIM_TypeDef* LPTIMx, uint32_t LPTIM_Update)
{
/* Check the parameters */
assert_param(IS_LPTIM_ALL_PERIPH(LPTIMx));
assert_param(IS_LPTIM_UPDATE(LPTIM_Update));
/* Clear the PRELOAD bit */
LPTIMx->CFGR &= ~(LPTIM_CFGR_PRELOAD);
/* Set or Reset the PRELOAD bit according to LPTIM_Update */
LPTIMx->CFGR |= (LPTIM_Update);
}
/**
* @brief Writes the passed parameter in the Autoreload register.
* @param LPTIMx: where x can be 1.
* @param LPTIM_Autoreload: The Autoreload value.
* This parameter must be a value between 0x0000 and 0xFFFF
* @retval None
*/
void LPTIM_SetAutoreloadValue(LPTIM_TypeDef* LPTIMx, uint32_t LPTIM_Autoreload)
{
/* Check the parameters */
assert_param(IS_LPTIM_ALL_PERIPH(LPTIMx));
assert_param(IS_LPTIM_AUTORELOAD(LPTIM_Autoreload));
/* Write LPTIM_Autoreload in Autoreload register */
LPTIMx->ARR = LPTIM_Autoreload;
}
/**
* @brief Writes the passed parameter in the Compare register.
* @param LPTIMx: where x can be 1.
* @param LPTIM_Compare: The Compare value.
* This parameter must be a value between 0x0000 and 0xFFFF
* @retval None
*/
void LPTIM_SetCompareValue(LPTIM_TypeDef* LPTIMx, uint32_t LPTIM_Compare)
{
/* Check the parameters */
assert_param(IS_LPTIM_ALL_PERIPH(LPTIMx));
assert_param(IS_LPTIM_COMPARE(LPTIM_Compare));
/* Write LPTIM_Compare in Compare register */
LPTIMx->CMP = LPTIM_Compare;
}
/**
* @brief Enables or disables the Counter mode. When the Counter mode is enabled,
* the counter is incremented each valid event on ULPTIM
* @param LPTIMx: where x can be 1.
* @param NewState: new state of the Counter mode.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*
* @note It is mandatory to disable the peripheral to use this function.
*/
void LPTIM_SelectCounterMode(LPTIM_TypeDef* LPTIMx, FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_LPTIM_ALL_PERIPH(LPTIMx));
assert_param(IS_FUNCTIONAL_STATE(NewState));
if(NewState != DISABLE)
{
/* Set the COUNTMODE bit */
LPTIMx->CFGR |= LPTIM_CFGR_COUNTMODE;
}
else
{
/* Reset the COUNTMODE bit */
LPTIMx->CFGR &= ~(LPTIM_CFGR_COUNTMODE);
}
}
/**
* @brief Enables or disables the Encoder mode.
* @param LPTIMx: where x can be 1.
* @param NewState: New state of the encoder mode.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*
* @note It is mandatory to disable the peripheral to use this function.
*/
void LPTIM_SelectEncoderMode(LPTIM_TypeDef* LPTIMx, FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_LPTIM_ALL_PERIPH(LPTIMx));
assert_param(IS_FUNCTIONAL_STATE(NewState));
if(NewState != DISABLE)
{
/* Set the ENC bit */
LPTIMx->CFGR |= LPTIM_CFGR_ENC;
}
else
{
/* Reset the ENC bit */
LPTIMx->CFGR &= ~(LPTIM_CFGR_ENC);
}
}
/**
* @brief Gets the LPTIMx counter value.
* @param LPTIMx: where x can be 1.
* @retval Counter Register value
*/
uint32_t LPTIM_GetCounterValue(LPTIM_TypeDef* LPTIMx)
{
/* Check the parameters */
assert_param(IS_LPTIM_ALL_PERIPH(LPTIMx));
/* Get the Counter Register value */
return LPTIMx->CNT;
}
/**
* @brief Gets the LPTIMx Autoreload value.
* @param LPTIMx: where x can be 1.
* @retval Counter Register value
*/
uint32_t LPTIM_GetAutoreloadValue(LPTIM_TypeDef* LPTIMx)
{
/* Check the parameters */
assert_param(IS_LPTIM_ALL_PERIPH(LPTIMx));
/* Get the Counter Register value */
return LPTIMx->ARR;
}
/**
* @brief Gets the LPTIMx Compare value.
* @param LPTIMx: where x can be 1.
* @retval Counter Register value
*/
uint32_t LPTIM_GetCompareValue(LPTIM_TypeDef* LPTIMx)
{
/* Check the parameters */
assert_param(IS_LPTIM_ALL_PERIPH(LPTIMx));
/* Get the Counter Register value */
return LPTIMx->CMP;
}
/**
* @brief LPTIM Input 1 Remap.
* @param LPTIMx: where x can be 1.
* @param LPTIM_OPTR :
* This Parameter can be :
* @arg LPTIM_OP_PAD_AF : Port B5 on AF1 or Port C0 on AF1 for input timer
* @arg LPTIM_OP_PAD_PA4 : Input remapped to Port A4
* @arg RCC_LPTIM1CLKSOURCE_LSI : Input remapped to Port B9
* @arg LPTIM_OP_TIM_DAC : Input coming from timer 6 output (for encoder mode)
* @retval Counter Register value
*/
void LPTIM_RemapConfig(LPTIM_TypeDef* LPTIMx, uint32_t LPTIM_OPTR)
{
/* Check the parameters */
assert_param(IS_LPTIM_ALL_PERIPH(LPTIMx));
/* Get the Counter Register value */
LPTIMx->OR = LPTIM_OPTR;
}
/**
* @}
*/
/** @defgroup LPTIM_Group3 Interrupts and flags management functions
* @brief Interrupts and flags management functions
*
@verbatim
===============================================================================
Interrupts and flags management functions
===============================================================================
This section provides functions allowing to configure the LPTIM Interrupts, get
the status and clear flags bits.
The LPTIM provides 7 Flags and Interrupts sources (2 flags and Interrupt sources
are available only on LPTIM peripherals equipped with encoder mode interface)
Flags and Interrupts sources:
=============================
1. Compare match.
2. Auto-reload match.
3. External trigger event.
4. Autoreloaded register write completed.
5. Compare register write completed.
6. Direction change: from up to down [Available only for LPTIM peripheral with
encoder mode module]
7. Direction change: from down to up [Available only for LPTIM peripheral with
encoder mode module]
- To enable a specific interrupt source, use "LPTIM_ITConfig" function.
- To check if an interrupt was occurred, call "LPTIM_GetITStatus" function and read
the returned value.
- To get a flag status, call the "LPTIM_GetFlagStatus" function and read the returned
value.
- To clear a flag or an interrupt, use LPTIM_ClearFlag function with the
corresponding flag (interrupt).
@endverbatim
* @{
*/
/**
* @brief Enables or disables the specified LPTIM interrupts.
* @param LPTIMx: where x can be 1.
* @param LPTIM_IT: specifies the TIM interrupts sources to be enabled or disabled.
* This parameter can be any combination of the following values:
* @arg LPTIM_IT_DOWN: Counter direction change up to down Interrupt source
* @arg LPTIM_IT_UP: Counter direction change down to up Interrupt source
* @arg LPTIM_IT_ARROK: Autoreload register update OK Interrupt source
* @arg LPTIM_IT_CMPOK: Compare register update OK Interrupt source
* @arg LPTIM_IT_EXTTRIG: External trigger edge event Interrupt source
* @arg LPTIM_IT_ARRM: Autoreload match Interrupt source
* @arg LPTIM_IT_CMPM: Compare match Interrupt source
* @note LPTIM_IT_DOWN is available only for LPTIM1.
* @note LPTIM_IT_UP is available only for LPTIM1.
* @param NewState: new state of the TIM interrupts.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*
* @note It is mandatory to disable the peripheral to use this function.
*/
void LPTIM_ITConfig(LPTIM_TypeDef* LPTIMx, uint32_t LPTIM_IT, FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_LPTIM_ALL_PERIPH(LPTIMx));
assert_param(IS_LPTIM_IT(LPTIM_IT));
assert_param(IS_FUNCTIONAL_STATE(NewState));
if(NewState != DISABLE)
{
/* Enable the Interrupt sources */
LPTIMx->IER |= LPTIM_IT;
}
else
{
/* Disable the Interrupt sources */
LPTIMx->IER &= ~(LPTIM_IT);
}
}
/**
* @brief Checks whether the specified LPTIM flag is set or not.
* @param LPTIMx: where x can be 1.
* @param LPTIM_FLAG: specifies the flag to check.
* This parameter can be any combination of the following values:
* @arg LPTIM_FLAG_DOWN: Counter direction change up Flag
* @arg LPTIM_FLAG_UP: Counter direction change down to up Flag
* @arg LPTIM_FLAG_ARROK: Autoreload register update OK Flag
* @arg LPTIM_FLAG_CMPOK: Compare register update OK Flag
* @arg LPTIM_FLAG_EXTTRIG: External trigger edge event Flag
* @arg LPTIM_FLAG_ARRM: Autoreload match Flag
* @arg LPTIM_FLAG_CMPM: Compare match Flag
* @note LPTIM_Flag_DOWN is generated only for LPTIM1.
* @note LPTIM_Flag_UP is generated only for LPTIM1.
* @param NewState: new state of the TIM interrupts.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
FlagStatus LPTIM_GetFlagStatus(LPTIM_TypeDef* LPTIMx, uint32_t LPTIM_FLAG)
{
ITStatus bitstatus = RESET;
/* Check the parameters */
assert_param(IS_LPTIM_ALL_PERIPH(LPTIMx));
assert_param(IS_LPTIM_GET_FLAG(LPTIM_FLAG));
if((LPTIMx->ISR & LPTIM_FLAG) != (RESET))
{
bitstatus = SET;
}
else
{
bitstatus = RESET;
}
return bitstatus;
}
/**
* @brief Clears the LPTIMx's pending flag.
* @param LPTIMx: where x can be 1.
* @param LPTIM_CLEARF: specifies the pending bit to clear.
* This parameter can be any combination of the following values:
* @arg LPTIM_CLEARF_DOWN: Counter direction change up Clear Flag
* @arg LPTIM_CLEARF_UP: Counter direction change down to up Clear Flag
* @arg LPTIM_CLEARF_ARROK: Autoreload register update OK Clear Flag
* @arg LPTIM_CLEARF_CMPOK: Compare register update OK Clear Flag
* @arg LPTIM_CLEARF_EXTTRIG: External trigger edge event Clear Flag
* @arg LPTIM_CLEARF_ARRM: Autoreload match Clear Flag
* @arg LPTIM_CLEARF_CMPM: Compare match Clear Flag
* @note LPTIM_Flag_DOWN is generated only for LPTIM1.
* @note LPTIM_Flag_UP is generated only for LPTIM1.
* @retval None
*/
void LPTIM_ClearFlag(LPTIM_TypeDef* LPTIMx, uint32_t LPTIM_CLEARF)
{
/* Check the parameters */
assert_param(IS_LPTIM_ALL_PERIPH(LPTIMx));
assert_param(IS_LPTIM_CLEAR_FLAG(LPTIM_CLEARF));
/* Clear the IT pending Bit */
LPTIMx->ICR |= LPTIM_CLEARF;
}
/**
* @brief Check whether the specified LPTIM interrupt has occurred or not.
* @param LPTIMx: where x can be 1.
* @param LPTIM_IT: specifies the LPTIM interrupt source to check.
* @arg LPTIM_IT_DOWN: Counter direction change up to down Interrupt source
* @arg LPTIM_IT_UP: Counter direction change down to up Interrupt source
* @arg LPTIM_IT_ARROK: Autoreload register update OK Interrupt source
* @arg LPTIM_IT_CMPOK: Compare register update OK Interrupt source
* @arg LPTIM_IT_EXTTRIG: External trigger edge event Interrupt source
* @arg LPTIM_IT_ARRM: Autoreload match Interrupt source
* @arg LPTIM_IT_CMPM: Compare match Interrupt source
* @retval The new state of LPTIM_IT (SET or RESET).
*/
ITStatus LPTIM_GetITStatus(LPTIM_TypeDef* LPTIMx, uint32_t LPTIM_IT)
{
ITStatus bitstatus = RESET;
uint32_t itstatus = 0x0, itenable = 0x0;
/* Check the parameters */
assert_param(IS_LPTIM_ALL_PERIPH(LPTIMx));
assert_param(IS_LPTIM_IT(LPTIM_IT));
/* Get the Interrupt Status bit value */
itstatus = LPTIMx->ISR & LPTIM_IT;
/* Check if the Interrupt is enabled */
itenable = LPTIMx->IER & LPTIM_IT;
if((itstatus != RESET) && (itenable != RESET))
{
bitstatus = SET;
}
else
{
bitstatus = RESET;
}
return bitstatus;
}
/**
* @}
*/
/**
* @}
*/
#endif /* STM32F410xx */
/**
* @}
*/
/**
* @}
*/
/************************ (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

View file

@ -0,0 +1,911 @@
/**
******************************************************************************
* @file stm32f4xx_qspi.c
* @author MCD Application Team
* @version V1.6.1
* @date 21-October-2015
* @brief This file provides firmware functions to manage the following
* functionalities of the Serial peripheral interface (QSPI):
* + Initialization and Configuration
* + Indirect Data Read/Write functions
* + Memory Mapped Mode Data Read functions
* + Automatic Polling functions
* + DMA transfers management
* + Interrupts and flags management
*
* @verbatim
*
===============================================================================
##### How to use this driver #####
===============================================================================
[..]
(#) Enable peripheral clock using RCC_AHB3PeriphClockCmd(RCC_AHB3Periph_QSPI,ENABLE);
function.
(#) Enable CLK, BK1_IO0, BK1_IO1, BK1_IO2, BK1_IO3, BK1_NCS, BK2_IO0,
BK2_IO1, BK2_IO2, BK2_IO3 and BK2_NCS GPIO clocks using
RCC_AHB1PeriphClockCmd() function.
(#) Peripherals alternate function:
(++) Connect the pin to the desired peripherals' Alternate
Function (AF) using GPIO_PinAFConfig() function.
(++) Configure the desired pin in alternate function by:
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.
(#) Program the Flash Size, CS High Time, Sample Shift, Prescaler, Clock Mode
values using the QSPI_Init() function.
(#) Enable QSPI using QSPI_Cmd() function.
(#) Set QSPI Data Length using QSPI_SetDataLength() function.
(#) Configure the FIFO threshold using QSPI_SetFIFOThreshold() to select
at which threshold the FTF event is generated.
(#) Enable the NVIC and the corresponding interrupt using the function
QSPI_ITConfig() if you need to use interrupt mode.
(#) When using the DMA mode
(++) Configure the DMA using DMA_Init() function.
(++) Active the needed channel Request using SPI_I2S_DMACmd() function.
(#) Enable the SPI using the QSPI_DMACmd() function.
(#) Enable the DMA using the DMA_Cmd() function when using DMA mode.
@endverbatim
*
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2015 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 "stm32f4xx_qspi.h"
/** @addtogroup STM32F4xx_StdPeriph_Driver
* @{
*/
/** @defgroup QSPI
* @brief QSPI driver modules
* @{
*/
#if defined(STM32F446xx) || defined(STM32F469_479xx)
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
#define QSPI_CR_CLEAR_MASK 0x00FFFFCF
#define QSPI_DCR_CLEAR_MASK 0xFFE0F7FE
#define QSPI_CCR_CLEAR_MASK 0x90800000
#define QSPI_PIR_CLEAR_MASK 0xFFFF0000
#define QSPI_LPTR_CLEAR_MASK 0xFFFF0000
#define QSPI_CCR_CLEAR_INSTRUCTION_MASK 0xFFFFFF00
#define QSPI_CCR_CLEAR_DCY_MASK 0xFFC3FFFF
#define QSPI_CR_CLEAR_FIFOTHRESHOLD_MASK 0xFFFFF0FF
#define QSPI_CR_INTERRUPT_MASK 0x001F0000
#define QSPI_SR_INTERRUPT_MASK 0x0000001F
#define QSPI_FSR_INTERRUPT_MASK 0x0000001B
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/* Initialization and Configuration functions *********************************/
/** @defgroup <PPP>_Private_Functions
* @{
*/
/** @defgroup <PPP>_Group1 Function Group1 Name
* @brief Function group1 name description (copied from the header file)
*
@verbatim
===============================================================================
##### < Function group1 name (copied from the header file)
Note: do not use "Peripheral" or "PPP" word in the function group name > #####
===============================================================================
[..] < OPTIONAL:
Add here the most important information to know about the IP features
covered by this group of function.
For system IPs, this section contains how to use this group API.
>
@endverbatim
* @{
*/
/**
* @brief Deinitializes the QSPI peripheral registers to their default
* reset values.
* @param None
* @retval None
*/
void QSPI_DeInit(void)
{
/* Enable QSPI reset state */
RCC_AHB3PeriphResetCmd(RCC_AHB3Periph_QSPI, ENABLE);
/* Release QSPI from reset state */
RCC_AHB3PeriphResetCmd(RCC_AHB3Periph_QSPI, DISABLE);
}
/**
* @brief Fills each QSPI_InitStruct member with its default value.
* @param QSPI_InitStruct: pointer to a QSPI_InitTypeDef structure which will be initialized.
* @retval None
*/
void QSPI_StructInit(QSPI_InitTypeDef* QSPI_InitStruct)
{
/*--------- Reset QSPI init structure parameters default values ------------*/
/* Initialize the QSPI_SShift member */
QSPI_InitStruct->QSPI_SShift = QSPI_SShift_NoShift ;
/* Initialize the QSPI_Prescaler member */
QSPI_InitStruct->QSPI_Prescaler = 0 ;
/* Initialize the QSPI_CKMode member */
QSPI_InitStruct->QSPI_CKMode = QSPI_CKMode_Mode0 ;
/* Initialize the QSPI_CSHTime member */
QSPI_InitStruct->QSPI_CSHTime = QSPI_CSHTime_1Cycle ;
/* Initialize the QSPI_FSize member */
QSPI_InitStruct->QSPI_FSize = 0 ;
/* Initialize the QSPI_FSelect member */
QSPI_InitStruct->QSPI_FSelect = QSPI_FSelect_1 ;
/* Initialize the QSPI_DFlash member */
QSPI_InitStruct->QSPI_DFlash = QSPI_DFlash_Disable ;
}
/**
* @brief Fills each QSPI_ComConfig_InitStruct member with its default value.
* @param QSPI_ComConfig_InitStruct: pointer to a QSPI_ComConfig_InitTypeDef structure which will be initialized.
* @retval None
*/
void QSPI_ComConfig_StructInit(QSPI_ComConfig_InitTypeDef* QSPI_ComConfig_InitStruct)
{
/*--------- Reset QSPI ComConfig init structure parameters default values ------------*/
/* Set QSPI Communication configuration structure parameters default values */
/* Initialize the QSPI_ComConfig_DDRMode member */
QSPI_ComConfig_InitStruct->QSPI_ComConfig_DDRMode = QSPI_ComConfig_DDRMode_Disable ;
/* Initialize the QSPI_ComConfig_DHHC member */
QSPI_ComConfig_InitStruct->QSPI_ComConfig_DHHC = QSPI_ComConfig_DHHC_Disable ;
/* Initialize the QSPI_ComConfig_SIOOMode member */
QSPI_ComConfig_InitStruct->QSPI_ComConfig_SIOOMode = QSPI_ComConfig_SIOOMode_Disable ;
/* Initialize the QSPI_ComConfig_FMode member */
QSPI_ComConfig_InitStruct->QSPI_ComConfig_FMode = QSPI_ComConfig_FMode_Indirect_Write ;
/* Initialize the QSPI_ComConfig_DMode member */
QSPI_ComConfig_InitStruct->QSPI_ComConfig_DMode = QSPI_ComConfig_DMode_NoData ;
/* Initialize the QSPI_ComConfig_DummyCycles member */
QSPI_ComConfig_InitStruct->QSPI_ComConfig_DummyCycles = 0 ;
/* Initialize the QSPI_ComConfig_ABSize member */
QSPI_ComConfig_InitStruct->QSPI_ComConfig_ABSize = QSPI_ComConfig_ABSize_8bit ;
/* Initialize the QSPI_ComConfig_ABMode member */
QSPI_ComConfig_InitStruct->QSPI_ComConfig_ABMode = QSPI_ComConfig_ABMode_NoAlternateByte ;
/* Initialize the QSPI_ComConfig_ADSize member */
QSPI_ComConfig_InitStruct->QSPI_ComConfig_ADSize = QSPI_ComConfig_ADSize_8bit ;
/* Initialize the QSPI_ComConfig_ADMode member */
QSPI_ComConfig_InitStruct->QSPI_ComConfig_ADMode = QSPI_ComConfig_ADMode_NoAddress ;
/* Initialize the QSPI_ComConfig_IMode member */
QSPI_ComConfig_InitStruct->QSPI_ComConfig_IMode = QSPI_ComConfig_IMode_NoInstruction ;
/* Initialize the QSPI_ComConfig_Ins member */
QSPI_ComConfig_InitStruct->QSPI_ComConfig_Ins = 0 ;
}
/**
* @brief Initializes the QSPI peripheral according to the specified
* parameters in the QSPI_InitStruct.
* @param QSPI_InitStruct: pointer to a QSPI_InitTypeDef structure that
* contains the configuration information for the specified QSPI peripheral.
* @retval None
*/
void QSPI_Init(QSPI_InitTypeDef* QSPI_InitStruct)
{
uint32_t tmpreg = 0;
/* Check the QSPI parameters */
assert_param(IS_QSPI_SSHIFT(QSPI_InitStruct->QSPI_SShift));
assert_param(IS_QSPI_PRESCALER(QSPI_InitStruct->QSPI_Prescaler));
assert_param(IS_QSPI_CKMODE(QSPI_InitStruct->QSPI_CKMode));
assert_param(IS_QSPI_CSHTIME(QSPI_InitStruct->QSPI_CSHTime));
assert_param(IS_QSPI_FSIZE(QSPI_InitStruct->QSPI_FSize));
assert_param(IS_QSPI_FSEL(QSPI_InitStruct->QSPI_FSelect));
assert_param(IS_QSPI_DFM(QSPI_InitStruct->QSPI_DFlash));
/*------------------------ QSPI CR Configuration ------------------------*/
/* Get the QUADSPI CR1 value */
tmpreg = QUADSPI->CR;
/* Clear PRESCALER and SSHIFT bits */
tmpreg &= QSPI_CR_CLEAR_MASK;
/* Configure QUADSPI: Prescaler and Sample Shift */
tmpreg |= (uint32_t)(((QSPI_InitStruct->QSPI_Prescaler)<<24)
|(QSPI_InitStruct->QSPI_SShift)
|(QSPI_InitStruct->QSPI_FSelect)
|(QSPI_InitStruct->QSPI_DFlash));
/* Write to QUADSPI CR */
QUADSPI->CR = tmpreg;
/*------------------------ QUADSPI DCR Configuration ------------------------*/
/* Get the QUADSPI DCR value */
tmpreg = QUADSPI->DCR;
/* Clear FSIZE, CSHT and CKMODE bits */
tmpreg &= QSPI_DCR_CLEAR_MASK;
/* Configure QSPI: Flash Size, Chip Select High Time and Clock Mode */
tmpreg |= (uint32_t)(((QSPI_InitStruct->QSPI_FSize)<<16)
|(QSPI_InitStruct->QSPI_CSHTime)
|(QSPI_InitStruct->QSPI_CKMode));
/* Write to QSPI DCR */
QUADSPI->DCR = tmpreg;
}
/**
* @brief Initializes the QSPI CCR according to the specified
* parameters in the QSPI_ComConfig_InitStruct.
* @param QSPI_ComConfig_InitStruct: pointer to a QSPI_ComConfig_InitTypeDef structure that
* contains the communication configuration informations about QSPI peripheral.
* @retval None
*/
void QSPI_ComConfig_Init(QSPI_ComConfig_InitTypeDef* QSPI_ComConfig_InitStruct)
{
uint32_t tmpreg = 0;
/* Check the QSPI Communication Control parameters */
assert_param(IS_QSPI_FMODE (QSPI_ComConfig_InitStruct->QSPI_ComConfig_FMode));
assert_param(IS_QSPI_SIOOMODE (QSPI_ComConfig_InitStruct->QSPI_ComConfig_SIOOMode));
assert_param(IS_QSPI_DMODE (QSPI_ComConfig_InitStruct->QSPI_ComConfig_DMode));
assert_param(IS_QSPI_DCY (QSPI_ComConfig_InitStruct->QSPI_ComConfig_DummyCycles));
assert_param(IS_QSPI_ABSIZE (QSPI_ComConfig_InitStruct->QSPI_ComConfig_ABSize));
assert_param(IS_QSPI_ABMODE (QSPI_ComConfig_InitStruct->QSPI_ComConfig_ABMode));
assert_param(IS_QSPI_ADSIZE (QSPI_ComConfig_InitStruct->QSPI_ComConfig_ADSize));
assert_param(IS_QSPI_ADMODE (QSPI_ComConfig_InitStruct->QSPI_ComConfig_ADMode));
assert_param(IS_QSPI_IMODE (QSPI_ComConfig_InitStruct->QSPI_ComConfig_IMode));
assert_param(IS_QSPI_INSTRUCTION (QSPI_ComConfig_InitStruct->QSPI_ComConfig_Ins));
assert_param(IS_QSPI_DDRMODE (QSPI_ComConfig_InitStruct->QSPI_ComConfig_DDRMode));
assert_param(IS_QSPI_DHHC (QSPI_ComConfig_InitStruct->QSPI_ComConfig_DHHC));
/*------------------------ QUADSPI CCR Configuration ------------------------*/
/* Get the QUADSPI CCR value */
tmpreg = QUADSPI->CCR;
/* Clear FMODE Mode bits */
tmpreg &= QSPI_CCR_CLEAR_MASK;
/* Configure QUADSPI: CCR Configuration */
tmpreg |= (uint32_t)( (QSPI_ComConfig_InitStruct->QSPI_ComConfig_FMode)
| (QSPI_ComConfig_InitStruct->QSPI_ComConfig_DDRMode)
| (QSPI_ComConfig_InitStruct->QSPI_ComConfig_DHHC)
| (QSPI_ComConfig_InitStruct->QSPI_ComConfig_SIOOMode)
| (QSPI_ComConfig_InitStruct->QSPI_ComConfig_DMode)
| (QSPI_ComConfig_InitStruct->QSPI_ComConfig_ABSize)
| (QSPI_ComConfig_InitStruct->QSPI_ComConfig_ABMode)
| (QSPI_ComConfig_InitStruct->QSPI_ComConfig_ADSize)
| (QSPI_ComConfig_InitStruct->QSPI_ComConfig_ADMode)
| (QSPI_ComConfig_InitStruct->QSPI_ComConfig_IMode)
| (QSPI_ComConfig_InitStruct->QSPI_ComConfig_Ins)
|((QSPI_ComConfig_InitStruct->QSPI_ComConfig_DummyCycles)<<18));
/* Write to QUADSPI DCR */
QUADSPI->CCR = tmpreg;
}
/**
* @brief Enables or disables QSPI peripheral.
* @param NewState: new state of the QSPI peripheral.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void QSPI_Cmd(FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
/* Enable QSPI peripheral */
QUADSPI->CR |= QUADSPI_CR_EN;
}
else
{
/* Disable QSPI peripheral */
QUADSPI->CR &= ~ QUADSPI_CR_EN;
}
}
/**
* @brief Configure the QSPI Automatic Polling Mode.
* @param QSPI_Match: Value to be compared with the masked status register to get a match.
* This parameter can be any value between 0x00000000 and 0xFFFFFFFF.
* @param QSPI_Mask: Mask to be applied to the status bytes received in polling mode..
* This parameter can be any value between 0x00000000 and 0xFFFFFFFF.
* @param QSPI_Match_Mode: indicates which method should be used for determining a match during
* automatic polling mode.
* This parameter can be any value of :
* @arg QSPI_PMM_AND: AND match mode- SMF is set if all the unmasked bits received from the flash match
* the corresponding bits in the match register
* @arg QSPI_PMM_OR: OR match mode- SMF is set if any one of the unmasked bits received from the flash
matches its corresponding bit in the match register.
* @note This function is used only in Automatic Polling Mode
* @retval None
*/
void QSPI_AutoPollingMode_Config(uint32_t QSPI_Match, uint32_t QSPI_Mask , uint32_t QSPI_Match_Mode)
{
/* Check the parameters */
assert_param(IS_QSPI_PMM(QSPI_Match_Mode));
if (!(QUADSPI->SR & QUADSPI_SR_BUSY))
/* Device is not Busy */
{
/* Set the Match Register */
QUADSPI->PSMAR = QSPI_Match ;
/* Set the Mask Register */
QUADSPI->PSMKR = QSPI_Mask ;
/* Set the Polling Match Mode */
if(QSPI_Match_Mode)
/* OR Match Mode */
{
/* Set the PMM bit */
QUADSPI->CR |= QUADSPI_CR_PMM;
}
else
/* AND Match Mode */
{
/* Reset the PMM bit */
QUADSPI->CR &= ~ QUADSPI_CR_PMM;
}
}
}
/**
* @brief Sets the number of CLK cycle between two read during automatic polling phases.
* @param QSPI_Interval: The number of CLK cycle between two read during automatic polling phases.
* This parameter can be any value of between 0x0000 and 0xFFFF
* @note This function is used only in Automatic Polling Mode
* @retval None
*/
void QSPI_AutoPollingMode_SetInterval(uint32_t QSPI_Interval)
{
uint32_t tmpreg = 0;
/* Check the parameters */
assert_param(IS_QSPI_PIR(QSPI_Interval));
if (!(QUADSPI->SR & QUADSPI_SR_BUSY))
/* Device is not Busy */
{
/* Read the PIR Register */
tmpreg = QUADSPI->PIR ;
/* Clear Polling interval Bits */
tmpreg &= QSPI_PIR_CLEAR_MASK ;
/* Set the QSPI Polling Interval Bits */
tmpreg |= QSPI_Interval;
/* Write the PIR Register */
QUADSPI->PIR = tmpreg;
}
}
/**
* @brief Sets the value of the Timeout in Memory Mapped mode
* @param QSPI_Timeout: This field indicates how many CLK cycles QSPI waits after the
* FIFO becomes full until it raises nCS, putting the flash memory
* in a lowerconsumption state.
* This parameter can be any value of between 0x0000 and 0xFFFF
* @note This function is used only in Memory Mapped Mode
* @retval None
*/
void QSPI_MemoryMappedMode_SetTimeout(uint32_t QSPI_Timeout)
{
uint32_t tmpreg = 0;
/* Check the parameters */
assert_param(IS_QSPI_TIMEOUT(QSPI_Timeout));
if (!(QUADSPI->SR & QUADSPI_SR_BUSY))
/* Device is not Busy */
{
/* Read the LPTR Register */
tmpreg = QUADSPI->LPTR ;
/* Clear Timeout Bits */
tmpreg &= QSPI_LPTR_CLEAR_MASK ;
/* Set Timeout Bits */
tmpreg |= QSPI_Timeout;
/* Write the LPTR Register */
QUADSPI->LPTR = tmpreg;
}
}
/**
* @brief Sets the value of the Address
* @param QSPI_Address: Address to be send to the external flash memory.
* This parameter can be any value of between 0x00000000 and 0xFFFFFFFF
* @note This function is used only in Indirect Mode
* @retval None
*/
void QSPI_SetAddress(uint32_t QSPI_Address)
{
if (!(QUADSPI->SR & QUADSPI_SR_BUSY))
/* Device is not Busy */
{
/* Write the AR Register */
QUADSPI->AR = QSPI_Address;
}
}
/**
* @brief Sets the value of the Alternate Bytes
* @param QSPI_AlternateByte: Optional data to be send to the external QSPI device right after the address.
* This parameter can be any value of between 0x00000000 and 0xFFFFFFFF
* @note This function is used only in Indirect Mode
* @retval None
*/
void QSPI_SetAlternateByte(uint32_t QSPI_AlternateByte)
{
if (!(QUADSPI->SR & QUADSPI_SR_BUSY))
/* Device is not Busy */
{
/* Write the ABR Register */
QUADSPI->ABR = QSPI_AlternateByte;
}
}
/**
* @brief Sets the FIFO Threshold
* @param QSPI_FIFOThres: Defines, in indirect mode, the threshold number
* of bytes in the FIFO which will cause the FIFO Threshold Flag
* FTF to be set.
* This parameter can be any value of between 0x00 and 0x0F
* @retval None
*/
void QSPI_SetFIFOThreshold(uint32_t QSPI_FIFOThreshold)
{
uint32_t tmpreg = 0;
/* Check the parameters */
assert_param(IS_QSPI_FIFOTHRESHOLD(QSPI_FIFOThreshold));
/* Read the CR Register */
tmpreg = QUADSPI->CR ;
/* Clear FIFO Threshold Bits */
tmpreg &= QSPI_CR_CLEAR_FIFOTHRESHOLD_MASK ;
/* Set FIFO Threshold Bits */
tmpreg |= (QSPI_FIFOThreshold << 8);
/* Write the CR Register */
QUADSPI->CR = tmpreg;
}
/**
* @brief Sets number of Bytes to be transferred
* @param QSPI_DataLength: Number of data to be retrieved (value+1)
* in indirect and status-polling modes. A value no greater than 3
* (indicating 4 bytes) should be used for status-polling mode.
* All 1s in indirect mode means undefined length, where QSPI will
* continue until the end of memory, as defined by FSIZE
* This parameter can be any value of between 0x00000000 and 0xFFFFFFFF
* 0x0000_0000: 1 byte is to be transferred
* 0x0000_0001: 2 bytes are to be transferred
* 0x0000_0002: 3 bytes are to be transferred
* 0x0000_0003: 4 bytes are to be transferred
* ...
* 0xFFFF_FFFD: 4,294,967,294 (4G-2) bytes are to be transferred
* 0xFFFF_FFFE: 4,294,967,295 (4G-1) bytes are to be transferred
* 0xFFFF_FFFF: undefined length -- all bytes until the end of flash memory (as defined
* by FSIZE) are to be transferred
* @note This function is not used in Memory Mapped Mode.
* @retval None
*/
void QSPI_SetDataLength(uint32_t QSPI_DataLength)
{
if (!(QUADSPI->SR & QUADSPI_SR_BUSY))
/* Device is not Busy */
{
/* Write the DLR Register */
QUADSPI->DLR = QSPI_DataLength;
}
}
/**
* @brief Enables or disables The Timeout Counter.
* @param NewState: new state of the Timeout Counter.
* This parameter can be: ENABLE or DISABLE.
* @note This function is used only in Memory Mapped Mode.
* @retval None
*/
void QSPI_TimeoutCounterCmd(FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (!(QUADSPI->SR & QUADSPI_SR_BUSY))
/* Device is not Busy */
{
if (NewState != DISABLE)
{
/* Enable Timeout Counter */
QUADSPI->CR |= QUADSPI_CR_TCEN;
}
else
{
/* Disable Timeout Counter */
QUADSPI->CR &= ~ QUADSPI_CR_TCEN;
}
}
}
/**
* @brief Enables or disables Automatic Polling Mode Stop when a match occurs.
* @param NewState: new state of the Automatic Polling Mode Stop.
* This parameter can be: ENABLE or DISABLE.
* @note This function is used only in Automatic Polling Mode.
* @retval None
*/
void QSPI_AutoPollingModeStopCmd(FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (!(QUADSPI->SR & QUADSPI_SR_BUSY))
/* Device is not Busy */
{
if (NewState != DISABLE)
{
/* Enable Automatic Polling Mode Stop */
QUADSPI->CR |= QUADSPI_CR_APMS;
}
else
{
/* Disable Automatic Polling Mode Stop */
QUADSPI->CR &= ~ QUADSPI_CR_APMS;
}
}
}
/**
* @brief Abort the on-going command sequence.
* @param None
* @retval None
*/
void QSPI_AbortRequest(void)
{
/* Enable the ABORT request bit in CR */
QUADSPI->CR |= QUADSPI_CR_ABORT;
}
/* Data transfers functions ***************************************************/
/**
* @brief Transmits a 8bit Data through the QSPI peripheral.
* @param Data: Data to be transmitted.
* @retval None
*/
void QSPI_SendData8(uint8_t Data)
{
uint32_t quadspibase = 0;
quadspibase = (uint32_t)QUADSPI;
quadspibase += 0x20;
*(__IO uint8_t *) quadspibase = Data;
}
/**
* @brief Transmits a 16bit Data through the QSPI peripheral.
* @param Data: Data to be transmitted.
* @retval None
*/
void QSPI_SendData16(uint16_t Data)
{
uint32_t quadspibase = 0;
quadspibase = (uint32_t)QUADSPI;
quadspibase += 0x20;
*(__IO uint16_t *) quadspibase = Data;
}
/**
* @brief Transmits a 32bit Data through the QSPI peripheral.
* @param Data: Data to be transmitted.
* @retval None
*/
void QSPI_SendData32(uint32_t Data)
{
QUADSPI->DR = Data;
}
/**
* @brief Returns the most recent received 8bit data by the QSPI peripheral.
* @retval The value of the received data.
*/
uint8_t QSPI_ReceiveData8(void)
{
uint32_t quadspibase = 0;
quadspibase = (uint32_t)QUADSPI;
quadspibase += 0x20;
return *(__IO uint8_t *) quadspibase;
}
/**
* @brief Returns the most recent received 16bit data by the QSPI peripheral.
* @retval The value of the received data.
*/
uint16_t QSPI_ReceiveData16(void)
{
uint32_t quadspibase = 0;
quadspibase = (uint32_t)QUADSPI;
quadspibase += 0x20;
return *(__IO uint16_t *) quadspibase;
}
/**
* @brief Returns the most recent received 32bit data by the QSPI peripheral.
* @retval The value of the received data.
*/
uint32_t QSPI_ReceiveData32(void)
{
return QUADSPI->DR;
}
/* DMA transfers management functions *****************************************/
/**
* @brief Enables or disables DMA for Indirect Mode.
* @param NewState: new state of the Timeout Counter.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void QSPI_DMACmd(FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
/* Enable DMA */
QUADSPI->CR |= QUADSPI_CR_DMAEN;
}
else
{
/* Disable DMA */
QUADSPI->CR &= ~ QUADSPI_CR_DMAEN;
}
}
/* Interrupts and flags management functions **********************************/
/**
* @brief Enables or disables the specified QSPI interrupts.
* @param QSPI_IT: specifies the QSPI interrupt source to be enabled or disabled.
* This parameter can be one of the following values:
* @arg QSPI_IT_TO: Timeout interrupt
* @arg QSPI_IT_SM: Status Match interrupt
* @arg QSPI_IT_FT: FIFO Threshold
* @arg QSPI_IT_TC: Transfer Complete
* @arg QSPI_IT_TE: Transfer Error
* @param NewState: new state of the specified QSPI interrupt.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void QSPI_ITConfig(uint32_t QSPI_IT, FunctionalState NewState)
{
uint32_t tmpreg = 0;
/* Check the parameters */
assert_param(IS_FUNCTIONAL_STATE(NewState));
assert_param(IS_QSPI_IT(QSPI_IT));
/* Read the CR Register */
tmpreg = QUADSPI->CR ;
if(NewState != DISABLE)
{
/* Enable the selected QSPI interrupt */
tmpreg |= (uint32_t)(QSPI_IT & QSPI_CR_INTERRUPT_MASK);
}
else
{
/* Disable the selected QSPI interrupt */
tmpreg &= ~(uint32_t)(QSPI_IT & QSPI_CR_INTERRUPT_MASK);
}
/* Write the CR Register */
QUADSPI->CR = tmpreg ;
}
/**
* @brief Returns the current QSPI FIFO filled level.
* @retval Number of valid bytes which are being held in the FIFO.
* 0x00 : FIFO is empty
* 0x1F : FIFO is full
*/
uint32_t QSPI_GetFIFOLevel(void)
{
/* Get the QSPI FIFO level bits */
return ((QUADSPI->SR & QUADSPI_SR_FLEVEL)>> 8);
}
/**
* @brief Returns the QSPI functional mode.
* @param None
* @retval QSPI Functional Mode .The returned value can be one of the following:
* - 0x00000000: QSPI_FMode_Indirect_Write
* - 0x04000000: QSPI_FMode_Indirect_Read
* - 0x08000000: QSPI_FMode_AutoPolling
* - 0x0C000000: QSPI_FMode_MemoryMapped
*/
uint32_t QSPI_GetFMode(void)
{
/* Return the QSPI_FMode */
return (QUADSPI->CCR & QUADSPI_CCR_FMODE);
}
/**
* @brief Checks whether the specified QSPI flag is set or not.
* @param QSPI_FLAG: specifies the QSPI flag to check.
* This parameter can be one of the following values:
* @arg QSPI_FLAG_TO: Timeout interrupt flag
* @arg QSPI_FLAG_SM: Status Match interrupt flag
* @arg QSPI_FLAG_FT: FIFO Threshold flag
* @arg QSPI_FLAG_TC: Transfer Complete flag
* @arg QSPI_FLAG_TE: Transfer Error flag
* @arg QSPI_FLAG_BUSY: Busy flag
* @retval The new state of QSPI_FLAG (SET or RESET).
*/
FlagStatus QSPI_GetFlagStatus(uint32_t QSPI_FLAG)
{
FlagStatus bitstatus = RESET;
/* Check the parameters */
assert_param(IS_QSPI_GET_FLAG(QSPI_FLAG));
/* Check the status of the specified QSPI flag */
if (QUADSPI->SR & QSPI_FLAG)
{
/* QSPI_FLAG is set */
bitstatus = SET;
}
else
{
/* QSPI_FLAG is reset */
bitstatus = RESET;
}
/* Return the QSPI_FLAG status */
return bitstatus;
}
/**
* @brief Clears the QSPI flag.
* @param QSPI_FLAG: specifies the QSPI flag to clear.
* This parameter can be one of the following values:
* @arg QSPI_FLAG_TO: Timeout interrupt flag
* @arg QSPI_FLAG_SM: Status Match interrupt flag
* @arg QSPI_FLAG_TC: Transfer Complete flag
* @arg QSPI_FLAG_TE: Transfer Error flag
* @retval None
*/
void QSPI_ClearFlag(uint32_t QSPI_FLAG)
{
/* Check the parameters */
assert_param(IS_QSPI_CLEAR_FLAG(QSPI_FLAG));
/* Clear the selected QSPI flags */
QUADSPI->FCR = QSPI_FLAG;
}
/**
* @brief Checks whether the specified QSPI interrupt has occurred or not.
* @param QSPI_IT: specifies the QSPI interrupt source to check.
* This parameter can be one of the following values:
* @arg QSPI_IT_TO: Timeout interrupt
* @arg QSPI_IT_SM: Status Match interrupt
* @arg QSPI_IT_FT: FIFO Threshold
* @arg QSPI_IT_TC: Transfer Complete
* @arg QSPI_IT_TE: Transfer Error
* @retval The new state of QSPI_IT (SET or RESET).
*/
ITStatus QSPI_GetITStatus(uint32_t QSPI_IT)
{
ITStatus bitstatus = RESET;
__IO uint32_t tmpcreg = 0, tmpsreg = 0;
/* Check the parameters */
assert_param(IS_QSPI_IT(QSPI_IT));
/* Read the QUADSPI CR */
tmpcreg = QUADSPI->CR;
tmpcreg &= (uint32_t)(QSPI_IT & QSPI_CR_INTERRUPT_MASK);
/* Read the QUADSPI SR */
tmpsreg = QUADSPI->SR;
tmpsreg &= (uint32_t)(QSPI_IT & QSPI_SR_INTERRUPT_MASK);
/* Check the status of the specified QSPI interrupt */
if((tmpcreg != RESET) && (tmpsreg != RESET))
{
/* QSPI_IT is set */
bitstatus = SET;
}
else
{
/* QSPI_IT is reset */
bitstatus = RESET;
}
/* Return the QSPI_IT status */
return bitstatus;
}
/**
* @brief Clears the QSPI's interrupt pending bits.
* @param QSPI_IT: specifies the QSPI pending bit to clear.
* This parameter can be one of the following values:
* @arg QSPI_IT_TO: Timeout interrupt
* @arg QSPI_IT_SM: Status Match interrupt
* @arg QSPI_IT_TC: Transfer Complete
* @arg QSPI_IT_TE: Transfer Error
* @retval None
*/
void QSPI_ClearITPendingBit(uint32_t QSPI_IT)
{
/* Check the parameters */
assert_param(IS_QSPI_CLEAR_IT(QSPI_IT));
QUADSPI->FCR = (uint32_t)(QSPI_IT & QSPI_FSR_INTERRUPT_MASK);
}
/**
* @brief Enables or disables QSPI Dual Flash Mode.
* @param NewState: new state of the QSPI Dual Flash Mode.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void QSPI_DualFlashMode_Cmd(FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
/* Enable QSPI Dual Flash Mode */
QUADSPI->CR |= QUADSPI_CR_DFM;
}
else
{
/* Disable QSPI Dual Flash Mode */
QUADSPI->CR &= ~ QUADSPI_CR_DFM;
}
}
/**
* @}
*/
/**
* @}
*/
#endif /* STM32F446xx || STM32F469_479xx */
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

File diff suppressed because it is too large Load diff

View file

@ -0,0 +1,406 @@
/**
******************************************************************************
* @file stm32f4xx_rng.c
* @author MCD Application Team
* @version V1.6.1
* @date 21-October-2015
* @brief This file provides firmware functions to manage the following
* functionalities of the Random Number Generator (RNG) peripheral:
* + Initialization and Configuration
* + Get 32 bit Random number
* + Interrupts and flags management
*
@verbatim
===================================================================
##### How to use this driver #####
===================================================================
[..]
(#) Enable The RNG controller clock using
RCC_AHB2PeriphClockCmd(RCC_AHB2Periph_RNG, ENABLE) function.
(#) Activate the RNG peripheral using RNG_Cmd() function.
(#) Wait until the 32 bit Random number Generator contains a valid random data
(using polling/interrupt mode). For more details, refer to "Interrupts and
flags management functions" module description.
(#) Get the 32 bit Random number using RNG_GetRandomNumber() function
(#) To get another 32 bit Random number, go to step 3.
@endverbatim
*
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2015 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 "stm32f4xx_rng.h"
#include "stm32f4xx_rcc.h"
/** @addtogroup STM32F4xx_StdPeriph_Driver
* @{
*/
/** @defgroup RNG
* @brief RNG driver modules
* @{
*/
#if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F410xx) || defined(STM32F429_439xx) || defined(STM32F469_479xx)
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/** @defgroup RNG_Private_Functions
* @{
*/
/** @defgroup RNG_Group1 Initialization and Configuration functions
* @brief Initialization and Configuration functions
*
@verbatim
===============================================================================
##### Initialization and Configuration functions #####
===============================================================================
[..] This section provides functions allowing to
(+) Initialize the RNG peripheral
(+) Enable or disable the RNG peripheral
@endverbatim
* @{
*/
/**
* @brief De-initializes the RNG peripheral registers to their default reset values.
* @param None
* @retval None
*/
void RNG_DeInit(void)
{
#if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F469_479xx)
/* Enable RNG reset state */
RCC_AHB2PeriphResetCmd(RCC_AHB2Periph_RNG, ENABLE);
/* Release RNG from reset state */
RCC_AHB2PeriphResetCmd(RCC_AHB2Periph_RNG, DISABLE);
#endif /* STM32F40_41xxx || STM32F427_437xx || STM32F429_439xx || STM32F469_479xx */
#if defined(STM32F410xx)
/* Enable RNG reset state */
RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_RNG, ENABLE);
/* Release RNG from reset state */
RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_RNG, DISABLE);
#endif /* STM32F410xx*/
}
/**
* @brief Enables or disables the RNG peripheral.
* @param NewState: new state of the RNG peripheral.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void RNG_Cmd(FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
/* Enable the RNG */
RNG->CR |= RNG_CR_RNGEN;
}
else
{
/* Disable the RNG */
RNG->CR &= ~RNG_CR_RNGEN;
}
}
/**
* @}
*/
/** @defgroup RNG_Group2 Get 32 bit Random number function
* @brief Get 32 bit Random number function
*
@verbatim
===============================================================================
##### Get 32 bit Random number function #####
===============================================================================
[..] This section provides a function allowing to get the 32 bit Random number
(@) Before to call this function you have to wait till DRDY flag is set,
using RNG_GetFlagStatus(RNG_FLAG_DRDY) function.
@endverbatim
* @{
*/
/**
* @brief Returns a 32-bit random number.
*
* @note Before to call this function you have to wait till DRDY (data ready)
* flag is set, using RNG_GetFlagStatus(RNG_FLAG_DRDY) function.
* @note Each time the Random number data is read (using RNG_GetRandomNumber()
* function), the RNG_FLAG_DRDY flag is automatically cleared.
* @note In the case of a seed error, the generation of random numbers is
* interrupted for as long as the SECS bit is '1'. If a number is
* available in the RNG_DR register, it must not be used because it may
* not have enough entropy. In this case, it is recommended to clear the
* SEIS bit(using RNG_ClearFlag(RNG_FLAG_SECS) function), then disable
* and enable the RNG peripheral (using RNG_Cmd() function) to
* reinitialize and restart the RNG.
* @note In the case of a clock error, the RNG is no more able to generate
* random numbers because the PLL48CLK clock is not correct. User have
* to check that the clock controller is correctly configured to provide
* the RNG clock and clear the CEIS bit (using RNG_ClearFlag(RNG_FLAG_CECS)
* function) . The clock error has no impact on the previously generated
* random numbers, and the RNG_DR register contents can be used.
*
* @param None
* @retval 32-bit random number.
*/
uint32_t RNG_GetRandomNumber(void)
{
/* Return the 32 bit random number from the DR register */
return RNG->DR;
}
/**
* @}
*/
/** @defgroup RNG_Group3 Interrupts and flags management functions
* @brief Interrupts and flags management functions
*
@verbatim
===============================================================================
##### Interrupts and flags management functions #####
===============================================================================
[..] This section provides functions allowing to configure the RNG Interrupts and
to get the status and clear flags and Interrupts pending bits.
[..] The RNG provides 3 Interrupts sources and 3 Flags:
*** Flags : ***
===============
[..]
(#) RNG_FLAG_DRDY : In the case of the RNG_DR register contains valid
random data. it is cleared by reading the valid data(using
RNG_GetRandomNumber() function).
(#) RNG_FLAG_CECS : In the case of a seed error detection.
(#) RNG_FLAG_SECS : In the case of a clock error detection.
*** Interrupts ***
==================
[..] If enabled, an RNG interrupt is pending :
(#) In the case of the RNG_DR register contains valid random data.
This interrupt source is cleared once the RNG_DR register has been read
(using RNG_GetRandomNumber() function) until a new valid value is
computed; or
(#) In the case of a seed error : One of the following faulty sequences has
been detected:
(++) More than 64 consecutive bits at the same value (0 or 1)
(++) More than 32 consecutive alternance of 0 and 1 (0101010101...01)
This interrupt source is cleared using RNG_ClearITPendingBit(RNG_IT_SEI)
function; or
(#) In the case of a clock error : the PLL48CLK (RNG peripheral clock source)
was not correctly detected (fPLL48CLK< fHCLK/16). This interrupt source is
cleared using RNG_ClearITPendingBit(RNG_IT_CEI) function.
-@- note In this case, User have to check that the clock controller is
correctly configured to provide the RNG clock.
*** Managing the RNG controller events : ***
============================================
[..] The user should identify which mode will be used in his application to manage
the RNG controller events: Polling mode or Interrupt mode.
(#) In the Polling Mode it is advised to use the following functions:
(++) RNG_GetFlagStatus() : to check if flags events occur.
(++) RNG_ClearFlag() : to clear the flags events.
-@@- RNG_FLAG_DRDY can not be cleared by RNG_ClearFlag(). it is cleared only
by reading the Random number data.
(#) In the Interrupt Mode it is advised to use the following functions:
(++) RNG_ITConfig() : to enable or disable the interrupt source.
(++) RNG_GetITStatus() : to check if Interrupt occurs.
(++) RNG_ClearITPendingBit() : to clear the Interrupt pending Bit
(corresponding Flag).
@endverbatim
* @{
*/
/**
* @brief Enables or disables the RNG interrupt.
* @note The RNG provides 3 interrupt sources,
* - Computed data is ready event (DRDY), and
* - Seed error Interrupt (SEI) and
* - Clock error Interrupt (CEI),
* all these interrupts sources are enabled by setting the IE bit in
* CR register. However, each interrupt have its specific status bit
* (see RNG_GetITStatus() function) and clear bit except the DRDY event
* (see RNG_ClearITPendingBit() function).
* @param NewState: new state of the RNG interrupt.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void RNG_ITConfig(FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
/* Enable the RNG interrupt */
RNG->CR |= RNG_CR_IE;
}
else
{
/* Disable the RNG interrupt */
RNG->CR &= ~RNG_CR_IE;
}
}
/**
* @brief Checks whether the specified RNG flag is set or not.
* @param RNG_FLAG: specifies the RNG flag to check.
* This parameter can be one of the following values:
* @arg RNG_FLAG_DRDY: Data Ready flag.
* @arg RNG_FLAG_CECS: Clock Error Current flag.
* @arg RNG_FLAG_SECS: Seed Error Current flag.
* @retval The new state of RNG_FLAG (SET or RESET).
*/
FlagStatus RNG_GetFlagStatus(uint8_t RNG_FLAG)
{
FlagStatus bitstatus = RESET;
/* Check the parameters */
assert_param(IS_RNG_GET_FLAG(RNG_FLAG));
/* Check the status of the specified RNG flag */
if ((RNG->SR & RNG_FLAG) != (uint8_t)RESET)
{
/* RNG_FLAG is set */
bitstatus = SET;
}
else
{
/* RNG_FLAG is reset */
bitstatus = RESET;
}
/* Return the RNG_FLAG status */
return bitstatus;
}
/**
* @brief Clears the RNG flags.
* @param RNG_FLAG: specifies the flag to clear.
* This parameter can be any combination of the following values:
* @arg RNG_FLAG_CECS: Clock Error Current flag.
* @arg RNG_FLAG_SECS: Seed Error Current flag.
* @note RNG_FLAG_DRDY can not be cleared by RNG_ClearFlag() function.
* This flag is cleared only by reading the Random number data (using
* RNG_GetRandomNumber() function).
* @retval None
*/
void RNG_ClearFlag(uint8_t RNG_FLAG)
{
/* Check the parameters */
assert_param(IS_RNG_CLEAR_FLAG(RNG_FLAG));
/* Clear the selected RNG flags */
RNG->SR = ~(uint32_t)(((uint32_t)RNG_FLAG) << 4);
}
/**
* @brief Checks whether the specified RNG interrupt has occurred or not.
* @param RNG_IT: specifies the RNG interrupt source to check.
* This parameter can be one of the following values:
* @arg RNG_IT_CEI: Clock Error Interrupt.
* @arg RNG_IT_SEI: Seed Error Interrupt.
* @retval The new state of RNG_IT (SET or RESET).
*/
ITStatus RNG_GetITStatus(uint8_t RNG_IT)
{
ITStatus bitstatus = RESET;
/* Check the parameters */
assert_param(IS_RNG_GET_IT(RNG_IT));
/* Check the status of the specified RNG interrupt */
if ((RNG->SR & RNG_IT) != (uint8_t)RESET)
{
/* RNG_IT is set */
bitstatus = SET;
}
else
{
/* RNG_IT is reset */
bitstatus = RESET;
}
/* Return the RNG_IT status */
return bitstatus;
}
/**
* @brief Clears the RNG interrupt pending bit(s).
* @param RNG_IT: specifies the RNG interrupt pending bit(s) to clear.
* This parameter can be any combination of the following values:
* @arg RNG_IT_CEI: Clock Error Interrupt.
* @arg RNG_IT_SEI: Seed Error Interrupt.
* @retval None
*/
void RNG_ClearITPendingBit(uint8_t RNG_IT)
{
/* Check the parameters */
assert_param(IS_RNG_IT(RNG_IT));
/* Clear the selected RNG interrupt pending bit */
RNG->SR = (uint8_t)~RNG_IT;
}
/**
* @}
*/
/**
* @}
*/
#endif /* STM32F40_41xxx || STM32F427_437xx || STM32F410xx || STM32F429_439xx || STM32F469_479xx */
/**
* @}
*/
/**
* @}
*/
/************************ (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

View file

@ -0,0 +1,494 @@
/**
******************************************************************************
* @file stm32f4xx_spdifrx.c
* @author MCD Application Team
* @version V1.6.1
* @date 21-October-2015
* @brief This file provides firmware functions to manage the following
* functionalities of the Serial Audio Interface (SPDIFRX):
* + Initialization and Configuration
* + Data transfers functions
* + DMA transfers management
* + Interrupts and flags management
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2015 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 "stm32f4xx_spdifrx.h"
#include "stm32f4xx_rcc.h"
/** @addtogroup STM32F4xx_StdPeriph_Driver
* @{
*/
/** @defgroup SPDIFRX
* @brief SPDIFRX driver modules
* @{
*/
#if defined(STM32F446xx)
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
#define CR_CLEAR_MASK 0x000000FE7
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/** @defgroup SPDIFRX_Private_Functions
* @{
*/
/** @defgroup SPDIFRX_Group1 Initialization and Configuration functions
* @brief Initialization and Configuration functions
*
@verbatim
===============================================================================
##### Initialization and Configuration functions #####
===============================================================================
[..]
This section provides a set of functions allowing to initialize the SPDIFRX Audio
Block Mode, Audio Protocol, Data size, Synchronization between audio block,
Master clock Divider, FIFO threshold, Frame configuration, slot configuration,
Tristate mode, Companding mode and Mute mode.
[..]
The SPDIFRX_Init(), SPDIFRX_FrameInit() and SPDIFRX_SlotInit() functions follows the SPDIFRX Block
configuration procedures for Master mode and Slave mode (details for these procedures
are available in reference manual(RMxxxx).
@endverbatim
* @{
*/
/**
* @brief Deinitialize the SPDIFRXx peripheral registers to their default reset values.
* @param void
* @retval None
*/
void SPDIFRX_DeInit(void)
{
/* Enable SPDIFRX reset state */
RCC_APB1PeriphResetCmd(RCC_APB1Periph_SPDIFRX, ENABLE);
/* Release SPDIFRX from reset state */
RCC_APB1PeriphResetCmd(RCC_APB1Periph_SPDIFRX, DISABLE);
}
/**
* @brief Initializes the SPDIFRX peripheral according to the specified
* parameters in the SPDIFRX_InitStruct.
*
* @note SPDIFRX clock is generated from a specific output of the PLLSPDIFRX or a specific
* output of the PLLI2S or from an alternate function bypassing the PLL I2S.
*
* @param SPDIFRX_InitStruct: pointer to a SPDIFRX_InitTypeDef structure that
* contains the configuration information for the specified SPDIFRX Block peripheral.
* @retval None
*/
void SPDIFRX_Init(SPDIFRX_InitTypeDef* SPDIFRX_InitStruct)
{
uint32_t tmpreg = 0;
/* Check the SPDIFRX parameters */
assert_param(IS_STEREO_MODE(SPDIFRX_InitStruct->SPDIFRX_StereoMode));
assert_param(IS_SPDIFRX_INPUT_SELECT(SPDIFRX_InitStruct->SPDIFRX_InputSelection));
assert_param(IS_SPDIFRX_MAX_RETRIES(SPDIFRX_InitStruct->SPDIFRX_Retries));
assert_param(IS_SPDIFRX_WAIT_FOR_ACTIVITY(SPDIFRX_InitStruct->SPDIFRX_WaitForActivity));
assert_param(IS_SPDIFRX_CHANNEL(SPDIFRX_InitStruct->SPDIFRX_ChannelSelection));
assert_param(IS_SPDIFRX_DATA_FORMAT(SPDIFRX_InitStruct->SPDIFRX_DataFormat));
/* SPDIFRX CR Configuration */
/* Get the SPDIFRX CR value */
tmpreg = SPDIFRX->CR;
/* Clear INSEL, WFA, NBTR, CHSEL, DRFMT and RXSTEO bits */
tmpreg &= CR_CLEAR_MASK;
/* Configure SPDIFRX: Input selection, Maximum allowed re-tries during synchronization phase,
wait for activity, Channel Selection, Data samples format and stereo/mono mode */
/* Set INSEL bits according to SPDIFRX_InputSelection value */
/* Set WFA bit according to SPDIFRX_WaitForActivity value */
/* Set NBTR bit according to SPDIFRX_Retries value */
/* Set CHSEL bit according to SPDIFRX_ChannelSelection value */
/* Set DRFMT bits according to SPDIFRX_DataFormat value */
/* Set RXSTEO bit according to SPDIFRX_StereoMode value */
tmpreg |= (uint32_t)(SPDIFRX_InitStruct->SPDIFRX_InputSelection | SPDIFRX_InitStruct->SPDIFRX_WaitForActivity |
SPDIFRX_InitStruct->SPDIFRX_Retries | SPDIFRX_InitStruct->SPDIFRX_ChannelSelection |
SPDIFRX_InitStruct->SPDIFRX_DataFormat | SPDIFRX_InitStruct->SPDIFRX_StereoMode
);
/* Write to SPDIFRX CR */
SPDIFRX->CR = tmpreg;
}
/**
* @brief Fills each SPDIFRX_InitStruct member with its default value.
* @param SPDIFRX_InitStruct: pointer to a SPDIFRX_InitTypeDef structure which will
* be initialized.
* @retval None
*/
void SPDIFRX_StructInit(SPDIFRX_InitTypeDef* SPDIFRX_InitStruct)
{
/* Reset SPDIFRX init structure parameters values */
/* Initialize the PDIF_InputSelection member */
SPDIFRX_InitStruct->SPDIFRX_InputSelection = SPDIFRX_Input_IN0;
/* Initialize the SPDIFRX_WaitForActivity member */
SPDIFRX_InitStruct->SPDIFRX_WaitForActivity = SPDIFRX_WaitForActivity_On;
/* Initialize the SPDIFRX_Retries member */
SPDIFRX_InitStruct->SPDIFRX_Retries = SPDIFRX_16MAX_RETRIES;
/* Initialize the SPDIFRX_ChannelSelection member */
SPDIFRX_InitStruct->SPDIFRX_ChannelSelection = SPDIFRX_Select_Channel_A;
/* Initialize the SPDIFRX_DataFormat member */
SPDIFRX_InitStruct->SPDIFRX_DataFormat = SPDIFRX_MSB_DataFormat;
/* Initialize the SPDIFRX_StereoMode member */
SPDIFRX_InitStruct->SPDIFRX_StereoMode = SPDIFRX_StereoMode_Enabled;
}
/**
* @brief Enables or disables the SPDIFRX frame x bit.
* @param NewState: new state of the selected SPDIFRX frame bit.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void SPDIFRX_SetPreambleTypeBit(FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
/* Enable the selected SPDIFRX frame bit */
SPDIFRX->CR |= SPDIFRX_CR_PTMSK;
}
else
{
/* Disable the selected SPDIFRX frame bit */
SPDIFRX->CR &= ~(SPDIFRX_CR_PTMSK);
}
}
/**
* @brief Enables or disables the SPDIFRX frame x bit.
* @param NewState: new state of the selected SPDIFRX frame bit.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void SPDIFRX_SetUserDataChannelStatusBits(FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
/* Enable the selected SPDIFRX frame bit */
SPDIFRX->CR |= SPDIFRX_CR_CUMSK;
}
else
{
/* Disable the selected SPDIFRX frame bit */
SPDIFRX->CR &= ~(SPDIFRX_CR_CUMSK);
}
}
/**
* @brief Enables or disables the SPDIFRX frame x bit.
* @param NewState: new state of the selected SPDIFRX frame bit.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void SPDIFRX_SetValidityBit(FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
/* Enable the selected SPDIFRX frame bit */
SPDIFRX->CR |= SPDIFRX_CR_VMSK;
}
else
{
/* Disable the selected SPDIFRX frame bit */
SPDIFRX->CR &= ~(SPDIFRX_CR_VMSK);
}
}
/**
* @brief Enables or disables the SPDIFRX frame x bit.
* @param NewState: new state of the selected SPDIFRX frame bit.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void SPDIFRX_SetParityBit(FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
/* Enable the selected SPDIFRX frame bit */
SPDIFRX->CR |= SPDIFRX_CR_PMSK;
}
else
{
/* Disable the selected SPDIFRX frame bit */
SPDIFRX->CR &= ~(SPDIFRX_CR_PMSK);
}
}
/**
* @brief Enables or disables the SPDIFRX DMA interface (RX).
* @param NewState: new state of the selected SPDIFRX DMA transfer request.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void SPDIFRX_RxDMACmd(FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
/* Enable the selected SPDIFRX DMA requests */
SPDIFRX->CR |= SPDIFRX_CR_RXDMAEN;
}
else
{
/* Disable the selected SPDIFRX DMA requests */
SPDIFRX->CR &= ~(SPDIFRX_CR_RXDMAEN);
}
}
/**
* @brief Enables or disables the SPDIFRX DMA interface (Control Buffer).
* @param NewState: new state of the selected SPDIFRX DMA transfer request.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void SPDIFRX_CbDMACmd(FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
/* Enable the selected SPDIFRX DMA requests */
SPDIFRX->CR |= SPDIFRX_CR_CBDMAEN;
}
else
{
/* Disable the selected SPDIFRX DMA requests */
SPDIFRX->CR &= ~(SPDIFRX_CR_CBDMAEN);
}
}
/**
* @brief Enables or disables the SPDIFRX peripheral.
* @param SPDIFRX_State: specifies the SPDIFRX peripheral state.
* This parameter can be one of the following values:
* @arg SPDIFRX_STATE_IDLE : Disable SPDIFRX-RX (STATE_IDLE)
* @arg SPDIFRX_STATE_SYNC : Enable SPDIFRX-RX Synchronization only
* @arg SPDIFRX_STATE_RCV : Enable SPDIFRX Receiver
* @retval None
*/
void SPDIFRX_Cmd(uint32_t SPDIFRX_State)
{
/* Check the parameters */
assert_param(IS_SPDIFRX_STATE(SPDIFRX_State));
/* Clear SPDIFRXEN bits */
SPDIFRX->CR &= ~(SPDIFRX_CR_SPDIFEN);
/* Set new SPDIFRXEN value */
SPDIFRX->CR |= SPDIFRX_State;
}
/**
* @brief Enables or disables the specified SPDIFRX Block interrupts.
* @param SPDIFRX_IT: specifies the SPDIFRX interrupt source to be enabled or disabled.
* This parameter can be one of the following values:
* @arg SPDIFRX_IT_RXNE: RXNE interrupt enable
* @arg SPDIFRX_IT_CSRNE: Control Buffer Ready Interrupt Enable
* @arg SPDIFRX_IT_PERRIE: Parity error interrupt enable
* @arg SPDIFRX_IT_OVRIE: Overrun error Interrupt Enable
* @arg SPDIFRX_IT_SBLKIE: Synchronization Block Detected Interrupt Enable
* @arg SPDIFRX_IT_SYNCDIE: Synchronization Done
* @arg SPDIFRX_IT_IFEIE: Serial Interface Error Interrupt Enable
* @param NewState: new state of the specified SPDIFRX interrupt.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void SPDIFRX_ITConfig(uint32_t SPDIFRX_IT, FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_FUNCTIONAL_STATE(NewState));
assert_param(IS_SPDIFRX_CONFIG_IT(SPDIFRX_IT));
if (NewState != DISABLE)
{
/* Enable the selected SPDIFRX interrupt */
SPDIFRX->IMR |= SPDIFRX_IT;
}
else
{
/* Disable the selected SPDIFRX interrupt */
SPDIFRX->IMR &= ~(SPDIFRX_IT);
}
}
/**
* @brief Checks whether the specified SPDIFRX flag is set or not.
* @param SPDIFRX_FLAG: specifies the SPDIFRX flag to check.
* This parameter can be one of the following values:
* @arg SPDIFRX_FLAG_RXNE: Read data register not empty flag.
* @arg SPDIFRX_FLAG_CSRNE: The Control Buffer register is not empty flag.
* @arg SPDIFRX_FLAG_PERR: Parity error flag.
* @arg SPDIFRX_FLAG_OVR: Overrun error flag.
* @arg SPDIFRX_FLAG_SBD: Synchronization Block Detected flag.
* @arg SPDIFRX_FLAG_SYNCD: Synchronization Done flag.
* @arg SPDIFRX_FLAG_FERR: Framing error flag.
* @arg SPDIFRX_FLAG_SERR: Synchronization error flag.
* @arg SPDIFRX_FLAG_TERR: Time-out error flag.
* @retval The new state of SPDIFRX_FLAG (SET or RESET).
*/
FlagStatus SPDIFRX_GetFlagStatus(uint32_t SPDIFRX_FLAG)
{
FlagStatus bitstatus = RESET;
/* Check the parameters */
assert_param(IS_SPDIFRX_FLAG(SPDIFRX_FLAG));
/* Check the status of the specified SPDIFRX flag */
if ((SPDIFRX->SR & SPDIFRX_FLAG) != (uint32_t)RESET)
{
/* SPDIFRX_FLAG is set */
bitstatus = SET;
}
else
{
/* SPDIFRX_FLAG is reset */
bitstatus = RESET;
}
/* Return the SPDIFRX_FLAG status */
return bitstatus;
}
/**
* @brief Clears the specified SPDIFRX flag.
* @param SPDIFRX_FLAG: specifies the SPDIFRX flag to check.
* This parameter can be one of the following values:
* @arg SPDIFRX_FLAG_PERR: Parity error flag.
* @arg SPDIFRX_FLAG_OVR: Overrun error flag.
* @arg SPDIFRX_FLAG_SBD: Synchronization Block Detected flag.
* @arg SPDIFRX_FLAG_SYNCD: Synchronization Done flag.
*
* @retval None
*/
void SPDIFRX_ClearFlag(uint32_t SPDIFRX_FLAG)
{
/* Check the parameters */
assert_param(IS_SPDIFRX_CLEAR_FLAG(SPDIFRX_FLAG));
/* Clear the selected SPDIFRX Block flag */
SPDIFRX->IFCR |= SPDIFRX_FLAG;
}
/**
* @brief Checks whether the specified SPDIFRX interrupt has occurred or not.
* @param SPDIFRX_IT: specifies the SPDIFRX interrupt source to be enabled or disabled.
* This parameter can be one of the following values:
* @arg SPDIFRX_IT_RXNE: RXNE interrupt enable
* @arg SPDIFRX_IT_CSRNE: Control Buffer Ready Interrupt Enable
* @arg SPDIFRX_IT_PERRIE: Parity error interrupt enable
* @arg SPDIFRX_IT_OVRIE: Overrun error Interrupt Enable
* @arg SPDIFRX_IT_SBLKIE: Synchronization Block Detected Interrupt Enable
* @arg SPDIFRX_IT_SYNCDIE: Synchronization Done
* @arg SPDIFRX_IT_IFEIE: Serial Interface Error Interrupt Enable
* @retval The new state of SPDIFRX_IT (SET or RESET).
*/
ITStatus SPDIFRX_GetITStatus(uint32_t SPDIFRX_IT)
{
ITStatus bitstatus = RESET;
uint32_t enablestatus = 0;
/* Check the parameters */
assert_param(IS_SPDIFRX_CONFIG_IT(SPDIFRX_IT));
/* Get the SPDIFRX_IT enable bit status */
enablestatus = (SPDIFRX->IMR & SPDIFRX_IT) ;
/* Check the status of the specified SPDIFRX interrupt */
if (((SPDIFRX->SR & SPDIFRX_IT) != (uint32_t)RESET) && (enablestatus != (uint32_t)RESET))
{
/* SPDIFRX_IT is set */
bitstatus = SET;
}
else
{
/* SPDIFRX_IT is reset */
bitstatus = RESET;
}
/* Return the SPDIFRX_IT status */
return bitstatus;
}
/**
* @brief Clears the SPDIFRX interrupt pending bit.
* @param SAI_IT: specifies the SPDIFRX interrupt pending bit to clear.
* This parameter can be one of the following values:
* @arg SPDIFRX_IT_MUTEDET: MUTE detection interrupt.
* @arg SPDIFRX_IT_OVRUDR: overrun/underrun interrupt.
* @arg SPDIFRX_IT_WCKCFG: wrong clock configuration interrupt.
* @arg SPDIFRX_IT_CNRDY: codec not ready interrupt.
* @arg SPDIFRX_IT_AFSDET: anticipated frame synchronization detection interrupt.
* @arg SPDIFRX_IT_LFSDET: late frame synchronization detection interrupt.
*
* @note FREQ (FIFO Request) flag is cleared :
* - When the audio block is transmitter and the FIFO is full or the FIFO
* has one data (one buffer mode) depending the bit FTH in the
* SPDIFRX_xCR2 register.
* - When the audio block is receiver and the FIFO is not empty
*
* @retval None
*/
void SPDIFRX_ClearITPendingBit(uint32_t SPDIFRX_IT)
{
/* Check the parameters */
assert_param(IS_SPDIFRX_CLEAR_FLAG(SPDIFRX_IT));
/* Clear the selected SPDIFRX interrupt pending bit */
SPDIFRX->IFCR |= SPDIFRX_IT;
}
/**
* @}
*/
/**
* @}
*/
#endif /* STM32F446xx */
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

File diff suppressed because it is too large Load diff

View file

@ -0,0 +1,259 @@
/**
******************************************************************************
* @file stm32f4xx_syscfg.c
* @author MCD Application Team
* @version V1.6.1
* @date 21-October-2015
* @brief This file provides firmware functions to manage the SYSCFG peripheral.
*
@verbatim
===============================================================================
##### How to use this driver #####
===============================================================================
[..] This driver provides functions for:
(#) Remapping the memory accessible in the code area using SYSCFG_MemoryRemapConfig()
(#) Swapping the internal flash Bank1 and Bank2 this features is only visible for
STM32F42xxx/43xxx devices Devices.
(#) Manage the EXTI lines connection to the GPIOs using SYSCFG_EXTILineConfig()
(#) Select the ETHERNET media interface (RMII/RII) using SYSCFG_ETH_MediaInterfaceConfig()
-@- SYSCFG APB clock must be enabled to get write access to SYSCFG registers,
using RCC_APB2PeriphClockCmd(RCC_APB2Periph_SYSCFG, ENABLE);
@endverbatim
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2015 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 "stm32f4xx_syscfg.h"
#include "stm32f4xx_rcc.h"
/** @addtogroup STM32F4xx_StdPeriph_Driver
* @{
*/
/** @defgroup SYSCFG
* @brief SYSCFG driver modules
* @{
*/
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* ------------ RCC registers bit address in the alias region ----------- */
#define SYSCFG_OFFSET (SYSCFG_BASE - PERIPH_BASE)
/* --- MEMRMP Register ---*/
/* Alias word address of UFB_MODE bit */
#define MEMRMP_OFFSET SYSCFG_OFFSET
#define UFB_MODE_BitNumber ((uint8_t)0x8)
#define UFB_MODE_BB (PERIPH_BB_BASE + (MEMRMP_OFFSET * 32) + (UFB_MODE_BitNumber * 4))
/* --- PMC Register ---*/
/* Alias word address of MII_RMII_SEL bit */
#define PMC_OFFSET (SYSCFG_OFFSET + 0x04)
#define MII_RMII_SEL_BitNumber ((uint8_t)0x17)
#define PMC_MII_RMII_SEL_BB (PERIPH_BB_BASE + (PMC_OFFSET * 32) + (MII_RMII_SEL_BitNumber * 4))
/* --- CMPCR Register ---*/
/* Alias word address of CMP_PD bit */
#define CMPCR_OFFSET (SYSCFG_OFFSET + 0x20)
#define CMP_PD_BitNumber ((uint8_t)0x00)
#define CMPCR_CMP_PD_BB (PERIPH_BB_BASE + (CMPCR_OFFSET * 32) + (CMP_PD_BitNumber * 4))
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/** @defgroup SYSCFG_Private_Functions
* @{
*/
/**
* @brief Deinitializes the Alternate Functions (remap and EXTI configuration)
* registers to their default reset values.
* @param None
* @retval None
*/
void SYSCFG_DeInit(void)
{
RCC_APB2PeriphResetCmd(RCC_APB2Periph_SYSCFG, ENABLE);
RCC_APB2PeriphResetCmd(RCC_APB2Periph_SYSCFG, DISABLE);
}
/**
* @brief Changes the mapping of the specified pin.
* @param SYSCFG_Memory: 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_SystemFlash: System Flash memory mapped at 0x00000000
* @arg SYSCFG_MemoryRemap_FSMC: FSMC (Bank1 (NOR/PSRAM 1 and 2) mapped at 0x00000000 for STM32F405xx/407xx and STM32F415xx/417xx devices.
* @arg SYSCFG_MemoryRemap_FMC: FMC (Bank1 (NOR/PSRAM 1 and 2) mapped at 0x00000000 for STM32F42xxx/43xxx devices.
* @arg SYSCFG_MemoryRemap_ExtMEM: External Memory mapped at 0x00000000 for STM32F446xx/STM32F469_479xx devices.
* @arg SYSCFG_MemoryRemap_SRAM: Embedded SRAM (112kB) mapped at 0x00000000
* @arg SYSCFG_MemoryRemap_SDRAM: FMC (External SDRAM) mapped at 0x00000000 for STM32F42xxx/43xxx devices.
* @retval None
*/
void SYSCFG_MemoryRemapConfig(uint8_t SYSCFG_MemoryRemap)
{
/* Check the parameters */
assert_param(IS_SYSCFG_MEMORY_REMAP_CONFING(SYSCFG_MemoryRemap));
SYSCFG->MEMRMP = SYSCFG_MemoryRemap;
}
/**
* @brief Enables or disables the Internal FLASH Bank Swapping.
*
* @note This function can be used only for STM32F42xxx/43xxx devices.
*
* @param NewState: new state of Internal FLASH Bank swapping.
* This parameter can be one of the following values:
* @arg ENABLE: Flash Bank2 mapped at 0x08000000 (and aliased @0x00000000)
* and Flash Bank1 mapped at 0x08100000 (and aliased at 0x00100000)
* @arg DISABLE:(the default state) Flash Bank1 mapped at 0x08000000 (and aliased @0x0000 0000)
and Flash Bank2 mapped at 0x08100000 (and aliased at 0x00100000)
* @retval None
*/
void SYSCFG_MemorySwappingBank(FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_FUNCTIONAL_STATE(NewState));
*(__IO uint32_t *) UFB_MODE_BB = (uint32_t)NewState;
}
/**
* @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..K) for STM32F42xxx/43xxx devices, (A..I)
* for STM32F405xx/407xx and STM32F415xx/417xx devices or (A, B, C, D and H)
* for STM32401xx devices.
*
* @param EXTI_PinSourcex: specifies the EXTI line to be configured.
* This parameter can be EXTI_PinSourcex where x can be (0..15, except
* for EXTI_PortSourceGPIOI x can be (0..11) for STM32F405xx/407xx
* and STM32F405xx/407xx devices and for EXTI_PortSourceGPIOK x can
* be (0..7) for STM32F42xxx/43xxx devices.
*
* @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 Selects the ETHERNET media interface
* @param SYSCFG_ETH_MediaInterface: specifies the Media Interface mode.
* This parameter can be one of the following values:
* @arg SYSCFG_ETH_MediaInterface_MII: MII mode selected
* @arg SYSCFG_ETH_MediaInterface_RMII: RMII mode selected
* @retval None
*/
void SYSCFG_ETH_MediaInterfaceConfig(uint32_t SYSCFG_ETH_MediaInterface)
{
assert_param(IS_SYSCFG_ETH_MEDIA_INTERFACE(SYSCFG_ETH_MediaInterface));
/* Configure MII_RMII selection bit */
*(__IO uint32_t *) PMC_MII_RMII_SEL_BB = SYSCFG_ETH_MediaInterface;
}
/**
* @brief Enables or disables the I/O Compensation Cell.
* @note The I/O compensation cell can be used only when the device supply
* voltage ranges from 2.4 to 3.6 V.
* @param NewState: new state of the I/O Compensation Cell.
* This parameter can be one of the following values:
* @arg ENABLE: I/O compensation cell enabled
* @arg DISABLE: I/O compensation cell power-down mode
* @retval None
*/
void SYSCFG_CompensationCellCmd(FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_FUNCTIONAL_STATE(NewState));
*(__IO uint32_t *) CMPCR_CMP_PD_BB = (uint32_t)NewState;
}
/**
* @brief Checks whether the I/O Compensation Cell ready flag is set or not.
* @param None
* @retval The new state of the I/O Compensation Cell ready flag (SET or RESET)
*/
FlagStatus SYSCFG_GetCompensationCellStatus(void)
{
FlagStatus bitstatus = RESET;
if ((SYSCFG->CMPCR & SYSCFG_CMPCR_READY ) != (uint32_t)RESET)
{
bitstatus = SET;
}
else
{
bitstatus = RESET;
}
return bitstatus;
}
#if defined(STM32F410xx)
/**
* @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/8.
* @arg SYSCFG_Break_HardFault: Lockup output of CortexM4 is connected to the break input of TIM1/8.
* @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;
}
#endif /* STM32F410xx */
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/************************ (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

View file

@ -0,0 +1,307 @@
/**
******************************************************************************
* @file stm32f4xx_wwdg.c
* @author MCD Application Team
* @version V1.6.1
* @date 21-October-2015
* @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 @42 MHz(PCLK1): ~97.5 us / ~49.9 ms
##### 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>&copy; COPYRIGHT 2015 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 "stm32f4xx_wwdg.h"
#include "stm32f4xx_rcc.h"
/** @addtogroup STM32F4xx_StdPeriph_Driver
* @{
*/
/** @defgroup WWDG
* @brief WWDG driver modules
* @{
*/
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* ----------- WWDG registers bit address in the alias region ----------- */
#define WWDG_OFFSET (WWDG_BASE - PERIPH_BASE)
/* Alias word address of EWI bit */
#define CFR_OFFSET (WWDG_OFFSET + 0x04)
#define EWI_BitNumber 0x09
#define CFR_EWI_BB (PERIPH_BB_BASE + (CFR_OFFSET * 32) + (EWI_BitNumber * 4))
/* --------------------- 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)
{
*(__IO uint32_t *) CFR_EWI_BB = (uint32_t)ENABLE;
}
/**
* @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****/