Reorganisation of NUCLEO_L053R8 and DISCO_L053C8 cmsis folders - part4

Moves cmsis files to new location.
pull/635/head
ohagendorf 2014-11-02 23:28:54 +01:00
parent bd046b3f67
commit 022838af31
93 changed files with 65800 additions and 0 deletions

View File

@ -0,0 +1,702 @@
/**
******************************************************************************
* @file stm32l0xx_hal.c
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief HAL module driver.
* This is the common part of the HAL initialization
*
@verbatim
==============================================================================
##### How to use this driver #####
==============================================================================
[..]
The common HAL driver contains a set of generic and common APIs that can be
used by the PPP peripheral drivers and the user to start using the HAL.
[..]
The HAL contains two APIs' categories:
(+) Common HAL APIs
(+) Services HAL APIs
@endverbatim
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @defgroup HAL
* @brief HAL module driver.
* @{
*/
#ifdef HAL_MODULE_ENABLED
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/**
* @brief STM32L0xx HAL Driver version number V1.1.0
*/
#define __STM32L0xx_HAL_VERSION_MAIN (0x01) /*!< [31:24] main version */
#define __STM32L0xx_HAL_VERSION_SUB1 (0x01) /*!< [23:16] sub1 version */
#define __STM32L0xx_HAL_VERSION_SUB2 (0x00) /*!< [15:8] sub2 version */
#define __STM32L0xx_HAL_VERSION_RC (0x00) /*!< [7:0] release candidate */
#define __STM32L0xx_HAL_VERSION ((__STM32L0xx_HAL_VERSION_MAIN << 24)\
|(__STM32L0xx_HAL_VERSION_SUB1 << 16)\
|(__STM32L0xx_HAL_VERSION_SUB2 << 8 )\
|(__STM32L0xx_HAL_VERSION_RC))
#define IDCODE_DEVID_MASK ((uint32_t)0x00000FFF)
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
static __IO uint32_t uwTick;
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/** @defgroup HAL_Private_Functions
* @{
*/
/** @defgroup HAL_Group1 Initialization and de-initialization Functions
* @brief Initialization and de-initialization functions
*
@verbatim
===============================================================================
##### Initialization and de-initialization functions #####
===============================================================================
[..] This section provides functions allowing to:
(+) Initializes the Flash interface, the NVIC allocation and initial clock
configuration. It initializes the source of time base also when timeout
is needed and the backup domain when enabled.
(+) de-Initializes common part of the HAL.
(+) Configure The time base source to have 1ms time base with a dedicated
Tick interrupt priority.
(++) Systick timer is used by default as source of time base, but user
can eventually implement his proper time base source (a general purpose
timer for example or other time source), keeping in mind that Time base
duration should be kept 1ms since PPP_TIMEOUT_VALUEs are defined and
handled in milliseconds basis.
(++) Time base configuration function (HAL_InitTick ()) is called automatically
at the beginning of the program after reset by HAL_Init() or at any time
when clock is configured, by HAL_RCC_ClockConfig().
(++) Source of time base is configured to generate interrupts at regular
time intervals. Care must be taken if HAL_Delay() is called from a
peripheral ISR process, the Tick interrupt line must have higher priority
(numerically lower) than the peripheral interrupt. Otherwise the caller
ISR process will be blocked.
(++) functions affecting time base configurations are declared as __Weak
to make override possible in case of other implementations in user file.
@endverbatim
* @{
*/
/**
* @brief This function configures the Flash prefetch, Flash preread and Buffer cache,
* Configures time base source, NVIC and Low level hardware
* @note This function is called at the beginning of program after reset and before
* the clock configuration
* @note The time base configuration is based on MSI clock when exiting from Reset.
* Once done, time base tick start incrementing.
* In the default implementation,Systick is used as source of time base.
* the tick variable is incremented each 1ms in its ISR.
* @param None
* @retval HAL status
*/
HAL_StatusTypeDef HAL_Init(void)
{
/* Configure Buffer cache, Flash prefetch, Flash preread */
#if (BUFFER_CACHE_DISABLE != 0)
__HAL_FLASH_BUFFER_CACHE_DISABLE();
#endif /* BUFFER_CACHE_DISABLE */
#if (PREREAD_ENABLE != 0)
__HAL_FLASH_PREREAD_BUFFER_ENABLE();
#endif /* PREREAD_ENABLE */
#if (PREFETCH_ENABLE != 0)
__HAL_FLASH_PREFETCH_BUFFER_ENABLE();
#endif /* PREFETCH_ENABLE */
/* Use systick as time base source and configure 1ms tick (default clock after Reset is MSI) */
HAL_InitTick(TICK_INT_PRIORITY);
/* Init the low level hardware */
HAL_MspInit();
/* Return function status */
return HAL_OK;
}
/**
* @brief This function de-Initializes common part of the HAL and stops the source
* of time base.
* @note This function is optional.
* @param None
* @retval HAL status
*/
HAL_StatusTypeDef HAL_DeInit(void)
{
/* Reset of all peripherals */
__APB1_FORCE_RESET();
__APB1_RELEASE_RESET();
__APB2_FORCE_RESET();
__APB2_RELEASE_RESET();
__AHB_FORCE_RESET();
__AHB_RELEASE_RESET();
__IOP_FORCE_RESET();
__IOP_RELEASE_RESET();
/* De-Init the low level hardware */
HAL_MspDeInit();
/* Return function status */
return HAL_OK;
}
/**
* @brief Initializes the MSP.
* @param None
* @retval None
*/
__weak void HAL_MspInit(void)
{
/* NOTE : This function Should not be modified, when the callback is needed,
the HAL_MspInit could be implemented in the user file
*/
}
/**
* @brief DeInitializes the MSP.
* @param None
* @retval None
*/
__weak void HAL_MspDeInit(void)
{
/* NOTE : This function Should not be modified, when the callback is needed,
the HAL_MspDeInit could be implemented in the user file
*/
}
/**
* @}
*/
/**
* @brief This function configures the source of the time base.
* The time source is configured to have 1ms time base with a dedicated
* Tick interrupt priority.
* @note This function is called automatically at the beginning of program after
* reset by HAL_Init() or at any time when clock is reconfigured by HAL_RCC_ClockConfig().
* @note In the default implementation, SysTick timer is the source of time base.
* It is used to generate interrupts at regular time intervals.
* Care must be taken if HAL_Delay() is called from a peripheral ISR process,
* The the SysTick interrupt must have higher priority (numerically lower)
* than the peripheral interrupt. Otherwise the caller ISR process will be blocked.
* The function is declared as __Weak to be overwritten in case of other
* implementation in user file.
* @param TickPriority: Tick interrupt priority.
* @retval HAL status
*/
__weak HAL_StatusTypeDef HAL_InitTick(uint32_t TickPriority)
{
/*Configure the SysTick to have interrupt in 1ms time basis*/
HAL_SYSTICK_Config(HAL_RCC_GetHCLKFreq()/1000);
/*Configure the SysTick IRQ priority */
HAL_NVIC_SetPriority(SysTick_IRQn, TickPriority ,0);
/* Return function status */
return HAL_OK;
}
/** @defgroup HAL_Group2 HAL Control functions
* @brief HAL Control functions
*
@verbatim
===============================================================================
##### HAL Control functions #####
===============================================================================
[..] This section provides functions allowing to:
(+) Provide a tick value in millisecond
(+) Provide a blocking delay in millisecond
(+) Suspend the time base source interrupt
(+) Resume the time base source interrupt
(+) Get the HAL API driver version
(+) Get the device identifier
(+) Get the device revision identifier
(+) Configures low power mode behavior when the MCU is in Debug mode
@endverbatim
* @{
*/
/**
* @brief This function is called to increment a global variable "uwTick"
* used as application time base.
* @note In the default implementation, this variable is incremented each 1ms
* in Systick ISR.
* @note This function is declared as __weak to be overwritten in case of other
* implementations in user file.
* @param None
* @retval None
*/
__weak void HAL_IncTick(void)
{
uwTick++;
}
/**
* @brief Provides a tick value in millisecond.
* @note This function is declared as __weak to be overwritten in case of other
* implementations in user file.
* @param None
* @retval tick value
*/
__weak uint32_t HAL_GetTick(void)
{
return uwTick;
}
/**
* @brief This function provides accurate delay (in milliseconds) based
* on variable incremented.
* @note In the default implementation , SysTick timer is the source of time base.
* It is used to generate interrupts at regular time intervals where uwTick
* is incremented.
* @note ThiS function is declared as __weak to be overwritten in case of other
* implementations in user file.
* @param Delay: specifies the delay time length, in milliseconds.
* @retval None
*/
__weak void HAL_Delay(__IO uint32_t Delay)
{
uint32_t tickstart = 0;
tickstart = HAL_GetTick();
while((HAL_GetTick() - tickstart) < Delay)
{
}
}
/**
* @brief Suspend Tick increment.
* @note In the default implementation , SysTick timer is the source of time base. It is
* used to generate interrupts at regular time intervals. Once HAL_SuspendTick()
* is called, the the SysTick interrupt will be disabled and so Tick increment
* is suspended.
* @note This function is declared as __weak to be overwritten in case of other
* implementations in user file.
* @param None
* @retval None
*/
__weak void HAL_SuspendTick(void)
{
/* Disable SysTick Interrupt */
SysTick->CTRL &= ~SysTick_CTRL_TICKINT_Msk;
}
/**
* @brief Resume Tick increment.
* @note In the default implementation , SysTick timer is the source of time base. It is
* used to generate interrupts at regular time intervals. Once HAL_ResumeTick()
* is called, the the SysTick interrupt will be enabled and so Tick increment
* is resumed.
* @note This function is declared as __weak to be overwritten in case of other
* implementations in user file.
* @param None
* @retval None
*/
__weak void HAL_ResumeTick(void)
{
/* Enable SysTick Interrupt */
SysTick->CTRL |= SysTick_CTRL_TICKINT_Msk;
}
/**
* @brief Returns the HAL revision
* @param None
* @retval version: 0xXYZR (8bits for each decimal, R for RC)
*/
uint32_t HAL_GetHalVersion(void)
{
return __STM32L0xx_HAL_VERSION;
}
/**
* @brief Returns the device revision identifier.
* @param None
* @retval Device revision identifier
*/
uint32_t HAL_GetREVID(void)
{
return((DBGMCU->IDCODE) >> 16);
}
/**
* @brief Returns the device identifier.
* @param None
* @retval Device identifier
*/
uint32_t HAL_GetDEVID(void)
{
return((DBGMCU->IDCODE) & IDCODE_DEVID_MASK);
}
/**
* @brief Enable the Debug Module during SLEEP mode
* @param None
* @retval None
*/
void HAL_EnableDBGSleepMode(void)
{
SET_BIT(DBGMCU->CR, DBGMCU_CR_DBG_SLEEP);
}
/**
* @brief Disable the Debug Module during SLEEP mode
* @param None
* @retval None
*/
void HAL_DisableDBGSleepMode(void)
{
CLEAR_BIT(DBGMCU->CR, DBGMCU_CR_DBG_SLEEP);
}
/**
* @brief Enable the Debug Module during STOP mode
* @param None
* @retval None
*/
void HAL_EnableDBGStopMode(void)
{
SET_BIT(DBGMCU->CR, DBGMCU_CR_DBG_STOP);
}
/**
* @brief Disable the Debug Module during STOP mode
* @param None
* @retval None
*/
void HAL_DisableDBGStopMode(void)
{
CLEAR_BIT(DBGMCU->CR, DBGMCU_CR_DBG_STOP);
}
/**
* @brief Enable the Debug Module during STANDBY mode
* @param None
* @retval None
*/
void HAL_EnableDBGStandbyMode(void)
{
SET_BIT(DBGMCU->CR, DBGMCU_CR_DBG_STANDBY);
}
/**
* @brief Disable the Debug Module during STANDBY mode
* @param None
* @retval None
*/
void HAL_DisableDBGStandbyMode(void)
{
CLEAR_BIT(DBGMCU->CR, DBGMCU_CR_DBG_STANDBY);
}
/**
* @brief Configures low power mode behavior when the MCU is in Debug mode.
* @param 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 HAL_DBG_LowPowerConfig(uint32_t Periph, FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_DBGMCU_PERIPH(Periph));
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
DBGMCU->CR |= Periph;
}
else
{
DBGMCU->CR &= ~Periph;
}
}
/**
* @brief Returns the boot mode as configured by user.
* @param None.
* @retval The boot mode as configured by user. The returned value can be one
* of the following values:
* - 0x00000000: Boot is configured in Main Flash memory
* - 0x00000100: Boot is configured in System Flash memory
* - 0x00000300: Boot is configured in Embedded SRAM memory
*/
uint32_t HAL_GetBootMode(void)
{
return (SYSCFG->CFGR1 & SYSCFG_CFGR1_BOOT_MODE);
}
/**
* @brief Configures the I2C fast mode plus driving capability.
* @param SYSCFG_I2CFastModePlus: selects the pin.
* This parameter can be one of the following values:
* @arg SYSCFG_I2CFastModePlus_PB6: Configure fast mode plus driving capability for PB6
* @arg SYSCFG_I2CFastModePlus_PB7: Configure fast mode plus driving capability for PB7
* @arg SYSCFG_I2CFastModePlus_PB8: Configure fast mode plus driving capability for PB8
* @arg SYSCFG_I2CFastModePlus_PB9: Configure fast mode plus driving capability for PB9
* @arg SYSCFG_I2CFastModePlus_I2C1: Configure fast mode plus driving capability for I2C1 pins
* @arg SYSCFG_I2CFastModePlus_I2C2: Configure fast mode plus driving capability for I2C2 pins
* @param NewState: This parameter can be:
* ENABLE: Enable fast mode plus driving capability for selected I2C pin
* DISABLE: Disable fast mode plus driving capability for selected I2C pin
* @note For I2C1, fast mode plus driving capability can be enabled on all selected
* I2C1 pins using SYSCFG_I2CFastModePlus_I2C1 parameter or independently
* on each one of the following pins PB6, PB7, PB8 and PB9.
* @note For remaining I2C1 pins (PA14, PA15...) fast mode plus driving capability
* can be enabled only by using SYSCFG_I2CFastModePlus_I2C1 parameter.
* @note For all I2C2 pins fast mode plus driving capability can be enabled
* only by using SYSCFG_I2CFastModePlus_I2C2 parameter.
* @retval None
*/
void HAL_I2CFastModePlusConfig(uint32_t SYSCFG_I2CFastModePlus, FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_SYSCFG_I2C_FMP(SYSCFG_I2CFastModePlus));
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
/* Enable fast mode plus driving capability for selected pin */
SYSCFG->CFGR2 |= (uint32_t)SYSCFG_I2CFastModePlus;
}
else
{
/* Disable fast mode plus driving capability for selected pin */
SYSCFG->CFGR2 &= (uint32_t)(~SYSCFG_I2CFastModePlus);
}
}
/**
* @brief Enables or disables the VREFINT.
* @param NewState: new state of the Vrefint.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void HAL_VREFINT_Cmd(FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
/* Enable the VREFINT by setting EN_VREFINT bit in the CFGR3 register */
SYSCFG->CFGR3 |= SYSCFG_CFGR3_EN_VREFINT;
}
else
{
/* Disable the VREFINT by setting EN_VREFINT bit in the CFGR3 register */
SYSCFG->CFGR3 &= (uint32_t)~((uint32_t)SYSCFG_CFGR3_EN_VREFINT);
}
}
/**
* @brief Selects the output of internal reference voltage (VREFINT).
* The VREFINT output can be routed to(PB0) or
* (PB1) or both.
* @param SYSCFG_Vrefint_OUTPUT: new state of the Vrefint output.
* This parameter can be one of the following values:
* @arg SYSCFG_VREFINT_OUT_NONE
* @arg SYSCFG_VREFINT_OUT_PB0
* @arg SYSCFG_VREFINT_OUT_PB1
* @arg SYSCFG_VREFINT_OUT_PB0_PB1
* @retval None
*/
void HAL_VREFINT_OutputSelect(uint32_t SYSCFG_Vrefint_OUTPUT)
{
/* Check the parameters */
assert_param(IS_SYSCFG_VREFINT_OUT_SELECT(SYSCFG_Vrefint_OUTPUT));
/* Set the output Vrefint pin */
SYSCFG->CFGR3 &= ~(SYSCFG_CFGR3_VREF_OUT);
SYSCFG->CFGR3 |= (uint32_t)(SYSCFG_Vrefint_OUTPUT);
}
/**
* @brief Enables or disables the Buffer Vrefint for the ADC.
* @param NewState: new state of the Vrefint.
* This parameter can be: ENABLE or DISABLE.
* @note This is functional only if the LOCK is not set
* @retval None
*/
void HAL_ADC_EnableBuffer_Cmd(FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
/* Enable the Buffer for the ADC by setting EN_VREFINT bit and the ENBUF_VREFINT_ADC in the CFGR3 register */
SYSCFG->CFGR3 |= (SYSCFG_CFGR3_ENBUF_VREFINT_ADC | SYSCFG_CFGR3_EN_VREFINT);
}
else
{
/* Disable the Vrefint by resetting ENBUF_BGAP_ADC bit and the EN_VREFINT bit in the CFGR3 register */
SYSCFG->CFGR3 &= (uint32_t)~((uint32_t)(SYSCFG_CFGR3_ENBUF_VREFINT_ADC | SYSCFG_CFGR3_EN_VREFINT));
}
}
/**
* @brief Enables or disables the Buffer Sensor for the ADC.
* @param NewState: new state of the Vrefint.
* This parameter can be: ENABLE or DISABLE.
* @note This is functional only if the LOCK is not set.
* @retval None
*/
void HAL_ADC_EnableBufferSensor_Cmd(FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
/* Enable the Buffer for the ADC by setting EN_VREFINT bit and the ENBUF_SENSOR_ADC in the CFGR3 register */
SYSCFG->CFGR3 |= (SYSCFG_CFGR3_ENBUF_SENSOR_ADC | SYSCFG_CFGR3_EN_VREFINT);
}
else
{
/* Disable the Vrefint by resetting EN_VREFINT bit and the ENBUF_SENSOR_ADC in the CFGR3 register */
SYSCFG->CFGR3 &= (uint32_t)~((uint32_t)(SYSCFG_CFGR3_ENBUF_SENSOR_ADC | SYSCFG_CFGR3_EN_VREFINT));
}
}
/**
* @brief Enables or disables the Buffer Vrefint for the COMP.
* @param NewState: new state of the Vrefint.
* This parameter can be: ENABLE or DISABLE.
* @note This is functional only if the LOCK is not set
* @retval None
*/
void HAL_COMP_EnableBuffer_Cmd(FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
/* Enable the Buffer for the COMP by setting EN_VREFINT bit and the ENBUFLP_VREFINT_COMP in the CFGR3 register */
SYSCFG->CFGR3 |= (SYSCFG_CFGR3_ENBUFLP_VREFINT_COMP | SYSCFG_CFGR3_EN_VREFINT);
}
else
{
/* Disable the Vrefint by resetting ENBUFLP_BGAP_COMP bit and the EN_VREFINT bit in the CFGR3 register */
SYSCFG->CFGR3 &= (uint32_t)~((uint32_t)(SYSCFG_CFGR3_ENBUFLP_VREFINT_COMP | SYSCFG_CFGR3_EN_VREFINT));
}
}
/**
* @brief Enables or disables the Buffer Vrefint for the RC48.
* @param NewState: new state of the Vrefint.
* This parameter can be: ENABLE or DISABLE.
* @note This is functional only if the LOCK is not set
* @retval None
*/
void HAL_RC48_EnableBuffer_Cmd(FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
/* Enable the Buffer for the ADC by setting EN_VREFINT bit and the SYSCFG_CFGR3_ENREF_HSI48 in the CFGR3 register */
SYSCFG->CFGR3 |= (SYSCFG_CFGR3_ENREF_HSI48 | SYSCFG_CFGR3_EN_VREFINT);
}
else
{
/* Disable the Vrefint by resetting SYSCFG_CFGR3_ENREF_HSI48 bit and the EN_VREFINT bit in the CFGR3 register */
SYSCFG->CFGR3 &= (uint32_t)~((uint32_t)(SYSCFG_CFGR3_ENREF_HSI48 | SYSCFG_CFGR3_EN_VREFINT));
}
}
/**
* @brief Enables or disables the Lock.
* @param NewState: new state of the Lock.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void HAL_Lock_Cmd(FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
/* Enable the LOCK by setting REF_LOCK bit in the CFGR3 register */
SYSCFG->CFGR3 |= SYSCFG_CFGR3_REF_LOCK;
}
else
{
/* Disable the LOCK by setting REF_LOCK bit in the CFGR3 register */
SYSCFG->CFGR3 &= (uint32_t)~((uint32_t)SYSCFG_CFGR3_REF_LOCK);
}
}
/**
* @}
*/
/**
* @}
*/
#endif /* HAL_MODULE_ENABLED */
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,240 @@
/**
******************************************************************************
* @file stm32l0xx_hal.h
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief This file contains all the functions prototypes for the HAL
* module driver.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32L0xx_HAL_H
#define __STM32L0xx_HAL_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal_conf.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @addtogroup HAL
* @{
*/
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
/** @defgroup HAL_Exported_Constants
* @{
*/
/** @defgroup HAL_DBGMCU_Low_Power_Config
* @{
*/
#define DBGMCU_SLEEP DBGMCU_CR_DBG_SLEEP
#define DBGMCU_STOP DBGMCU_CR_DBG_STOP
#define DBGMCU_STANDBY DBGMCU_CR_DBG_STANDBY
#define IS_DBGMCU_PERIPH(PERIPH) ((((PERIPH) & 0xFFFFFFF8) == 0x00) && ((PERIPH) != 0x00))
/**
* @}
*/
/** @defgroup HAL_SYSCFG_I2C_FastModePlus_Config
* @{
*/
#define SYSCFG_I2CFastModePlus_PB6 SYSCFG_CFGR2_I2C_PB6_FMP /* Enable Fast Mode Plus on PB6 */
#define SYSCFG_I2CFastModePlus_PB7 SYSCFG_CFGR2_I2C_PB7_FMP /* Enable Fast Mode Plus on PB7 */
#define SYSCFG_I2CFastModePlus_PB8 SYSCFG_CFGR2_I2C_PB8_FMP /* Enable Fast Mode Plus on PB8 */
#define SYSCFG_I2CFastModePlus_PB9 SYSCFG_CFGR2_I2C_PB9_FMP /* Enable Fast Mode Plus on PB9 */
#define SYSCFG_I2CFastModePlus_I2C1 SYSCFG_CFGR2_I2C1_FMP /*!< Enable Fast Mode Plus on I2C1 pins */
#define SYSCFG_I2CFastModePlus_I2C2 SYSCFG_CFGR2_I2C2_FMP /*!< Enable Fast Mode Plus on I2C2 pins */
#define IS_SYSCFG_I2C_FMP(PIN) (((PIN) == SYSCFG_I2CFastModePlus_PB6) || \
((PIN) == SYSCFG_I2CFastModePlus_PB7) || \
((PIN) == SYSCFG_I2CFastModePlus_PB8) || \
((PIN) == SYSCFG_I2CFastModePlus_PB9) || \
((PIN) == SYSCFG_I2CFastModePlus_I2C1) || \
((PIN) == SYSCFG_I2CFastModePlus_I2C2))
/**
* @}
*/
/** @defgroup HAL_SYSCFG_VREFINT_OUT_SELECT
* @{
*/
#define SYSCFG_VREFINT_OUT_NONE ((uint32_t)0x00000000) /* no pad connected */
#define SYSCFG_VREFINT_OUT_PB0 SYSCFG_CFGR3_VREF_OUT_0 /* Selects PBO as output for the Vrefint */
#define SYSCFG_VREFINT_OUT_PB1 SYSCFG_CFGR3_VREF_OUT_1 /* Selects PB1 as output for the Vrefint */
#define SYSCFG_VREFINT_OUT_PB0_PB1 SYSCFG_CFGR3_VREF_OUT /* Selects PBO and PB1 as output for the Vrefint */
#define IS_SYSCFG_VREFINT_OUT_SELECT(OUTPUT) (((OUTPUT) == SYSCFG_VREFINT_OUT_PB0) || \
((OUTPUT) == SYSCFG_VREFINT_OUT_PB1) || \
((OUTPUT) == SYSCFG_VREFINT_OUT_PB0_PB1))
/**
* @}
*/
/** @defgroup HAL_SYSCFG_flags_definition
* @{
*/
#define SYSCFG_FLAG_RC48 SYSCFG_CFGR3_REF_HSI48_RDYF
#define SYSCFG_FLAG_SENSOR_ADC SYSCFG_CFGR3_SENSOR_ADC_RDYF
#define SYSCFG_FLAG_VREF_ADC SYSCFG_VREFINT_ADC_RDYF
#define SYSCFG_FLAG_VREF_COMP SYSCFG_CFGR3_VREFINT_COMP_RDYF
#define SYSCFG_FLAG_VREF_READY SYSCFG_CFGR3_VREFINT_RDYF
#define IS_SYSCFG_FLAG(FLAG) (((FLAG) == SYSCFG_FLAG_RC48) || \
((FLAG) == SYSCFG_FLAG_SENSOR_ADC) || \
((FLAG) == SYSCFG_FLAG_VREF_ADC) || \
((FLAG) == SYSCFG_FLAG_VREF_COMP) || \
((FLAG) == SYSCFG_FLAG_VREF_READY))
/**
* @}
*/
/* Exported macro ------------------------------------------------------------*/
/** @brief Freeze/Unfreeze Peripherals in Debug mode
*/
#define __HAL_FREEZE_TIM2_DBGMCU() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_TIM2_STOP))
#define __HAL_FREEZE_TIM6_DBGMCU() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_TIM6_STOP))
#define __HAL_FREEZE_RTC_DBGMCU() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_RTC_STOP))
#define __HAL_FREEZE_WWDG_DBGMCU() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_WWDG_STOP))
#define __HAL_FREEZE_IWDG_DBGMCU() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_IWDG_STOP))
#define __HAL_FREEZE_I2C1_TIMEOUT_DBGMCU() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_I2C1_STOP))
#define __HAL_FREEZE_I2C2_TIMEOUT_DBGMCU() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_I2C2_STOP))
#define __HAL_FREEZE_LPTIMER_DBGMCU() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_LPTIMER_STOP))
#define __HAL_FREEZE_TIM22_DBGMCU() (DBGMCU->APB2FZ |= (DBGMCU_APB2_FZ_DBG_TIM22_STOP))
#define __HAL_FREEZE_TIM21_DBGMCU() (DBGMCU->APB2FZ |= (DBGMCU_APB2_FZ_DBG_TIM21_STOP))
#define __HAL_UNFREEZE_TIM2_DBGMCU() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_TIM2_STOP))
#define __HAL_UNFREEZE_TIM6_DBGMCU() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_TIM6_STOP))
#define __HAL_UNFREEZE_RTC_DBGMCU() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_RTC_STOP))
#define __HAL_UNFREEZE_WWDG_DBGMCU() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_WWDG_STOP))
#define __HAL_UNFREEZE_IWDG_DBGMCU() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_IWDG_STOP))
#define __HAL_UNFREEZE_I2C1_TIMEOUT_DBGMCU() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_I2C1_STOP))
#define __HAL_UNFREEZE_I2C2_TIMEOUT_DBGMCU() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_I2C2_STOP))
#define __HAL_UNFREEZE_LPTIMER_DBGMCU() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_LPTIMER_STOP))
#define __HAL_UNFREEZE_TIM22_DBGMCU() (DBGMCU->APB2FZ &= ~(DBGMCU_APB2_FZ_DBG_TIM22_STOP))
#define __HAL_UNFREEZE_TIM21_DBGMCU() (DBGMCU->APB2FZ &= ~(DBGMCU_APB2_FZ_DBG_TIM21_STOP))
/** @brief Main Flash memory mapped at 0x00000000
*/
#define __HAL_REMAPMEMORY_FLASH (SYSCFG->CFGR1 &= ~(SYSCFG_CFGR1_MEM_MODE))
/** @brief System Flash memory mapped at 0x00000000
*/
#define __HAL_REMAPMEMORY_SYSTEMFLASH do {SYSCFG->CFGR1 &= ~(SYSCFG_CFGR1_MEM_MODE);\
SYSCFG->CFGR1 |= SYSCFG_CFGR1_MEM_MODE_0;\
}while(0);
/** @brief Embedded SRAM mapped at 0x00000000
*/
#define __HAL_REMAPMEMORY_SRAM do {SYSCFG->CFGR1 &= ~(SYSCFG_CFGR1_MEM_MODE);\
SYSCFG->CFGR1 |= (SYSCFG_CFGR1_MEM_MODE_0 | SYSCFG_CFGR1_MEM_MODE_1);\
}while(0);
/** @brief Check whether the specified SYSCFG flag is set or not.
* @param __FLAG__: specifies the flag to check.
* This parameter can be one of the following values:
* SYSCFG_FLAG_PE: SRAM parity error flag.
* @arg SYSCFG_FLAG_RC48
* @arg SYSCFG_FLAG_SENSOR_ADC
* @arg SYSCFG_FLAG_VREF_ADC
* @arg SYSCFG_FLAG_VREF_COMP
* @arg SYSCFG_FLAG_VREF_READY
* @retval The new state of __FLAG__ (TRUE or FALSE).
*/
#define __HAL_SYSCFG_GET_FLAG(__FLAG__) (((SYSCFG->CFGR3) & (__FLAG__)) == (__FLAG__))
/**
* @}
*/
/* Exported functions --------------------------------------------------------*/
/* Initialization and de-initialization functions ******************************/
HAL_StatusTypeDef HAL_Init(void);
HAL_StatusTypeDef HAL_DeInit(void);
void HAL_MspInit(void);
void HAL_MspDeInit(void);
HAL_StatusTypeDef HAL_InitTick (uint32_t TickPriority);
/* Peripheral Control functions ************************************************/
void HAL_IncTick(void);
void HAL_Delay(__IO uint32_t Delay);
uint32_t HAL_GetTick(void);
void HAL_SuspendTick(void);
void HAL_ResumeTick(void);
uint32_t HAL_GetHalVersion(void);
uint32_t HAL_GetREVID(void);
uint32_t HAL_GetDEVID(void);
void HAL_EnableDBGSleepMode(void);
void HAL_DisableDBGSleepMode(void);
void HAL_EnableDBGStopMode(void);
void HAL_DisableDBGStopMode(void);
void HAL_EnableDBGStandbyMode(void);
void HAL_DisableDBGStandbyMode(void);
void HAL_DBG_LowPowerConfig(uint32_t Periph, FunctionalState NewState);
uint32_t HAL_GetBootMode(void);
void HAL_I2CFastModePlusConfig(uint32_t SYSCFG_I2CFastModePlus, FunctionalState NewState);
void HAL_VREFINT_Cmd(FunctionalState NewState);
void HAL_VREFINT_OutputSelect(uint32_t SYSCFG_Vrefint_OUTPUT);
void HAL_ADC_EnableBuffer_Cmd(FunctionalState NewState);
void HAL_ADC_EnableBufferSensor_Cmd(FunctionalState NewState);
void HAL_COMP_EnableBuffer_Cmd(FunctionalState NewState);
void HAL_RC48_EnableBuffer_Cmd(FunctionalState NewState);
void HAL_Lock_Cmd(FunctionalState NewState);
/**
* @}
*/
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif /* __STM32L0xx_HAL_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,939 @@
/**
******************************************************************************
* @file stm32l0xx_hal_adc.h
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief This file contains all the functions prototypes for the ADC firmware
* library.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32L0xx_ADC_H
#define __STM32L0xx_ADC_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal_def.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @addtogroup ADC
* @{
*/
/* Exported types ------------------------------------------------------------*/
/**
* @brief HAL State structures definition
*/
typedef enum
{
HAL_ADC_STATE_RESET = 0x00, /*!< ADC not yet initialized or disabled */
HAL_ADC_STATE_READY = 0x01, /*!< ADC peripheral ready for use */
HAL_ADC_STATE_BUSY = 0x02, /*!< An internal process is ongoing */
HAL_ADC_STATE_BUSY_REG = 0x12, /*!< Regular conversion is ongoing */
HAL_ADC_STATE_TIMEOUT = 0x03, /*!< Timeout state */
HAL_ADC_STATE_ERROR = 0x04, /*!< ADC state error */
HAL_ADC_STATE_EOC = 0x05, /*!< Conversion is completed */
HAL_ADC_STATE_AWD = 0x06, /*!< ADC state analog watchdog */
}HAL_ADC_StateTypeDef;
/**
* @brief ADC Oversampler structure definition
*/
typedef struct
{
uint32_t Ratio; /*!< Configures the oversampling ratio.
This parameter can be a value of @ref ADC_Oversampling_Ratio */
uint32_t RightBitShift; /*!< Configures the division coefficient for the Oversampler.
This parameter can be a value of @ref ADC_Right_Bit_Shift */
uint32_t TriggeredMode; /*!< Selects the regular triggered oversampling mode
This parameter can be a value of @ref ADC_Triggered_Oversampling_Mode */
}ADC_OversamplingTypeDef;
/**
* @brief ADC Init structure definition
* @note The setting of these parameters with function HAL_ADC_Init() is conditioned by the ADC state.
* If ADC is not in the appropriate state to modify some parameters, these parameters setting is bypassed
* without error reporting (as it can be the expected behaviour in case of intended action to update antother parameter (which fullfills the ADC state condition) on the fly).
*/
typedef struct
{
uint32_t OversamplingMode; /*!< Specifies whether the oversampling feature is enabled or disabled
This parameter can be set to ENABLE or DISABLE.
Note: This parameter can be modified only if there is no conversion is ongoing. */
ADC_OversamplingTypeDef Oversample; /*!< Specifies the Oversampling parameters
Note: This parameter can be modified only if there is no conversion is ongoing. */
uint32_t ClockPrescaler; /*!< Selects the ADC clock frequency.
This parameter can be a value of @ref ADC_ClockPrescaler
Note: This parameter can be modified only if ADC is disabled. */
uint32_t Resolution; /*!< Configures the ADC resolution mode.
This parameter can be a value of @ref ADC_Resolution
Note: This parameter can be modified only if ADC is disabled. */
uint32_t SamplingTime; /*!< The sample time value to be set for all channels.
This parameter can be a value of @ref ADC_sampling_times
Note: This parameter can be modified only if there is no conversion ongoing. */
uint32_t ScanDirection; /*!< The scan sequence direction.
This parameter can be a value of @ref ADC_scan_direction
Note: This parameter can be modified only if there is no conversion is ongoing. */
uint32_t DataAlign; /*!< Specifies whether the ADC data alignment is left or right.
This parameter can be a value of @ref ADC_data_align
Note: This parameter can be modified only if there is no conversion is ongoing. */
uint32_t ContinuousConvMode; /*!< Specifies whether the conversion is performed in Continuous or Single mode.
This parameter can be set to ENABLE or DISABLE.
Note: This parameter can be modified only if there is no conversion is ongoing. */
uint32_t DiscontinuousConvMode; /*!< Specifies whether the conversion is performed
in Complete-sequence/Discontinuous-sequence.
Discontinuous mode can be enabled only if continuous mode is disabled.
This parameter can be set to ENABLE or DISABLE.
Note: This parameter can be modified only if there is no conversion is ongoing. */
uint32_t ExternalTrigConvEdge; /*!< Select the external trigger edge and enable the trigger.
This parameter can be a value of @ref ADC_External_trigger_Edge
Note: This parameter can be modified only if there is no conversion is ongoing. */
uint32_t ExternalTrigConv; /*!< Select the external event used to trigger the start of conversion.
This parameter can be a value of @ref ADC_External_trigger_Source
Note: This parameter can be modified only if there is no conversion is ongoing. */
uint32_t DMAContinuousRequests; /*!< Specifies whether the DMA requests are performed in one shot mode (DMA transfer stop when number of conversions is reached)
or in Continuous mode (DMA transfer unlimited, whatever number of conversions).
Note: In continuous mode, DMA must be configured in circular mode. Otherwise an overrun will be triggered when DMA buffer max pointer is reached.
This parameter can be set to ENABLE or DISABLE.
Note: This parameter can be modified only if there is no conversion is ongoing. */
uint32_t EOCSelection; /*!< Specifies what EOC (End Of Conversion) flag is used for conversion polling and interruption:
end of single channel conversion or end of channels conversions sequence.
This parameter can be a value of @ref ADC_EOCSelection */
uint32_t Overrun; /*!< Select the behaviour in case of overrun: data preserved or overwritten
This parameter has an effect on regular channels only, including in DMA mode.
This parameter can be a value of @ref ADC_Overrun
Note: This parameter can be modified only if there is no conversion is ongoing. */
uint32_t LowPowerAutoWait; /*!< Specifies the usage of dynamic low power Auto Delay: new conversion start only
when the previous conversion (for regular channel) is completed.
This avoids risk of overrun for low frequency application.
This parameter can be set to ENABLE or DISABLE.
Note: This parameter can be modified only if there is no conversion is ongoing. */
uint32_t LowPowerFrequencyMode; /*!< When selecting an analog ADC clock frequency lower than 2.8MHz,
it is mandatory to first enable the Low Frequency Mode.
This parameter can be set to ENABLE or DISABLE.
Note: This parameter can be modified only if there is no conversion is ongoing. */
uint32_t LowPowerAutoOff; /*!< When setting the AutoOff feature, the ADC is always powered off when not converting and automatically
wakes-up when a conversion is started (by software or hardware trigger).
This parameter can be set to ENABLE or DISABLE.
Note: This parameter can be modified only if there is no conversion is ongoing. */
}ADC_InitTypeDef;
/**
* @brief ADC handle Structure definition
*/
typedef struct __ADC_HandleTypeDef
{
ADC_TypeDef *Instance; /*!< Register base address */
ADC_InitTypeDef Init; /*!< ADC required parameters */
DMA_HandleTypeDef *DMA_Handle; /*!< Pointer DMA Handler */
HAL_LockTypeDef Lock; /*!< ADC locking object */
__IO HAL_ADC_StateTypeDef State; /*!< ADC communication state */
__IO uint32_t ErrorCode; /*!< ADC Error code */
}ADC_HandleTypeDef;
/**
* @brief ADC Configuration regular Channel structure definition
*/
typedef struct
{
uint32_t Channel; /*!< the ADC channel to configure
This parameter can be a value of @ref ADC_channels */
}ADC_ChannelConfTypeDef;
/**
* @brief ADC Configuration analog watchdog definition
*/
typedef struct
{
uint32_t WatchdogMode; /*!< Configures the ADC analog watchdog mode: single/all channels.
This parameter can be a value of @ref ADC_analog_watchdog_mode */
uint32_t Channel; /*!< Selects which ADC channel to monitor by analog watchdog.
This parameter has an effect only if watchdog mode is configured on single channel (parameter WatchdogMode)
This parameter can be a value of @ref ADC_channels */
uint32_t ITMode; /*!< Specifies whether the analog watchdog is configured in interrupt or polling mode.
This parameter can be set to ENABLE or DISABLE */
uint32_t HighThreshold; /*!< Configures the ADC analog watchdog High threshold value.
Depending of ADC resolution selected (12, 10, 8 or 6 bits),
this parameter must be a number between Min_Data = 0x000 and Max_Data = 0xFFF, 0x3FF, 0xFF or 0x3F respectively. */
uint32_t LowThreshold; /*!< Configures the ADC analog watchdog High threshold value.
Depending of ADC resolution selected (12, 10, 8 or 6 bits),
this parameter must be a number between Min_Data = 0x000 and Max_Data = 0xFFF, 0x3FF, 0xFF or 0x3F respectively. */
}ADC_AnalogWDGConfTypeDef;
/* Exported constants --------------------------------------------------------*/
/** @defgroup ADC_Exported_Constants
* @{
*/
/** @defgroup ADC_Error_Code
* @{
*/
#define HAL_ADC_ERROR_NONE ((uint32_t)0x00) /*!< No error */
#define HAL_ADC_ERROR_INTERNAL ((uint32_t)0x01) /*!< ADC IP internal error: if problem of clocking,
enable/disable, erroneous state */
#define HAL_ADC_ERROR_OVR ((uint32_t)0x01) /*!< OVR error */
#define HAL_ADC_ERROR_DMA ((uint32_t)0x02) /*!< DMA transfer error */
/**
* @}
*/
/** @defgroup ADC_TimeOut_Values
* @{
*/
/* Fixed timeout values for ADC calibration, enable settling time, disable */
/* settling time. */
/* Values defined to be higher than worst cases: low clocks freq, */
/* maximum prescalers. */
/* Unit: ms */
#define ADC_ENABLE_TIMEOUT 10
#define ADC_DISABLE_TIMEOUT 10
#define ADC_STOP_CONVERSION_TIMEOUT 10
/* Delay of 10us fixed to worst case: maximum CPU frequency 180MHz to have */
/* the minimum number of CPU cycles to fulfill this delay */
#define ADC_DELAY_10US_MIN_CPU_CYCLES 1800
/**
* @}
*/
/** @defgroup ADC_ClockPrescaler
* @{
*/
#define ADC_CLOCK_ASYNC_DIV1 ((uint32_t)0x00000000) /*!< ADC Asynchronous clock mode divided by 1 */
#define ADC_CLOCK_ASYNC_DIV2 (ADC_CCR_PRESC_0) /*!< ADC Asynchronous clock mode divided by 2 */
#define ADC_CLOCK_ASYNC_DIV4 (ADC_CCR_PRESC_1) /*!< ADC Asynchronous clock mode divided by 2 */
#define ADC_CLOCK_ASYNC_DIV6 (ADC_CCR_PRESC_1 | ADC_CCR_PRESC_0) /*!< ADC Asynchronous clock mode divided by 2 */
#define ADC_CLOCK_ASYNC_DIV8 (ADC_CCR_PRESC_2) /*!< ADC Asynchronous clock mode divided by 2 */
#define ADC_CLOCK_ASYNC_DIV10 (ADC_CCR_PRESC_2 | ADC_CCR_PRESC_0) /*!< ADC Asynchronous clock mode divided by 2 */
#define ADC_CLOCK_ASYNC_DIV12 (ADC_CCR_PRESC_2 | ADC_CCR_PRESC_1) /*!< ADC Asynchronous clock mode divided by 2 */
#define ADC_CLOCK_ASYNC_DIV16 (ADC_CCR_PRESC_2 | ADC_CCR_PRESC_1 | ADC_CCR_PRESC_0) /*!< ADC Asynchronous clock mode divided by 2 */
#define ADC_CLOCK_ASYNC_DIV32 (ADC_CCR_PRESC_3) /*!< ADC Asynchronous clock mode divided by 2 */
#define ADC_CLOCK_ASYNC_DIV64 (ADC_CCR_PRESC_3 | ADC_CCR_PRESC_0) /*!< ADC Asynchronous clock mode divided by 2 */
#define ADC_CLOCK_ASYNC_DIV128 (ADC_CCR_PRESC_3 | ADC_CCR_PRESC_1) /*!< ADC Asynchronous clock mode divided by 2 */
#define ADC_CLOCK_ASYNC_DIV256 (ADC_CCR_PRESC_3 | ADC_CCR_PRESC_1 | ADC_CCR_PRESC_0) /*!< ADC Asynchronous clock mode divided by 2 */
#define ADC_CLOCKPRESCALER_PCLK_DIV1 ((uint32_t)ADC_CFGR2_CKMODE_0) /*!< Synchronous clock mode divided by 1 */
#define ADC_CLOCKPRESCALER_PCLK_DIV2 ((uint32_t)ADC_CFGR2_CKMODE_1) /*!< Synchronous clock mode divided by 2 */
#define ADC_CLOCKPRESCALER_PCLK_DIV4 ((uint32_t)ADC_CFGR2_CKMODE) /*!< Synchronous clock mode divided by 4 */
#define IS_ADC_CLOCKPRESCALER(ADC_CLOCK) (((ADC_CLOCK) == ADC_CLOCK_ASYNC_DIV1) ||\
((ADC_CLOCK) == ADC_CLOCKPRESCALER_PCLK_DIV1) ||\
((ADC_CLOCK) == ADC_CLOCKPRESCALER_PCLK_DIV2) ||\
((ADC_CLOCK) == ADC_CLOCKPRESCALER_PCLK_DIV4) ||\
((ADC_CLOCK) == ADC_CLOCK_ASYNC_DIV1 ) ||\
((ADC_CLOCK) == ADC_CLOCK_ASYNC_DIV2 ) ||\
((ADC_CLOCK) == ADC_CLOCK_ASYNC_DIV4 ) ||\
((ADC_CLOCK) == ADC_CLOCK_ASYNC_DIV6 ) ||\
((ADC_CLOCK) == ADC_CLOCK_ASYNC_DIV8 ) ||\
((ADC_CLOCK) == ADC_CLOCK_ASYNC_DIV10 ) ||\
((ADC_CLOCK) == ADC_CLOCK_ASYNC_DIV12 ) ||\
((ADC_CLOCK) == ADC_CLOCK_ASYNC_DIV16 ) ||\
((ADC_CLOCK) == ADC_CLOCK_ASYNC_DIV32 ) ||\
((ADC_CLOCK) == ADC_CLOCK_ASYNC_DIV64 ) ||\
((ADC_CLOCK) == ADC_CLOCK_ASYNC_DIV128 ) ||\
((ADC_CLOCK) == ADC_CLOCK_ASYNC_DIV256))
/**
* @}
*/
/** @defgroup ADC_Resolution
* @{
*/
#define ADC_RESOLUTION12b ((uint32_t)0x00000000) /*!< ADC 12-bit resolution */
#define ADC_RESOLUTION10b ((uint32_t)ADC_CFGR1_RES_0) /*!< ADC 10-bit resolution */
#define ADC_RESOLUTION8b ((uint32_t)ADC_CFGR1_RES_1) /*!< ADC 8-bit resolution */
#define ADC_RESOLUTION6b ((uint32_t)ADC_CFGR1_RES) /*!< ADC 6-bit resolution */
#define IS_ADC_RESOLUTION(RESOLUTION) (((RESOLUTION) == ADC_RESOLUTION12b) || \
((RESOLUTION) == ADC_RESOLUTION10b) || \
((RESOLUTION) == ADC_RESOLUTION8b) || \
((RESOLUTION) == ADC_RESOLUTION6b))
#define IS_ADC_RESOLUTION_8_6_BITS(RESOLUTION) (((RESOLUTION) == ADC_RESOLUTION8b) || \
((RESOLUTION) == ADC_RESOLUTION6b))
/**
* @}
*/
/** @defgroup ADC_data_align
* @{
*/
#define ADC_DATAALIGN_RIGHT ((uint32_t)0x00000000)
#define ADC_DATAALIGN_LEFT ((uint32_t)ADC_CFGR1_ALIGN)
#define IS_ADC_DATA_ALIGN(ALIGN) (((ALIGN) == ADC_DATAALIGN_RIGHT) || \
((ALIGN) == ADC_DATAALIGN_LEFT))
/**
* @}
*/
/** @defgroup ADC_External_trigger_Edge
* @{
*/
#define ADC_EXTERNALTRIG_EDGE_NONE ((uint32_t)0x00000000)
#define ADC_EXTERNALTRIG_EDGE_RISING ((uint32_t)ADC_CFGR1_EXTEN_0)
#define ADC_EXTERNALTRIG_EDGE_FALLING ((uint32_t)ADC_CFGR1_EXTEN_1)
#define ADC_EXTERNALTRIG_EDGE_RISINGFALLING ((uint32_t)ADC_CFGR1_EXTEN)
#define IS_ADC_EXTTRIG_EDGE(EDGE) (((EDGE) == ADC_EXTERNALTRIG_EDGE_NONE) || \
((EDGE) == ADC_EXTERNALTRIG_EDGE_RISING) || \
((EDGE) == ADC_EXTERNALTRIG_EDGE_FALLING) || \
((EDGE) == ADC_EXTERNALTRIG_EDGE_RISINGFALLING))
/**
* @}
*/
/** @defgroup ADC_External_trigger_Source
* @{
*/
#define ADC_EXTERNALTRIG0_T6_TRGO ((uint32_t)0x00000000)
#define ADC_EXTERNALTRIG1_T21_CC2 ADC_CFGR1_EXTSEL_0
#define ADC_EXTERNALTRIG2_T2_TRGO ADC_CFGR1_EXTSEL_1
#define ADC_EXTERNALTRIG3_T2_CC4 ((uint32_t)0x000000C0)
#define ADC_EXTERNALTRIG4_T22_TRGO ADC_CFGR1_EXTSEL_2
#define ADC_EXTERNALTRIG7_EXT_IT11 ADC_CFGR1_EXTSEL
#define IS_ADC_EXTERNAL_TRIG_CONV(CONV) (((CONV) == ADC_EXTERNALTRIG0_T6_TRGO ) || \
((CONV) == ADC_EXTERNALTRIG1_T21_CC2 ) || \
((CONV) == ADC_EXTERNALTRIG2_T2_TRGO ) || \
((CONV) == ADC_EXTERNALTRIG3_T2_CC4 ) || \
((CONV) == ADC_EXTERNALTRIG4_T22_TRGO ) || \
((CONV) == ADC_EXTERNALTRIG7_EXT_IT11 ))
/**
* @}
*/
/** @defgroup ADC_EOCSelection
* @{
*/
#define EOC_SINGLE_CONV ((uint32_t) ADC_ISR_EOC)
#define EOC_SEQ_CONV ((uint32_t) ADC_ISR_EOS)
#define EOC_SINGLE_SEQ_CONV ((uint32_t)(ADC_ISR_EOC | ADC_ISR_EOS)) /*!< reserved for future use */
#define IS_ADC_EOC_SELECTION(EOC_SELECTION) (((EOC_SELECTION) == EOC_SINGLE_CONV) || \
((EOC_SELECTION) == EOC_SEQ_CONV) || \
((EOC_SELECTION) == EOC_SINGLE_SEQ_CONV))
/**
* @}
*/
/** @defgroup ADC_Overrun
* @{
*/
#define OVR_DATA_PRESERVED ((uint32_t)0x00000000)
#define OVR_DATA_OVERWRITTEN ((uint32_t)ADC_CFGR1_OVRMOD)
#define IS_ADC_OVERRUN(OVR) (((OVR) == OVR_DATA_PRESERVED) || \
((OVR) == OVR_DATA_OVERWRITTEN))
/**
* @}
*/
/** @defgroup ADC_channels
* @{
*/
#define ADC_CHANNEL_0 ((uint32_t)(ADC_CHSELR_CHSEL0))
#define ADC_CHANNEL_1 ((uint32_t)(ADC_CHSELR_CHSEL1) | ADC_CFGR1_AWDCH_0)
#define ADC_CHANNEL_2 ((uint32_t)(ADC_CHSELR_CHSEL2) | ADC_CFGR1_AWDCH_1)
#define ADC_CHANNEL_3 ((uint32_t)(ADC_CHSELR_CHSEL3)| ADC_CFGR1_AWDCH_1 | ADC_CFGR1_AWDCH_0)
#define ADC_CHANNEL_4 ((uint32_t)(ADC_CHSELR_CHSEL4)| ADC_CFGR1_AWDCH_2)
#define ADC_CHANNEL_5 ((uint32_t)(ADC_CHSELR_CHSEL5)| ADC_CFGR1_AWDCH_2| ADC_CFGR1_AWDCH_0)
#define ADC_CHANNEL_6 ((uint32_t)(ADC_CHSELR_CHSEL6)| ADC_CFGR1_AWDCH_2| ADC_CFGR1_AWDCH_1)
#define ADC_CHANNEL_7 ((uint32_t)(ADC_CHSELR_CHSEL7)| ADC_CFGR1_AWDCH_2| ADC_CFGR1_AWDCH_1 | ADC_CFGR1_AWDCH_0)
#define ADC_CHANNEL_8 ((uint32_t)(ADC_CHSELR_CHSEL8)| ADC_CFGR1_AWDCH_3)
#define ADC_CHANNEL_9 ((uint32_t)(ADC_CHSELR_CHSEL9)| ADC_CFGR1_AWDCH_3| ADC_CFGR1_AWDCH_0)
#define ADC_CHANNEL_10 ((uint32_t)(ADC_CHSELR_CHSEL10)| ADC_CFGR1_AWDCH_3| ADC_CFGR1_AWDCH_1)
#define ADC_CHANNEL_11 ((uint32_t)(ADC_CHSELR_CHSEL11)| ADC_CFGR1_AWDCH_3| ADC_CFGR1_AWDCH_1| ADC_CFGR1_AWDCH_0)
#define ADC_CHANNEL_12 ((uint32_t)(ADC_CHSELR_CHSEL12)| ADC_CFGR1_AWDCH_3| ADC_CFGR1_AWDCH_2)
#define ADC_CHANNEL_13 ((uint32_t)(ADC_CHSELR_CHSEL13)| ADC_CFGR1_AWDCH_3| ADC_CFGR1_AWDCH_2| ADC_CFGR1_AWDCH_0)
#define ADC_CHANNEL_14 ((uint32_t)(ADC_CHSELR_CHSEL14)| ADC_CFGR1_AWDCH_3| ADC_CFGR1_AWDCH_2| ADC_CFGR1_AWDCH_1)
#define ADC_CHANNEL_15 ((uint32_t)(ADC_CHSELR_CHSEL15)| ADC_CFGR1_AWDCH_3| ADC_CFGR1_AWDCH_2| ADC_CFGR1_AWDCH_1| ADC_CFGR1_AWDCH_0)
#define ADC_CHANNEL_16 ((uint32_t)(ADC_CHSELR_CHSEL16)| ADC_CFGR1_AWDCH_4)
#define ADC_CHANNEL_17 ((uint32_t)(ADC_CHSELR_CHSEL17)| ADC_CFGR1_AWDCH_4| ADC_CFGR1_AWDCH_0)
#define ADC_CHANNEL_18 ((uint32_t)(ADC_CHSELR_CHSEL18)| ADC_CFGR1_AWDCH_4| ADC_CFGR1_AWDCH_1)
/* Internal channels */
#define ADC_CHANNEL_VLCD ADC_CHANNEL_16
#define ADC_CHANNEL_VREFINT ADC_CHANNEL_17
#define ADC_CHANNEL_TEMPSENSOR ADC_CHANNEL_18
#define IS_ADC_CHANNEL(CHANNEL) (((CHANNEL) == ADC_CHANNEL_0) || \
((CHANNEL) == ADC_CHANNEL_1) || \
((CHANNEL) == ADC_CHANNEL_2) || \
((CHANNEL) == ADC_CHANNEL_3) || \
((CHANNEL) == ADC_CHANNEL_4) || \
((CHANNEL) == ADC_CHANNEL_5) || \
((CHANNEL) == ADC_CHANNEL_6) || \
((CHANNEL) == ADC_CHANNEL_7) || \
((CHANNEL) == ADC_CHANNEL_8) || \
((CHANNEL) == ADC_CHANNEL_9) || \
((CHANNEL) == ADC_CHANNEL_10) || \
((CHANNEL) == ADC_CHANNEL_11) || \
((CHANNEL) == ADC_CHANNEL_12) || \
((CHANNEL) == ADC_CHANNEL_13) || \
((CHANNEL) == ADC_CHANNEL_14) || \
((CHANNEL) == ADC_CHANNEL_15) || \
((CHANNEL) == ADC_CHANNEL_TEMPSENSOR) || \
((CHANNEL) == ADC_CHANNEL_VREFINT) || \
((CHANNEL) == ADC_CHANNEL_VLCD))
/**
* @}
*/
/** @defgroup ADC_Channel_AWD_Masks
* @{
*/
#define ADC_CHANNEL_MASK ((uint32_t)0x0007FFFF)
#define ADC_CHANNEL_AWD_MASK ((uint32_t)0x7C000000)
/**
* @}
*/
/** @defgroup ADC_sampling_times
* @{
*/
#define ADC_SAMPLETIME_1CYCLE_5 ((uint32_t)0x00000000) /*!< ADC sampling time 1.5 cycle */
#define ADC_SAMPLETIME_7CYCLES_5 ((uint32_t)ADC_SMPR_SMPR_0) /*!< ADC sampling time 7.5 CYCLES */
#define ADC_SAMPLETIME_13CYCLES_5 ((uint32_t)ADC_SMPR_SMPR_1) /*!< ADC sampling time 13.5 CYCLES */
#define ADC_SAMPLETIME_28CYCLES_5 ((uint32_t)(ADC_SMPR_SMPR_1 | ADC_SMPR_SMPR_0)) /*!< ADC sampling time 28.5 CYCLES */
#define ADC_SAMPLETIME_41CYCLES_5 ((uint32_t)ADC_SMPR_SMPR_2) /*!< ADC sampling time 41.5 CYCLES */
#define ADC_SAMPLETIME_55CYCLES_5 ((uint32_t)(ADC_SMPR_SMPR_2 | ADC_SMPR_SMPR_0)) /*!< ADC sampling time 55.5 CYCLES */
#define ADC_SAMPLETIME_71CYCLES_5 ((uint32_t)(ADC_SMPR_SMPR_2 | ADC_SMPR_SMPR_1)) /*!< ADC sampling time 71.5 CYCLES */
#define ADC_SAMPLETIME_239CYCLES_5 ((uint32_t)ADC_SMPR_SMPR) /*!< ADC sampling time 239.5 CYCLES */
#define IS_ADC_SAMPLE_TIME(TIME) (((TIME) == ADC_SAMPLETIME_1CYCLE_5 ) || \
((TIME) == ADC_SAMPLETIME_7CYCLES_5 ) || \
((TIME) == ADC_SAMPLETIME_13CYCLES_5 ) || \
((TIME) == ADC_SAMPLETIME_28CYCLES_5 ) || \
((TIME) == ADC_SAMPLETIME_41CYCLES_5 ) || \
((TIME) == ADC_SAMPLETIME_55CYCLES_5 ) || \
((TIME) == ADC_SAMPLETIME_71CYCLES_5 ) || \
((TIME) == ADC_SAMPLETIME_239CYCLES_5))
/**
* @}
*/
/** @defgroup ADC_scan_direction
* @{
*/
#define ADC_SCAN_DIRECTION_UPWARD ((uint32_t)0x00000000)
#define ADC_SCAN_DIRECTION_BACKWARD ADC_CFGR1_SCANDIR
#define IS_ADC_SCAN_DIRECTION(DIRECTION) (((DIRECTION) == ADC_SCAN_DIRECTION_UPWARD) || \
((DIRECTION) == ADC_SCAN_DIRECTION_BACKWARD))
/**
* @}
*/
/** @defgroup ADC_Oversampling_Ratio
* @{
*/
#define ADC_OVERSAMPLING_RATIO_2 ((uint32_t)0x00000000) /*!< ADC Oversampling ratio 2x */
#define ADC_OVERSAMPLING_RATIO_4 ((uint32_t)0x00000004) /*!< ADC Oversampling ratio 4x */
#define ADC_OVERSAMPLING_RATIO_8 ((uint32_t)0x00000008) /*!< ADC Oversampling ratio 8x */
#define ADC_OVERSAMPLING_RATIO_16 ((uint32_t)0x0000000C) /*!< ADC Oversampling ratio 16x */
#define ADC_OVERSAMPLING_RATIO_32 ((uint32_t)0x00000010) /*!< ADC Oversampling ratio 32x */
#define ADC_OVERSAMPLING_RATIO_64 ((uint32_t)0x00000014) /*!< ADC Oversampling ratio 64x */
#define ADC_OVERSAMPLING_RATIO_128 ((uint32_t)0x00000018) /*!< ADC Oversampling ratio 128x */
#define ADC_OVERSAMPLING_RATIO_256 ((uint32_t)0x0000001C) /*!< ADC Oversampling ratio 256x */
#define IS_ADC_OVERSAMPLING_RATIO(RATIO) (((RATIO) == ADC_OVERSAMPLING_RATIO_2 ) || \
((RATIO) == ADC_OVERSAMPLING_RATIO_4 ) || \
((RATIO) == ADC_OVERSAMPLING_RATIO_8 ) || \
((RATIO) == ADC_OVERSAMPLING_RATIO_16 ) || \
((RATIO) == ADC_OVERSAMPLING_RATIO_32 ) || \
((RATIO) == ADC_OVERSAMPLING_RATIO_64 ) || \
((RATIO) == ADC_OVERSAMPLING_RATIO_128 ) || \
((RATIO) == ADC_OVERSAMPLING_RATIO_256 ))
/**
* @}
*/
/** @defgroup ADC_Right_Bit_Shift
* @{
*/
#define ADC_RIGHTBITSHIFT_NONE ((uint32_t)0x00000000) /*!< ADC No bit shift for oversampling */
#define ADC_RIGHTBITSHIFT_1 ((uint32_t)0x00000020) /*!< ADC 1 bit shift for oversampling */
#define ADC_RIGHTBITSHIFT_2 ((uint32_t)0x00000040) /*!< ADC 2 bits shift for oversampling */
#define ADC_RIGHTBITSHIFT_3 ((uint32_t)0x00000060) /*!< ADC 3 bits shift for oversampling */
#define ADC_RIGHTBITSHIFT_4 ((uint32_t)0x00000080) /*!< ADC 4 bits shift for oversampling */
#define ADC_RIGHTBITSHIFT_5 ((uint32_t)0x000000A0) /*!< ADC 5 bits shift for oversampling */
#define ADC_RIGHTBITSHIFT_6 ((uint32_t)0x000000C0) /*!< ADC 6 bits shift for oversampling */
#define ADC_RIGHTBITSHIFT_7 ((uint32_t)0x000000E0) /*!< ADC 7 bits shift for oversampling */
#define ADC_RIGHTBITSHIFT_8 ((uint32_t)0x00000100) /*!< ADC 8 bits shift for oversampling */
#define IS_ADC_RIGHT_BIT_SHIFT(SHIFT) (((SHIFT) == ADC_RIGHTBITSHIFT_NONE) || \
((SHIFT) == ADC_RIGHTBITSHIFT_1 ) || \
((SHIFT) == ADC_RIGHTBITSHIFT_2 ) || \
((SHIFT) == ADC_RIGHTBITSHIFT_3 ) || \
((SHIFT) == ADC_RIGHTBITSHIFT_4 ) || \
((SHIFT) == ADC_RIGHTBITSHIFT_5 ) || \
((SHIFT) == ADC_RIGHTBITSHIFT_6 ) || \
((SHIFT) == ADC_RIGHTBITSHIFT_7 ) || \
((SHIFT) == ADC_RIGHTBITSHIFT_8 ))
/**
* @}
*/
/** @defgroup ADC_Triggered_Oversampling_Mode
* @{
*/
#define ADC_TRIGGEREDMODE_SINGLE_TRIGGER ((uint32_t)0x00000000) /*!< ADC No bit shift for oversampling */
#define ADC_TRIGGEREDMODE_MULTI_TRIGGER ((uint32_t)0x00000200) /*!< ADC No bit shift for oversampling */
#define IS_ADC_TRIGGERED_OVERSAMPLING_MODE(MODE) (((MODE) == ADC_TRIGGEREDMODE_SINGLE_TRIGGER) || \
((MODE) == ADC_TRIGGEREDMODE_MULTI_TRIGGER) )
/**
* @}
*/
/** @defgroup ADC_analog_watchdog_mode
* @{
*/
#define ADC_ANALOGWATCHDOG_NONE ((uint32_t) 0x00000000)
#define ADC_ANALOGWATCHDOG_SINGLE_REG ((uint32_t)(ADC_CFGR1_AWDSGL | ADC_CFGR1_AWDEN))
#define ADC_ANALOGWATCHDOG_ALL_REG ((uint32_t) ADC_CFGR1_AWDEN)
#define IS_ADC_ANALOG_WATCHDOG_MODE(WATCHDOG) (((WATCHDOG) == ADC_ANALOGWATCHDOG_NONE ) || \
((WATCHDOG) == ADC_ANALOGWATCHDOG_SINGLE_REG) || \
((WATCHDOG) == ADC_ANALOGWATCHDOG_ALL_REG ))
/**
* @}
*/
/** @defgroup ADC_conversion_type
* @{
*/
#define REGULAR_GROUP ((uint32_t)(ADC_FLAG_EOC | ADC_FLAG_EOS))
#define IS_ADC_CONVERSION_GROUP(CONVERSION) ((CONVERSION) == REGULAR_GROUP)
/**
* @}
*/
/** @defgroup ADC_Event_type
* @{
*/
#define AWD_EVENT ((uint32_t)ADC_FLAG_AWD)
#define OVR_EVENT ((uint32_t)ADC_FLAG_OVR)
#define IS_ADC_EVENT_TYPE(EVENT) (((EVENT) == AWD_EVENT) || \
((EVENT) == OVR_EVENT))
/**
* @}
*/
/** @defgroup ADC_interrupts_definition
* @{
*/
#define ADC_IT_RDY ADC_IER_ADRDYIE /*!< ADC Ready (ADRDY) interrupt source */
#define ADC_IT_EOSMP ADC_IER_EOSMPIE /*!< ADC End of Sampling interrupt source */
#define ADC_IT_EOC ADC_IER_EOCIE /*!< ADC End of Regular Conversion interrupt source */
#define ADC_IT_EOS ADC_IER_EOSEQIE /*!< ADC End of Regular sequence of Conversions interrupt source */
#define ADC_IT_OVR ADC_IER_OVRIE /*!< ADC overrun interrupt source */
#define ADC_IT_AWD ADC_IER_AWDIE /*!< ADC Analog watchdog 1 interrupt source */
#define ADC_IT_EOCAL ADC_IER_EOCALIE /*!< ADC End of Calibration interrupt source */
/* Check of single flag */
#define IS_ADC_IT(IT) (((IT) == ADC_IT_AWD) || ((IT) == ADC_IT_RDY) || \
((IT) == ADC_IT_EOSMP) || ((IT) == ADC_IT_EOC) || \
((IT) == ADC_IT_EOS) || ((IT) == ADC_IT_OVR))
/**
* @}
*/
/** @defgroup ADC_flags_definition
* @{
*/
#define ADC_FLAG_RDY ADC_ISR_ADRDY /*!< ADC Ready (ADRDY) flag */
#define ADC_FLAG_EOSMP ADC_ISR_EOSMP /*!< ADC End of Sampling flag */
#define ADC_FLAG_EOC ADC_ISR_EOC /*!< ADC End of Regular Conversion flag */
#define ADC_FLAG_EOS ADC_ISR_EOSEQ /*!< ADC End of Regular sequence of Conversions flag */
#define ADC_FLAG_OVR ADC_ISR_OVR /*!< ADC overrun flag */
#define ADC_FLAG_AWD ADC_ISR_AWD /*!< ADC Analog watchdog flag */
#define ADC_FLAG_EOCAL ADC_ISR_EOCAL /*!< ADC Enf Of Calibration flag */
#define ADC_FLAG_ALL (ADC_FLAG_RDY | ADC_FLAG_EOSMP | ADC_FLAG_EOC | ADC_FLAG_EOS | \
ADC_FLAG_OVR | ADC_FLAG_AWD | ADC_FLAG_EOCAL)
/* Check of single flag */
#define IS_ADC_FLAG(FLAG) (((FLAG) == ADC_FLAG_RDY) || ((FLAG) == ADC_FLAG_EOSMP) || \
((FLAG) == ADC_FLAG_EOC) || ((FLAG) == ADC_FLAG_EOS) || \
((FLAG) == ADC_FLAG_OVR) || ((FLAG) == ADC_FLAG_AWD) || \
((FLAG) == ADC_FLAG_EOCAL))
/**
* @}
*/
/** @defgroup ADC_range_verification
* in function of ADC resolution selected (12, 10, 8 or 6 bits)
* @{
*/
#define IS_ADC_RANGE(RESOLUTION, ADC_VALUE) \
((((RESOLUTION) == ADC_RESOLUTION12b) && ((ADC_VALUE) <= ((uint32_t)0x0FFF))) || \
(((RESOLUTION) == ADC_RESOLUTION10b) && ((ADC_VALUE) <= ((uint32_t)0x03FF))) || \
(((RESOLUTION) == ADC_RESOLUTION8b) && ((ADC_VALUE) <= ((uint32_t)0x00FF))) || \
(((RESOLUTION) == ADC_RESOLUTION6b) && ((ADC_VALUE) <= ((uint32_t)0x003F))))
/**
* @}
*/
/** @defgroup ADC_regular_nb_conv_verification
* @{
*/
#define IS_ADC_REGULAR_NB_CONV(LENGTH) (((LENGTH) >= ((uint32_t)1)) && ((LENGTH) <= ((uint32_t)16)))
/**
* @}
*/
/**
* @}
*/
/* Exported macro ------------------------------------------------------------*/
/** @defgroup ADC_Exported_Macro
* @{
*/
/** @brief Reset ADC handle state
* @param __HANDLE__: ADC handle
* @retval None
*/
#define __HAL_ADC_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_ADC_STATE_RESET)
/**
* @brief Enable the ADC peripheral
* @param __HANDLE__: ADC handle
* @retval None
*/
#define __HAL_ADC_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR |= ADC_CR_ADEN)
/**
* @brief Verification of hardware constraints before ADC can be enabled
* @param __HANDLE__: ADC handle
* @retval SET (ADC can be enabled) or RESET (ADC cannot be enabled)
*/
#define __HAL_ADC_ENABLING_CONDITIONS(__HANDLE__) \
(( ( ((__HANDLE__)->Instance->CR) & \
(ADC_CR_ADCAL | ADC_CR_ADSTP | ADC_CR_ADSTART | \
ADC_CR_ADDIS | ADC_CR_ADEN ) \
) == RESET \
) ? SET : RESET)
/**
* @brief Disable the ADC peripheral
* @param __HANDLE__: ADC handle
* @retval None
*/
#define __HAL_ADC_DISABLE(__HANDLE__) \
do{ \
(__HANDLE__)->Instance->CR |= ADC_CR_ADDIS; \
__HAL_ADC_CLEAR_FLAG((__HANDLE__), (ADC_FLAG_EOSMP | ADC_FLAG_RDY)); \
} while(0)
/**
* @brief Verification of hardware constraints before ADC can be disabled
* @param __HANDLE__: ADC handle
* @retval SET (ADC can be disabled) or RESET (ADC cannot be disabled)
*/
#define __HAL_ADC_DISABLING_CONDITIONS(__HANDLE__) \
(( ( ((__HANDLE__)->Instance->CR) & \
(ADC_CR_ADSTART | ADC_CR_ADEN)) == ADC_CR_ADEN \
) ? SET : RESET)
/**
* @brief Verification of ADC state: enabled or disabled
* @param __HANDLE__: ADC handle
* @retval SET (ADC enabled) or RESET (ADC disabled)
*/
#define __HAL_ADC_IS_ENABLED(__HANDLE__) \
(( ((((__HANDLE__)->Instance->CR) & (ADC_CR_ADEN | ADC_CR_ADDIS)) == ADC_CR_ADEN) && \
((((__HANDLE__)->Instance->ISR) & ADC_FLAG_RDY) == ADC_FLAG_RDY) \
) ? SET : RESET)
/**
* @brief Returns resolution bits in CFGR register: RES[1:0]. Return value among parameter to @ref ADC_Resolution.
* @param __HANDLE__: ADC handle
* @retval None
*/
#define __HAL_ADC_GET_RESOLUTION(__HANDLE__) (((__HANDLE__)->Instance->CFGR1) & ADC_CFGR1_RES)
/**
* @brief Check if no conversion is ongoing on regular groups
* @param __HANDLE__: ADC handle
* @retval SET (conversion is on going) or RESET (no conversion is on going)
*/
#define __HAL_ADC_IS_CONVERSION_ONGOING(__HANDLE__) \
(( (((__HANDLE__)->Instance->CR) & (ADC_CR_ADSTART)) == RESET ) ? RESET : SET)
/**
* @brief Enable ADC continuous conversion mode.
* @param _CONTINUOUS_MODE_: Continuous mode.
* @retval None
*/
#define __HAL_ADC_CFGR1_CONTINUOUS(_CONTINUOUS_MODE_) ((_CONTINUOUS_MODE_) << 13)
/**
* @brief Configures the number of discontinuous conversions for the regular group channels.
* @param _NBR_DISCONTINUOUS_CONV_: Number of discontinuous conversions.
* @retval None
*/
#define __HAL_ADC_CFGR1_DISCONTINUOUS_NUM(_NBR_DISCONTINUOUS_CONV_) (((_NBR_DISCONTINUOUS_CONV_) - 1) << 17)
/**
* @brief Enable the ADC DMA continuous request.
* @param _DMAContReq_MODE_: DMA continuous request mode.
* @retval None
*/
#define __HAL_ADC_CFGR1_DMAContReq(_DMAContReq_MODE_) ((_DMAContReq_MODE_) << 1)
/**
* @brief Enable the ADC Auto Delay.
* @param _AutoDelay_: Auto delay bit enable or disable.
* @retval None
*/
#define __HAL_ADC_CFGR1_AutoDelay(_AutoDelay_) ((_AutoDelay_) << 14)
/**
* @brief Enable the ADC LowPowerAutoOff.
* @param _AUTOFF_: AutoOff bit enable or disable.
* @retval None
*/
#define __HAL_ADC_CFGR1_AUTOFF(_AUTOFF_) ((_AUTOFF_) << 15)
/**
* @brief Configure the analog watchdog high threshold into registers TR1, TR2 or TR3.
* @param _Threshold_: Threshold value
* @retval None
*/
#define __HAL_ADC_TRx_HighThreshold(_Threshold_) ((_Threshold_) << 16)
/**
* @brief Enable the ADC Low Frequency mode.
* @param _LOW_FREQUENCY_MODE_: Low Frequency mode.
* @retval None
*/
#define __HAL_ADC_CCR_LOWFREQUENCY(_LOW_FREQUENCY_MODE_) ((_LOW_FREQUENCY_MODE_) << 25)
/**
* @brief Shift the offset in function of the selected ADC resolution.
* Offset has to be left-aligned on bit 11, the LSB (right bits) are set to 0
* If resolution 12 bits, no shift.
* If resolution 10 bits, shift of 2 ranks on the right.
* If resolution 8 bits, shift of 4 ranks on the right.
* If resolution 6 bits, shift of 6 ranks on the right.
* therefore, shift = (12 - resolution) = 12 - (12- (((RES[1:0]) >> 3)*2))
* @param __HANDLE__: ADC handle.
* @param _Offset_: Value to be shifted
* @retval None
*/
#define __HAL_ADC_Offset_shift_resolution(__HANDLE__, _Offset_) \
((_Offset_) << ((((__HANDLE__)->Instance->CFGR & ADC_CFGR1_RES) >> 3)*2))
/**
* @brief Shift the AWD1 threshold in function of the selected ADC resolution.
* Thresholds have to be left-aligned on bit 11, the LSB (right bits) are set to 0
* If resolution 12 bits, no shift.
* If resolution 10 bits, shift of 2 ranks on the right.
* If resolution 8 bits, shift of 4 ranks on the right.
* If resolution 6 bits, shift of 6 ranks on the right.
* therefore, shift = (12 - resolution) = 12 - (12- (((RES[1:0]) >> 3)*2))
* @param __HANDLE__: ADC handle.
* @param _Threshold_: Value to be shifted
* @retval None
*/
#define __HAL_ADC_AWD1Threshold_shift_resolution(__HANDLE__, _Threshold_) \
((_Threshold_) << ((((__HANDLE__)->Instance->CFGR1 & ADC_CFGR1_RES) >> 3)*2))
/**
* @brief Shift the value on the left, less significant are set to 0.
* @param _Value_: Value to be shifted
* @param _Shift_: Number of shift to be done
* @retval None
*/
#define __HAL_ADC_Value_Shift_left(_Value_, _Shift_) ((_Value_) << (_Shift_))
/**
* @brief Enable the ADC end of conversion interrupt.
* @param __HANDLE__: ADC handle.
* @param __INTERRUPT__: ADC Interrupt.
* @retval None
*/
#define __HAL_ADC_ENABLE_IT(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->IER) |= (__INTERRUPT__))
/**
* @brief Disable the ADC end of conversion interrupt.
* @param __HANDLE__: ADC handle.
* @param __INTERRUPT__: ADC interrupt.
* @retval None
*/
#define __HAL_ADC_DISABLE_IT(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->IER) &= ~(__INTERRUPT__))
/** @brief Checks if the specified ADC interrupt source is enabled or disabled.
* @param __HANDLE__: specifies the ADC Handle.
* @param __INTERRUPT__: specifies the ADC interrupt source to check.
* @retval The new state of __IT__ (TRUE or FALSE).
*/
#define __HAL_ADC_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) ((((__HANDLE__)->Instance->IER & (__INTERRUPT__)) == (__INTERRUPT__)) ? SET : RESET)
/**
* @brief Clear the ADC's pending flags
* @param __HANDLE__: ADC handle.
* @param __FLAG__: ADC flag.
* @retval None
*/
/* Note: bit cleared bit by writing 1 */
#define __HAL_ADC_CLEAR_FLAG(__HANDLE__, __FLAG__) (((__HANDLE__)->Instance->ISR) = (__FLAG__))
/**
* @brief Get the selected ADC's flag status.
* @param __HANDLE__: ADC handle.
* @param __FLAG__: ADC flag.
* @retval None
*/
#define __HAL_ADC_GET_FLAG(__HANDLE__, __FLAG__) ((((__HANDLE__)->Instance->ISR) & (__FLAG__)) == (__FLAG__))
/**
* @brief Configuration of ADC clock & prescaler: clock source PCLK or Asynchronous with selectable prescaler
* @param __HANDLE__: ADC handle
* @retval None
*/
#define __HAL_ADC_CLOCK_PRESCALER(__HANDLE__) \
do{ \
if ((((__HANDLE__)->Init.ClockPrescaler) == ADC_CLOCKPRESCALER_PCLK_DIV1) || \
(((__HANDLE__)->Init.ClockPrescaler) == ADC_CLOCKPRESCALER_PCLK_DIV2) || \
(((__HANDLE__)->Init.ClockPrescaler) == ADC_CLOCKPRESCALER_PCLK_DIV2)) \
{ \
(__HANDLE__)->Instance->CFGR2 &= ~(ADC_CFGR2_CKMODE); \
(__HANDLE__)->Instance->CFGR2 |= (__HANDLE__)->Init.ClockPrescaler; \
} \
else \
{ \
/* CKMOD bits must be reset */ \
(__HANDLE__)->Instance->CFGR2 &= ~(ADC_CFGR2_CKMODE); \
ADC->CCR &= ~(ADC_CCR_PRESC); \
ADC->CCR |= (__HANDLE__)->Init.ClockPrescaler; \
} \
} while(0)
/**
* @}
*/
/* Include ADC HAL Extension module */
#include "stm32l0xx_hal_adc_ex.h"
/* Exported functions --------------------------------------------------------*/
/* Initialization and de-initialization functions **********************************/
HAL_StatusTypeDef HAL_ADC_Init(ADC_HandleTypeDef* hadc);
HAL_StatusTypeDef HAL_ADC_DeInit(ADC_HandleTypeDef *hadc);
void HAL_ADC_MspInit(ADC_HandleTypeDef* hadc);
void HAL_ADC_MspDeInit(ADC_HandleTypeDef* hadc);
/* IO operation functions *****************************************************/
/* Blocking mode: Polling */
HAL_StatusTypeDef HAL_ADC_Start(ADC_HandleTypeDef* hadc);
HAL_StatusTypeDef HAL_ADC_Stop(ADC_HandleTypeDef* hadc);
HAL_StatusTypeDef HAL_ADC_PollForConversion(ADC_HandleTypeDef* hadc, uint32_t Timeout);
HAL_StatusTypeDef HAL_ADC_PollForEvent(ADC_HandleTypeDef* hadc, uint32_t EventType, uint32_t Timeout);
/* Non-blocking mode: Interruption */
HAL_StatusTypeDef HAL_ADC_Start_IT(ADC_HandleTypeDef* hadc);
HAL_StatusTypeDef HAL_ADC_Stop_IT(ADC_HandleTypeDef* hadc);
/* Non-blocking mode: DMA */
HAL_StatusTypeDef HAL_ADC_Start_DMA(ADC_HandleTypeDef* hadc, uint32_t* pData, uint32_t Length);
HAL_StatusTypeDef HAL_ADC_Stop_DMA(ADC_HandleTypeDef* hadc);
/* ADC retrieve conversion value intended to be used with polling or interruption */
uint32_t HAL_ADC_GetValue(ADC_HandleTypeDef* hadc);
/* ADC IRQHandler and Callbacks used in non-blocking modes (Interruption and DMA) */
void HAL_ADC_IRQHandler(ADC_HandleTypeDef* hadc);
void HAL_ADC_ConvCpltCallback(ADC_HandleTypeDef* hadc);
void HAL_ADC_ConvHalfCpltCallback(ADC_HandleTypeDef* hadc);
void HAL_ADC_LevelOutOfWindowCallback(ADC_HandleTypeDef* hadc);
void HAL_ADC_ErrorCallback(ADC_HandleTypeDef *hadc);
/* Peripheral Control functions ***********************************************/
HAL_StatusTypeDef HAL_ADC_ConfigChannel(ADC_HandleTypeDef* hadc, ADC_ChannelConfTypeDef* sConfig);
HAL_StatusTypeDef HAL_ADC_AnalogWDGConfig(ADC_HandleTypeDef* hadc, ADC_AnalogWDGConfTypeDef* AnalogWDGConfig);
/* Peripheral State functions *************************************************/
HAL_ADC_StateTypeDef HAL_ADC_GetState(ADC_HandleTypeDef* hadc);
uint32_t HAL_ADC_GetError(ADC_HandleTypeDef *hadc);
/**
* @}
*/
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif /*__STM32L0xx_ADC_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,273 @@
/**
******************************************************************************
* @file stm32l0xx_hal_adc_ex.c
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief This file provides firmware functions to manage the following
* functionalities of the Analog to Digital Convertor (ADC)
* peripheral:
* + Start calibration.
* + Read the calibration factor.
* + Set a calibration factor.
*
@verbatim
==============================================================================
##### ADC specific features #####
==============================================================================
[..]
(#) Self calibration.
##### How to use this driver #####
==============================================================================
[..]
(#) Call HAL_ADCEx_Calibration_Start() to start calibration
(#) Read the calibration factor using HAL_ADCEx_Calibration_GetValue()
(#) User can set a his calibration factor using HAL_ADCEx_Calibration_SetValue()
@endverbatim
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @addtogroup ADCEx
* @brief ADC driver modules
* @{
*/
#ifdef HAL_ADC_MODULE_ENABLED
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/** @defgroup ADCEx_Group ADC Extended features functions
* @brief ADC Extended features functions
*
@verbatim
===============================================================================
##### ADC Extended features functions #####
===============================================================================
[..]
This subsection provides functions allowing to:
(+) Start calibration.
(+) Get calibration factor.
(+) Set calibration factor.
@endverbatim
* @{
*/
/**
* @brief Start an automatic calibration
* @param hadc: pointer to a ADC_HandleTypeDef structure that contains
* the configuration information for the specified ADC.
* @param SingleDiff: Selection of single-ended or differential input
* This parameter can be only of the following values:
* @arg ADC_SINGLE_ENDED: Channel in mode input single ended
* @retval HAL status
*/
HAL_StatusTypeDef HAL_ADCEx_Calibration_Start(ADC_HandleTypeDef* hadc, uint32_t SingleDiff)
{
uint32_t tickstart = 0;
/* Check the parameters */
assert_param(IS_ADC_ALL_INSTANCE(hadc->Instance));
assert_param(IS_ADC_SINGLE_DIFFERENTIAL(SingleDiff));
/* Process locked */
__HAL_LOCK(hadc);
/* Disable the ADC (if not already disabled) */
if (__HAL_ADC_IS_ENABLED(hadc) != RESET )
{
/* Check if conditions to disable the ADC are fulfilled */
if (__HAL_ADC_DISABLING_CONDITIONS(hadc) != RESET)
{
__HAL_ADC_DISABLE(hadc);
}
else
{
hadc->State= HAL_ADC_STATE_ERROR;
/* Process unlocked */
__HAL_UNLOCK(hadc);
return HAL_ERROR;
}
/* Wait for ADC effectively disabled */
/* Get timeout */
tickstart = HAL_GetTick();
/* Wait for disabling completion */
while(HAL_IS_BIT_SET(hadc->Instance->CR, ADC_CR_ADEN))
{
/* Check for the Timeout */
if(ADC_DISABLE_TIMEOUT != HAL_MAX_DELAY)
{
if((HAL_GetTick() - tickstart ) > ADC_DISABLE_TIMEOUT)
{
hadc->State= HAL_ADC_STATE_TIMEOUT;
/* Process unlocked */
__HAL_UNLOCK(hadc);
return HAL_TIMEOUT;
}
}
}
}
/* Start ADC calibration */
hadc->Instance->CR |= ADC_CR_ADCAL;
/* Get timeout */
tickstart = HAL_GetTick();
/* Wait for calibration completion */
while(HAL_IS_BIT_SET(hadc->Instance->CR, ADC_CR_ADCAL))
{
/* Check for the Timeout */
if(ADC_CALIBRATION_TIMEOUT != HAL_MAX_DELAY)
{
if((HAL_GetTick() - tickstart ) > ADC_CALIBRATION_TIMEOUT)
{
hadc->State= HAL_ADC_STATE_TIMEOUT;
/* Process unlocked */
__HAL_UNLOCK(hadc);
return HAL_TIMEOUT;
}
}
}
/* Process unlocked */
__HAL_UNLOCK(hadc);
/* Return function status */
return HAL_OK;
}
/**
* @brief Get the calibration factor.
* @param hadc: ADC handle.
* @param SingleDiff: This parameter can be only:
* @arg ADC_SINGLE_ENDED: Channel in mode input single ended.
* @retval Calibration value.
*/
uint32_t HAL_ADCEx_Calibration_GetValue(ADC_HandleTypeDef* hadc, uint32_t SingleDiff)
{
/* Check the parameters */
assert_param(IS_ADC_ALL_INSTANCE(hadc->Instance));
assert_param(IS_ADC_SINGLE_DIFFERENTIAL(SingleDiff));
/* Return the ADC calibration value */
return ((hadc->Instance->CALFACT) & 0x0000007F);
}
/**
* @brief Set the calibration factor to overwrite automatic conversion result.
* ADC must be enabled and no conversion is ongoing.
* @param hadc: ADC handle
* @param SingleDiff: This parameter can be only:
* @arg ADC_SINGLE_ENDED: Channel in mode input single ended.
* @param CalibrationFactor: Calibration factor (coded on 7 bits maximum)
* @retval HAL state
*/
HAL_StatusTypeDef HAL_ADCEx_Calibration_SetValue(ADC_HandleTypeDef* hadc, uint32_t SingleDiff, uint32_t CalibrationFactor)
{
HAL_StatusTypeDef tmpHALStatus = HAL_OK;
/* Check the parameters */
assert_param(IS_ADC_ALL_INSTANCE(hadc->Instance));
assert_param(IS_ADC_SINGLE_DIFFERENTIAL(SingleDiff));
assert_param(IS_ADC_CALFACT(CalibrationFactor));
/* Process locked */
__HAL_LOCK(hadc);
/* Verification of hardware constraints before modifying the calibration */
/* factors register: ADC must be enabled, no conversion on going. */
if ( (__HAL_ADC_IS_ENABLED(hadc) != RESET) &&
(__HAL_ADC_IS_CONVERSION_ONGOING(hadc) == RESET) )
{
/* Set the selected ADC calibration value */
hadc->Instance->CALFACT &= ~ADC_CALFACT_CALFACT;
hadc->Instance->CALFACT |= CalibrationFactor;
}
else
{
/* Update ADC state machine to error */
hadc->State = HAL_ADC_STATE_ERROR;
/* Update ADC state machine to error */
tmpHALStatus = HAL_ERROR;
}
/* Process unlocked */
__HAL_UNLOCK(hadc);
/* Return function status */
return tmpHALStatus;
}
/**
* @}
*/
#endif /* HAL_ADC_MODULE_ENABLED */
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,121 @@
/**
******************************************************************************
* @file stm32l0xx_hal_adc_ex.h
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief This file contains all the functions prototypes for the ADC firmware
* library.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32L0xx_ADC_EX_H
#define __STM32L0xx_ADC_EX_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal_def.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @addtogroup ADCEx
* @{
*/
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
/** @defgroup ADCEx_Exported_Constants
* @{
*/
/** @defgroup ADCEx_TimeOut_Values
* @{
*/
#define ADC_CALIBRATION_TIMEOUT 10
/**
* @}
*/
/** @defgroup ADCEx_Channel_Mode
* @{
*/
#define ADC_SINGLE_ENDED (uint32_t)0x00000000 /* dummy value */
#define IS_ADC_SINGLE_DIFFERENTIAL(SING_DIFF) ((SING_DIFF) == ADC_SINGLE_ENDED)
/**
* @}
*/
/** @defgroup ADCEx_calibration_factor_length_verification
* @{
*/
/**
* @brief Calibration factor lenght verification (7 bits maximum)
* @param _Calibration_Factor_: Calibration factor value
* @retval None
*/
#define IS_ADC_CALFACT(_Calibration_Factor_) ((_Calibration_Factor_) <= ((uint32_t)0x7F))
/**
* @}
*/
/**
* @}
*/
/* Exported functions --------------------------------------------------------*/
/* Peripheral Control functions ***********************************************/
HAL_StatusTypeDef HAL_ADCEx_Calibration_Start(ADC_HandleTypeDef* hadc, uint32_t SingleDiff);
uint32_t HAL_ADCEx_Calibration_GetValue(ADC_HandleTypeDef* hadc, uint32_t SingleDiff);
HAL_StatusTypeDef HAL_ADCEx_Calibration_SetValue(ADC_HandleTypeDef* hadc, uint32_t SingleDiff, uint32_t CalibrationFactor);
/**
* @}
*/
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif /*__STM32L0xx_ADC_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,614 @@
/**
******************************************************************************
* @file stm32l0xx_hal_comp.c
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief COMP HAL module driver.
*
* This file provides firmware functions to manage the following
* functionalities of the COMP peripheral:
* + Initialization/de-initialization functions
* + I/O operation functions
* + Peripheral Control functions
* + Peripheral State functions
*
@verbatim
================================================================================
##### COMP Peripheral features #####
================================================================================
[..]
The STM32L0xx device family integrates 2 analog comparators COMP1 and COMP2:
(#) The non inverting input and inverting input can be set to GPIO pins
as shown in table1. COMP Inputs below.
(#) The COMP output is available using HAL_COMP_GetOutputLevel()
and can be set on GPIO pins. Refer to table 2. COMP Outputs below.
(#) The COMP output can be redirected to embedded timers (TIM2, TIM21, TIM22...) and LPTIM
Refer to TIM and LPTIM drivers.
(#) The comparators COMP1 and COMP2 can be combined in window mode and only COMP2 non inverting input can be used as non-inverting input.
(#) The 2 comparators have interrupt capability with wake-up
from Sleep and Stop modes (through the EXTI controller):
(++) COMP1 is internally connected to EXTI Line 21
(++) COMP2 is internally connected to EXTI Line 22
From the corresponding IRQ handler, the right interrupt source can be retrieved with the
macro __HAL_COMP_EXTI_GET_FLAG(). Possible values are:
(++) COMP_EXTI_LINE_COMP1_EVENT
(++) COMP_EXTI_LINE_COMP2_EVENT
[..] Table 1. COMP Inputs for the STM32L0xx devices
+--------------------------------------------------+
| | | COMP1 | COMP2 |
|-----------------|----------------|---------------|
| | 1/4 VREFINT | -- | OK |
| | 1/2 VREFINT | -- | OK |
| | 3/4 VREFINT | -- | OK |
| Inverting Input | VREFINT | OK | OK |
| | DAC OUT (PA4) | OK | OK |
| | IO1 | PA0 | PA2 |
| | IO2 | PA5 | PA5 |
| | IO3 | --- | PB3 |
|-----------------|----------------|-------|-------|
| Non Inverting | IO1 | PA1 | PA3 |
| Input | IO2 | --- | PB4 |
| | IO3 | --- | PB5 |
| | IO4 | --- | PB6 |
| | IO5 | --- | PB7 |
+--------------------------------------------------+
[..] Table 2. COMP Outputs for the STM32L0xx devices
+---------------+
| COMP1 | COMP2 |
|-------|-------|
| PA0 | PA2 |
| PA6 | PA7 |
| PA11 | PA12 |
+---------------+
##### How to use this driver #####
================================================================================
[..]
This driver provides functions to configure and program the Comparators of all STM32L0xx devices.
To use the comparator, perform the following steps:
(#) Initialize the COMP low level resources by implementing the HAL_COMP_MspInit().
(++) Configure the comparator input in analog mode using HAL_GPIO_Init().
(++) Configure the comparator output in alternate function mode using HAL_GPIO_Init() to map the comparator
output to the GPIO pin.
(++) If required enable the VREFINT reference using HAL_VREFINT_Cmd() and HAL_COMP_EnableBuffer_Cmd().
(++) If required enable the COMP interrupt by configuring and enabling EXTI line in Interrupt mode and
selecting the desired sensitivity level using HAL_GPIO_Init() function. After that enable the comparator
interrupt vector using HAL_NVIC_EnableIRQ() function.
(#) Configure the comparator using HAL_COMP_Init() function:
(++) Select the inverting input
(++) Select the non-inverting input
(++) Select the output polarity
(++) Select the power mode
(++) Select the window mode
(#) Enable the comparator using HAL_COMP_Start() function
@endverbatim
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @defgroup COMP
* @brief COMP HAL module driver
* @{
*/
#ifdef HAL_COMP_MODULE_ENABLED
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* CSR register reset value */
#define COMP_CSR_RESET_VALUE ((uint32_t)0x00000000)
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/** @defgroup COMP_Private_Functions
* @{
*/
/** @defgroup HAL_COMP_Group1 Initialization/de-initialization functions
* @brief Initialization and Configuration functions
*
@verbatim
===============================================================================
##### Initialization/de-initialization functions #####
===============================================================================
[..] This section provides functions to initialize and de-initialize comparators
@endverbatim
* @{
*/
/**
* @brief Initializes the COMP according to the specified
* parameters in the COMP_InitTypeDef and create the associated handle.
* @note If the selected comparator is locked, initialization can't be performed.
* To unlock the configuration, perform a system reset.
* @note When the LPTIM connection is enabled, the following pins LPTIM_IN1(PB5, PC0)
and LPTIM_IN2(PB7, PC2) should not be configured in AF.
* @param hcomp: COMP handle
* @retval HAL status
*/
HAL_StatusTypeDef HAL_COMP_Init(COMP_HandleTypeDef *hcomp)
{
HAL_StatusTypeDef status = HAL_OK;
/* Check the COMP handle allocation and lock status */
if((hcomp == NULL) || ((hcomp->State & COMP_STATE_BIT_LOCK) != 0x00))
{
status = HAL_ERROR;
}
else
{
/* Check the parameter */
assert_param(IS_COMP_ALL_INSTANCE(hcomp->Instance));
assert_param(IS_COMP_INVERTINGINPUT(hcomp->Init.InvertingInput));
assert_param(IS_COMP_NONINVERTINGINPUT(hcomp->Init.NonInvertingInput));
assert_param(IS_COMP_LPTIMCONNECTION(hcomp->Init.LPTIMConnection));
assert_param(IS_COMP_OUTPUTPOL(hcomp->Init.OutputPol));
assert_param(IS_COMP_MODE(hcomp->Init.Mode));
if(hcomp->Init.WindowMode != COMP_WINDOWMODE_DISABLED)
{
assert_param(IS_COMP_WINDOWMODE_INSTANCE(hcomp->Instance));
assert_param(IS_COMP_WINDOWMODE(hcomp->Init.WindowMode));
}
if(hcomp->State == HAL_COMP_STATE_RESET)
{
/* Init SYSCFG and the low level hardware to access comparators */
__SYSCFG_CLK_ENABLE();
/* Init the low level hardware : SYSCFG to access comparators */
HAL_COMP_MspInit(hcomp);
}
/* Change COMP peripheral state */
hcomp->State = HAL_COMP_STATE_BUSY;
/* Set COMP parameters */
/* Set COMPxINSEL bits according to hcomp->Init.InvertingInput value */
/* Set COMPxNONINSEL bits according to hcomp->Init.NonInvertingInput value */
/* Set COMPxPOL bit according to hcomp->Init.OutputPol value */
/* Set COMPxMODE bits according to hcomp->Init.Mode value */
/* Set COMP1WM bit according to hcomp->Init.WindowMode value */
MODIFY_REG(hcomp->Instance->CSR, COMP_CSR_UPDATE_PARAMETERS_MASK, \
hcomp->Init.InvertingInput | \
hcomp->Init.NonInvertingInput | \
hcomp->Init.LPTIMConnection | \
hcomp->Init.OutputPol | \
hcomp->Init.Mode | \
hcomp->Init.WindowMode);
/* Initialize the COMP state*/
hcomp->State = HAL_COMP_STATE_READY;
}
return status;
}
/**
* @brief DeInitializes the COMP peripheral
* @note Deinitialization can't be performed if the COMP configuration is locked.
* To unlock the configuration, perform a system reset.
* @param hcomp: COMP handle
* @retval HAL status
*/
HAL_StatusTypeDef HAL_COMP_DeInit(COMP_HandleTypeDef *hcomp)
{
HAL_StatusTypeDef status = HAL_OK;
/* Check the COMP handle allocation and lock status */
if((hcomp == NULL) || ((hcomp->State & COMP_STATE_BIT_LOCK) != 0x00))
{
status = HAL_ERROR;
}
else
{
/* Check the parameter */
assert_param(IS_COMP_ALL_INSTANCE(hcomp->Instance));
/* Set COMP_CSR register to reset value */
WRITE_REG(hcomp->Instance->CSR, COMP_CSR_RESET_VALUE);
/* DeInit the low level hardware: SYSCFG, GPIO, CLOCK and NVIC */
HAL_COMP_MspDeInit(hcomp);
hcomp->State = HAL_COMP_STATE_RESET;
/* Release Lock */
__HAL_UNLOCK(hcomp);
}
return status;
}
/**
* @brief Initializes the COMP MSP.
* @param hcomp: COMP handle
* @retval None
*/
__weak void HAL_COMP_MspInit(COMP_HandleTypeDef *hcomp)
{
/* NOTE : This function Should not be modified, when the callback is needed,
the HAL_COMP_MspInit could be implenetd in the user file
*/
}
/**
* @brief DeInitializes COMP MSP.
* @param hcomp: COMP handle
* @retval None
*/
__weak void HAL_COMP_MspDeInit(COMP_HandleTypeDef *hcomp)
{
/* NOTE : This function Should not be modified, when the callback is needed,
the HAL_COMP_MspDeInit could be implenetd in the user file
*/
}
/**
* @}
*/
/** @defgroup HAL_COMP_Group2 I/O operation functions
* @brief Data transfers functions
*
@verbatim
===============================================================================
##### IO operation functions #####
===============================================================================
[..]
This subsection provides a set of functions allowing to manage the COMP data
transfers.
@endverbatim
* @{
*/
/**
* @brief Start the comparator
* @param hcomp: COMP handle
* @retval HAL status
*/
HAL_StatusTypeDef HAL_COMP_Start(COMP_HandleTypeDef *hcomp)
{
HAL_StatusTypeDef status = HAL_OK;
/* Check the COMP handle allocation and lock status */
if((hcomp == NULL) || ((hcomp->State & COMP_STATE_BIT_LOCK) != 0x00))
{
status = HAL_ERROR;
}
else
{
/* Check the parameter */
assert_param(IS_COMP_ALL_INSTANCE(hcomp->Instance));
if(hcomp->State == HAL_COMP_STATE_READY)
{
/* Enable the selected comparator */
__HAL_COMP_ENABLE(hcomp);
hcomp->State = HAL_COMP_STATE_BUSY;
}
else
{
status = HAL_ERROR;
}
}
return status;
}
/**
* @brief Stop the comparator
* @param hcomp: COMP handle
* @retval HAL status
*/
HAL_StatusTypeDef HAL_COMP_Stop(COMP_HandleTypeDef *hcomp)
{
HAL_StatusTypeDef status = HAL_OK;
/* Check the COMP handle allocation and lock status */
if((hcomp == NULL) || ((hcomp->State & COMP_STATE_BIT_LOCK) != 0x00))
{
status = HAL_ERROR;
}
else
{
/* Check the parameter */
assert_param(IS_COMP_ALL_INSTANCE(hcomp->Instance));
if(hcomp->State == HAL_COMP_STATE_BUSY)
{
/* Disable the selected comparator */
__HAL_COMP_DISABLE(hcomp);
hcomp->State = HAL_COMP_STATE_READY;
}
else
{
status = HAL_ERROR;
}
}
return status;
}
/**
* @brief Enables the interrupt and starts the comparator
* @param hcomp: COMP handle
* @param mode: IT trigger mode: a value of @ref COMP_TriggerMode
* @retval HAL status.
*/
HAL_StatusTypeDef HAL_COMP_Start_IT(COMP_HandleTypeDef *hcomp)
{
HAL_StatusTypeDef status = HAL_OK;
uint32_t extiline = 0;
status = HAL_COMP_Start(hcomp);
if(status == HAL_OK)
{
/* Check the Exti Line output configuration */
extiline = __HAL_COMP_GET_EXTI_LINE(hcomp->Instance);
/* Configure the rising edge */
if((hcomp->Init.TriggerMode & COMP_TRIGGERMODE_IT_RISING) != 0x00)
{
__HAL_COMP_EXTI_RISING_IT_ENABLE(extiline);
}
else
{
__HAL_COMP_EXTI_RISING_IT_DISABLE(extiline);
}
/* Configure the falling edge */
if((hcomp->Init.TriggerMode & COMP_TRIGGERMODE_IT_FALLING) != 0x00)
{
__HAL_COMP_EXTI_FALLING_IT_ENABLE(extiline);
}
else
{
__HAL_COMP_EXTI_FALLING_IT_DISABLE(extiline);
}
/* Enable Exti interrupt mode */
__HAL_COMP_EXTI_ENABLE_IT(extiline);
/* Clear COMP Exti pending bit */
__HAL_COMP_EXTI_CLEAR_FLAG(extiline);
}
return status;
}
/**
* @brief Disable the interrupt and Stop the comparator
* @param hcomp: COMP handle
* @retval HAL status
*/
HAL_StatusTypeDef HAL_COMP_Stop_IT(COMP_HandleTypeDef *hcomp)
{
HAL_StatusTypeDef status = HAL_OK;
/* Disable the Exti Line interrupt mode */
__HAL_COMP_EXTI_DISABLE_IT(__HAL_COMP_GET_EXTI_LINE(hcomp->Instance));
status = HAL_COMP_Stop(hcomp);
return status;
}
/**
* @brief Comparator IRQ Handler
* @param hcomp: COMP handle
* @retval HAL status
*/
void HAL_COMP_IRQHandler(COMP_HandleTypeDef *hcomp)
{
uint32_t extiline = __HAL_COMP_GET_EXTI_LINE(hcomp->Instance);
/* Check COMP Exti flag */
if(__HAL_COMP_EXTI_GET_FLAG(extiline) != RESET)
{
/* Clear COMP Exti pending bit */
__HAL_COMP_EXTI_CLEAR_FLAG(extiline);
}
/* COMP trigger user callback */
HAL_COMP_TriggerCallback(hcomp);
}
/**
* @}
*/
/** @defgroup HAL_COMP_Group3 Peripheral Control functions
* @brief management functions
*
@verbatim
===============================================================================
##### Peripheral Control functions #####
===============================================================================
[..]
This subsection provides a set of functions allowing to control the COMP data
transfers.
@endverbatim
* @{
*/
/**
* @brief Lock the selected comparator configuration.
* @param hcomp: COMP handle
* @retval HAL status
*/
HAL_StatusTypeDef HAL_COMP_Lock(COMP_HandleTypeDef *hcomp)
{
HAL_StatusTypeDef status = HAL_OK;
/* Check the COMP handle allocation and lock status */
if((hcomp == NULL) || ((hcomp->State & COMP_STATE_BIT_LOCK) != 0x00))
{
status = HAL_ERROR;
}
else
{
/* Check the parameter */
assert_param(IS_COMP_ALL_INSTANCE(hcomp->Instance));
/* Set lock flag */
hcomp->State |= COMP_STATE_BIT_LOCK;
/* Set the lock bit corresponding to selected comparator */
__HAL_COMP_LOCK(hcomp);
}
return status;
}
/**
* @brief Return the output level (high or low) of the selected comparator.
* The output level depends on the selected polarity.
* If the polarity is not inverted:
* - Comparator output is low when the non-inverting input is at a lower
* voltage than the inverting input
* - Comparator output is high when the non-inverting input is at a higher
* voltage than the inverting input
* If the polarity is inverted:
* - Comparator output is high when the non-inverting input is at a lower
* voltage than the inverting input
* - Comparator output is low when the non-inverting input is at a higher
* voltage than the inverting input
* @param hcomp: COMP handle
* @retval Returns the selected comparator output level: COMP_OUTPUTLEVEL_LOW or COMP_OUTPUTLEVEL_HIGH.
*
*/
uint32_t HAL_COMP_GetOutputLevel(COMP_HandleTypeDef *hcomp)
{
/* Check the parameter */
assert_param(IS_COMP_ALL_INSTANCE(hcomp->Instance));
return((uint32_t)(hcomp->Instance->CSR & COMP_OUTPUTLEVEL_HIGH));
}
/**
* @brief Comparator callback.
* @param hcomp: COMP handle
* @retval None
*/
__weak void HAL_COMP_TriggerCallback(COMP_HandleTypeDef *hcomp)
{
/* NOTE : This function should not be modified, when the callback is needed,
the HAL_COMP_TriggerCallback should be implemented in the user file
*/
}
/**
* @}
*/
/** @defgroup HAL_COMP_Group4 Peripheral State functions
* @brief Peripheral State functions
*
@verbatim
===============================================================================
##### Peripheral State functions #####
===============================================================================
[..]
This subsection permit to get in run-time the status of the peripheral
and the data flow.
@endverbatim
* @{
*/
/**
* @brief Return the COMP state
* @param hcomp : COMP handle
* @retval HAL state
*/
HAL_COMP_StateTypeDef HAL_COMP_GetState(COMP_HandleTypeDef *hcomp)
{
/* Check the COMP handle allocation */
if(hcomp == NULL)
{
return HAL_COMP_STATE_RESET;
}
/* Check the parameter */
assert_param(IS_COMP_ALL_INSTANCE(hcomp->Instance));
return hcomp->State;
}
/**
* @}
*/
/**
* @}
*/
#endif /* HAL_COMP_MODULE_ENABLED */
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,425 @@
/**
******************************************************************************
* @file stm32l0xx_hal_comp.h
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief Header file of COMP HAL module.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32L0xx_HAL_COMP_H
#define __STM32L0xx_HAL_COMP_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal_def.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @addtogroup COMP
* @{
*/
/* Exported types ------------------------------------------------------------*/
/**
* @brief COMP Init structure definition
*/
typedef struct
{
uint32_t InvertingInput; /*!< Selects the inverting input of the comparator.
This parameter can be a value of @ref COMP_InvertingInput */
uint32_t NonInvertingInput; /*!< Selects the non inverting input of the comparator.
This parameter can be a value of @ref COMP_NonInvertingInput */
uint32_t LPTIMConnection; /*!< Selects if the COMP connection to the LPTIM is established or not.
This parameter can be a value of @ref COMP_LPTIMConnection */
uint32_t OutputPol; /*!< Selects the output polarity of the comparator.
This parameter can be a value of @ref COMP_OutputPolarity */
uint32_t Mode; /*!< Selects the operating comsumption mode of the comparator
to adjust the speed/consumption.
This parameter can be a value of @ref COMP_Mode */
uint32_t WindowMode; /*!< Selects the window mode of the comparator 2.
This parameter can be a value of @ref COMP_WindowMode */
uint32_t TriggerMode; /*!< Selects the trigger mode of the comparator (interrupt mode).
This parameter can be a value of @ref COMP_TriggerMode */
}COMP_InitTypeDef;
/**
* @brief HAL State structures definition
*/
typedef enum
{
HAL_COMP_STATE_RESET = 0x00, /*!< COMP not yet initialized or disabled */
HAL_COMP_STATE_READY = 0x01, /*!< COMP initialized and ready for use */
HAL_COMP_STATE_READY_LOCKED = 0x11, /*!< COMP initialized but the configuration is locked */
HAL_COMP_STATE_BUSY = 0x02, /*!< COMP is running */
HAL_COMP_STATE_BUSY_LOCKED = 0x12 /*!< COMP is running and the configuration is locked */
}HAL_COMP_StateTypeDef;
/**
* @brief COMP Handle Structure definition
*/
typedef struct
{
COMP_TypeDef *Instance; /*!< Register base address */
COMP_InitTypeDef Init; /*!< COMP required parameters */
HAL_LockTypeDef Lock; /*!< Locking object */
__IO HAL_COMP_StateTypeDef State; /*!< COMP communication state */
} COMP_HandleTypeDef;
/* Exported constants --------------------------------------------------------*/
/** @defgroup COMP_Exported_Constants
* @{
*/
/** @defgroup COMP_OutputPolarity
* @{
*/
#define COMP_OUTPUTPOL_NONINVERTED ((uint32_t)0x00000000) /*!< COMP output on GPIO isn't inverted */
#define COMP_OUTPUTPOL_INVERTED COMP_CSR_COMPxPOLARITY /*!< COMP output on GPIO is inverted */
#define IS_COMP_OUTPUTPOL(POL) (((POL) == COMP_OUTPUTPOL_NONINVERTED) || \
((POL) == COMP_OUTPUTPOL_INVERTED))
/**
* @}
*/
/** @defgroup COMP_InvertingInput
* @{
*/
/* Inverting Input specific to COMP1 */
#define COMP_INVERTINGINPUT_VREFINT ((uint32_t)0x00000000) /*!< VREFINT connected to comparator1 inverting input */
#define COMP_INVERTINGINPUT_IO1 ((uint32_t)0x00000010) /*!< I/O1 connected to comparator inverting input (PA0) for COMP1 and (PA2) for COMP2*/
#define COMP_INVERTINGINPUT_DAC1 ((uint32_t)0x00000020) /*!< DAC1_OUT (PA4) connected to comparator inverting input */
#define COMP_INVERTINGINPUT_IO2 ((uint32_t)0x00000030) /*!< I/O2 (PA5) connected to comparator inverting input */
/* Inverting Input specific to COMP2 */
#define COMP_INVERTINGINPUT_1_4VREFINT ((uint32_t)0x00000040) /*!< 1/4 VREFINT connected to comparator inverting input */
#define COMP_INVERTINGINPUT_1_2VREFINT ((uint32_t)0x00000050) /*!< 1/2 VREFINT connected to comparator inverting input */
#define COMP_INVERTINGINPUT_3_4VREFINT ((uint32_t)0x00000060) /*!< 3/4 VREFINT connected to comparator inverting input */
#define COMP_INVERTINGINPUT_IO3 ((uint32_t)0x00000070) /*!< I/O3 (PB3) for COMP2 connected to comparator inverting input */
#define IS_COMP_INVERTINGINPUT(INPUT) (((INPUT) == COMP_INVERTINGINPUT_VREFINT) || \
((INPUT) == COMP_INVERTINGINPUT_IO1) || \
((INPUT) == COMP_INVERTINGINPUT_DAC1) || \
((INPUT) == COMP_INVERTINGINPUT_IO2) || \
((INPUT) == COMP_INVERTINGINPUT_1_4VREFINT) || \
((INPUT) == COMP_INVERTINGINPUT_1_2VREFINT) || \
((INPUT) == COMP_INVERTINGINPUT_3_4VREFINT) || \
((INPUT) == COMP_INVERTINGINPUT_IO3))
/**
* @}
*/
/** @defgroup COMP_NonInvertingInput
* @{
*/
#define COMP_NONINVERTINGINPUT_IO1 ((uint32_t)0x00000000) /*!< I/O1 (PA3) connected to comparator non inverting input */
#define COMP_NONINVERTINGINPUT_IO2 ((uint32_t)0x00000100) /*!< I/O2 (PB4) connected to comparator non inverting input */
#define COMP_NONINVERTINGINPUT_IO3 ((uint32_t)0x00000200) /*!< I/O3 (PB5) connected to comparator non inverting input */
#define COMP_NONINVERTINGINPUT_IO4 ((uint32_t)0x00000300) /*!< I/O1 (PB6) connected to comparator non inverting input */
#define COMP_NONINVERTINGINPUT_IO5 ((uint32_t)0x00000400) /*!< I/O3 (PB7) connected to comparator non inverting input */
#define COMP_NONINVERTINGINPUT_IO6 ((uint32_t)0x00000500) /*!< I/O3 (PB7) connected to comparator non inverting input */
#define COMP_NONINVERTINGINPUT_IO7 ((uint32_t)0x00000600) /*!< I/O3 (PB7) connected to comparator non inverting input */
#define COMP_NONINVERTINGINPUT_IO8 ((uint32_t)0x00000700) /*!< I/O3 (PB7) connected to comparator non inverting input */
#define IS_COMP_NONINVERTINGINPUT(INPUT) (((INPUT) == COMP_NONINVERTINGINPUT_IO1) || \
((INPUT) == COMP_NONINVERTINGINPUT_IO2) || \
((INPUT) == COMP_NONINVERTINGINPUT_IO3) || \
((INPUT) == COMP_NONINVERTINGINPUT_IO4) || \
((INPUT) == COMP_NONINVERTINGINPUT_IO5) || \
((INPUT) == COMP_NONINVERTINGINPUT_IO6) || \
((INPUT) == COMP_NONINVERTINGINPUT_IO7) || \
((INPUT) == COMP_NONINVERTINGINPUT_IO8))
/**
* @}
*/
/** @defgroup COMP_Mode
* @{
*/
/* Please refer to the electrical characteristics in the device datasheet for
the power consumption values */
#define COMP_MODE_HIGHSPEED COMP_CSR_COMP2SPEED /*!< High Speed */
#define COMP_MODE_LOWSPEED ((uint32_t)0x00000000) /*!< Low Speed */
#define IS_COMP_MODE(SPEED) (((SPEED) == COMP_MODE_HIGHSPEED) || \
((SPEED) == COMP_MODE_LOWSPEED))
/**
* @}
*/
/** @defgroup COMP_WindowMode
* @{
*/
#define COMP_WINDOWMODE_DISABLED ((uint32_t)0x00000000) /*!< Window mode disabled (Plus input of comparator 1 connected to PA1)*/
#define COMP_WINDOWMODE_ENABLED COMP_CSR_COMP1WM /*!< Window mode enabled: Plus input of comparator 1 shorted with Plus input of comparator 2 */
#define IS_COMP_WINDOWMODE(WINDOWMODE) (((WINDOWMODE) == COMP_WINDOWMODE_DISABLED) || \
((WINDOWMODE) == COMP_WINDOWMODE_ENABLED))
#define IS_COMP_WINDOWMODE_INSTANCE(INSTANCE) ((INSTANCE) == COMP1)
/**
* @}
*/
/** @defgroup COMP_LPTIMConnection
* @{
*/
#define COMP_LPTIMCONNECTION_DISABLED ((uint32_t)0x00000000) /*!< COMPx signal is gated */
#define COMP_LPTIMCONNECTION_ENABLED COMP_CSR_COMP1LPTIM1IN1 /*!< COMPx signal is connected to LPTIM */
#define IS_COMP_LPTIMCONNECTION(LPTIMCONNECTION) (((LPTIMCONNECTION) == COMP_LPTIMCONNECTION_DISABLED) || \
((LPTIMCONNECTION) == COMP_LPTIMCONNECTION_ENABLED))
/**
* @}
*/
/** @defgroup COMP_OutputLevel
* @{
*/
/* When output polarity is not inverted, comparator output is low when
the non-inverting input is at a lower voltage than the inverting input*/
#define COMP_OUTPUTLEVEL_LOW ((uint32_t)0x00000000)
/* When output polarity is not inverted, comparator output is high when
the non-inverting input is at a higher voltage than the inverting input */
#define COMP_OUTPUTLEVEL_HIGH COMP_CSR_COMPxOUTVALUE
/**
* @}
*/
/* CSR register Mask */
#define COMP_CSR_UPDATE_PARAMETERS_MASK ((uint32_t)0xC0008779)
#define COMP_LOCK_DISABLE ((uint32_t)0x00000000)
#define COMP_LOCK_ENABLE COMP_CSR_COMPxLOCK
#define COMP_STATE_BIT_LOCK ((uint32_t)0x10)
/** @defgroup COMP_TriggerMode
* @{
*/
#define COMP_TRIGGERMODE_IT_RISING ((uint32_t)0x00000001) /*!< External Interrupt Mode with Rising edge trigger detection */
#define COMP_TRIGGERMODE_IT_FALLING ((uint32_t)0x00000002) /*!< External Interrupt Mode with Falling edge trigger detection */
#define COMP_TRIGGERMODE_IT_RISING_FALLING ((uint32_t)0x00000003) /*!< External Interrupt Mode with Rising/Falling edge trigger detection */
#define IS_COMP_TRIGGERMODE(MODE) (((MODE) == COMP_TRIGGERMODE_IT_RISING) || \
((MODE) == COMP_TRIGGERMODE_IT_FALLING) || \
((MODE) == COMP_TRIGGERMODE_IT_RISING_FALLING))
/**
* @}
*/
/** @defgroup COMP_ExtiLineEvent
* @{
*/
#define COMP_EXTI_LINE_COMP2_EVENT ((uint32_t)0x00400000) /*!< External interrupt line 22 Connected to COMP2 */
#define COMP_EXTI_LINE_COMP1_EVENT ((uint32_t)0x00200000) /*!< External interrupt line 21 Connected to COMP1 */
/**
* @}
*/
/**
* @}
*/
/* Exported macro ------------------------------------------------------------*/
/** @brief Reset COMP handle state
* @param __HANDLE__: COMP handle.
* @retval None
*/
#define __HAL_COMP_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_COMP_STATE_RESET)
/**
* @brief Enables the specified comparator
* @param __HANDLE__: COMP handle.
* @retval None.
*/
#define __HAL_COMP_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CSR |= (COMP_CSR_COMPxEN))
/**
* @brief Disables the specified comparator
* @param __HANDLE__: COMP handle.
* @retval None.
*/
#define __HAL_COMP_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CSR &= ~(COMP_CSR_COMPxEN))
/**
* @brief Lock the specified comparator configuration
* @param __HANDLE__: COMP handle.
* @retval None.
*/
#define __HAL_COMP_LOCK(__HANDLE__) ((__HANDLE__)->Instance->CSR |= COMP_CSR_COMPxLOCK)
/** @brief Checks whether the specified COMP flag is set or not.
* @param __HANDLE__: specifies the COMP Handle.
* @param __FLAG__: specifies the flag to check.
* This parameter can be one of the following values:
* @arg COMP_FLAG_LOCK: lock flag
* @retval The new state of __FLAG__ (TRUE or FALSE).
*/
#define __HAL_COMP_GET_FLAG(__HANDLE__, __FLAG__) (((__HANDLE__)->Instance->CSR & (__FLAG__)) == (__FLAG__))
/**
* @brief Enable the Exti Line rising edge trigger.
* @param __EXTILINE__: specifies the COMP Exti sources to be enabled.
* This parameter can be a value of @ref COMP_ExtiLineEvent
* @retval None.
*/
#define __HAL_COMP_EXTI_RISING_IT_ENABLE(__EXTILINE__) (EXTI->RTSR |= (__EXTILINE__))
/**
* @brief Disable the Exti Line rising edge trigger.
* @param __EXTILINE__: specifies the COMP Exti sources to be disabled.
* This parameter can be a value of @ref COMP_ExtiLineEvent
* @retval None.
*/
#define __HAL_COMP_EXTI_RISING_IT_DISABLE(__EXTILINE__) (EXTI->RTSR &= ~(__EXTILINE__))
/**
* @brief Enable the Exti Line falling edge trigger.
* @param __EXTILINE__: specifies the COMP Exti sources to be enabled.
* This parameter can be a value of @ref COMP_ExtiLineEvent
* @retval None.
*/
#define __HAL_COMP_EXTI_FALLING_IT_ENABLE(__EXTILINE__) (EXTI->FTSR |= (__EXTILINE__))
/**
* @brief Disable the Exti Line falling edge trigger.
* @param __EXTILINE__: specifies the COMP Exti sources to be disabled.
* This parameter can be a value of @ref COMP_ExtiLineEvent
* @retval None.
*/
#define __HAL_COMP_EXTI_FALLING_IT_DISABLE(__EXTILINE__) (EXTI->FTSR &= ~(__EXTILINE__))
/**
* @brief Get the specified EXTI line for a comparator instance
* @param __INSTANCE__: specifies the COMP instance.
* @retval value of @ref COMP_ExtiLineEvent
*/
#define __HAL_COMP_GET_EXTI_LINE(__INSTANCE__) (((__INSTANCE__) == COMP1) ? COMP_EXTI_LINE_COMP1_EVENT : \
COMP_EXTI_LINE_COMP2_EVENT)
/**
* @brief Enable the COMP Exti Line.
* @param __EXTILINE__: specifies the COMP Exti sources to be enabled.
* This parameter can be a value of @ref COMP_ExtiLineEvent
* @retval None.
*/
#define __HAL_COMP_EXTI_ENABLE_IT(__EXTILINE__) (EXTI->IMR |= (__EXTILINE__))
/**
* @brief Disable the COMP Exti Line.
* @param __EXTILINE__: specifies the COMP Exti sources to be disabled.
* This parameter can be a value of @ref COMP_ExtiLineEvent
* @retval None.
*/
#define __HAL_COMP_EXTI_DISABLE_IT(__EXTILINE__) (EXTI->IMR &= ~(__EXTILINE__))
/**
* @brief Checks whether the specified EXTI line flag is set or not.
* @param __FLAG__: specifies the COMP Exti sources to be checked.
* This parameter can be a value of @ref COMP_ExtiLineEvent
* @retval The state of __FLAG__ (SET or RESET).
*/
#define __HAL_COMP_EXTI_GET_FLAG(__FLAG__) (EXTI->PR & (__FLAG__))
/**
* @brief Clear the COMP Exti flags.
* @param __FLAG__: specifies the COMP Exti sources to be cleared.
* This parameter can be a value of @ref COMP_ExtiLineEvent
* @retval None.
*/
#define __HAL_COMP_EXTI_CLEAR_FLAG(__FLAG__) (EXTI->PR = (__FLAG__))
/* Exported functions --------------------------------------------------------*/
/* Initialization/de-initialization functions **********************************/
HAL_StatusTypeDef HAL_COMP_Init(COMP_HandleTypeDef *hcomp);
HAL_StatusTypeDef HAL_COMP_DeInit (COMP_HandleTypeDef *hcomp);
void HAL_COMP_MspInit(COMP_HandleTypeDef *hcomp);
void HAL_COMP_MspDeInit(COMP_HandleTypeDef *hcomp);
/* I/O operation functions *****************************************************/
HAL_StatusTypeDef HAL_COMP_Start(COMP_HandleTypeDef *hcomp);
HAL_StatusTypeDef HAL_COMP_Stop(COMP_HandleTypeDef *hcomp);
HAL_StatusTypeDef HAL_COMP_Start_IT(COMP_HandleTypeDef *hcomp);
HAL_StatusTypeDef HAL_COMP_Stop_IT(COMP_HandleTypeDef *hcomp);
void HAL_COMP_IRQHandler(COMP_HandleTypeDef *hcomp);
/* Peripheral Control functions ************************************************/
HAL_StatusTypeDef HAL_COMP_Lock(COMP_HandleTypeDef *hcomp);
uint32_t HAL_COMP_GetOutputLevel(COMP_HandleTypeDef *hcomp);
/* Callback in Interrupt mode */
void HAL_COMP_TriggerCallback(COMP_HandleTypeDef *hcomp);
/* Peripheral State functions **************************************************/
HAL_COMP_StateTypeDef HAL_COMP_GetState(COMP_HandleTypeDef *hcomp);
/**
* @}
*/
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif /* __STM32L0xx_HAL_COMP_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,292 @@
/**
******************************************************************************
* @file stm32l0xx_hal_conf.h
* @author MCD Application Team
* @version V1.0.0
* @date 22-April-2014
* @brief HAL configuration file.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32L0xx_HAL_CONF_H
#define __STM32L0xx_HAL_CONF_H
#ifdef __cplusplus
extern "C" {
#endif
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
/* ########################## Module Selection ############################## */
/**
* @brief This is the list of modules to be used in the HAL driver
*/
#define HAL_MODULE_ENABLED
#define HAL_ADC_MODULE_ENABLED
#define HAL_COMP_MODULE_ENABLED
#define HAL_CRC_MODULE_ENABLED
#define HAL_CRYP_MODULE_ENABLED
#define HAL_DAC_MODULE_ENABLED
#define HAL_DMA_MODULE_ENABLED
#define HAL_FLASH_MODULE_ENABLED
#define HAL_GPIO_MODULE_ENABLED
#define HAL_I2C_MODULE_ENABLED
#define HAL_I2S_MODULE_ENABLED
#define HAL_IWDG_MODULE_ENABLED
#define HAL_LCD_MODULE_ENABLED
#define HAL_LPTIM_MODULE_ENABLED
#define HAL_PWR_MODULE_ENABLED
#define HAL_RCC_MODULE_ENABLED
#define HAL_RNG_MODULE_ENABLED
#define HAL_RTC_MODULE_ENABLED
#define HAL_SPI_MODULE_ENABLED
#define HAL_TIM_MODULE_ENABLED
#define HAL_TSC_MODULE_ENABLED
#define HAL_UART_MODULE_ENABLED
#define HAL_USART_MODULE_ENABLED
#define HAL_IRDA_MODULE_ENABLED
#define HAL_SMARTCARD_MODULE_ENABLED
#define HAL_SMBUS_MODULE_ENABLED
#define HAL_WWDG_MODULE_ENABLED
#define HAL_CORTEX_MODULE_ENABLED
#define HAL_PCD_MODULE_ENABLED
/* ########################## Oscillator Values adaptation ####################*/
/**
* @brief Adjust the value of External High Speed oscillator (HSE) used in your application.
* This value is used by the RCC HAL module to compute the system frequency
* (when HSE is used as system clock source, directly or through the PLL).
*/
#if !defined (HSE_VALUE)
#define HSE_VALUE ((uint32_t)8000000) /*!< Value of the External oscillator in Hz */
#endif /* HSE_VALUE */
#if !defined (HSE_STARTUP_TIMEOUT)
#define HSE_STARTUP_TIMEOUT ((uint32_t)50) /*!< Time out for HSE start up, in ms */
#endif /* HSE_STARTUP_TIMEOUT */
/**
* @brief Internal Multiple Speed oscillator (MSI) default value.
* This value is the default MSI range value after Reset.
*/
#if !defined (MSI_VALUE)
#define MSI_VALUE ((uint32_t)2000000) /*!< Value of the Internal oscillator in Hz*/
#endif /* MSI_VALUE */
/**
* @brief Internal High Speed oscillator (HSI) value.
* This value is used by the RCC HAL module to compute the system frequency
* (when HSI is used as system clock source, directly or through the PLL).
*/
#if !defined (HSI_VALUE)
#define HSI_VALUE ((uint32_t)16000000) /*!< Value of the Internal oscillator in Hz*/
#endif /* HSI_VALUE */
/**
* @brief External Low Speed oscillator (LSE) value.
* This value is used by the UART, RTC HAL module to compute the system frequency
*/
#if !defined (LSE_VALUE)
#define LSE_VALUE ((uint32_t)32768) /*!< Value of the External oscillator in Hz*/
#endif /* LSE_VALUE */
#if !defined (LSE_STARTUP_TIMEOUT)
#define LSE_STARTUP_TIMEOUT ((uint32_t)500) /*!< Time out for LSE start up, in ms */
#endif /* HSE_STARTUP_TIMEOUT */
/* Tip: To avoid modifying this file each time you need to use different HSE,
=== you can define the HSE value in your toolchain compiler preprocessor. */
/* ########################### System Configuration ######################### */
/**
* @brief This is the HAL system configuration section
*/
#define VDD_VALUE ((uint32_t)3300) /*!< Value of VDD in mv */
#define TICK_INT_PRIORITY ((uint32_t)3) /*!< tick interrupt priority */
#define USE_RTOS 0
#define PREFETCH_ENABLE 1
#define PREREAD_ENABLE 1
#define BUFFER_CACHE_DISABLE 0
/* ########################## Assert Selection ############################## */
/**
* @brief Uncomment the line below to expanse the "assert_param" macro in the
* HAL drivers code
*/
/* #define USE_FULL_ASSERT 1 */
/* Includes ------------------------------------------------------------------*/
/**
* @brief Include module's header file
*/
#ifdef HAL_RCC_MODULE_ENABLED
#include "stm32l0xx_hal_rcc.h"
#endif /* HAL_RCC_MODULE_ENABLED */
#ifdef HAL_GPIO_MODULE_ENABLED
#include "stm32l0xx_hal_gpio.h"
#endif /* HAL_GPIO_MODULE_ENABLED */
#ifdef HAL_DMA_MODULE_ENABLED
#include "stm32l0xx_hal_dma.h"
#endif /* HAL_DMA_MODULE_ENABLED */
#ifdef HAL_CORTEX_MODULE_ENABLED
#include "stm32l0xx_hal_cortex.h"
#endif /* HAL_CORTEX_MODULE_ENABLED */
#ifdef HAL_ADC_MODULE_ENABLED
#include "stm32l0xx_hal_adc.h"
#endif /* HAL_ADC_MODULE_ENABLED */
#ifdef HAL_COMP_MODULE_ENABLED
#include "stm32l0xx_hal_comp.h"
#endif /* HAL_COMP_MODULE_ENABLED */
#ifdef HAL_CRC_MODULE_ENABLED
#include "stm32l0xx_hal_crc.h"
#endif /* HAL_CRC_MODULE_ENABLED */
#ifdef HAL_CRYP_MODULE_ENABLED
#include "stm32l0xx_hal_cryp.h"
#endif /* HAL_CRYP_MODULE_ENABLED */
#ifdef HAL_DAC_MODULE_ENABLED
#include "stm32l0xx_hal_dac.h"
#endif /* HAL_DAC_MODULE_ENABLED */
#ifdef HAL_FLASH_MODULE_ENABLED
#include "stm32l0xx_hal_flash.h"
#endif /* HAL_FLASH_MODULE_ENABLED */
#ifdef HAL_I2C_MODULE_ENABLED
#include "stm32l0xx_hal_i2c.h"
#endif /* HAL_I2C_MODULE_ENABLED */
#ifdef HAL_I2S_MODULE_ENABLED
#include "stm32l0xx_hal_i2s.h"
#endif /* HAL_I2S_MODULE_ENABLED */
#ifdef HAL_IWDG_MODULE_ENABLED
#include "stm32l0xx_hal_iwdg.h"
#endif /* HAL_IWDG_MODULE_ENABLED */
#ifdef HAL_LCD_MODULE_ENABLED
#include "stm32l0xx_hal_lcd.h"
#endif /* HAL_LCD_MODULE_ENABLED */
#ifdef HAL_LPTIM_MODULE_ENABLED
#include "stm32l0xx_hal_lptim.h"
#endif /* HAL_LPTIM_MODULE_ENABLED */
#ifdef HAL_PWR_MODULE_ENABLED
#include "stm32l0xx_hal_pwr.h"
#endif /* HAL_PWR_MODULE_ENABLED */
#ifdef HAL_RNG_MODULE_ENABLED
#include "stm32l0xx_hal_rng.h"
#endif /* HAL_RNG_MODULE_ENABLED */
#ifdef HAL_RTC_MODULE_ENABLED
#include "stm32l0xx_hal_rtc.h"
#endif /* HAL_RTC_MODULE_ENABLED */
#ifdef HAL_SPI_MODULE_ENABLED
#include "stm32l0xx_hal_spi.h"
#endif /* HAL_SPI_MODULE_ENABLED */
#ifdef HAL_TIM_MODULE_ENABLED
#include "stm32l0xx_hal_tim.h"
#endif /* HAL_TIM_MODULE_ENABLED */
#ifdef HAL_TSC_MODULE_ENABLED
#include "stm32l0xx_hal_tsc.h"
#endif /* HAL_TSC_MODULE_ENABLED */
#ifdef HAL_UART_MODULE_ENABLED
#include "stm32l0xx_hal_uart.h"
#endif /* HAL_UART_MODULE_ENABLED */
#ifdef HAL_USART_MODULE_ENABLED
#include "stm32l0xx_hal_usart.h"
#endif /* HAL_USART_MODULE_ENABLED */
#ifdef HAL_IRDA_MODULE_ENABLED
#include "stm32l0xx_hal_irda.h"
#endif /* HAL_IRDA_MODULE_ENABLED */
#ifdef HAL_SMARTCARD_MODULE_ENABLED
#include "stm32l0xx_hal_smartcard.h"
#endif /* HAL_SMARTCARD_MODULE_ENABLED */
#ifdef HAL_SMBUS_MODULE_ENABLED
#include "stm32l0xx_hal_smbus.h"
#endif /* HAL_SMBUS_MODULE_ENABLED */
#ifdef HAL_WWDG_MODULE_ENABLED
#include "stm32l0xx_hal_wwdg.h"
#endif /* HAL_WWDG_MODULE_ENABLED */
#ifdef HAL_PCD_MODULE_ENABLED
#include "stm32l0xx_hal_pcd.h"
#endif /* HAL_PCD_MODULE_ENABLED */
/* Exported macro ------------------------------------------------------------*/
#ifdef USE_FULL_ASSERT
/**
* @brief The assert_param macro is used for function's parameters check.
* @param expr: If expr is false, it calls assert_failed function
* which reports the name of the source file and the source
* line number of the call that failed.
* If expr is true, it returns no value.
* @retval None
*/
#define assert_param(expr) ((expr) ? (void)0 : assert_failed((uint8_t *)__FILE__, __LINE__))
/* Exported functions ------------------------------------------------------- */
void assert_failed(uint8_t* file, uint32_t line);
#else
#define assert_param(expr) ((void)0)
#endif /* USE_FULL_ASSERT */
#ifdef __cplusplus
}
#endif
#endif /* __STM32L0xx_HAL_CONF_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,292 @@
/**
******************************************************************************
* @file stm32l0xx_hal_conf.h
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief HAL configuration file.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32L0xx_HAL_CONF_H
#define __STM32L0xx_HAL_CONF_H
#ifdef __cplusplus
extern "C" {
#endif
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
/* ########################## Module Selection ############################## */
/**
* @brief This is the list of modules to be used in the HAL driver
*/
#define HAL_MODULE_ENABLED
#define HAL_ADC_MODULE_ENABLED
#define HAL_COMP_MODULE_ENABLED
#define HAL_CRC_MODULE_ENABLED
#define HAL_CRYP_MODULE_ENABLED
#define HAL_DAC_MODULE_ENABLED
#define HAL_DMA_MODULE_ENABLED
#define HAL_FLASH_MODULE_ENABLED
#define HAL_GPIO_MODULE_ENABLED
#define HAL_I2C_MODULE_ENABLED
#define HAL_I2S_MODULE_ENABLED
#define HAL_IWDG_MODULE_ENABLED
#define HAL_LCD_MODULE_ENABLED
#define HAL_LPTIM_MODULE_ENABLED
#define HAL_PWR_MODULE_ENABLED
#define HAL_RCC_MODULE_ENABLED
#define HAL_RNG_MODULE_ENABLED
#define HAL_RTC_MODULE_ENABLED
#define HAL_SPI_MODULE_ENABLED
#define HAL_TIM_MODULE_ENABLED
#define HAL_TSC_MODULE_ENABLED
#define HAL_UART_MODULE_ENABLED
#define HAL_USART_MODULE_ENABLED
#define HAL_IRDA_MODULE_ENABLED
#define HAL_SMARTCARD_MODULE_ENABLED
#define HAL_SMBUS_MODULE_ENABLED
#define HAL_WWDG_MODULE_ENABLED
#define HAL_CORTEX_MODULE_ENABLED
#define HAL_PCD_MODULE_ENABLED
/* ########################## Oscillator Values adaptation ####################*/
/**
* @brief Adjust the value of External High Speed oscillator (HSE) used in your application.
* This value is used by the RCC HAL module to compute the system frequency
* (when HSE is used as system clock source, directly or through the PLL).
*/
#if !defined (HSE_VALUE)
#define HSE_VALUE ((uint32_t)8000000) /*!< Value of the External oscillator in Hz */
#endif /* HSE_VALUE */
#if !defined (HSE_STARTUP_TIMEOUT)
#define HSE_STARTUP_TIMEOUT ((uint32_t)5000) /*!< Time out for HSE start up, in ms */
#endif /* HSE_STARTUP_TIMEOUT */
/**
* @brief Internal Multiple Speed oscillator (MSI) default value.
* This value is the default MSI range value after Reset.
*/
#if !defined (MSI_VALUE)
#define MSI_VALUE ((uint32_t)2000000) /*!< Value of the Internal oscillator in Hz*/
#endif /* MSI_VALUE */
/**
* @brief Internal High Speed oscillator (HSI) value.
* This value is used by the RCC HAL module to compute the system frequency
* (when HSI is used as system clock source, directly or through the PLL).
*/
#if !defined (HSI_VALUE)
#define HSI_VALUE ((uint32_t)16000000) /*!< Value of the Internal oscillator in Hz*/
#endif /* HSI_VALUE */
/**
* @brief External Low Speed oscillator (LSE) value.
* This value is used by the UART, RTC HAL module to compute the system frequency
*/
#if !defined (LSE_VALUE)
#define LSE_VALUE ((uint32_t)32768) /*!< Value of the External oscillator in Hz*/
#endif /* LSE_VALUE */
#if !defined (LSE_STARTUP_TIMEOUT)
#define LSE_STARTUP_TIMEOUT ((uint32_t)5000) /*!< Time out for LSE start up, in ms */
#endif /* HSE_STARTUP_TIMEOUT */
/* Tip: To avoid modifying this file each time you need to use different HSE,
=== you can define the HSE value in your toolchain compiler preprocessor. */
/* ########################### System Configuration ######################### */
/**
* @brief This is the HAL system configuration section
*/
#define VDD_VALUE ((uint32_t)3300) /*!< Value of VDD in mv */
#define TICK_INT_PRIORITY ((uint32_t)3) /*!< tick interrupt priority */
#define USE_RTOS 0
#define PREFETCH_ENABLE 1
#define PREREAD_ENABLE 1
#define BUFFER_CACHE_DISABLE 0
/* ########################## Assert Selection ############################## */
/**
* @brief Uncomment the line below to expanse the "assert_param" macro in the
* HAL drivers code
*/
/* #define USE_FULL_ASSERT 1 */
/* Includes ------------------------------------------------------------------*/
/**
* @brief Include module's header file
*/
#ifdef HAL_RCC_MODULE_ENABLED
#include "stm32l0xx_hal_rcc.h"
#endif /* HAL_RCC_MODULE_ENABLED */
#ifdef HAL_GPIO_MODULE_ENABLED
#include "stm32l0xx_hal_gpio.h"
#endif /* HAL_GPIO_MODULE_ENABLED */
#ifdef HAL_DMA_MODULE_ENABLED
#include "stm32l0xx_hal_dma.h"
#endif /* HAL_DMA_MODULE_ENABLED */
#ifdef HAL_CORTEX_MODULE_ENABLED
#include "stm32l0xx_hal_cortex.h"
#endif /* HAL_CORTEX_MODULE_ENABLED */
#ifdef HAL_ADC_MODULE_ENABLED
#include "stm32l0xx_hal_adc.h"
#endif /* HAL_ADC_MODULE_ENABLED */
#ifdef HAL_COMP_MODULE_ENABLED
#include "stm32l0xx_hal_comp.h"
#endif /* HAL_COMP_MODULE_ENABLED */
#ifdef HAL_CRC_MODULE_ENABLED
#include "stm32l0xx_hal_crc.h"
#endif /* HAL_CRC_MODULE_ENABLED */
#ifdef HAL_CRYP_MODULE_ENABLED
#include "stm32l0xx_hal_cryp.h"
#endif /* HAL_CRYP_MODULE_ENABLED */
#ifdef HAL_DAC_MODULE_ENABLED
#include "stm32l0xx_hal_dac.h"
#endif /* HAL_DAC_MODULE_ENABLED */
#ifdef HAL_FLASH_MODULE_ENABLED
#include "stm32l0xx_hal_flash.h"
#endif /* HAL_FLASH_MODULE_ENABLED */
#ifdef HAL_I2C_MODULE_ENABLED
#include "stm32l0xx_hal_i2c.h"
#endif /* HAL_I2C_MODULE_ENABLED */
#ifdef HAL_I2S_MODULE_ENABLED
#include "stm32l0xx_hal_i2s.h"
#endif /* HAL_I2S_MODULE_ENABLED */
#ifdef HAL_IWDG_MODULE_ENABLED
#include "stm32l0xx_hal_iwdg.h"
#endif /* HAL_IWDG_MODULE_ENABLED */
#ifdef HAL_LCD_MODULE_ENABLED
#include "stm32l0xx_hal_lcd.h"
#endif /* HAL_LCD_MODULE_ENABLED */
#ifdef HAL_LPTIM_MODULE_ENABLED
#include "stm32l0xx_hal_lptim.h"
#endif /* HAL_LPTIM_MODULE_ENABLED */
#ifdef HAL_PWR_MODULE_ENABLED
#include "stm32l0xx_hal_pwr.h"
#endif /* HAL_PWR_MODULE_ENABLED */
#ifdef HAL_RNG_MODULE_ENABLED
#include "stm32l0xx_hal_rng.h"
#endif /* HAL_RNG_MODULE_ENABLED */
#ifdef HAL_RTC_MODULE_ENABLED
#include "stm32l0xx_hal_rtc.h"
#endif /* HAL_RTC_MODULE_ENABLED */
#ifdef HAL_SPI_MODULE_ENABLED
#include "stm32l0xx_hal_spi.h"
#endif /* HAL_SPI_MODULE_ENABLED */
#ifdef HAL_TIM_MODULE_ENABLED
#include "stm32l0xx_hal_tim.h"
#endif /* HAL_TIM_MODULE_ENABLED */
#ifdef HAL_TSC_MODULE_ENABLED
#include "stm32l0xx_hal_tsc.h"
#endif /* HAL_TSC_MODULE_ENABLED */
#ifdef HAL_UART_MODULE_ENABLED
#include "stm32l0xx_hal_uart.h"
#endif /* HAL_UART_MODULE_ENABLED */
#ifdef HAL_USART_MODULE_ENABLED
#include "stm32l0xx_hal_usart.h"
#endif /* HAL_USART_MODULE_ENABLED */
#ifdef HAL_IRDA_MODULE_ENABLED
#include "stm32l0xx_hal_irda.h"
#endif /* HAL_IRDA_MODULE_ENABLED */
#ifdef HAL_SMARTCARD_MODULE_ENABLED
#include "stm32l0xx_hal_smartcard.h"
#endif /* HAL_SMARTCARD_MODULE_ENABLED */
#ifdef HAL_SMBUS_MODULE_ENABLED
#include "stm32l0xx_hal_smbus.h"
#endif /* HAL_SMBUS_MODULE_ENABLED */
#ifdef HAL_WWDG_MODULE_ENABLED
#include "stm32l0xx_hal_wwdg.h"
#endif /* HAL_WWDG_MODULE_ENABLED */
#ifdef HAL_PCD_MODULE_ENABLED
#include "stm32l0xx_hal_pcd.h"
#endif /* HAL_PCD_MODULE_ENABLED */
/* Exported macro ------------------------------------------------------------*/
#ifdef USE_FULL_ASSERT
/**
* @brief The assert_param macro is used for function's parameters check.
* @param expr: If expr is false, it calls assert_failed function
* which reports the name of the source file and the source
* line number of the call that failed.
* If expr is true, it returns no value.
* @retval None
*/
#define assert_param(expr) ((expr) ? (void)0 : assert_failed((uint8_t *)__FILE__, __LINE__))
/* Exported functions ------------------------------------------------------- */
void assert_failed(uint8_t* file, uint32_t line);
#else
#define assert_param(expr) ((void)0)
#endif /* USE_FULL_ASSERT */
#ifdef __cplusplus
}
#endif
#endif /* __STM32L0xx_HAL_CONF_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,333 @@
/**
******************************************************************************
* @file stm32l0xx_hal_cortex.c
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief CORTEX HAL module driver.
* This file provides firmware functions to manage the following
* functionalities of the CORTEX:
* + Initialization and de-initialization functions
* + Peripheral Control functions
*
@verbatim
==============================================================================
##### How to use this driver #####
==============================================================================
[..]
*** How to configure Interrupts using CORTEX HAL driver ***
===========================================================
[..]
This section provide functions allowing to configure the NVIC interrupts (IRQ).
The Cortex-M0+ exceptions are managed by CMSIS functions.
(#) Enable and Configure the priority of the selected IRQ Channels.
The priority can be 0..3.
-@- Lower priority values gives higher priority.
-@- Priority Order:
(#@) Lowest priority.
(#@) Lowest hardware priority (IRQn position).
(#) Configure the priority of the selected IRQ Channels using HAL_NVIC_SetPriority()
(#) Enable the selected IRQ Channels using HAL_NVIC_EnableIRQ()
[..]
*** How to configure Systick using CORTEX HAL driver ***
========================================================
[..]
Setup SysTick Timer for time base
(+) The HAL_SYSTICK_Config()function calls the SysTick_Config() function which
is a CMSIS function that:
(++) Configures the SysTick Reload register with value passed as function parameter.
(++) Configures the SysTick IRQ priority to the lowest value (0x03).
(++) Resets the SysTick Counter register.
(++) Configures the SysTick Counter clock source to be Core Clock Source (HCLK).
(++) Enables the SysTick Interrupt.
(++) Starts the SysTick Counter.
(+) You can change the SysTick Clock source to be HCLK_Div8 by calling the macro
__HAL_CORTEX_SYSTICKCLK_CONFIG(SYSTICK_CLKSOURCE_HCLK_DIV8) just after the
HAL_SYSTICK_Config() function call. The __HAL_CORTEX_SYSTICKCLK_CONFIG() macro is defined
inside the stm32l0xx_hal_cortex.h file.
(+) You can change the SysTick IRQ priority by calling the
HAL_NVIC_SetPriority(SysTick_IRQn,...) function just after the HAL_SYSTICK_Config() function
call. The HAL_NVIC_SetPriority() call the NVIC_SetPriority() function which is a CMSIS function.
(+) To adjust the SysTick time base, use the following formula:
Reload Value = SysTick Counter Clock (Hz) x Desired Time base (s)
(++) Reload Value is the parameter to be passed for HAL_SYSTICK_Config() function
(++) Reload Value should not exceed 0xFFFFFF
@endverbatim
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @defgroup CORTEX
* @brief CORTEX HAL module driver
* @{
*/
#ifdef HAL_CORTEX_MODULE_ENABLED
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/** @defgroup CORTEX_Private_Functions
* @{
*/
/** @defgroup CORTEX_Group1 Initialization and de-initialization functions
* @brief Initialization and Configuration functions
*
@verbatim
==============================================================================
##### Initialization and de-initialization functions #####
==============================================================================
[..]
This section provides the CORTEX HAL driver functions allowing to configure Interrupts
Systick functionalities
@endverbatim
* @{
*/
/**
* @brief Sets the priority of an interrupt.
* @param IRQn: External interrupt number .
* This parameter can be an enumerator of IRQn_Type enumeration
* (For the complete STM32 Devices IRQ Channels list, please refer to stm32l0xx.h file)
* @param PreemptPriority: The pre-emption priority for the IRQn channel.
* This parameter can be a value between 0 and 3.
* A lower priority value indicates a higher priority
* @param SubPriority: The subpriority level for the IRQ channel.
* with stm32l0xx devices, this parameter is a dummy value and it is ignored, because
* no subpriority supported in Cortex M0+ based products.
* @retval None
*/
void HAL_NVIC_SetPriority(IRQn_Type IRQn, uint32_t PreemptPriority, uint32_t SubPriority)
{
/* Check the parameters */
assert_param(IS_NVIC_PREEMPTION_PRIORITY(PreemptPriority));
NVIC_SetPriority(IRQn,PreemptPriority);
}
/**
* @brief Enables a device specific interrupt in the NVIC interrupt controller.
* @note To configure interrupts priority correctly, the NVIC_PriorityGroupConfig()
* function should be called before.
* @param IRQn External interrupt number .
* This parameter can be an enumerator of IRQn_Type enumeration
* (For the complete STM32 Devices IRQ Channels list, please refer to stm32l0xx.h file)
* @retval None
*/
void HAL_NVIC_EnableIRQ(IRQn_Type IRQn)
{
/* Enable interrupt */
NVIC_EnableIRQ(IRQn);
}
/**
* @brief Disables a device specific interrupt in the NVIC interrupt controller.
* @param IRQn External interrupt number .
* This parameter can be an enumerator of IRQn_Type enumeration
* (For the complete STM32 Devices IRQ Channels list, please refer to stm32l0xx.h file)
* @retval None
*/
void HAL_NVIC_DisableIRQ(IRQn_Type IRQn)
{
/* Disable interrupt */
NVIC_DisableIRQ(IRQn);
}
/**
* @brief Initiates a system reset request to reset the MCU.
* @param None
* @retval None
*/
void HAL_NVIC_SystemReset(void)
{
/* System Reset */
NVIC_SystemReset();
}
/**
* @brief Initializes the System Timer and its interrupt, and starts the System Tick Timer.
* Counter is in free running mode to generate periodic interrupts.
* @param TicksNumb: Specifies the ticks Number of ticks between two interrupts.
* @retval status: - 0 Function succeeded.
* - 1 Function failed.
*/
uint32_t HAL_SYSTICK_Config(uint32_t TicksNumb)
{
return SysTick_Config(TicksNumb);
}
/**
* @}
*/
/** @defgroup CORTEX_Group2 Peripheral Control functions
* @brief Cortex control functions
*
@verbatim
==============================================================================
##### Peripheral Control functions #####
==============================================================================
[..]
This subsection provides a set of functions allowing to control the CORTEX
(NVIC, SYSTICK) functionalities.
@endverbatim
* @{
*/
/**
* @brief Sets Pending bit of an external interrupt.
* @param IRQn External interrupt number
* This parameter can be an enumerator of @ref IRQn_Type enumeration
* (For the complete STM32 Devices IRQ Channels list, please refer to stm32l0xx.h file)
* @retval None
*/
void HAL_NVIC_SetPendingIRQ(IRQn_Type IRQn)
{
/* Set interrupt pending */
NVIC_SetPendingIRQ(IRQn);
}
/**
* @brief Gets Pending Interrupt (reads the pending register in the NVIC
* and returns the pending bit for the specified interrupt).
* @param IRQn External interrupt number .
* This parameter can be an enumerator of IRQn_Type enumeration
* (For the complete STM32 Devices IRQ Channels list, please refer to stm32l0xx.h file)
* @retval status: - 0 Interrupt status is not pending.
* - 1 Interrupt status is pending.
*/
uint32_t HAL_NVIC_GetPendingIRQ(IRQn_Type IRQn)
{
/* Return 1 if pending else 0 */
return NVIC_GetPendingIRQ(IRQn);
}
/**
* @brief Clears the pending bit of an external interrupt.
* @param IRQn External interrupt number .
* This parameter can be an enumerator of IRQn_Type enumeration
* (For the complete STM32 Devices IRQ Channels list, please refer to stm32l0xx.h file)
* @retval None
*/
void HAL_NVIC_ClearPendingIRQ(IRQn_Type IRQn)
{
/* Clear pending interrupt */
NVIC_ClearPendingIRQ(IRQn);
}
/**
* @brief Configures the SysTick clock source.
* @param 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 HAL_SYSTICK_CLKSourceConfig(uint32_t CLKSource)
{
/* Check the parameters */
assert_param(IS_SYSTICK_CLK_SOURCE(CLKSource));
if (CLKSource == SYSTICK_CLKSOURCE_HCLK)
{
SysTick->CTRL |= SYSTICK_CLKSOURCE_HCLK;
}
else
{
SysTick->CTRL &= ~SYSTICK_CLKSOURCE_HCLK;
}
}
/**
* @brief This function handles SYSTICK interrupt request.
* @param None
* @retval None
*/
void HAL_SYSTICK_IRQHandler(void)
{
HAL_SYSTICK_Callback();
}
/**
* @brief SYSTICK callback.
* @param None
* @retval None
*/
__weak void HAL_SYSTICK_Callback(void)
{
/* NOTE : This function Should not be modified, when the callback is needed,
the HAL_SYSTICK_Callback could be implemented in the user file
*/
}
/**
* @}
*/
/**
* @}
*/
#endif /* HAL_CORTEX_MODULE_ENABLED */
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,132 @@
/**
******************************************************************************
* @file stm32l0xx_hal_cortex.h
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief Header file of CORTEX HAL module.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32L0xx_HAL_CORTEX_H
#define __STM32L0xx_HAL_CORTEX_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal_def.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @addtogroup CORTEX
* @{
*/
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
/** @defgroup CORTEX_Exported_Constants
* @{
*/
#define IS_NVIC_PREEMPTION_PRIORITY(PRIORITY) ((PRIORITY) < 0x4)
/** @defgroup CORTEX_SysTick_clock_source
* @{
*/
#define SYSTICK_CLKSOURCE_HCLK_DIV8 ((uint32_t)0x00000000)
#define SYSTICK_CLKSOURCE_HCLK ((uint32_t)0x00000004)
#define IS_SYSTICK_CLK_SOURCE(SOURCE) (((SOURCE) == SYSTICK_CLKSOURCE_HCLK) || \
((SOURCE) == SYSTICK_CLKSOURCE_HCLK_DIV8))
/**
* @}
*/
/* Exported Macros -----------------------------------------------------------*/
/** @brief Configures the SysTick clock source.
* @param __CLKSRC__: 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
*/
#define __HAL_CORTEX_SYSTICKCLK_CONFIG(__CLKSRC__) \
do { \
if ((__CLKSRC__) == SYSTICK_CLKSOURCE_HCLK) \
{ \
SysTick->CTRL |= SYSTICK_CLKSOURCE_HCLK; \
} \
else \
SysTick->CTRL &= ~SYSTICK_CLKSOURCE_HCLK; \
} while(0)
/**
* @}
*/
/* Exported macro ------------------------------------------------------------*/
/* Exported functions --------------------------------------------------------*/
/* Initialization and de-initialization functions *******************************/
void HAL_NVIC_SetPriority(IRQn_Type IRQn, uint32_t PreemptPriority, uint32_t SubPriority);
void HAL_NVIC_EnableIRQ(IRQn_Type IRQn);
void HAL_NVIC_DisableIRQ(IRQn_Type IRQn);
void HAL_NVIC_SystemReset(void);
uint32_t HAL_SYSTICK_Config(uint32_t TicksNumb);
/* Peripheral Control functions *************************************************/
uint32_t HAL_NVIC_GetPendingIRQ(IRQn_Type IRQn);
void HAL_NVIC_SetPendingIRQ(IRQn_Type IRQn);
void HAL_NVIC_ClearPendingIRQ(IRQn_Type IRQn);
void HAL_SYSTICK_CLKSourceConfig(uint32_t CLKSource);
void HAL_SYSTICK_IRQHandler(void);
void HAL_SYSTICK_Callback(void);
/**
* @}
*/
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif /* __STM32L0xx_HAL_CORTEX_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,508 @@
/**
******************************************************************************
* @file stm32l0xx_hal_crc.c
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief CRC HAL module driver.
*
* This file provides firmware functions to manage the following
* functionalities of the CRC peripheral:
* + Initialization and de-initialization functions
* + Peripheral Control functions
* + Peripheral State functions
*
@verbatim
===============================================================================
##### CRC How to use this driver #####
===============================================================================
[..]
(#) Enable CRC AHB clock using __CRC_CLK_ENABLE();
(#) Initialize CRC calculator
(++) specify generating polynomial (IP default or non-default one)
(++) specify initialization value (IP default or non-default one)
(++) specify input data format
(++) specify input or output data inversion mode if any
(#) Use HAL_CRC_Accumulate() function to compute the CRC value of the
input data buffer starting with the previously computed CRC as
initialization value
(#) Use HAL_CRC_Calculate() function to compute the CRC value of the
input data buffer starting with the defined initialization value
(default or non-default) to initiate CRC calculation
@endverbatim
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @defgroup CRC
* @brief CRC HAL module driver
* @{
*/
#ifdef HAL_CRC_MODULE_ENABLED
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
static uint32_t CRC_Handle_8(CRC_HandleTypeDef *hcrc, uint8_t pBuffer[], uint32_t BufferLength);
static uint32_t CRC_Handle_16(CRC_HandleTypeDef *hcrc, uint16_t pBuffer[], uint32_t BufferLength);
/* Private functions ---------------------------------------------------------*/
/** @defgroup CRC_Private_Functions
* @{
*/
/** @defgroup CRC_Group1 Initialization and de-initialization functions
* @brief Initialization and Configuration functions
*
@verbatim
===============================================================================
##### Initialization and de-initialization functions #####
===============================================================================
[..]
This section provides functions allowing to:
(#) Initialize the CRC according to the specified parameters
in the CRC_InitTypeDef and create the associated handle
(#) DeInitialize the CRC peripheral
(#) Initialize the CRC MSP
(#) DeInitialize CRC MSP
@endverbatim
* @{
*/
/**
* @brief Initializes the CRC according to the specified
* parameters in the CRC_InitTypeDef and creates the associated handle.
* @param hcrc: CRC handle
* @retval HAL status
*/
HAL_StatusTypeDef HAL_CRC_Init(CRC_HandleTypeDef *hcrc)
{
/* Check the CRC handle allocation */
if(hcrc == NULL)
{
return HAL_ERROR;
}
assert_param(IS_CRC_INSTANCE(hcrc->Instance));
if(hcrc->State == HAL_CRC_STATE_RESET)
{
/* Init the low level hardware */
HAL_CRC_MspInit(hcrc);
}
/* Change CRC peripheral state */
hcrc->State = HAL_CRC_STATE_BUSY;
/* check whether or not non-default generating polynomial has been
* picked up by user */
assert_param(IS_DEFAULT_POLYNOMIAL(hcrc->Init.DefaultPolynomialUse));
if (hcrc->Init.DefaultPolynomialUse == DEFAULT_POLYNOMIAL_ENABLE)
{
/* initialize IP with default generating polynomial */
WRITE_REG(hcrc->Instance->POL, DEFAULT_CRC32_POLY);
MODIFY_REG(hcrc->Instance->CR, CRC_CR_POLYSIZE, CRC_POLYLENGTH_32B);
}
else
{
/* initialize CRC IP with generating polynomial defined by user */
if (HAL_CRCEx_Polynomial_Set(hcrc, hcrc->Init.GeneratingPolynomial, hcrc->Init.CRCLength) != HAL_OK)
{
return HAL_ERROR;
}
}
/* check whether or not non-default CRC initial value has been
* picked up by user */
assert_param(IS_DEFAULT_INIT_VALUE(hcrc->Init.DefaultInitValueUse));
if (hcrc->Init.DefaultInitValueUse == DEFAULT_INIT_VALUE_ENABLE)
{
WRITE_REG(hcrc->Instance->INIT, DEFAULT_CRC_INITVALUE);
}
else
{
WRITE_REG(hcrc->Instance->INIT, hcrc->Init.InitValue);
}
/* set input data inversion mode */
assert_param(IS_CRC_INPUTDATA_INVERSION_MODE(hcrc->Init.InputDataInversionMode));
MODIFY_REG(hcrc->Instance->CR, CRC_CR_REV_IN, hcrc->Init.InputDataInversionMode);
/* set output data inversion mode */
assert_param(IS_CRC_OUTPUTDATA_INVERSION_MODE(hcrc->Init.OutputDataInversionMode));
MODIFY_REG(hcrc->Instance->CR, CRC_CR_REV_OUT, hcrc->Init.OutputDataInversionMode);
/* makes sure the input data format (bytes, halfwords or words stream)
* is properly specified by user */
assert_param(IS_CRC_INPUTDATA_FORMAT(hcrc->InputDataFormat));
/* Change CRC peripheral state */
hcrc->State = HAL_CRC_STATE_READY;
/* Return function status */
return HAL_OK;
}
/**
* @brief DeInitializes the CRC peripheral.
* @param hcrc: CRC handle
* @retval HAL status
*/
HAL_StatusTypeDef HAL_CRC_DeInit(CRC_HandleTypeDef *hcrc)
{
/* Check the CRC handle allocation */
if(hcrc == NULL)
{
return HAL_ERROR;
}
assert_param(IS_CRC_INSTANCE(hcrc->Instance));
/* Check the CRC peripheral state */
if(hcrc->State == HAL_CRC_STATE_BUSY)
{
return HAL_BUSY;
}
/* Change CRC peripheral state */
hcrc->State = HAL_CRC_STATE_BUSY;
/* DeInit the low level hardware */
HAL_CRC_MspDeInit(hcrc);
/* Change CRC peripheral state */
hcrc->State = HAL_CRC_STATE_RESET;
/* Process unlocked */
__HAL_UNLOCK(hcrc);
/* Return function status */
return HAL_OK;
}
/**
* @brief Initializes the CRC MSP.
* @param hcrc: CRC handle
* @retval None
*/
__weak void HAL_CRC_MspInit(CRC_HandleTypeDef *hcrc)
{
/* NOTE : This function should not be modified, when the callback is needed,
the HAL_CRC_MspInit can be implemented in the user file
*/
}
/**
* @brief DeInitializes the CRC MSP.
* @param hcrc: CRC handle
* @retval None
*/
__weak void HAL_CRC_MspDeInit(CRC_HandleTypeDef *hcrc)
{
/* NOTE : This function should not be modified, when the callback is needed,
the HAL_CRC_MspDeInit can be implemented in the user file
*/
}
/**
* @}
*/
/** @defgroup CRC_Group2 Peripheral Control functions
* @brief management functions.
*
@verbatim
===============================================================================
##### Peripheral Control functions #####
===============================================================================
[..] This section provides functions allowing to:
(#) Compute the 7, 8, 16 or 32-bit CRC value of an 8, 16 or 32-bit data buffer
using combination of the previous CRC value and the new one.
or
(#) Compute the 7, 8, 16 or 32-bit CRC value of an 8, 16 or 32-bit data buffer
independently of the previous CRC value.
@endverbatim
* @{
*/
/**
* @brief Compute the 7, 8, 16 or 32-bit CRC value of an 8, 16 or 32-bit data buffer
* starting with the previously computed CRC as initialization value.
* @param hcrc: CRC handle
* @param pBuffer: pointer to the input data buffer, exact input data format is
* provided by hcrc->InputDataFormat.
* @param BufferLength: input data buffer length
* @retval uint32_t CRC (returned value LSBs for CRC shorter than 32 bits)
*/
uint32_t HAL_CRC_Accumulate(CRC_HandleTypeDef *hcrc, uint32_t pBuffer[], uint32_t BufferLength)
{
uint32_t index = 0; /* CRC input data buffer index */
uint32_t temp = 0; /* CRC output (read from hcrc->Instance->DR register) */
/* Process locked */
__HAL_LOCK(hcrc);
/* Change CRC peripheral state */
hcrc->State = HAL_CRC_STATE_BUSY;
switch (hcrc->InputDataFormat)
{
case CRC_INPUTDATA_FORMAT_WORDS:
/* Enter Data to the CRC calculator */
for(index = 0; index < BufferLength; index++)
{
hcrc->Instance->DR = pBuffer[index];
}
temp = hcrc->Instance->DR;
break;
case CRC_INPUTDATA_FORMAT_BYTES:
temp = CRC_Handle_8(hcrc, (uint8_t*)pBuffer, BufferLength);
break;
case CRC_INPUTDATA_FORMAT_HALFWORDS:
temp = CRC_Handle_16(hcrc, (uint16_t*)pBuffer, BufferLength);
break;
default:
break;
}
/* Change CRC peripheral state */
hcrc->State = HAL_CRC_STATE_READY;
/* Process unlocked */
__HAL_UNLOCK(hcrc);
/* Return the CRC computed value */
return temp;
}
/**
* @brief Compute the 7, 8, 16 or 32-bit CRC value of an 8, 16 or 32-bit data buffer
* starting with hcrc->Instance->INIT as initialization value.
* @param hcrc: CRC handle
* @param pBuffer: pointer to the input data buffer, exact input data format is
* provided by hcrc->InputDataFormat.
* @param BufferLength: input data buffer length
* @retval uint32_t CRC (returned value LSBs for CRC shorter than 32 bits)
*/
uint32_t HAL_CRC_Calculate(CRC_HandleTypeDef *hcrc, uint32_t pBuffer[], uint32_t BufferLength)
{
uint32_t index = 0; /* CRC input data buffer index */
uint32_t temp = 0; /* CRC output (read from hcrc->Instance->DR register) */
/* Process locked */
__HAL_LOCK(hcrc);
/* Change CRC peripheral state */
hcrc->State = HAL_CRC_STATE_BUSY;
/* Reset CRC Calculation Unit (hcrc->Instance->INIT is
* written in hcrc->Instance->DR) */
__HAL_CRC_DR_RESET(hcrc);
switch (hcrc->InputDataFormat)
{
case CRC_INPUTDATA_FORMAT_WORDS:
/* Enter 32-bit input data to the CRC calculator */
for(index = 0; index < BufferLength; index++)
{
hcrc->Instance->DR = pBuffer[index];
}
temp = hcrc->Instance->DR;
break;
case CRC_INPUTDATA_FORMAT_BYTES:
/* Specific 8-bit input data handling */
temp = CRC_Handle_8(hcrc, (uint8_t*)pBuffer, BufferLength);
break;
case CRC_INPUTDATA_FORMAT_HALFWORDS:
/* Specific 16-bit input data handling */
temp = CRC_Handle_16(hcrc, (uint16_t*)pBuffer, BufferLength);
break;
default:
break;
}
/* Change CRC peripheral state */
hcrc->State = HAL_CRC_STATE_READY;
/* Process unlocked */
__HAL_UNLOCK(hcrc);
/* Return the CRC computed value */
return temp;
}
/**
* @}
*/
/** @defgroup CRC_Group3 Peripheral State functions
* @brief Peripheral State functions.
*
@verbatim
===============================================================================
##### Peripheral State functions #####
===============================================================================
[..]
This subsection permits to get in run-time the status of the peripheral
and the data flow.
@endverbatim
* @{
*/
/**
* @brief Returns the CRC state.
* @param hcrc: CRC handle
* @retval HAL state
*/
HAL_CRC_StateTypeDef HAL_CRC_GetState(CRC_HandleTypeDef *hcrc)
{
return hcrc->State;
}
/**
* @}
*/
/**
* @brief Enter 8-bit input data to the CRC calculator.
* Specific data handling to optimize processing time.
* @param hcrc: CRC handle
* @param pBuffer: pointer to the input data buffer
* @param BufferLength: input data buffer length
* @retval uint32_t CRC (returned value LSBs for CRC shorter than 32 bits)
*/
static uint32_t CRC_Handle_8(CRC_HandleTypeDef *hcrc, uint8_t pBuffer[], uint32_t BufferLength)
{
uint32_t i; /* input data buffer index */
/* Processing time optimization: 4 bytes are entered in a row with a single word write,
* last bytes must be carefully fed to the CRC calculator to ensure a correct type
* handling by the IP */
for(i = 0; i < (BufferLength/4); i++)
{
hcrc->Instance->DR = (uint32_t)(((uint32_t)(pBuffer[4*i])<<24) | ((uint32_t)(pBuffer[4*i+1])<<16) | ((uint32_t)(pBuffer[4*i+2])<<8) | (uint32_t)(pBuffer[4*i+3]));
}
/* last bytes specific handling */
if ((BufferLength%4) != 0)
{
if (BufferLength%4 == 1)
{
*(__IO uint8_t*) (&hcrc->Instance->DR) = pBuffer[4*i];
}
if (BufferLength%4 == 2)
{
*(__IO uint16_t*) (&hcrc->Instance->DR) = (uint16_t)(((uint32_t)(pBuffer[4*i])<<8) | (uint32_t)(pBuffer[4*i+1]));
}
if (BufferLength%4 == 3)
{
*(__IO uint16_t*) (&hcrc->Instance->DR) = (uint16_t)(((uint32_t)(pBuffer[4*i])<<8) | (uint32_t)(pBuffer[4*i+1]));
*(__IO uint8_t*) (&hcrc->Instance->DR) = pBuffer[4*i+2];
}
}
/* Return the CRC computed value */
return hcrc->Instance->DR;
}
/**
* @brief Enter 16-bit input data to the CRC calculator.
* Specific data handling to optimize processing time.
* @param hcrc: CRC handle
* @param pBuffer: pointer to the input data buffer
* @param BufferLength: input data buffer length
* @retval uint32_t CRC (returned value LSBs for CRC shorter than 32 bits)
*/
static uint32_t CRC_Handle_16(CRC_HandleTypeDef *hcrc, uint16_t pBuffer[], uint32_t BufferLength)
{
uint32_t i ; /* input data buffer index */
/* Processing time optimization: 2 HalfWords are entered in a row with a single word write,
* in case of odd length, last HalfWord must be carefully fed to the CRC calculator to ensure
* a correct type handling by the IP */
for(i = 0; i < (BufferLength/2); i++)
{
hcrc->Instance->DR = (((uint32_t)(pBuffer[2*i])<<16) | (uint32_t)(pBuffer[2*i+1]));
}
if ((BufferLength%2) != 0)
{
*(__IO uint16_t*) (&hcrc->Instance->DR) = pBuffer[2*i];
}
/* Return the CRC computed value */
return hcrc->Instance->DR;
}
/**
* @}
*/
#endif /* HAL_CRC_MODULE_ENABLED */
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,346 @@
/**
******************************************************************************
* @file stm32l0xx_hal_crc.h
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief Header file of CRC HAL module.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32L0xx_HAL_CRC_H
#define __STM32L0xx_HAL_CRC_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal_def.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @addtogroup CRC
* @{
*/
/* Exported types ------------------------------------------------------------*/
/**
* @brief CRC HAL State Structure definition
*/
typedef enum
{
HAL_CRC_STATE_RESET = 0x00, /*!< CRC Reset State */
HAL_CRC_STATE_READY = 0x01, /*!< CRC Initialized and ready for use */
HAL_CRC_STATE_BUSY = 0x02, /*!< CRC process is ongoing */
HAL_CRC_STATE_TIMEOUT = 0x03, /*!< CRC Timeout State */
HAL_CRC_STATE_ERROR = 0x04 /*!< CRC Error State */
}HAL_CRC_StateTypeDef;
/**
* @brief CRC Init Structure definition
*/
typedef struct
{
uint8_t DefaultPolynomialUse; /*!< This parameter is a value of @ref CRC_Default_Polynomial and indicates if default polynomial is used.
If set to DEFAULT_POLYNOMIAL_ENABLE, resort to default
X^32 + X^26 + X^23 + X^22 + X^16 + X^12 + X^11 + X^10 +X^8 + X^7 + X^5 + X^4 + X^2+ X +1.
In that case, there is no need to set GeneratingPolynomial field.
If otherwise set to DEFAULT_POLYNOMIAL_DISABLE, GeneratingPolynomial and CRCLength fields must be set */
uint8_t DefaultInitValueUse; /*!< This parameter is a value of @ref CRC_Default_InitValue_Use and indicates if default init value is used.
If set to DEFAULT_INIT_VALUE_ENABLE, resort to default
0xFFFFFFFF value. In that case, there is no need to set InitValue field.
If otherwise set to DEFAULT_INIT_VALUE_DISABLE, InitValue field must be set */
uint32_t GeneratingPolynomial; /*!< Set CRC generating polynomial. 7, 8, 16 or 32-bit long value for a polynomial degree
respectively equal to 7, 8, 16 or 32. This field is written in normal representation,
e.g., for a polynomial of degree 7, X^7 + X^6 + X^5 + X^2 + 1 is written 0x65.
No need to specify it if DefaultPolynomialUse is set to DEFAULT_POLYNOMIAL_ENABLE */
uint32_t CRCLength; /*!< This parameter is a value of @ref CRC_Polynomial_Size_Definitions and indicates CRC length.
Value can be either one of
CRC_POLYLENGTH_32B (32-bit CRC)
CRC_POLYLENGTH_16B (16-bit CRC)
CRC_POLYLENGTH_8B (8-bit CRC)
CRC_POLYLENGTH_7B (7-bit CRC) */
uint32_t InitValue; /*!< Init value to initiate CRC computation. No need to specify it if DefaultInitValueUse
is set to DEFAULT_INIT_VALUE_ENABLE */
uint32_t InputDataInversionMode; /*!< This parameter is a value of @ref CRC_Input_Data_Inversion and specifies input data inversion mode.
Can be either one of the following values
CRC_INPUTDATA_INVERSION_NONE no input data inversion
CRC_INPUTDATA_INVERSION_BYTE byte-wise inversion, 0x1A2B3C4D becomes 0x58D43CB2
CRC_INPUTDATA_INVERSION_HALFWORD halfword-wise inversion, 0x1A2B3C4D becomes 0xD458B23C
CRC_INPUTDATA_INVERSION_WORD word-wise inversion, 0x1A2B3C4D becomes 0xB23CD458 */
uint32_t OutputDataInversionMode; /*!< This parameter is a value of @ref CRC_Output_Data_Inversion and specifies output data (i.e. CRC) inversion mode.
Can be either
CRC_OUTPUTDATA_INVERSION_DISABLED no CRC inversion, or
CRC_OUTPUTDATA_INVERSION_ENABLED CRC 0x11223344 is converted into 0x22CC4488 */
}CRC_InitTypeDef;
/**
* @brief CRC Handle Structure definition
*/
typedef struct
{
CRC_TypeDef *Instance; /*!< Register base address */
CRC_InitTypeDef Init; /*!< CRC configuration parameters */
HAL_LockTypeDef Lock; /*!< CRC Locking object */
__IO HAL_CRC_StateTypeDef State; /*!< CRC communication state */
uint32_t InputDataFormat; /*!< This parameter is a value of @ref CRC_Input_Buffer_Format and specifies input data format.
Can be either
CRC_INPUTDATA_FORMAT_BYTES input data is a stream of bytes (8-bit data)
CRC_INPUTDATA_FORMAT_HALFWORDS input data is a stream of half-words (16-bit data)
CRC_INPUTDATA_FORMAT_WORDS input data is a stream of words (32-bits data)
Note that constant CRC_INPUT_FORMAT_UNDEFINED is defined but an initialization error
must occur if InputBufferFormat is not one of the three values listed above */
}CRC_HandleTypeDef;
/* Exported constants --------------------------------------------------------*/
/** @defgroup CRC_Exported_Constants
* @{
*/
/** @defgroup CRC_Default_Polynomial_Value
* @{
*/
#define DEFAULT_CRC32_POLY 0x04C11DB7
/**
* @}
*/
/** @defgroup CRC_Default_Init_Value
* @{
*/
#define DEFAULT_CRC_INITVALUE 0xFFFFFFFF
/**
* @}
*/
/** @defgroup CRC_Default_Polynomial
* @{
*/
#define DEFAULT_POLYNOMIAL_ENABLE ((uint8_t)0x00)
#define DEFAULT_POLYNOMIAL_DISABLE ((uint8_t)0x01)
#define IS_DEFAULT_POLYNOMIAL(DEFAULT) (((DEFAULT) == DEFAULT_POLYNOMIAL_ENABLE) || \
((DEFAULT) == DEFAULT_POLYNOMIAL_DISABLE))
/**
* @}
*/
/** @defgroup CRC_Default_InitValue_Use
* @{
*/
#define DEFAULT_INIT_VALUE_ENABLE ((uint8_t)0x00)
#define DEFAULT_INIT_VALUE_DISABLE ((uint8_t)0x01)
#define IS_DEFAULT_INIT_VALUE(VALUE) (((VALUE) == DEFAULT_INIT_VALUE_ENABLE) || \
((VALUE) == DEFAULT_INIT_VALUE_DISABLE))
/**
* @}
*/
/** @defgroup CRC_Polynomial_Sizes
* @{
*/
#define CRC_POLYLENGTH_32B ((uint32_t)0x00000000)
#define CRC_POLYLENGTH_16B ((uint32_t)CRC_CR_POLYSIZE_0)
#define CRC_POLYLENGTH_8B ((uint32_t)CRC_CR_POLYSIZE_1)
#define CRC_POLYLENGTH_7B ((uint32_t)CRC_CR_POLYSIZE)
#define IS_CRC_POL_LENGTH(LENGTH) (((LENGTH) == CRC_POLYLENGTH_32B) || \
((LENGTH) == CRC_POLYLENGTH_16B) || \
((LENGTH) == CRC_POLYLENGTH_8B) || \
((LENGTH) == CRC_POLYLENGTH_7B))
/**
* @}
*/
/** @defgroup CRC_Polynomial_Size_Definitions
* @{
*/
#define HAL_CRC_LENGTH_32B 32
#define HAL_CRC_LENGTH_16B 16
#define HAL_CRC_LENGTH_8B 8
#define HAL_CRC_LENGTH_7B 7
/**
* @}
*/
/** @defgroup CRC_Input_Data_Inversion
* @{
*/
#define CRC_INPUTDATA_INVERSION_NONE ((uint32_t)0x00000000)
#define CRC_INPUTDATA_INVERSION_BYTE ((uint32_t)CRC_CR_REV_IN_0)
#define CRC_INPUTDATA_INVERSION_HALFWORD ((uint32_t)CRC_CR_REV_IN_1)
#define CRC_INPUTDATA_INVERSION_WORD ((uint32_t)CRC_CR_REV_IN)
#define IS_CRC_INPUTDATA_INVERSION_MODE(MODE) (((MODE) == CRC_INPUTDATA_INVERSION_NONE) || \
((MODE) == CRC_INPUTDATA_INVERSION_BYTE) || \
((MODE) == CRC_INPUTDATA_INVERSION_HALFWORD) || \
((MODE) == CRC_INPUTDATA_INVERSION_WORD))
/**
* @}
*/
/** @defgroup CRC_Output_Data_Inversion
* @{
*/
#define CRC_OUTPUTDATA_INVERSION_DISABLED ((uint32_t)0x00000000)
#define CRC_OUTPUTDATA_INVERSION_ENABLED ((uint32_t)CRC_CR_REV_OUT)
#define IS_CRC_OUTPUTDATA_INVERSION_MODE(MODE) (((MODE) == CRC_OUTPUTDATA_INVERSION_DISABLED) || \
((MODE) == CRC_OUTPUTDATA_INVERSION_ENABLED))
/**
* @}
*/
/** @defgroup CRC_Input_Buffer_Format
* @{
*/
/* WARNING: CRC_INPUT_FORMAT_UNDEFINED is created for reference purposes but
* an error is triggered in HAL_CRC_Init() if InputDataFormat field is set
* to CRC_INPUT_FORMAT_UNDEFINED: the format MUST be defined by the user for
* the CRC APIs to provide a correct result */
#define CRC_INPUTDATA_FORMAT_UNDEFINED ((uint32_t)0x00000000)
#define CRC_INPUTDATA_FORMAT_BYTES ((uint32_t)0x00000001)
#define CRC_INPUTDATA_FORMAT_HALFWORDS ((uint32_t)0x00000002)
#define CRC_INPUTDATA_FORMAT_WORDS ((uint32_t)0x00000003)
#define IS_CRC_INPUTDATA_FORMAT(FORMAT) (((FORMAT) == CRC_INPUTDATA_FORMAT_BYTES) || \
((FORMAT) == CRC_INPUTDATA_FORMAT_HALFWORDS) || \
((FORMAT) == CRC_INPUTDATA_FORMAT_WORDS))
/**
* @}
*/
/**
* @}
*/
/* Exported macro ------------------------------------------------------------*/
/** @defgroup CRC_Exported_Macro
* @{
*/
/** @brief Reset CRC handle state
* @param __HANDLE__: CRC handle
* @retval None
*/
#define __HAL_CRC_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_CRC_STATE_RESET)
/**
* @brief Check that instance is correctly set to CRC
* @param __PERIPH__: CRC handle instance
* @retval None.
*/
#define IS_CRC_INSTANCE(__PERIPH__) ((__PERIPH__) == CRC)
/**
* @brief Reset CRC Data Register.
* @param __HANDLE__: CRC handle
* @retval None.
*/
#define __HAL_CRC_DR_RESET(__HANDLE__) ((__HANDLE__)->Instance->CR |= CRC_CR_RESET)
/**
* @brief Set CRC INIT non-default value
* @param __HANDLE__ : CRC handle
* @param __INIT__ : 32-bit initial value
* @retval None.
*/
#define __HAL_CRC_INITIALCRCVALUE_CONFIG(__HANDLE__, __INIT__) ((__HANDLE__)->Instance->INIT = (__INIT__))
/**
* @brief Set CRC output reversal
* @param __HANDLE__ : CRC handle
* @retval None.
*/
#define __HAL_CRC_OUTPUTREVERSAL_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR |= CRC_CR_REV_OUT)
/**
* @brief Unset CRC output reversal
* @param __HANDLE__ : CRC handle
* @retval None.
*/
#define __HAL_CRC_OUTPUTREVERSAL_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR &= ~(CRC_CR_REV_OUT))
/**
* @}
*/
/* Include CRC HAL Extension module */
#include "stm32l0xx_hal_crc_ex.h"
/* Exported functions --------------------------------------------------------*/
/* Initialization and de-initialization functions ****************************/
HAL_StatusTypeDef HAL_CRC_Init(CRC_HandleTypeDef *hcrc);
HAL_StatusTypeDef HAL_CRC_DeInit (CRC_HandleTypeDef *hcrc);
void HAL_CRC_MspInit(CRC_HandleTypeDef *hcrc);
void HAL_CRC_MspDeInit(CRC_HandleTypeDef *hcrc);
/* Peripheral Control functions ***********************************************/
uint32_t HAL_CRC_Accumulate(CRC_HandleTypeDef *hcrc, uint32_t pBuffer[], uint32_t BufferLength);
uint32_t HAL_CRC_Calculate(CRC_HandleTypeDef *hcrc, uint32_t pBuffer[], uint32_t BufferLength);
/* Peripheral State and Error functions ***************************************/
HAL_CRC_StateTypeDef HAL_CRC_GetState(CRC_HandleTypeDef *hcrc);
/**
* @}
*/
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif /* __STM32L0xx_HAL_CRC_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,249 @@
/**
******************************************************************************
* @file stm32l0xx_hal_crc_ex.c
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief Extended CRC HAL module driver.
*
* This file provides firmware functions to manage the following
* functionalities of the CRC peripheral:
* + Initialization/de-initialization functions
*
@verbatim
==============================================================================
##### CRC specific features #####
==============================================================================
[..]
(#) Polynomial configuration.
##### How to use this driver #####
==============================================================================
[..]
(#) Enable CRC AHB clock using __CRC_CLK_ENABLE();
(#) Initialize CRC calculator
(++) specify generating polynomial (IP default or non-default one)
(++) specify initialization value (IP default or non-default one)
(++) specify input data format
(++) specify input or output data inversion mode if any
(#) Use HAL_CRC_Accumulate() function to compute the CRC value of the
input data buffer starting with the previously computed CRC as
initialization value
(#) Use HAL_CRC_Calculate() function to compute the CRC value of the
input data buffer starting with the defined initialization value
(default or non-default) to initiate CRC calculation
@endverbatim
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @addtogroup CRCEx
* @brief CRC driver modules
* @{
*/
#ifdef HAL_CRC_MODULE_ENABLED
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/** @defgroup CRCEx_Group CRC Extended features functions
* @brief CRC Extended features functions
*
@verbatim
===============================================================================
##### CRC Extended features functions #####
===============================================================================
[..]
This subsection provides function allowing to:
(+) Set CRC polynomial if different from default one.
@endverbatim
* @{
*/
/**
* @brief Initializes the CRC polynomial if different from default one.
* @param hcrc: CRC handle
* @param Pol: CRC generating polynomial (7, 8, 16 or 32-bit long)
* This parameter is written in normal representation, e.g.
* for a polynomial of degree 7, X^7 + X^6 + X^5 + X^2 + 1 is written 0x65
* for a polynomial of degree 16, X^16 + X^12 + X^5 + 1 is written 0x1021
* @param PolyLength: CRC polynomial length
* This parameter can be one of the following values:
* @arg CRC_POLYLENGTH_7B: 7-bit long CRC (generating polynomial of degree 7)
* @arg CRC_POLYLENGTH_8B: 8-bit long CRC (generating polynomial of degree 8)
* @arg CRC_POLYLENGTH_16B: 16-bit long CRC (generating polynomial of degree 16)
* @arg CRC_POLYLENGTH_32B: 32-bit long CRC (generating polynomial of degree 32)
* @retval HAL status
*/
HAL_StatusTypeDef HAL_CRCEx_Polynomial_Set(CRC_HandleTypeDef *hcrc, uint32_t Pol, uint32_t PolyLength)
{
uint32_t msb = 31; /* polynomial degree is 32 at most, so msb is initialized to max value */
/* Check the parameters */
assert_param(IS_CRC_POL_LENGTH(PolyLength));
/* check polynomial definition vs polynomial size:
* polynomial length must be aligned with polynomial
* definition. HAL_ERROR is reported if Pol degree is
* larger than that indicated by PolyLength.
* Look for MSB position: msb will contain the degree of
* the second to the largest polynomial member. E.g., for
* X^7 + X^6 + X^5 + X^2 + 1, msb = 6. */
while (((Pol & ((uint32_t)(0x1) << msb)) == 0) && (msb-- > 0))
{
}
switch (PolyLength)
{
case CRC_POLYLENGTH_7B:
if (msb >= HAL_CRC_LENGTH_7B)
{
return HAL_ERROR;
}
break;
case CRC_POLYLENGTH_8B:
if (msb >= HAL_CRC_LENGTH_8B)
{
return HAL_ERROR;
}
break;
case CRC_POLYLENGTH_16B:
if (msb >= HAL_CRC_LENGTH_16B)
{
return HAL_ERROR;
}
break;
case CRC_POLYLENGTH_32B:
/* no polynomial definition vs. polynomial length issue possible */
break;
default:
break;
}
/* set generating polynomial */
WRITE_REG(hcrc->Instance->POL, Pol);
/* set generating polynomial size */
MODIFY_REG(hcrc->Instance->CR, CRC_CR_POLYSIZE, PolyLength);
/* Return function status */
return HAL_OK;
}
/**
* @brief Set the Reverse Input data mode.
* @param hcrc: CRC handle
* @param InputReverseMode: Input Data inversion mode
* This parameter can be one of the following values:
* @arg CRC_INPUTDATA_INVERSION_NONE: no change in bit order (default value)
* @arg CRC_INPUTDATA_INVERSION_BYTE: Byte-wise bit reversal
* @arg CRC_INPUTDATA_INVERSION_HALFWORD: HalfWord-wise bit reversal
* @arg CRC_INPUTDATA_INVERSION_WORD: Word-wise bit reversal
* @retval HAL status
*/
HAL_StatusTypeDef HAL_CRC_Input_Data_Reverse(CRC_HandleTypeDef *hcrc, uint32_t InputReverseMode)
{
/* Check the parameters */
assert_param(IS_CRC_INPUTDATA_INVERSION_MODE(InputReverseMode));
/* Change CRC peripheral state */
hcrc->State = HAL_CRC_STATE_BUSY;
/* set input data inversion mode */
MODIFY_REG(hcrc->Instance->CR, CRC_CR_REV_IN, InputReverseMode);
/* Change CRC peripheral state */
hcrc->State = HAL_CRC_STATE_READY;
/* Return function status */
return HAL_OK;
}
/**
* @brief Set the Reverse Output data mode.
* @param hcrc: CRC handle
* @param OutputReverseMode: Output Data inversion mode
* This parameter can be one of the following values:
* @arg CRC_OUTPUTDATA_INVERSION_DISABLED: no CRC inversion (default value)
* @arg CRC_OUTPUTDATA_INVERSION_ENABLED: bit-level inversion (e.g for a 8-bit CRC: 0xB5 becomes 0xAD)
* @retval HAL status
*/
HAL_StatusTypeDef HAL_CRC_Output_Data_Reverse(CRC_HandleTypeDef *hcrc, uint32_t OutputReverseMode)
{
/* Check the parameters */
assert_param(IS_CRC_OUTPUTDATA_INVERSION_MODE(OutputReverseMode));
/* Change CRC peripheral state */
hcrc->State = HAL_CRC_STATE_BUSY;
/* set output data inversion mode */
MODIFY_REG(hcrc->Instance->CR, CRC_CR_REV_OUT, OutputReverseMode);
/* Change CRC peripheral state */
hcrc->State = HAL_CRC_STATE_READY;
/* Return function status */
return HAL_OK;
}
/**
* @}
*/
#endif /* HAL_CRC_MODULE_ENABLED */
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,104 @@
/**
******************************************************************************
* @file stm32l0xx_hal_crc_ex.h
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief Header file of CRC HAL module.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32L0xx_HAL_CRC_EX_H
#define __STM32L0xx_HAL_CRC_EX_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal_def.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @addtogroup CRCEx
* @{
*/
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
/* Exported macro ------------------------------------------------------------*/
/** @defgroup CRCEx_Extended_Exported_Macro
* @{
*/
/**
* @brief Set CRC non-default polynomial
* @param __HANDLE__ : CRC handle
* @param __POLYNOMIAL__: 7, 8, 16 or 32-bit polynomial
* @retval None.
*/
#define __HAL_CRC_POLYNOMIAL_CONFIG(__HANDLE__, __POLYNOMIAL__) ((__HANDLE__)->Instance->POL = (__POLYNOMIAL__))
/**
* @}
*/
/* Exported functions --------------------------------------------------------*/
/* Initialization and de-initialization functions ****************************/
HAL_StatusTypeDef HAL_CRCEx_Polynomial_Set(CRC_HandleTypeDef *hcrc, uint32_t Pol, uint32_t PolyLength);
HAL_StatusTypeDef HAL_CRC_Input_Data_Reverse(CRC_HandleTypeDef *hcrc, uint32_t InputReverseMode);
HAL_StatusTypeDef HAL_CRC_Output_Data_Reverse(CRC_HandleTypeDef *hcrc, uint32_t OutputReverseMode);
/* Peripheral Control functions ***********************************************/
/* Peripheral State and Error functions ***************************************/
/**
* @}
*/
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif /* __STM32L0xx_HAL_CRC_EX_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,312 @@
/**
******************************************************************************
* @file stm32l0xx_hal_cryp.h
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief Header file of CRYP HAL module.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32L0xx_HAL_CRYP_H
#define __STM32L0xx_HAL_CRYP_H
#ifdef __cplusplus
extern "C" {
#endif
#if !defined (STM32L051xx) && !defined (STM32L052xx) && !defined (STM32L053xx)
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal_def.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @addtogroup CRYP
* @{
*/
/* Exported types ------------------------------------------------------------*/
/**
* @brief CRYP Configuration Structure definition
*/
typedef struct
{
uint32_t DataType; /*!< 32-bit data, 16-bit data, 8-bit data or 1-bit string.
This parameter can be a value of @ref CRYP_Data_Type */
uint8_t* pKey; /*!< The key used for encryption/decryption */
uint8_t* pInitVect; /*!< The initialization vector used also as initialization
counter in CTR mode */
}CRYP_InitTypeDef;
/**
* @brief HAL CRYP State structures definition
*/
typedef enum
{
HAL_CRYP_STATE_RESET = 0x00, /*!< CRYP not yet initialized or disabled */
HAL_CRYP_STATE_READY = 0x01, /*!< CRYP initialized and ready for use */
HAL_CRYP_STATE_BUSY = 0x02, /*!< CRYP internal processing is ongoing */
HAL_CRYP_STATE_TIMEOUT = 0x03, /*!< CRYP timeout state */
HAL_CRYP_STATE_ERROR = 0x04 /*!< CRYP error state */
}HAL_CRYP_STATETypeDef;
/**
* @brief HAL CRYP phase structures definition
*/
typedef enum
{
HAL_CRYP_PHASE_READY = 0x01, /*!< CRYP peripheral is ready for initialization. */
HAL_CRYP_PHASE_PROCESS = 0x02, /*!< CRYP peripheral is in processing phase */
}HAL_PhaseTypeDef;
/**
* @brief CRYP handle Structure definition
*/
typedef struct
{
CRYP_InitTypeDef Init; /*!< CRYP required parameters */
uint8_t *pCrypInBuffPtr; /*!< Pointer to CRYP processing (encryption, decryption,...) buffer */
uint8_t *pCrypOutBuffPtr; /*!< Pointer to CRYP processing (encryption, decryption,...) buffer */
__IO uint16_t CrypInCount; /*!< Counter of inputed data */
__IO uint16_t CrypOutCount; /*!< Counter of outputed data */
HAL_StatusTypeDef Status; /*!< CRYP peripheral status */
HAL_PhaseTypeDef Phase; /*!< CRYP peripheral phase */
DMA_HandleTypeDef *hdmain; /*!< CRYP In DMA handle parameters */
DMA_HandleTypeDef *hdmaout; /*!< CRYP Out DMA handle parameters */
HAL_LockTypeDef Lock; /*!< CRYP locking object */
__IO HAL_CRYP_STATETypeDef State; /*!< CRYP peripheral state */
}CRYP_HandleTypeDef;
/* Exported constants --------------------------------------------------------*/
/** @defgroup CRYP_Exported_Constants
* @{
*/
/** @defgroup CRYP_Data_Type
* @{
*/
#define CRYP_DATATYPE_32B ((uint32_t)0x00000000)
#define CRYP_DATATYPE_16B AES_CR_DATATYPE_0
#define CRYP_DATATYPE_8B AES_CR_DATATYPE_1
#define CRYP_DATATYPE_1B AES_CR_DATATYPE
#define IS_CRYP_DATATYPE(DATATYPE) (((DATATYPE) == CRYP_DATATYPE_32B) || \
((DATATYPE) == CRYP_DATATYPE_16B) || \
((DATATYPE) == CRYP_DATATYPE_8B) || \
((DATATYPE) == CRYP_DATATYPE_1B))
/**
* @}
*/
/** @defgroup CRYP_AlgoModeDirection
* @{
*/
#define CRYP_CR_ALGOMODE_DIRECTION (uint32_t)(AES_CR_MODE|AES_CR_CHMOD)
#define CRYP_CR_ALGOMODE_AES_ECB_ENCRYPT ((uint32_t)0x00000000)
#define CRYP_CR_ALGOMODE_AES_ECB_KEYDERDECRYPT (AES_CR_MODE)
#define CRYP_CR_ALGOMODE_AES_CBC_ENCRYPT (AES_CR_CHMOD_0)
#define CRYP_CR_ALGOMODE_AES_CBC_KEYDERDECRYPT ((uint32_t)(AES_CR_CHMOD_0|AES_CR_MODE))
#define CRYP_CR_ALGOMODE_AES_CTR_ENCRYPT (AES_CR_CHMOD_1)
#define CRYP_CR_ALGOMODE_AES_CTR_DECRYPT ((uint32_t)(AES_CR_CHMOD_1 | AES_CR_MODE_1))
/**
* @}
*/
/** @defgroup AES_Interrupts
* @{
*/
#define AES_IT_CC AES_CR_CCIE /*!< Computation Complete interrupt */
#define AES_IT_ERR AES_CR_ERRIE /*!< Error interrupt */
#define IS_AES_IT(IT) ((((IT) & (uint32_t)0xFFFFF9FF) == 0x00000000) && ((IT) != 0x00000000))
#define IS_AES_GET_IT(IT) (((IT) == AES_IT_CC) || ((IT) == AES_IT_ERR))
/**
* @}
*/
/** @defgroup AES_Flags
* @{
*/
#define AES_FLAG_CCF AES_SR_CCF /*!< Computation Complete Flag */
#define AES_FLAG_RDERR AES_SR_RDERR /*!< Read Error Flag */
#define AES_FLAG_WRERR AES_SR_WRERR /*!< Write Error Flag */
#define IS_AES_FLAG(FLAG) (((FLAG) == AES_FLAG_CCF) || \
((FLAG) == AES_FLAG_RDERR) || \
((FLAG) == AES_FLAG_WRERR))
/**
* @}
*/
/**
* @}
*/
/* Exported macro ------------------------------------------------------------*/
/** @brief Reset CRYP handle state
* @param __HANDLE__: specifies the CRYP Handle.
* @retval None
*/
#define __HAL_CRYP_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_CRYP_STATE_RESET)
/**
* @brief Enable/Disable the CRYP peripheral.
* @param None
* @retval None
*/
#define __HAL_CRYP_ENABLE() (AES->CR |= AES_CR_EN)
#define __HAL_CRYP_DISABLE() (AES->CR &= ~AES_CR_EN)
/**
* @brief Set the algorithm mode: AES-ECB, AES-CBC, AES-CTR, DES-ECB, DES-CBC,...
* @param MODE: The algorithm mode.
* @retval None
*/
#define __HAL_CRYP_SET_MODE(MODE) (AES->CR |= (uint32_t)(MODE))
/** @brief Check whether the specified CRYP flag is set or not.
* @param __FLAG__: specifies the flag to check.
* This parameter can be one of the following values:
* @arg AES_FLAG_CCF : Computation Complete Flag
* @arg AES_FLAG_RDERR : Read Error Flag
* @arg AES_FLAG_WRERR : Write Error Flag
* @retval The new state of __FLAG__ (TRUE or FALSE).
*/
#define __HAL_CRYP_GET_FLAG(__FLAG__) ((AES->SR & (__FLAG__)) == (__FLAG__))
/**
* @brief Enable the CRYP interrupt.
* @param __INTERRUPT__: CRYP Interrupt.
* @retval None
*/
#define __HAL_CRYP_ENABLE_IT(__INTERRUPT__) ((AES->CR) |= (__INTERRUPT__))
/**
* @brief Disable the CRYP interrupt.
* @param __INTERRUPT__: CRYP interrupt.
* @retval None
*/
#define __HAL_CRYP_DISABLE_IT(__INTERRUPT__) ((AES->CR) &= ~(__INTERRUPT__))
/* Include CRYP HAL Extension module */
#include "stm32l0xx_hal_cryp_ex.h"
/* Exported functions --------------------------------------------------------*/
/* Initialization/de-initialization functions *********************************/
HAL_StatusTypeDef HAL_CRYP_Init(CRYP_HandleTypeDef *hcryp);
HAL_StatusTypeDef HAL_CRYP_DeInit(CRYP_HandleTypeDef *hcryp);
/* AES encryption/decryption using polling ***********************************/
HAL_StatusTypeDef HAL_CRYP_AESECB_Encrypt(CRYP_HandleTypeDef *hcryp, uint8_t *pPlainData, uint16_t Size, uint8_t *pCypherData, uint32_t Timeout);
HAL_StatusTypeDef HAL_CRYP_AESECB_Decrypt(CRYP_HandleTypeDef *hcryp, uint8_t *pCypherData, uint16_t Size, uint8_t *pPlainData, uint32_t Timeout);
HAL_StatusTypeDef HAL_CRYP_AESCBC_Encrypt(CRYP_HandleTypeDef *hcryp, uint8_t *pPlainData, uint16_t Size, uint8_t *pCypherData, uint32_t Timeout);
HAL_StatusTypeDef HAL_CRYP_AESCBC_Decrypt(CRYP_HandleTypeDef *hcryp, uint8_t *pCypherData, uint16_t Size, uint8_t *pPlainData, uint32_t Timeout);
HAL_StatusTypeDef HAL_CRYP_AESCTR_Encrypt(CRYP_HandleTypeDef *hcryp, uint8_t *pPlainData, uint16_t Size, uint8_t *pCypherData, uint32_t Timeout);
HAL_StatusTypeDef HAL_CRYP_AESCTR_Decrypt(CRYP_HandleTypeDef *hcryp, uint8_t *pCypherData, uint16_t Size, uint8_t *pPlainData, uint32_t Timeout);
/* AES encryption/decryption using interrupt *********************************/
HAL_StatusTypeDef HAL_CRYP_AESECB_Encrypt_IT(CRYP_HandleTypeDef *hcryp, uint8_t *pPlainData, uint16_t Size, uint8_t *pCypherData);
HAL_StatusTypeDef HAL_CRYP_AESCBC_Encrypt_IT(CRYP_HandleTypeDef *hcryp, uint8_t *pPlainData, uint16_t Size, uint8_t *pCypherData);
HAL_StatusTypeDef HAL_CRYP_AESCTR_Encrypt_IT(CRYP_HandleTypeDef *hcryp, uint8_t *pPlainData, uint16_t Size, uint8_t *pCypherData);
HAL_StatusTypeDef HAL_CRYP_AESECB_Decrypt_IT(CRYP_HandleTypeDef *hcryp, uint8_t *pCypherData, uint16_t Size, uint8_t *pPlainData);
HAL_StatusTypeDef HAL_CRYP_AESCTR_Decrypt_IT(CRYP_HandleTypeDef *hcryp, uint8_t *pCypherData, uint16_t Size, uint8_t *pPlainData);
HAL_StatusTypeDef HAL_CRYP_AESCBC_Decrypt_IT(CRYP_HandleTypeDef *hcryp, uint8_t *pCypherData, uint16_t Size, uint8_t *pPlainData);
/* AES encryption/decryption using DMA ***************************************/
HAL_StatusTypeDef HAL_CRYP_AESECB_Encrypt_DMA(CRYP_HandleTypeDef *hcryp, uint8_t *pPlainData, uint16_t Size, uint8_t *pCypherData);
HAL_StatusTypeDef HAL_CRYP_AESECB_Decrypt_DMA(CRYP_HandleTypeDef *hcryp, uint8_t *pCypherData, uint16_t Size, uint8_t *pPlainData);
HAL_StatusTypeDef HAL_CRYP_AESCBC_Encrypt_DMA(CRYP_HandleTypeDef *hcryp, uint8_t *pPlainData, uint16_t Size, uint8_t *pCypherData);
HAL_StatusTypeDef HAL_CRYP_AESCBC_Decrypt_DMA(CRYP_HandleTypeDef *hcryp, uint8_t *pCypherData, uint16_t Size, uint8_t *pPlainData);
HAL_StatusTypeDef HAL_CRYP_AESCTR_Encrypt_DMA(CRYP_HandleTypeDef *hcryp, uint8_t *pPlainData, uint16_t Size, uint8_t *pCypherData);
HAL_StatusTypeDef HAL_CRYP_AESCTR_Decrypt_DMA(CRYP_HandleTypeDef *hcryp, uint8_t *pCypherData, uint16_t Size, uint8_t *pPlainData);
/* Processing functions ********************************************************/
void HAL_CRYP_IRQHandler(CRYP_HandleTypeDef *hcryp);
/* Peripheral State functions **************************************************/
HAL_CRYP_STATETypeDef HAL_CRYP_GetState(CRYP_HandleTypeDef *hcryp);
/* MSP functions *************************************************************/
void HAL_CRYP_MspInit(CRYP_HandleTypeDef *hcryp);
void HAL_CRYP_MspDeInit(CRYP_HandleTypeDef *hcryp);
/* CallBack functions ********************************************************/
void HAL_CRYP_ComputationCpltCallback(CRYP_HandleTypeDef *hcryp);
void HAL_CRYP_InCpltCallback(CRYP_HandleTypeDef *hcryp);
void HAL_CRYP_OutCpltCallback(CRYP_HandleTypeDef *hcryp);
void HAL_CRYP_ErrorCallback(CRYP_HandleTypeDef *hcryp);
/* Aliases for inter STM32 series compatibility */
#define HAL_CRYP_ComputationCpltCallback HAL_CRYPEx_ComputationCpltCallback
#endif /* STM32L051xx && STM32L052xx && STM32L053xx*/
/**
* @}
*/
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif /* __STM32L0xx_HAL_CRYP_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,168 @@
/**
******************************************************************************
* @file stm32l0xx_hal_cryp_ex.c
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief CRYPEx HAL module driver.
*
* This file provides firmware functions to manage the following
* functionalities of the Cryptography (CRYP) extension peripheral:
* + Computation completed callback.
*
@verbatim
==============================================================================
##### How to use this driver #####
==============================================================================
[..]
The CRYP HAL driver can be used as follows:
(#)Initialize the CRYP low level resources by implementing the HAL_CRYP_MspInit():
(##) Enable the CRYP interface clock using __CRYP_CLK_ENABLE()
(##) In case of using interrupts (e.g. HAL_AES_ECB_Encrypt_IT())
(+) Configure the CRYP interrupt priority using HAL_NVIC_SetPriority()
(+) Enable the CRYP IRQ handler using HAL_NVIC_EnableIRQ()
(+) In CRYP IRQ handler, call HAL_CRYP_IRQHandler()
(##) In case of using DMA to control data transfer (e.g. HAL_AES_ECB_Encrypt_DMA())
(+) Enable the DMA1 interface clock using
(++) __DMA1_CLK_ENABLE()
(+) Configure and enable two DMA Channels one for managing data transfer from
memory to peripheral (input channel) and another channel for managing data
transfer from peripheral to memory (output channel)
(+) Associate the initilalized DMA handle to the CRYP DMA handle
using __HAL_LINKDMA()
(+) Configure the priority and enable the NVIC for the transfer complete
interrupt on the two DMA Streams. The output stream should have higher
priority than the input stream.
(++) HAL_NVIC_SetPriority()
(++) HAL_NVIC_EnableIRQ()
(#)Initialize the CRYP HAL using HAL_CRYP_Init(). This function configures mainly:
(##) The data type: 1-bit, 8-bit, 16-bit and 32-bit
(##) The encryption/decryption key.
(##) The initialization vector (counter). It is not used ECB mode.
(#)Three processing (encryption/decryption) functions are available:
(##) Polling mode: encryption and decryption APIs are blocking functions
i.e. they process the data and wait till the processing is finished
e.g. HAL_CRYP_AESCBC_Encrypt()
(##) Interrupt mode: encryption and decryption APIs are not blocking functions
i.e. they process the data under interrupt
e.g. HAL_CRYP_AESCBC_Encrypt_IT()
(##) DMA mode: encryption and decryption APIs are not blocking functions
i.e. the data transfer is ensured by DMA
e.g. HAL_CRYP_AESCBC_Encrypt_DMA()
(#)When the processing function is called at first time after HAL_CRYP_Init()
the CRYP peripheral is initialized and processes the buffer in input.
At second call, the processing function performs an append of the already
processed buffer.
When a new data block is to be processed, call HAL_CRYP_Init() then the
processing function.
(#)Call HAL_CRYP_DeInit() to deinitialize the CRYP peripheral.
@endverbatim
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @defgroup CRYPEx
* @brief CRYP HAL Extended module driver.
* @{
*/
#ifdef HAL_CRYP_MODULE_ENABLED
#if !defined (STM32L051xx) && !defined (STM32L052xx) && !defined (STM32L053xx)
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/** @defgroup CRYPEx_Private_Functions
* @{
*/
/** @defgroup CRYPEX_Group1 Extended features functions
* @brief Extended features functions.
*
@verbatim
===============================================================================
##### Extended features functions #####
===============================================================================
[..] This section provides callback functions:
(+) Computation completed.
@endverbatim
* @{
*/
/**
* @brief Computation completed callbacks.
* @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains
* the configuration information for CRYP module
* @retval None
*/
__weak void HAL_CRYPEx_ComputationCpltCallback(CRYP_HandleTypeDef *hcryp)
{
/* NOTE : This function Should not be modified, when the callback is needed,
the HAL_CRYP_ComputationCpltCallback could be implemented in the user file
*/
}
/**
* @}
*/
/**
* @}
*/
#endif /* STM32L051xx && STM32L052xx && STM32L053xx*/
#endif /* HAL_CRYP_MODULE_ENABLED */
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,82 @@
/**
******************************************************************************
* @file stm32l0xx_hal_cryp_ex.h
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief Header file of CRYPEx HAL module.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32L0xx_HAL_CRYP_EX_H
#define __STM32L0xx_HAL_CRYP_EX_H
#ifdef __cplusplus
extern "C" {
#endif
#if !defined (STM32L051xx) && !defined (STM32L052xx) && !defined (STM32L053xx)
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal_def.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @addtogroup CRYPEx
* @{
*/
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
/* Exported functions --------------------------------------------------------*/
/* CallBack functions ********************************************************/
void HAL_CRYPEx_ComputationCpltCallback(CRYP_HandleTypeDef *hcryp);
#endif /* STM32L051xx && STM32L052xx && STM32L053xx*/
/**
* @}
*/
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif /* __STM32L0xx_HAL_CRYP_EX_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,770 @@
/**
******************************************************************************
* @file stm32l0xx_hal_dac.c
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief DAC HAL module driver.
*
* 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
*
*
@verbatim
==============================================================================
##### DAC Peripheral features #####
==============================================================================
[..]
*** DAC Channels ***
====================
[..]
The device integrates 1 12-bit Digital Analog Converters:
(#) DAC channel1 with DAC_OUT1 (PA4) 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.
[..]
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, TIM6 and TIM21
(DAC_Trigger_T2_TRGO, DAC_Trigger_T6_TRGO...)
(#) 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
sConfig.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 HAL_DAC_NoiseWaveGenerate()
(#) Triangle wave using HAL_DAC_TriangleWaveGenerate()
*** 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
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
HAL_DAC_Start_DMA()
[..]
DMA1 requests are mapped as following:
(#) DAC channel1 : mapped on DMA1 Request9 channel2 which must be
already configured
##### How to use this driver #####
==============================================================================
[..]
(+) DAC APB clock must be enabled to get write access to DAC
registers using HAL_DAC_Init()
(+) Configure DAC_OUTx (DAC_OUT1: PA4) in analog mode.
(+) Configure the DAC channel using HAL_DAC_ConfigChannel() function.
(+) Enable the DAC channel using HAL_DAC_Start() or HAL_DAC_Start_DMA functions
@endverbatim
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @defgroup DAC
* @brief DAC driver modules
* @{
*/
#ifdef HAL_DAC_MODULE_ENABLED
#if !defined (STM32L051xx) && !defined (STM32L061xx)
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
static void DAC_DMAConvCpltCh1(DMA_HandleTypeDef *hdma);
static void DAC_DMAErrorCh1(DMA_HandleTypeDef *hdma);
static void DAC_DMAHalfConvCpltCh1(DMA_HandleTypeDef *hdma);
/* Private functions ---------------------------------------------------------*/
/** @defgroup DAC_Private_Functions
* @{
*/
/** @defgroup DAC_Group1 Initialization and de-initialization functions
* @brief Initialization and Configuration functions
*
@verbatim
==============================================================================
##### Initialization and de-initialization functions #####
==============================================================================
[..] This section provides functions allowing to:
(+) Initialize and configure the DAC.
(+) De-initialize the DAC.
@endverbatim
* @{
*/
/**
* @brief Initializes the DAC peripheral according to the specified parameters
* in the DAC_InitStruct.
* @param hdac: pointer to a DAC_HandleTypeDef structure that contains
* the configuration information for the specified DAC.
* @retval HAL status
*/
HAL_StatusTypeDef HAL_DAC_Init(DAC_HandleTypeDef* hdac)
{
/* Check DAC handle */
if(hdac == NULL)
{
return HAL_ERROR;
}
/* Check the parameters */
assert_param(IS_DAC_ALL_INSTANCE(hdac->Instance));
if(hdac->State == HAL_DAC_STATE_RESET)
{
/* Init the low level hardware */
HAL_DAC_MspInit(hdac);
}
/* Initialize the DAC state*/
hdac->State = HAL_DAC_STATE_BUSY;
/* Set DAC error code to none */
hdac->ErrorCode = HAL_DAC_ERROR_NONE;
/* Initialize the DAC state*/
hdac->State = HAL_DAC_STATE_READY;
/* Return function status */
return HAL_OK;
}
/**
* @brief Deinitializes the DAC peripheral registers to their default reset values.
* @param hdac: pointer to a DAC_HandleTypeDef structure that contains
* the configuration information for the specified DAC.
* @retval HAL status
*/
HAL_StatusTypeDef HAL_DAC_DeInit(DAC_HandleTypeDef* hdac)
{
/* Check DAC handle */
if(hdac == NULL)
{
return HAL_ERROR;
}
/* Check the parameters */
assert_param(IS_DAC_ALL_INSTANCE(hdac->Instance));
/* Change DAC state */
hdac->State = HAL_DAC_STATE_BUSY;
/* DeInit the low level hardware */
HAL_DAC_MspDeInit(hdac);
/* Set DAC error code to none */
hdac->ErrorCode = HAL_DAC_ERROR_NONE;
/* Change DAC state */
hdac->State = HAL_DAC_STATE_RESET;
/* Release Lock */
__HAL_UNLOCK(hdac);
/* Return function status */
return HAL_OK;
}
/**
* @brief Initializes the DAC MSP.
* @param hdac: pointer to a DAC_HandleTypeDef structure that contains
* the configuration information for the specified DAC.
* @retval None
*/
__weak void HAL_DAC_MspInit(DAC_HandleTypeDef* hdac)
{
/* NOTE : This function Should not be modified, when the callback is needed,
the HAL_DAC_MspInit could be implemented in the user file
*/
}
/**
* @brief DeInitializes the DAC MSP.
* @param hdac: pointer to a DAC_HandleTypeDef structure that contains
* the configuration information for the specified DAC.
* @retval None
*/
__weak void HAL_DAC_MspDeInit(DAC_HandleTypeDef* hdac)
{
/* NOTE : This function Should not be modified, when the callback is needed,
the HAL_DAC_MspDeInit could be implemented in the user file
*/
}
/**
* @}
*/
/** @defgroup DAC_Group2 I/O operation functions
* @brief I/O operation functions
*
@verbatim
==============================================================================
##### IO operation functions #####
==============================================================================
[..] This section provides functions allowing to:
(+) Start conversion.
(+) Stop conversion.
(+) Start conversion and enable DMA transfer.
(+) Stop conversion and disable DMA transfer.
(+) Get result of conversion.
@endverbatim
* @{
*/
/**
* @brief Enables DAC and starts conversion of channel.
* @param hdac: pointer to a DAC_HandleTypeDef structure that contains
* the configuration information for the specified DAC.
* @param channel: The selected DAC channel.
* This parameter can be one of the following values:
* @arg DAC_CHANNEL_1: DAC Channel1 selected
* @retval HAL status
*/
HAL_StatusTypeDef HAL_DAC_Start(DAC_HandleTypeDef* hdac, uint32_t channel)
{
/* Check the parameters */
assert_param(IS_DAC_CHANNEL(channel));
/* Process locked */
__HAL_LOCK(hdac);
/* Change DAC state */
hdac->State = HAL_DAC_STATE_BUSY;
/* Enable the Peripharal */
__HAL_DAC_ENABLE(hdac, channel);
/* Check if software trigger enabled */
if(((hdac->Instance->CR & DAC_CR_TEN1) == DAC_CR_TEN1) && ((hdac->Instance->CR & DAC_CR_TSEL1) == DAC_CR_TSEL1))
{
/* Enable the selected DAC software conversion */
hdac->Instance->SWTRIGR |= (uint32_t)DAC_SWTRIGR_SWTRIG1;
}
/* Change DAC state */
hdac->State = HAL_DAC_STATE_READY;
/* Process unlocked */
__HAL_UNLOCK(hdac);
/* Return function status */
return HAL_OK;
}
/**
* @brief Disables DAC and stop conversion of channel.
* @param hdac: pointer to a DAC_HandleTypeDef structure that contains
* the configuration information for the specified DAC.
* @param channel: The selected DAC channel.
* This parameter can be one of the following values:
* @arg DAC_CHANNEL_1: DAC Channel1 selected
* @retval HAL status
*/
HAL_StatusTypeDef HAL_DAC_Stop(DAC_HandleTypeDef* hdac, uint32_t channel)
{
/* Check the parameters */
assert_param(IS_DAC_CHANNEL(channel));
/* Disable the Peripheral */
__HAL_DAC_DISABLE(hdac, channel);
/* Change DAC state */
hdac->State = HAL_DAC_STATE_READY;
/* Return function status */
return HAL_OK;
}
/**
* @brief Enables DAC and starts conversion of channel using DMA.
* @param hdac: pointer to a DAC_HandleTypeDef structure that contains
* the configuration information for the specified DAC.
* @param channel: The selected DAC channel.
* This parameter can be one of the following values:
* @arg DAC_CHANNEL_1: DAC Channel1 selected
* @param pData: The destination peripheral Buffer address.
* @param Length: The length of data to be transferred from memory to DAC peripheral
* @param alignment: Specifies the data alignment for DAC channel.
* 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
* @retval HAL status
*/
HAL_StatusTypeDef HAL_DAC_Start_DMA(DAC_HandleTypeDef* hdac, uint32_t channel, uint32_t* pData, uint32_t Length, uint32_t alignment)
{
uint32_t tmpreg = 0;
/* Check the parameters */
assert_param(IS_DAC_CHANNEL(channel));
assert_param(IS_DAC_ALIGN(alignment));
/* Process locked */
__HAL_LOCK(hdac);
/* Change DAC state */
hdac->State = HAL_DAC_STATE_BUSY;
/* Set the DMA transfer complete callback for channel1 */
hdac->DMA_Handle1->XferCpltCallback = DAC_DMAConvCpltCh1;
/* Set the DMA half transfer complete callback for channel1 */
hdac->DMA_Handle1->XferHalfCpltCallback = DAC_DMAHalfConvCpltCh1;
/* Set the DMA error callback for channel1 */
hdac->DMA_Handle1->XferErrorCallback = DAC_DMAErrorCh1;
/* Enable the selected DAC channel1 DMA request */
hdac->Instance->CR |= DAC_CR_DMAEN1;
/* Case of use of channel 1 */
switch(alignment)
{
case DAC_ALIGN_12B_R:
/* Get DHR12R1 address */
tmpreg = (uint32_t)&hdac->Instance->DHR12R1;
break;
case DAC_ALIGN_12B_L:
/* Get DHR12L1 address */
tmpreg = (uint32_t)&hdac->Instance->DHR12L1;
break;
case DAC_ALIGN_8B_R:
/* Get DHR8R1 address */
tmpreg = (uint32_t)&hdac->Instance->DHR8R1;
break;
default:
break;
}
/* Enable the DMA Channel */
/* Enable the DAC DMA underrun interrupt */
__HAL_DAC_ENABLE_IT(hdac, DAC_IT_DMAUDR1);
HAL_DMA_Start_IT(hdac->DMA_Handle1, (uint32_t)pData, tmpreg, Length);
/* Enable the Peripharal */
__HAL_DAC_ENABLE(hdac, channel);
/* Process Unlocked */
__HAL_UNLOCK(hdac);
/* Return function status */
return HAL_OK;
}
/**
* @brief Disables DAC and stop conversion of channel using DMA.
* @param hdac: pointer to a DAC_HandleTypeDef structure that contains
* the configuration information for the specified DAC.
* @param channel: The selected DAC channel.
* This parameter can be one of the following values:
* @arg DAC_CHANNEL_1: DAC Channel1 selected
* @retval HAL status
*/
HAL_StatusTypeDef HAL_DAC_Stop_DMA(DAC_HandleTypeDef* hdac, uint32_t channel)
{
/* Check the parameters */
assert_param(IS_DAC_CHANNEL(channel));
/* Disable the selected DAC channel DMA request */
hdac->Instance->CR &= ~(DAC_CR_DMAEN1 << channel);
/* Disable the Peripharal */
__HAL_DAC_DISABLE(hdac, channel);
/* Change DAC state */
hdac->State = HAL_DAC_STATE_READY;
/* Return function status */
return HAL_OK;
}
/**
* @brief Returns the last data output value of the selected DAC channel.
* @param hdac: pointer to a DAC_HandleTypeDef structure that contains
* the configuration information for the specified DAC.
* @param channel: The selected DAC channel.
* This parameter can be one of the following values:
* @arg DAC_CHANNEL_1: DAC Channel1 selected
* @retval The selected DAC channel data output value.
*/
uint32_t HAL_DAC_GetValue(DAC_HandleTypeDef* hdac, uint32_t channel)
{
/* Check the parameters */
assert_param(IS_DAC_CHANNEL(channel));
/* Returns the DAC channel data output register value */
return hdac->Instance->DOR1;
}
/**
* @}
*/
/** @defgroup DAC_Group3 Peripheral Control functions
* @brief Peripheral Control functions
*
@verbatim
==============================================================================
##### Peripheral Control functions #####
==============================================================================
[..] This section provides functions allowing to:
(+) Configure channels.
(+) Set the specified data holding register value for DAC channel.
(+) Set the specified data holding register value for Dual DAC channels.
@endverbatim
* @{
*/
/**
* @brief Configures the selected DAC channel.
* @param hdac: pointer to a DAC_HandleTypeDef structure that contains
* the configuration information for the specified DAC.
* @param sConfig: DAC configuration structure.
* @param channel: The selected DAC channel.
* This parameter can be one of the following values:
* @arg DAC_CHANNEL_1: DAC Channel1 selected
* @retval HAL status
*/
HAL_StatusTypeDef HAL_DAC_ConfigChannel(DAC_HandleTypeDef* hdac, DAC_ChannelConfTypeDef* sConfig, uint32_t channel)
{
uint32_t tmpreg1 = 0, tmpreg2 = 0;
/* Check the DAC parameters */
assert_param(IS_DAC_TRIGGER(sConfig->DAC_Trigger));
assert_param(IS_DAC_OUTPUT_BUFFER_STATE(sConfig->DAC_OutputBuffer));
assert_param(IS_DAC_TRIGGER(sConfig->DAC_Trigger));
/* Process locked */
__HAL_LOCK(hdac);
/* Change DAC state */
hdac->State = HAL_DAC_STATE_BUSY;
/* Get the DAC CR value */
tmpreg1 = DAC->CR;
/* Clear BOFFx, TENx, TSELx, WAVEx and MAMPx bits */
tmpreg1 &= ~(((uint32_t)(DAC_CR_MAMP1 | DAC_CR_WAVE1 | DAC_CR_TSEL1 | DAC_CR_TEN1 | DAC_CR_BOFF1)) << channel);
/* Configure for the selected DAC channel: buffer output, trigger */
/* Set TSELx and TENx bits according to DAC_Trigger value */
/* Set BOFFx bit according to DAC_OutputBuffer value */
tmpreg2 = (sConfig->DAC_Trigger | sConfig->DAC_OutputBuffer);
/* Calculate CR register value depending on DAC_Channel */
tmpreg1 |= tmpreg2 << channel;
/* Write to DAC CR */
DAC->CR = tmpreg1;
/* Disable wave generation */
DAC->CR &= ~(DAC_CR_WAVE1 << channel);
/* Change DAC state */
hdac->State = HAL_DAC_STATE_READY;
/* Process unlocked */
__HAL_UNLOCK(hdac);
/* Return function status */
return HAL_OK;
}
/**
* @brief Set the specified data holding register value for DAC channel.
* @param hdac: pointer to a DAC_HandleTypeDef structure that contains
* the configuration information for the specified DAC.
* @param alignment: 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 HAL status
*/
HAL_StatusTypeDef HAL_DAC_SetValue(DAC_HandleTypeDef* hdac, uint32_t channel, uint32_t alignment, uint32_t data)
{
__IO uint32_t tmp = 0;
/* Check the parameters */
assert_param(IS_DAC_CHANNEL(channel));
assert_param(IS_DAC_ALIGN(alignment));
assert_param(IS_DAC_DATA(data));
tmp = (uint32_t)DAC_BASE;
tmp += __HAL_DHR12R1_ALIGNEMENT(alignment);
/* Set the DAC channel1 selected data holding register */
*(__IO uint32_t *) tmp = data;
/* Return function status */
return HAL_OK;
}
/**
* @}
*/
/** @defgroup DAC_Group4 DAC Peripheral State functions
* @brief DAC Peripheral State functions
*
@verbatim
==============================================================================
##### DAC Peripheral State functions #####
==============================================================================
[..]
This subsection provides functions allowing to
(+) Check the DAC state.
@endverbatim
* @{
*/
/**
* @brief return the DAC state
* @param hdac: pointer to a DAC_HandleTypeDef structure that contains
* the configuration information for the specified DAC.
* @retval HAL state
*/
HAL_DAC_StateTypeDef HAL_DAC_GetState(DAC_HandleTypeDef* hdac)
{
/* Return DAC state */
return hdac->State;
}
/**
* @brief Handles DAC interrupt request
* @param hdac: pointer to a DAC_HandleTypeDef structure that contains
* the configuration information for the specified DAC.
* @retval None
*/
void HAL_DAC_IRQHandler(DAC_HandleTypeDef* hdac)
{
/* Check Overrun flag */
if(__HAL_DAC_GET_FLAG(hdac, DAC_FLAG_DMAUDR1))
{
/* Change DAC state to error state */
hdac->State = HAL_DAC_STATE_ERROR;
/* Set DAC error code to chanel1 DMA underrun error */
hdac->ErrorCode |= HAL_DAC_ERROR_DMAUNDERRUNCH1;
/* Clear the underrun flag */
__HAL_DAC_CLEAR_FLAG(hdac,DAC_FLAG_DMAUDR1);
/* Disable the selected DAC channel1 DMA request */
hdac->Instance->CR &= ~DAC_CR_DMAEN1;
/* Error callback */
HAL_DAC_DMAUnderrunCallbackCh1(hdac);
}
}
/**
* @brief Return the DAC error code
* @param hdac: pointer to a DAC_HandleTypeDef structure that contains
* the configuration information for the specified DAC.
* @retval DAC Error Code
*/
uint32_t HAL_DAC_GetError(DAC_HandleTypeDef *hdac)
{
return hdac->ErrorCode;
}
/**
* @}
*/
/**
* @brief Conversion complete callback in non blocking mode for Channel1
* @param hdac: pointer to a DAC_HandleTypeDef structure that contains
* the configuration information for the specified DAC.
* @retval None
*/
__weak void HAL_DAC_ConvCpltCallbackCh1(DAC_HandleTypeDef* hdac)
{
/* NOTE : This function Should not be modified, when the callback is needed,
the HAL_DAC_ConvCpltCallback could be implemented in the user file
*/
}
/**
* @brief Conversion half DMA transfer callback in non blocking mode for Channel1
* @param hdac: pointer to a DAC_HandleTypeDef structure that contains
* the configuration information for the specified DAC.
* @retval None
*/
__weak void HAL_DAC_ConvHalfCpltCallbackCh1(DAC_HandleTypeDef* hdac)
{
/* NOTE : This function Should not be modified, when the callback is needed,
the HAL_DAC_ConvHalfCpltCallbackCh1 could be implemented in the user file
*/
}
/**
* @brief Error DAC callback for Channel1.
* @param hdac: pointer to a DAC_HandleTypeDef structure that contains
* the configuration information for the specified DAC.
* @retval None
*/
__weak void HAL_DAC_ErrorCallbackCh1(DAC_HandleTypeDef *hdac)
{
/* NOTE : This function Should not be modified, when the callback is needed,
the HAL_DAC_ErrorCallback could be implemented in the user file
*/
}
/**
* @brief DMA underrun DAC callback for channel1.
* @param hdac: pointer to a DAC_HandleTypeDef structure that contains
* the configuration information for the specified DAC.
* @retval None
*/
__weak void HAL_DAC_DMAUnderrunCallbackCh1(DAC_HandleTypeDef *hdac)
{
/* NOTE : This function Should not be modified, when the callback is needed,
the HAL_DAC_DMAUnderrunCallbackCh1 could be implemented in the user file
*/
}
/**
* @brief DMA conversion complete callback.
* @param hdma: pointer to DMA handle.
* @retval None
*/
static void DAC_DMAConvCpltCh1(DMA_HandleTypeDef *hdma)
{
DAC_HandleTypeDef* hdac = ( DAC_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent;
HAL_DAC_ConvCpltCallbackCh1(hdac);
hdac->State= HAL_DAC_STATE_READY;
}
/**
* @brief DMA half transfer complete callback.
* @param hdma: pointer to DMA handle.
* @retval None
*/
static void DAC_DMAHalfConvCpltCh1(DMA_HandleTypeDef *hdma)
{
DAC_HandleTypeDef* hdac = ( DAC_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent;
/* Conversion complete callback */
HAL_DAC_ConvHalfCpltCallbackCh1(hdac);
}
/**
* @brief DMA error callback
* @param hdma: pointer to DMA handle.
* @retval None
*/
static void DAC_DMAErrorCh1(DMA_HandleTypeDef *hdma)
{
DAC_HandleTypeDef* hdac = ( DAC_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent;
/* Set DAC error code to DMA error */
hdac->ErrorCode |= HAL_DAC_ERROR_DMA;
HAL_DAC_ErrorCallbackCh1(hdac);
hdac->State= HAL_DAC_STATE_READY;
}
/**
* @}
*/
#endif /* STM32L051xx && STM32L061xx*/
#endif /* HAL_DAC_MODULE_ENABLED */
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,283 @@
/**
******************************************************************************
* @file stm32l0xx_hal_dac.h
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief Header file of DAC HAL module.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32L0xx_HAL_DAC_H
#define __STM32L0xx_HAL_DAC_H
#ifdef __cplusplus
extern "C" {
#endif
#if !defined (STM32L051xx) && !defined (STM32L061xx)
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal_def.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @addtogroup DAC
* @{
*/
/* Exported types ------------------------------------------------------------*/
/**
* @brief HAL State structures definition
*/
typedef enum
{
HAL_DAC_STATE_RESET = 0x00, /*!< DAC not yet initialized or disabled */
HAL_DAC_STATE_READY = 0x01, /*!< DAC initialized and ready for use */
HAL_DAC_STATE_BUSY = 0x02, /*!< DAC internal processing is ongoing */
HAL_DAC_STATE_TIMEOUT = 0x03, /*!< DAC timeout state */
HAL_DAC_STATE_ERROR = 0x04 /*!< DAC error state */
}HAL_DAC_StateTypeDef;
/**
* @brief DAC handle Structure definition
*/
typedef struct
{
DAC_TypeDef *Instance; /*!< Register base address */
__IO HAL_DAC_StateTypeDef State; /*!< DAC communication state */
HAL_LockTypeDef Lock; /*!< DAC locking object */
DMA_HandleTypeDef *DMA_Handle1; /*!< Pointer DMA handler for channel 1 */
__IO uint32_t ErrorCode; /*!< DAC Error code */
}DAC_HandleTypeDef;
/**
* @brief DAC Configuration regular Channel structure definition
*/
typedef struct
{
uint32_t DAC_Trigger; /*!< Specifies the external trigger for the selected DAC channel.
This parameter can be a value of @ref DAC_trigger_selection */
uint32_t DAC_OutputBuffer; /*!< Specifies whether the DAC channel output buffer is enabled or disabled.
This parameter can be a value of @ref DAC_output_buffer */
}DAC_ChannelConfTypeDef;
/* Exported constants --------------------------------------------------------*/
/** @defgroup HAL DAC Error Code
* @{
*/
#define HAL_DAC_ERROR_NONE 0x00 /*!< No error */
#define HAL_DAC_ERROR_DMAUNDERRUNCH1 0x01 /*!< DAC channel1 DMA underrun error */
#define HAL_DAC_ERROR_DMA 0x04 /*!< DMA error */
/**
* @}
*/
/** @defgroup DAC_trigger_selection
* @{
*/
#define DAC_TRIGGER_NONE ((uint32_t)0x00000000) /*!< Conversion is automatic once the DAC1_DHRxxxx register
has been loaded, and not by external trigger */
#define DAC_TRIGGER_T6_TRGO ((uint32_t)DAC_CR_TEN1) /*!< TIM6 TRGO selected as external conversion trigger for DAC channel */
#define DAC_TRIGGER_T21_TRGO ((uint32_t)(DAC_CR_TSEL1_1 | DAC_CR_TSEL1_0 | DAC_CR_TEN1)) /*!< TIM21 TRGO selected as external conversion trigger for DAC channel */
#define DAC_TRIGGER_T2_TRGO ((uint32_t)(DAC_CR_TSEL1_2 | DAC_CR_TEN1)) /*!< TIM2 TRGO selected as external conversion trigger for DAC channel */
#define DAC_TRIGGER_EXT_IT9 ((uint32_t)(DAC_CR_TSEL1_2 | DAC_CR_TSEL1_1 | DAC_CR_TEN1)) /*!< EXTI Line9 event selected as external conversion trigger for DAC channel */
#define DAC_TRIGGER_SOFTWARE ((uint32_t)(DAC_CR_TSEL1 | DAC_CR_TEN1)) /*!< Conversion started by software trigger for DAC channel */
#define IS_DAC_TRIGGER(TRIGGER) (((TRIGGER) == DAC_TRIGGER_NONE) || \
((TRIGGER) == DAC_TRIGGER_T6_TRGO) || \
((TRIGGER) == DAC_TRIGGER_T21_TRGO) || \
((TRIGGER) == DAC_TRIGGER_T2_TRGO) || \
((TRIGGER) == DAC_TRIGGER_EXT_IT9) || \
((TRIGGER) == DAC_TRIGGER_SOFTWARE))
/**
* @}
*/
/** @defgroup DAC_output_buffer
* @{
*/
#define DAC_OUTPUTBUFFER_ENABLE ((uint32_t)0x00000000)
#define DAC_OUTPUTBUFFER_DISABLE ((uint32_t)DAC_CR_BOFF1)
#define IS_DAC_OUTPUT_BUFFER_STATE(STATE) (((STATE) == DAC_OUTPUTBUFFER_ENABLE) || \
((STATE) == DAC_OUTPUTBUFFER_DISABLE))
/**
* @}
*/
/** @defgroup DAC_Channel_selection
* @{
*/
#define DAC_CHANNEL_1 ((uint32_t)0x00000000)
#define IS_DAC_CHANNEL(CHANNEL) ((CHANNEL) == DAC_CHANNEL_1)
/**
* @}
*/
/** @defgroup DAC_data_alignement
* @{
*/
#define DAC_ALIGN_12B_R ((uint32_t)0x00000000)
#define DAC_ALIGN_12B_L ((uint32_t)0x00000004)
#define DAC_ALIGN_8B_R ((uint32_t)0x00000008)
#define IS_DAC_ALIGN(ALIGN) (((ALIGN) == DAC_ALIGN_12B_R) || \
((ALIGN) == DAC_ALIGN_12B_L) || \
((ALIGN) == DAC_ALIGN_8B_R))
/**
* @}
*/
/** @defgroup DAC_data
* @{
*/
#define IS_DAC_DATA(DATA) ((DATA) <= 0xFFF0)
/**
* @}
*/
/** @defgroup DAC_flags_definition
* @{
*/
#define DAC_FLAG_DMAUDR1 ((uint32_t)DAC_SR_DMAUDR1)
#define IS_DAC_FLAG(FLAG) ((FLAG) == DAC_FLAG_DMAUDR1)
/**
* @}
*/
/** @defgroup DAC_flags_definition
* @{
*/
#define DAC_IT_DMAUDR1 ((uint32_t)DAC_CR_DMAUDRIE1)
#define IS_DAC_IT(IT) ((IT) == DAC_IT_DMAUDR1)
/**
* @}
*/
/* Exported macro ------------------------------------------------------------*/
/** @brief Reset DAC handle state
* @param __HANDLE__: specifies the DAC Handle.
* @retval None
*/
#define __HAL_DAC_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_DAC_STATE_RESET)
/* Enable the DAC peripheral */
#define __HAL_DAC_ENABLE(__HANDLE__, __DAC_Channel__) \
((__HANDLE__)->Instance->CR |= (DAC_CR_EN1 << (__DAC_Channel__)))
/* Disable the DAC peripheral */
#define __HAL_DAC_DISABLE(__HANDLE__, __DAC_Channel__) \
((__HANDLE__)->Instance->CR &= ~(DAC_CR_EN1 << (__DAC_Channel__)))
/* Set DHR12R1 alignment */
#define __HAL_DHR12R1_ALIGNEMENT(__ALIGNEMENT__) (((uint32_t)0x00000008) + (__ALIGNEMENT__))
/* Enable the DAC interrupt */
#define __HAL_DAC_ENABLE_IT(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->CR) |= (__INTERRUPT__))
/* Disable the DAC interrupt */
#define __HAL_DAC_DISABLE_IT(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->CR) &= ~(__INTERRUPT__))
/* Get the selected DAC's flag status */
#define __HAL_DAC_GET_FLAG(__HANDLE__, __FLAG__) ((((__HANDLE__)->Instance->SR) & (__FLAG__)) == (__FLAG__))
/* Clear the DAC's flag */
#define __HAL_DAC_CLEAR_FLAG(__HANDLE__, __FLAG__) (((__HANDLE__)->Instance->SR) = (__FLAG__))
/* Include DAC HAL Extension module */
#include "stm32l0xx_hal_dac_ex.h"
/* Exported functions --------------------------------------------------------*/
/* Initialization and de-initialization functions *****************************/
HAL_StatusTypeDef HAL_DAC_Init(DAC_HandleTypeDef* hdac);
HAL_StatusTypeDef HAL_DAC_DeInit(DAC_HandleTypeDef* hdac);
void HAL_DAC_MspInit(DAC_HandleTypeDef* hdac);
void HAL_DAC_MspDeInit(DAC_HandleTypeDef* hdac);
/* I/O operation functions ******************************************************/
HAL_StatusTypeDef HAL_DAC_Start(DAC_HandleTypeDef* hdac, uint32_t channel);
HAL_StatusTypeDef HAL_DAC_Stop(DAC_HandleTypeDef* hdac, uint32_t channel);
HAL_StatusTypeDef HAL_DAC_Start_DMA(DAC_HandleTypeDef* hdac, uint32_t channel, uint32_t* pData, uint32_t Length, uint32_t alignment);
HAL_StatusTypeDef HAL_DAC_Stop_DMA(DAC_HandleTypeDef* hdac, uint32_t channel);
uint32_t HAL_DAC_GetValue(DAC_HandleTypeDef* hdac, uint32_t channel);
/* Peripheral Control functions ***********************************************/
HAL_StatusTypeDef HAL_DAC_ConfigChannel(DAC_HandleTypeDef* hdac, DAC_ChannelConfTypeDef* sConfig, uint32_t channel);
HAL_StatusTypeDef HAL_DAC_SetValue(DAC_HandleTypeDef* hdac, uint32_t channel, uint32_t alignment, uint32_t data);
/* Peripheral State and Error functions ***************************************/
HAL_DAC_StateTypeDef HAL_DAC_GetState(DAC_HandleTypeDef* hdac);
void HAL_DAC_IRQHandler(DAC_HandleTypeDef* hdac);
uint32_t HAL_DAC_GetError(DAC_HandleTypeDef *hdac);
void HAL_DAC_ConvCpltCallbackCh1(DAC_HandleTypeDef* hdac);
void HAL_DAC_ConvHalfCpltCallbackCh1(DAC_HandleTypeDef* hdac);
void HAL_DAC_ErrorCallbackCh1(DAC_HandleTypeDef *hdac);
void HAL_DAC_DMAUnderrunCallbackCh1(DAC_HandleTypeDef *hdac);
#endif /* STM32L051xx && STM32L061xx*/
/**
* @}
*/
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif /*__STM32L0xx_HAL_DAC_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,202 @@
/**
******************************************************************************
* @file stm32l0xx_hal_dac_ex.c
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief DAC HAL module driver.
*
* This file provides firmware functions to manage the following
* functionalities of the Digital to Analog Converter (DAC) peripheral:
* + DAC wave generation
*
@verbatim
@endverbatim
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @defgroup DACEx
* @brief DAC driver modules
* @{
*/
#ifdef HAL_DAC_MODULE_ENABLED
#if !defined (STM32L051xx) && !defined (STM32L061xx)
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/** @defgroup DACEx_Private_Functions
* @{
*/
/** @defgroup DACEx_Group Peripheral Control functions
* @brief Peripheral Control functions
*
@verbatim
==============================================================================
##### Peripheral Control functions #####
==============================================================================
[..] This section provides functions allowing to:
(+) Configure Triangle wave generation.
(+) Configure Noise wave generation.
@endverbatim
* @{
*/
/**
* @brief Enables or disables the selected DAC channel wave triangle generation.
* @param hdac: pointer to a DAC_HandleTypeDef structure that contains
* the configuration information for the specified DAC.
* @param channel: The selected DAC channel.
* This parameter can be one of the following values:
* @arg DAC_CHANNEL_1: DAC Channel1 selected
* @param Amplitude: Select max triangle amplitude.
* This parameter can be one of the following values:
* @arg DAC_TRIANGLEAMPLITUDE_1: Select max triangle amplitude of 1
* @arg DAC_TRIANGLEAMPLITUDE_3: Select max triangle amplitude of 3
* @arg DAC_TRIANGLEAMPLITUDE_7: Select max triangle amplitude of 7
* @arg DAC_TRIANGLEAMPLITUDE_15: Select max triangle amplitude of 15
* @arg DAC_TRIANGLEAMPLITUDE_31: Select max triangle amplitude of 31
* @arg DAC_TRIANGLEAMPLITUDE_63: Select max triangle amplitude of 63
* @arg DAC_TRIANGLEAMPLITUDE_127: Select max triangle amplitude of 127
* @arg DAC_TRIANGLEAMPLITUDE_255: Select max triangle amplitude of 255
* @arg DAC_TRIANGLEAMPLITUDE_511: Select max triangle amplitude of 511
* @arg DAC_TRIANGLEAMPLITUDE_1023: Select max triangle amplitude of 1023
* @arg DAC_TRIANGLEAMPLITUDE_2047: Select max triangle amplitude of 2047
* @arg DAC_TRIANGLEAMPLITUDE_4095: Select max triangle amplitude of 4095
* @retval HAL status
*/
HAL_StatusTypeDef HAL_DACEx_TriangleWaveGenerate(DAC_HandleTypeDef* hdac, uint32_t channel, uint32_t Amplitude)
{
/* Check the parameters */
assert_param(IS_DAC_CHANNEL(channel));
assert_param(IS_DAC_LFSR_UNMASK_TRIANGLE_AMPLITUDE(Amplitude));
/* Process locked */
__HAL_LOCK(hdac);
/* Change DAC state */
hdac->State = HAL_DAC_STATE_BUSY;
/* Enable the selected wave generation for the selected DAC channel */
hdac->Instance->CR |= (DAC_WAVEGENERATION_TRIANGLE | Amplitude) << channel;
/* Change DAC state */
hdac->State = HAL_DAC_STATE_READY;
/* Process unlocked */
__HAL_UNLOCK(hdac);
/* Return function status */
return HAL_OK;
}
/**
* @brief Enables or disables the selected DAC channel wave noise generation.
* @param channel: The selected DAC channel.
* This parameter can be one of the following values:
* @arg DAC_CHANNEL_1: DAC Channel1 selected
* @param Amplitude: Unmask DAC channel LFSR for noise wave generation.
* This parameter can be one of the following values:
* @arg DAC_LFSRUNMASK_BIT0: Unmask DAC channel LFSR bit0 for noise wave generation
* @arg DAC_LFSRUNMASK_BITS1_0: Unmask DAC channel LFSR bit[1:0] for noise wave generation
* @arg DAC_LFSRUNMASK_BITS2_0: Unmask DAC channel LFSR bit[2:0] for noise wave generation
* @arg DAC_LFSRUNMASK_BITS3_0: Unmask DAC channel LFSR bit[3:0] for noise wave generation
* @arg DAC_LFSRUNMASK_BITS4_0: Unmask DAC channel LFSR bit[4:0] for noise wave generation
* @arg DAC_LFSRUNMASK_BITS5_0: Unmask DAC channel LFSR bit[5:0] for noise wave generation
* @arg DAC_LFSRUNMASK_BITS6_0: Unmask DAC channel LFSR bit[6:0] for noise wave generation
* @arg DAC_LFSRUNMASK_BITS7_0: Unmask DAC channel LFSR bit[7:0] for noise wave generation
* @arg DAC_LFSRUNMASK_BITS8_0: Unmask DAC channel LFSR bit[8:0] for noise wave generation
* @arg DAC_LFSRUNMASK_BITS9_0: Unmask DAC channel LFSR bit[9:0] for noise wave generation
* @arg DAC_LFSRUNMASK_BITS10_0: Unmask DAC channel LFSR bit[10:0] for noise wave generation
* @arg DAC_LFSRUNMASK_BITS11_0: Unmask DAC channel LFSR bit[11:0] for noise wave generation
* @retval HAL status
*/
HAL_StatusTypeDef HAL_DACEx_NoiseWaveGenerate(DAC_HandleTypeDef* hdac, uint32_t channel, uint32_t Amplitude)
{
/* Check the parameters */
assert_param(IS_DAC_CHANNEL(channel));
assert_param(IS_DAC_LFSR_UNMASK_TRIANGLE_AMPLITUDE(Amplitude));
/* Process locked */
__HAL_LOCK(hdac);
/* Change DAC state */
hdac->State = HAL_DAC_STATE_BUSY;
/* Enable the selected wave generation for the selected DAC channel */
hdac->Instance->CR |= (DAC_WAVEGENERATION_NOISE | Amplitude) << channel;
/* Change DAC state */
hdac->State = HAL_DAC_STATE_READY;
/* Process unlocked */
__HAL_UNLOCK(hdac);
/* Return function status */
return HAL_OK;
}
/**
* @}
*/
/**
* @}
*/
#endif /* STM32L051xx && STM32L061xx*/
#endif /* HAL_DAC_MODULE_ENABLED */
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,160 @@
/**
******************************************************************************
* @file stm32l0xx_hal_dac_ex.h
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief Header file of DAC HAL module.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32L0xx_HAL_DAC_EX_H
#define __STM32L0xx_HAL_DAC_EX_H
#ifdef __cplusplus
extern "C" {
#endif
#if !defined (STM32L051xx) && !defined (STM32L061xx)
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal_def.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @addtogroup DACEx
* @{
*/
/* Exported types ------------------------------------------------------------*/
/**
* @brief HAL State structures definition
*/
/* Exported constants --------------------------------------------------------*/
/** @defgroup DACEx_wave_generation
* @{
*/
#define DAC_WAVEGENERATION_NONE ((uint32_t)0x00000000)
#define DAC_WAVEGENERATION_NOISE ((uint32_t)DAC_CR_WAVE1_0)
#define DAC_WAVEGENERATION_TRIANGLE ((uint32_t)DAC_CR_WAVE1_1)
#define IS_DAC_GENERATE_WAVE(WAVE) (((WAVE) == DAC_WAVEGENERATION_NONE) || \
((WAVE) == DAC_WAVEGENERATION_NOISE) || \
((WAVE) == DAC_WAVEGENERATION_TRIANGLE))
/**
* @}
*/
/** @defgroup DACEx_lfsrunmask_triangleamplitude
* @{
*/
#define DAC_LFSRUNMASK_BIT0 ((uint32_t)0x00000000) /*!< Unmask DAC channel LFSR bit0 for noise wave generation */
#define DAC_LFSRUNMASK_BITS1_0 ((uint32_t)DAC_CR_MAMP1_0) /*!< Unmask DAC channel LFSR bit[1:0] for noise wave generation */
#define DAC_LFSRUNMASK_BITS2_0 ((uint32_t)DAC_CR_MAMP1_1) /*!< Unmask DAC channel LFSR bit[2:0] for noise wave generation */
#define DAC_LFSRUNMASK_BITS3_0 ((uint32_t)DAC_CR_MAMP1_1 | DAC_CR_MAMP1_0)/*!< Unmask DAC channel LFSR bit[3:0] for noise wave generation */
#define DAC_LFSRUNMASK_BITS4_0 ((uint32_t)DAC_CR_MAMP1_2) /*!< Unmask DAC channel LFSR bit[4:0] for noise wave generation */
#define DAC_LFSRUNMASK_BITS5_0 ((uint32_t)DAC_CR_MAMP1_2 | DAC_CR_MAMP1_0) /*!< Unmask DAC channel LFSR bit[5:0] for noise wave generation */
#define DAC_LFSRUNMASK_BITS6_0 ((uint32_t)DAC_CR_MAMP1_2 | DAC_CR_MAMP1_1) /*!< Unmask DAC channel LFSR bit[6:0] for noise wave generation */
#define DAC_LFSRUNMASK_BITS7_0 ((uint32_t)DAC_CR_MAMP1_2 | DAC_CR_MAMP1_1 | DAC_CR_MAMP1_0) /*!< Unmask DAC channel LFSR bit[7:0] for noise wave generation */
#define DAC_LFSRUNMASK_BITS8_0 ((uint32_t)DAC_CR_MAMP1_3) /*!< Unmask DAC channel LFSR bit[8:0] for noise wave generation */
#define DAC_LFSRUNMASK_BITS9_0 ((uint32_t)DAC_CR_MAMP1_3 | DAC_CR_MAMP1_0) /*!< Unmask DAC channel LFSR bit[9:0] for noise wave generation */
#define DAC_LFSRUNMASK_BITS10_0 ((uint32_t)DAC_CR_MAMP1_3 | DAC_CR_MAMP1_1) /*!< Unmask DAC channel LFSR bit[10:0] for noise wave generation */
#define DAC_LFSRUNMASK_BITS11_0 ((uint32_t)DAC_CR_MAMP1_3 | DAC_CR_MAMP1_1 | DAC_CR_MAMP1_0) /*!< Unmask DAC channel LFSR bit[11:0] for noise wave generation */
#define DAC_TRIANGLEAMPLITUDE_1 ((uint32_t)0x00000000) /*!< Select max triangle amplitude of 1 */
#define DAC_TRIANGLEAMPLITUDE_3 ((uint32_t)DAC_CR_MAMP1_0) /*!< Select max triangle amplitude of 3 */
#define DAC_TRIANGLEAMPLITUDE_7 ((uint32_t)DAC_CR_MAMP1_1) /*!< Select max triangle amplitude of 7 */
#define DAC_TRIANGLEAMPLITUDE_15 ((uint32_t)DAC_CR_MAMP1_1 | DAC_CR_MAMP1_0) /*!< Select max triangle amplitude of 15 */
#define DAC_TRIANGLEAMPLITUDE_31 ((uint32_t)DAC_CR_MAMP1_2) /*!< Select max triangle amplitude of 31 */
#define DAC_TRIANGLEAMPLITUDE_63 ((uint32_t)DAC_CR_MAMP1_2 | DAC_CR_MAMP1_0) /*!< Select max triangle amplitude of 63 */
#define DAC_TRIANGLEAMPLITUDE_127 ((uint32_t)DAC_CR_MAMP1_2 | DAC_CR_MAMP1_1) /*!< Select max triangle amplitude of 127 */
#define DAC_TRIANGLEAMPLITUDE_255 ((uint32_t)DAC_CR_MAMP1_2 | DAC_CR_MAMP1_1 | DAC_CR_MAMP1_0) /*!< Select max triangle amplitude of 255 */
#define DAC_TRIANGLEAMPLITUDE_511 ((uint32_t)DAC_CR_MAMP1_3) /*!< Select max triangle amplitude of 511 */
#define DAC_TRIANGLEAMPLITUDE_1023 ((uint32_t)DAC_CR_MAMP1_3 | DAC_CR_MAMP1_0) /*!< Select max triangle amplitude of 1023 */
#define DAC_TRIANGLEAMPLITUDE_2047 ((uint32_t)DAC_CR_MAMP1_3 | DAC_CR_MAMP1_1) /*!< Select max triangle amplitude of 2047 */
#define DAC_TRIANGLEAMPLITUDE_4095 ((uint32_t)DAC_CR_MAMP1_3 | DAC_CR_MAMP1_1 | DAC_CR_MAMP1_0) /*!< Select max triangle amplitude of 4095 */
#define IS_DAC_LFSR_UNMASK_TRIANGLE_AMPLITUDE(VALUE) (((VALUE) == DAC_LFSRUNMASK_BIT0) || \
((VALUE) == DAC_LFSRUNMASK_BITS1_0) || \
((VALUE) == DAC_LFSRUNMASK_BITS2_0) || \
((VALUE) == DAC_LFSRUNMASK_BITS3_0) || \
((VALUE) == DAC_LFSRUNMASK_BITS4_0) || \
((VALUE) == DAC_LFSRUNMASK_BITS5_0) || \
((VALUE) == DAC_LFSRUNMASK_BITS6_0) || \
((VALUE) == DAC_LFSRUNMASK_BITS7_0) || \
((VALUE) == DAC_LFSRUNMASK_BITS8_0) || \
((VALUE) == DAC_LFSRUNMASK_BITS9_0) || \
((VALUE) == DAC_LFSRUNMASK_BITS10_0) || \
((VALUE) == DAC_LFSRUNMASK_BITS11_0) || \
((VALUE) == DAC_TRIANGLEAMPLITUDE_1) || \
((VALUE) == DAC_TRIANGLEAMPLITUDE_3) || \
((VALUE) == DAC_TRIANGLEAMPLITUDE_7) || \
((VALUE) == DAC_TRIANGLEAMPLITUDE_15) || \
((VALUE) == DAC_TRIANGLEAMPLITUDE_31) || \
((VALUE) == DAC_TRIANGLEAMPLITUDE_63) || \
((VALUE) == DAC_TRIANGLEAMPLITUDE_127) || \
((VALUE) == DAC_TRIANGLEAMPLITUDE_255) || \
((VALUE) == DAC_TRIANGLEAMPLITUDE_511) || \
((VALUE) == DAC_TRIANGLEAMPLITUDE_1023) || \
((VALUE) == DAC_TRIANGLEAMPLITUDE_2047) || \
((VALUE) == DAC_TRIANGLEAMPLITUDE_4095))
/**
* @}
*/
/* Exported macro ------------------------------------------------------------*/
/* Exported functions --------------------------------------------------------*/
/* Peripheral Control methods *************************************************/
HAL_StatusTypeDef HAL_DACEx_TriangleWaveGenerate(DAC_HandleTypeDef* hdac, uint32_t channel, uint32_t Amplitude);
HAL_StatusTypeDef HAL_DACEx_NoiseWaveGenerate(DAC_HandleTypeDef* hdac, uint32_t channel, uint32_t Amplitude);
#endif /* STM32L051xx && STM32L061xx*/
/**
* @}
*/
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif /*__STM32L0xx_HAL_DAC_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,198 @@
/**
******************************************************************************
* @file stm32l0xx_hal_def.h
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief This file contains HAL common defines, enumeration, macros and
* structures definitions.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32L0xx_HAL_DEF
#define __STM32L0xx_HAL_DEF
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx.h"
/* Exported types ------------------------------------------------------------*/
/**
* @brief HAL Status structures definition
*/
typedef enum
{
HAL_OK = 0x00,
HAL_ERROR = 0x01,
HAL_BUSY = 0x02,
HAL_TIMEOUT = 0x03
} HAL_StatusTypeDef;
/**
* @brief HAL Lock structures definition
*/
typedef enum
{
HAL_UNLOCKED = 0x00,
HAL_LOCKED = 0x01
} HAL_LockTypeDef;
/* Exported macro ------------------------------------------------------------*/
#ifndef NULL
#define NULL (void *) 0
#endif
#define HAL_MAX_DELAY 0xFFFFFFFF
#define HAL_IS_BIT_SET(REG, BIT) (((REG) & (BIT)) != RESET)
#define HAL_IS_BIT_CLR(REG, BIT) (((REG) & (BIT)) == RESET)
#define __HAL_LINKDMA(__HANDLE__, __PPP_DMA_FIELD__, __DMA_HANDLE__) \
do{ \
(__HANDLE__)->__PPP_DMA_FIELD__ = &(__DMA_HANDLE__); \
(__DMA_HANDLE__).Parent = (__HANDLE__); \
} while(0)
/** @brief Reset the Handle's State field.
* @param __HANDLE__: specifies the Peripheral Handle.
* @note This macro can be used for the following purpose:
* - When the Handle is declared as local variable; before passing it as parameter
* to HAL_PPP_Init() for the first time, it is mandatory to use this macro
* to set to 0 the Handle's "State" field.
* Otherwise, "State" field may have any random value and the first time the function
* HAL_PPP_Init() is called, the low level hardware initialization will be missed
* (i.e. HAL_PPP_MspInit() will not be executed).
* - When there is a need to reconfigure the low level hardware: instead of calling
* HAL_PPP_DeInit() then HAL_PPP_Init(), user can make a call to this macro then HAL_PPP_Init().
* In this later function, when the Handle's "State" field is set to 0, it will execute the function
* HAL_PPP_MspInit() which will reconfigure the low level hardware.
* @retval None
*/
#define __HAL_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = 0)
#if (USE_RTOS == 1)
/* Reserved for future use */
#error “USE_RTOS should be 0 in the current HAL release”
#else
#define __HAL_LOCK(__HANDLE__) \
do{ \
if((__HANDLE__)->Lock == HAL_LOCKED) \
{ \
return HAL_BUSY; \
} \
else \
{ \
(__HANDLE__)->Lock = HAL_LOCKED; \
} \
}while (0)
#define __HAL_UNLOCK(__HANDLE__) \
do{ \
(__HANDLE__)->Lock = HAL_UNLOCKED; \
}while (0)
#endif /* USE_RTOS */
#if defined ( __GNUC__ )
#ifndef __weak
#define __weak __attribute__((weak))
#endif /* __weak */
#ifndef __packed
#define __packed __attribute__((__packed__))
#endif /* __packed */
#endif /* __GNUC__ */
/* Macro to get variable aligned on 4-bytes, for __ICCARM__ the directive "#pragma data_alignment=4" must be used instead */
#if defined (__GNUC__) /* GNU Compiler */
#ifndef __ALIGN_END
#define __ALIGN_END __attribute__ ((aligned (4)))
#endif /* __ALIGN_END */
#ifndef __ALIGN_BEGIN
#define __ALIGN_BEGIN
#endif /* __ALIGN_BEGIN */
#else
#ifndef __ALIGN_END
#define __ALIGN_END
#endif /* __ALIGN_END */
#ifndef __ALIGN_BEGIN
#if defined (__CC_ARM) /* ARM Compiler */
#define __ALIGN_BEGIN __align(4)
#elif defined (__ICCARM__) /* IAR Compiler */
#define __ALIGN_BEGIN
#endif /* __CC_ARM */
#endif /* __ALIGN_BEGIN */
#endif /* __GNUC__ */
/**
* @brief __RAM_FUNC definition
*/
#if defined ( __CC_ARM )
/* ARM Compiler
------------
RAM functions are defined using the toolchain options.
Functions that are 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.
*/
#define __RAM_FUNC HAL_StatusTypeDef
#elif defined ( __ICCARM__ )
/* ICCARM Compiler
---------------
RAM functions are defined using a specific toolchain keyword "__ramfunc".
*/
#define __RAM_FUNC __ramfunc HAL_StatusTypeDef
#elif defined ( __GNUC__ )
/* GNU Compiler
------------
RAM functions are defined using a specific toolchain attribute
"__attribute__((section(".RamFunc")))".
*/
#define __RAM_FUNC HAL_StatusTypeDef __attribute__((section(".RamFunc")))
#endif
#ifdef __cplusplus
}
#endif
#endif /* ___STM32L0xx_HAL_DEF */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,751 @@
/**
******************************************************************************
* @file stm32l0xx_hal_dma.c
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief DMA HAL module driver.
*
* This file provides firmware functions to manage the following
* functionalities of the Direct Memory Access (DMA) peripheral:
* + Initialization/de-initialization functions
* + I/O operation functions
* + Peripheral State functions
*
*
@verbatim
==============================================================================
##### How to use this driver #####
==============================================================================
[..]
(#) Enable and configure the peripheral to be connected to the DMA Channel
(except for internal SRAM / FLASH memories: no initialization is
necessary).
(#) For a given Channel, program the required configuration through the following parameters:
Channel request, Transfer Direction, Source and Destination data formats,
Circular, Normal or peripheral flow control mode, Channel Priority level,
Source and Destination Increment mode using HAL_DMA_Init() function.
*** Polling mode IO operation ***
=================================
[..]
(+) Use HAL_DMA_Start() to start DMA transfer after the configuration of Source
address and destination address and the Length of data to be transferred
(+) Use HAL_DMA_PollForTransfer() to poll for the end of current transfer, in this
case a fixed Timeout can be configured by User depending from his application.
*** Interrupt mode IO operation ***
===================================
[..]
(+) Configure the DMA interrupt priority using HAL_NVIC_SetPriority()
(+) Enable the DMA IRQ handler using HAL_NVIC_EnableIRQ()
(+) Use HAL_DMA_Start_IT() to start DMA transfer after the configuration of
Source address and destination address and the Length of data to be transferred. In this
case the DMA interrupt is configured
(+) Use HAL_DMA_IRQHandler() called under DMA_IRQHandler() Interrupt subroutine
(+) At the end of data transfer HAL_DMA_IRQHandler() function is executed and user can
add his own function by customization of function pointer XferCpltCallback and
XferErrorCallback (i.e a member of DMA handle structure).
(#) Use HAL_DMA_GetState() function to return the DMA state and HAL_DMA_GetError() in case of error
detection.
(#) Use HAL_DMA_Abort() function to abort the current transfer
-@- In Memory-to-Memory transfer mode, Circular mode is not allowed.
@endverbatim
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @defgroup DMA
* @brief DMA HAL module driver
* @{
*/
#ifdef HAL_DMA_MODULE_ENABLED
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
#define HAL_TIMEOUT_DMA_ABORT ((uint32_t)1000) /* 1s */
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
static void DMA_SetConfig(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t DataLength);
/* Private functions ---------------------------------------------------------*/
/** @defgroup DMA_Private_Functions
* @{
*/
/** @defgroup DMA_Group1 Initialization/de-initialization functions
* @brief Initialization/de-initialization functions
*
@verbatim
===============================================================================
##### Initialization and de-initialization functions #####
===============================================================================
[..] This section provides functions allowing to:
(+) Initialize and configure the DMA
(+) De-Initialize the DMA
@endverbatim
* @{
*/
/**
* @brief Initializes the DMA according to the specified
* parameters in the DMA_InitTypeDef and create the associated handle.
* @param hdma: Pointer to a DMA_HandleTypeDef structure that contains
* the configuration information for the specified DMA Channel.
* @retval HAL status
*/
HAL_StatusTypeDef HAL_DMA_Init(DMA_HandleTypeDef *hdma)
{
uint32_t tmp = 0;
/* Check the DMA peripheral state */
if(hdma == NULL)
{
return HAL_ERROR;
}
/* Check the parameters */
assert_param(IS_DMA_ALL_PERIPH(hdma->Instance));
assert_param(IS_DMA_ALL_REQUEST(hdma->Init.Request));
assert_param(IS_DMA_DIRECTION(hdma->Init.Direction));
assert_param(IS_DMA_PERIPHERAL_INC_STATE(hdma->Init.PeriphInc));
assert_param(IS_DMA_MEMORY_INC_STATE(hdma->Init.MemInc));
assert_param(IS_DMA_PERIPHERAL_DATA_SIZE(hdma->Init.PeriphDataAlignment));
assert_param(IS_DMA_MEMORY_DATA_SIZE(hdma->Init.MemDataAlignment));
assert_param(IS_DMA_MODE(hdma->Init.Mode));
assert_param(IS_DMA_PRIORITY(hdma->Init.Priority));
/* Change DMA peripheral state */
hdma->State = HAL_DMA_STATE_BUSY;
/* Get the CR register value */
tmp = hdma->Instance->CCR;
/* Clear PL, MSIZE, PSIZE, MINC, PINC, CIRC, DIR bits */
tmp &= ((uint32_t)~(DMA_CCR_PL | DMA_CCR_MSIZE | DMA_CCR_PSIZE | \
DMA_CCR_MINC | DMA_CCR_PINC | DMA_CCR_CIRC | \
DMA_CCR_DIR));
/* Prepare the DMA Channel configuration */
tmp |= hdma->Init.Direction |
hdma->Init.PeriphInc | hdma->Init.MemInc |
hdma->Init.PeriphDataAlignment | hdma->Init.MemDataAlignment |
hdma->Init.Mode | hdma->Init.Priority;
/* Write to DMA Channel CR register */
hdma->Instance->CCR = tmp;
/* Write to DMA channel selection register */
if (hdma->Instance == DMA1_Channel1)
{
/*Reset request selection for DMA1 Channel1*/
DMA1_CSELR->CSELR &= ~DMA_CSELR_C1S;
/* Configure request selection for DMA1 Channel1 */
DMA1_CSELR->CSELR |= hdma->Init.Request;
}
else if (hdma->Instance == DMA1_Channel2)
{
/*Reset request selection for DMA1 Channel2*/
DMA1_CSELR->CSELR &= ~DMA_CSELR_C2S;
/* Configure request selection for DMA1 Channel2 */
DMA1_CSELR->CSELR |= (uint32_t)(hdma->Init.Request << 4);
}
else if (hdma->Instance == DMA1_Channel3)
{
/*Reset request selection for DMA1 Channel3*/
DMA1_CSELR->CSELR &= ~DMA_CSELR_C3S;
/* Configure request selection for DMA1 Channel3 */
DMA1_CSELR->CSELR |= (uint32_t) (hdma->Init.Request << 8);
}
else if (hdma->Instance == DMA1_Channel4)
{
/*Reset request selection for DMA1 Channel4*/
DMA1_CSELR->CSELR &= ~DMA_CSELR_C4S;
/* Configure request selection for DMA1 Channel4 */
DMA1_CSELR->CSELR |= (uint32_t) (hdma->Init.Request << 12);
}
else if (hdma->Instance == DMA1_Channel5)
{
/*Reset request selection for DMA1 Channel5*/
DMA1_CSELR->CSELR &= ~DMA_CSELR_C5S;
/* Configure request selection for DMA1 Channel5 */
DMA1_CSELR->CSELR |= (uint32_t) (hdma->Init.Request << 16);
}
else if (hdma->Instance == DMA1_Channel6)
{
/*Reset request selection for DMA1 Channel6*/
DMA1_CSELR->CSELR &= ~DMA_CSELR_C6S;
/* Configure request selection for DMA1 Channel6 */
DMA1_CSELR->CSELR |= (uint32_t) (hdma->Init.Request << 20);
}
else if (hdma->Instance == DMA1_Channel7)
{
/*Reset request selection for DMA1 Channel7*/
DMA1_CSELR->CSELR &= ~DMA_CSELR_C7S;
/* Configure request selection for DMA1 Channel7 */
DMA1_CSELR->CSELR |= (uint32_t) (hdma->Init.Request << 24);
}
/* Initialize the DMA state*/
hdma->State = HAL_DMA_STATE_READY;
return HAL_OK;
}
/**
* @brief DeInitializes the DMA peripheral
* @param hdma: pointer to a DMA_HandleTypeDef structure that contains
* the configuration information for the specified DMA Channel.
* @retval HAL status
*/
HAL_StatusTypeDef HAL_DMA_DeInit(DMA_HandleTypeDef *hdma)
{
/* Check the DMA peripheral state */
if(hdma == NULL)
{
return HAL_ERROR;
}
/* Check the DMA peripheral state */
if(hdma->State == HAL_DMA_STATE_BUSY)
{
return HAL_ERROR;
}
/* Disable the selected DMA Channelx */
__HAL_DMA_DISABLE(hdma);
/* Reset DMA Channel control register */
hdma->Instance->CCR = 0;
/* Reset DMA Channel Number of Data to Transfer register */
hdma->Instance->CNDTR = 0;
/* Reset DMA Channel peripheral address register */
hdma->Instance->CPAR = 0;
/* Reset DMA Channel memory address register */
hdma->Instance->CMAR = 0;
/* Clear all flags */
__HAL_DMA_CLEAR_FLAG(hdma, __HAL_DMA_GET_GI_FLAG_INDEX(hdma));
__HAL_DMA_CLEAR_FLAG(hdma, __HAL_DMA_GET_TC_FLAG_INDEX(hdma));
__HAL_DMA_CLEAR_FLAG(hdma, __HAL_DMA_GET_TE_FLAG_INDEX(hdma));
__HAL_DMA_CLEAR_FLAG(hdma, __HAL_DMA_GET_HT_FLAG_INDEX(hdma));
/* Reset DMA channel selection register */
if (hdma->Instance == DMA1_Channel1)
{
/*Reset DMA request*/
DMA1_CSELR->CSELR &= ~DMA_CSELR_C1S;
}
else if (hdma->Instance == DMA1_Channel2)
{
/*Reset DMA request*/
DMA1_CSELR->CSELR &= ~DMA_CSELR_C2S;
}
else if (hdma->Instance == DMA1_Channel3)
{
/*Reset DMA request*/
DMA1_CSELR->CSELR &= ~DMA_CSELR_C3S;
}
else if (hdma->Instance == DMA1_Channel4)
{
/*Reset DMA request*/
DMA1_CSELR->CSELR &= ~DMA_CSELR_C4S;
}
else if (hdma->Instance == DMA1_Channel5)
{
/*Reset DMA request*/
DMA1_CSELR->CSELR &= ~DMA_CSELR_C5S;
}
else if (hdma->Instance == DMA1_Channel6)
{
/*Reset DMA request*/
DMA1_CSELR->CSELR &= ~DMA_CSELR_C6S;
}
else if (hdma->Instance == DMA1_Channel7)
{
/*Reset DMA request*/
DMA1_CSELR->CSELR &= ~DMA_CSELR_C7S;
}
/* Initialise the error code */
hdma->ErrorCode = HAL_DMA_ERROR_NONE;
/* Initialize the DMA state */
hdma->State = HAL_DMA_STATE_RESET;
/* Release Lock */
__HAL_UNLOCK(hdma);
return HAL_OK;
}
/**
* @}
*/
/** @defgroup DMA_Group2 I/O operation functions
* @brief I/O operation functions
*
@verbatim
===============================================================================
##### IO operation functions #####
===============================================================================
[..] This section provides functions allowing to:
(+) Configure the source, destination address and data length and Start DMA transfer
(+) Configure the source, destination address and data length and
Start DMA transfer with interrupt
(+) Abort DMA transfer
(+) Poll for transfer complete
(+) Handle DMA interrupt request
@endverbatim
* @{
*/
/**
* @brief Starts the DMA Transfer.
* @param hdma : pointer to a DMA_HandleTypeDef structure that contains
* the configuration information for the specified DMA Channel.
* @param SrcAddress: The source memory Buffer address
* @param DstAddress: The destination memory Buffer address
* @param DataLength: The length of data to be transferred from source to destination
* @retval HAL status
*/
HAL_StatusTypeDef HAL_DMA_Start(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t DataLength)
{
/* Process locked */
__HAL_LOCK(hdma);
/* Change DMA peripheral state */
hdma->State = HAL_DMA_STATE_BUSY;
/* Check the parameters */
assert_param(IS_DMA_BUFFER_SIZE(DataLength));
/* Disable the peripheral */
__HAL_DMA_DISABLE(hdma);
/* Configure the source, destination address and the data length */
DMA_SetConfig(hdma, SrcAddress, DstAddress, DataLength);
/* Enable the Peripheral */
__HAL_DMA_ENABLE(hdma);
return HAL_OK;
}
/**
* @brief Start the DMA Transfer with interrupt enabled.
* @param hdma: pointer to a DMA_HandleTypeDef structure that contains
* the configuration information for the specified DMA Channel.
* @param SrcAddress: The source memory Buffer address
* @param DstAddress: The destination memory Buffer address
* @param DataLength: The length of data to be transferred from source to destination
* @retval HAL status
*/
HAL_StatusTypeDef HAL_DMA_Start_IT(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t DataLength)
{
/* Process locked */
__HAL_LOCK(hdma);
/* Change DMA peripheral state */
hdma->State = HAL_DMA_STATE_BUSY;
/* Check the parameters */
assert_param(IS_DMA_BUFFER_SIZE(DataLength));
/* Disable the peripheral */
__HAL_DMA_DISABLE(hdma);
/* Configure the source, destination address and the data length */
DMA_SetConfig(hdma, SrcAddress, DstAddress, DataLength);
/* Enable the transfer complete interrupt */
__HAL_DMA_ENABLE_IT(hdma, DMA_IT_TC);
/* Enable the Half transfer complete interrupt */
__HAL_DMA_ENABLE_IT(hdma, DMA_IT_HT);
/* Enable the transfer Error interrupt */
__HAL_DMA_ENABLE_IT(hdma, DMA_IT_TE);
/* Enable the Peripheral */
__HAL_DMA_ENABLE(hdma);
return HAL_OK;
}
/**
* @brief Aborts the DMA Transfer.
* @param hdma : pointer to a DMA_HandleTypeDef structure that contains
* the configuration information for the specified DMA Channel.
* @param Timeout: Timeout duration
* @retval HAL status
*/
HAL_StatusTypeDef HAL_DMA_Abort(DMA_HandleTypeDef *hdma)
{
uint32_t tickstart = 0;
/* Disable the channel */
__HAL_DMA_DISABLE(hdma);
/* Get timeout */
tickstart = HAL_GetTick();
/* Check if the DMA Channel is effectively disabled */
while((hdma->Instance->CCR & DMA_CCR_EN) != 0)
{
/* Check for the Timeout */
if( (HAL_GetTick() - tickstart ) > HAL_TIMEOUT_DMA_ABORT)
{
/* Update error code */
hdma->ErrorCode |= HAL_DMA_ERROR_TIMEOUT;
/* Process Unlocked */
__HAL_UNLOCK(hdma);
/* Change the DMA state */
hdma->State = HAL_DMA_STATE_TIMEOUT;
return HAL_TIMEOUT;
}
}
/* Process Unlocked */
__HAL_UNLOCK(hdma);
/* Change the DMA state*/
hdma->State = HAL_DMA_STATE_READY;
return HAL_OK;
}
/**
* @brief Polling for transfer complete.
* @param hdma: pointer to a DMA_HandleTypeDef structure that contains
* the configuration information for the specified DMA Channel.
* @param CompleteLevel: Specifies the DMA level complete.
* @param Timeout: Timeout duration.
* @retval HAL status
*/
HAL_StatusTypeDef HAL_DMA_PollForTransfer(DMA_HandleTypeDef *hdma, uint32_t CompleteLevel, uint32_t Timeout)
{
uint32_t temp;
uint32_t tickstart = 0;
/* Get the level transfer complete flag */
if(CompleteLevel == HAL_DMA_FULL_TRANSFER)
{
/* Transfer Complete flag */
temp = __HAL_DMA_GET_TC_FLAG_INDEX(hdma);
}
else
{
/* Half Transfer Complete flag */
temp = __HAL_DMA_GET_HT_FLAG_INDEX(hdma);
}
/* Get timeout */
tickstart = HAL_GetTick();
while(__HAL_DMA_GET_FLAG(hdma, temp) == RESET)
{
if((__HAL_DMA_GET_FLAG(hdma, __HAL_DMA_GET_TE_FLAG_INDEX(hdma)) != RESET))
{
/* Clear the transfer error flags */
__HAL_DMA_CLEAR_FLAG(hdma, __HAL_DMA_GET_TE_FLAG_INDEX(hdma));
/* Update error code */
SET_BIT(hdma->ErrorCode, HAL_DMA_ERROR_TE);
/* Change the DMA state */
hdma->State= HAL_DMA_STATE_ERROR;
/* Process Unlocked */
__HAL_UNLOCK(hdma);
return HAL_ERROR;
}
/* Check for the Timeout */
if(Timeout != HAL_MAX_DELAY)
{
if((Timeout == 0)||((HAL_GetTick() - tickstart ) > Timeout))
{
/* Update error code */
SET_BIT(hdma->ErrorCode, HAL_DMA_ERROR_TIMEOUT);
/* Change the DMA state */
hdma->State= HAL_DMA_STATE_TIMEOUT;
/* Process Unlocked */
__HAL_UNLOCK(hdma);
return HAL_TIMEOUT;
}
}
}
if(CompleteLevel == HAL_DMA_FULL_TRANSFER)
{
/* Clear the transfer complete flag */
__HAL_DMA_CLEAR_FLAG(hdma, __HAL_DMA_GET_TC_FLAG_INDEX(hdma));
/* The selected Channelx EN bit is cleared (DMA is disabled and
all transfers are complete) */
hdma->State = HAL_DMA_STATE_READY;
/* Process unlocked */
__HAL_UNLOCK(hdma);
}
else
{
/* Clear the half transfer complete flag */
__HAL_DMA_CLEAR_FLAG(hdma, __HAL_DMA_GET_HT_FLAG_INDEX(hdma));
/* The selected Channelx EN bit is cleared (DMA is disabled and
all transfers are complete) */
hdma->State = HAL_DMA_STATE_READY_HALF;
/* Process unlocked */
__HAL_UNLOCK(hdma);
}
return HAL_OK;
}
/**
* @brief Handles DMA interrupt request.
* @param hdma: pointer to a DMA_HandleTypeDef structure that contains
* the configuration information for the specified DMA Channel.
* @retval None
*/
void HAL_DMA_IRQHandler(DMA_HandleTypeDef *hdma)
{
/* Transfer Error Interrupt management ***************************************/
if(__HAL_DMA_GET_FLAG(hdma, __HAL_DMA_GET_TE_FLAG_INDEX(hdma)) != RESET)
{
if(__HAL_DMA_GET_IT_SOURCE(hdma, DMA_IT_TE) != RESET)
{
/* Disable the transfer error interrupt */
__HAL_DMA_DISABLE_IT(hdma, DMA_IT_TE);
/* Clear the transfer error flag */
__HAL_DMA_CLEAR_FLAG(hdma, __HAL_DMA_GET_TE_FLAG_INDEX(hdma));
/* Update error code */
hdma->ErrorCode |= HAL_DMA_ERROR_TE;
/* Change the DMA state */
hdma->State = HAL_DMA_STATE_ERROR;
/* Process Unlocked */
__HAL_UNLOCK(hdma);
if (hdma->XferErrorCallback != NULL)
{
/* Transfer error callback */
hdma->XferErrorCallback(hdma);
}
}
}
/* Half Transfer Complete Interrupt management ******************************/
if(__HAL_DMA_GET_FLAG(hdma, __HAL_DMA_GET_HT_FLAG_INDEX(hdma)) != RESET)
{
if(__HAL_DMA_GET_IT_SOURCE(hdma, DMA_IT_HT) != RESET)
{
/* Disable the half transfer interrupt if the DMA mode is not CIRCULAR */
if((hdma->Instance->CCR & DMA_CCR_CIRC) == 0)
{
/* Disable the half transfer interrupt */
__HAL_DMA_DISABLE_IT(hdma, DMA_IT_HT);
}
/* Clear the half transfer complete flag */
__HAL_DMA_CLEAR_FLAG(hdma, __HAL_DMA_GET_HT_FLAG_INDEX(hdma));
/* Change DMA peripheral state */
hdma->State = HAL_DMA_STATE_READY_HALF;
if(hdma->XferHalfCpltCallback != NULL)
{
/* Half transfer callback */
hdma->XferHalfCpltCallback(hdma);
}
}
}
/* Transfer Complete Interrupt management ***********************************/
if(__HAL_DMA_GET_FLAG(hdma, __HAL_DMA_GET_TC_FLAG_INDEX(hdma)) != RESET)
{
if(__HAL_DMA_GET_IT_SOURCE(hdma, DMA_IT_TC) != RESET)
{
if((hdma->Instance->CCR & DMA_CCR_CIRC) == 0)
{
/* Disable the transfer complete interrupt */
__HAL_DMA_DISABLE_IT(hdma, DMA_IT_TC);
}
/* Clear the transfer complete flag */
__HAL_DMA_CLEAR_FLAG(hdma, __HAL_DMA_GET_TC_FLAG_INDEX(hdma));
/* Update error code */
hdma->ErrorCode |= HAL_DMA_ERROR_NONE;
/* Change the DMA state */
hdma->State = HAL_DMA_STATE_READY;
/* Process Unlocked */
__HAL_UNLOCK(hdma);
if(hdma->XferCpltCallback != NULL)
{
/* Transfer complete callback */
hdma->XferCpltCallback(hdma);
}
}
}
}
/**
* @}
*/
/** @defgroup DMA_Group3 Peripheral State functions
* @brief Peripheral State functions
*
@verbatim
===============================================================================
##### Peripheral State functions #####
===============================================================================
[..]
This subsection provides functions allowing to
(+) Check the DMA state
(+) Get error code
@endverbatim
* @{
*/
/**
* @brief Returns the DMA state.
* @param hdma: pointer to a DMA_HandleTypeDef structure that contains
* the configuration information for the specified DMA Channel.
* @retval HAL state
*/
HAL_DMA_StateTypeDef HAL_DMA_GetState(DMA_HandleTypeDef *hdma)
{
return hdma->State;
}
/**
* @brief Return the DMA error code
* @param hdma : pointer to a DMA_HandleTypeDef structure that contains
* the configuration information for the specified DMA Channel.
* @retval DMA Error Code
*/
uint32_t HAL_DMA_GetError(DMA_HandleTypeDef *hdma)
{
return hdma->ErrorCode;
}
/**
* @}
*/
/**
* @brief Sets the DMA Transfer parameter.
* @param hdma: pointer to a DMA_HandleTypeDef structure that contains
* the configuration information for the specified DMA Channel.
* @param SrcAddress: The source memory Buffer address
* @param DstAddress: The destination memory Buffer address
* @param DataLength: The length of data to be transferred from source to destination
* @retval HAL status
*/
static void DMA_SetConfig(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t DataLength)
{
/* Configure DMA Channel data length */
hdma->Instance->CNDTR = DataLength;
/* Peripheral to Memory */
if((hdma->Init.Direction) == DMA_MEMORY_TO_PERIPH)
{
/* Configure DMA Channel destination address */
hdma->Instance->CPAR = DstAddress;
/* Configure DMA Channel source address */
hdma->Instance->CMAR = SrcAddress;
}
/* Memory to Peripheral */
else
{
/* Configure DMA Channel source address */
hdma->Instance->CPAR = SrcAddress;
/* Configure DMA Channel destination address */
hdma->Instance->CMAR = DstAddress;
}
}
/**
* @}
*/
#endif /* HAL_DMA_MODULE_ENABLED */
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,542 @@
/**
******************************************************************************
* @file stm32l0xx_hal_dma.h
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief Header file of DMA HAL module.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32L0xx_HAL_DMA_H
#define __STM32L0xx_HAL_DMA_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal_def.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @addtogroup DMA
* @{
*/
/* Exported types ------------------------------------------------------------*/
/**
* @brief DMA Configuration Structure definition
*/
typedef struct
{
uint32_t Request; /*!< Specifies the request selected for the specified channel.
This parameter can be a value of @ref DMA_request */
uint32_t Direction; /*!< Specifies if the data will be transferred from memory to peripheral,
from memory to memory or from peripheral to memory.
This parameter can be a value of @ref DMA_Data_transfer_direction */
uint32_t PeriphInc; /*!< Specifies whether the Peripheral address register should be incremented or not.
This parameter can be a value of @ref DMA_Peripheral_incremented_mode */
uint32_t MemInc; /*!< Specifies whether the memory address register should be incremented or not.
This parameter can be a value of @ref DMA_Memory_incremented_mode */
uint32_t PeriphDataAlignment; /*!< Specifies the Peripheral data width.
This parameter can be a value of @ref DMA_Peripheral_data_size */
uint32_t MemDataAlignment; /*!< Specifies the Memory data width.
This parameter can be a value of @ref DMA_Memory_data_size */
uint32_t Mode; /*!< Specifies the operation mode of the DMAy Channelx.
This parameter can be a value of @ref DMA_mode
@note The circular buffer mode cannot be used if the memory-to-memory
data transfer is configured on the selected Channel */
uint32_t Priority; /*!< Specifies the software priority for the DMAy Channelx.
This parameter can be a value of @ref DMA_Priority_level */
} DMA_InitTypeDef;
/**
* @brief DMA Configuration enumeration values definition
*/
typedef enum
{
DMA_MODE = 0, /*!< Control related DMA mode Parameter in DMA_InitTypeDef */
DMA_PRIORITY = 1, /*!< Control related priority level Parameter in DMA_InitTypeDef */
} DMA_ControlTypeDef;
/**
* @brief HAL DMA State structures definition
*/
typedef enum
{
HAL_DMA_STATE_RESET = 0x00, /*!< DMA not yet initialized or disabled */
HAL_DMA_STATE_READY = 0x01, /*!< DMA process success and ready for use */
HAL_DMA_STATE_BUSY = 0x02, /*!< DMA process is ongoing */
HAL_DMA_STATE_TIMEOUT = 0x03, /*!< DMA timeout state */
HAL_DMA_STATE_ERROR = 0x04, /*!< DMA error state */
HAL_DMA_STATE_READY_HALF = 0x05, /*!< DMA Half process success */
}HAL_DMA_StateTypeDef;
/**
* @brief HAL DMA Error Code structure definition
*/
typedef enum
{
HAL_DMA_FULL_TRANSFER = 0x00, /*!< Full transfer */
HAL_DMA_HALF_TRANSFER = 0x01, /*!< Half Transfer */
}HAL_DMA_LevelCompleteTypeDef;
/**
* @brief DMA handle Structure definition
*/
typedef struct __DMA_HandleTypeDef
{
DMA_Channel_TypeDef *Instance; /*!< Register base address */
DMA_InitTypeDef Init; /*!< DMA communication parameters */
HAL_LockTypeDef Lock; /*!< DMA locking object */
__IO HAL_DMA_StateTypeDef State; /*!< DMA transfer state */
void *Parent; /*!< Parent object state */
void (* XferCpltCallback)( struct __DMA_HandleTypeDef * hdma); /*!< DMA transfer complete callback */
void (* XferHalfCpltCallback)( struct __DMA_HandleTypeDef * hdma); /*!< DMA Half transfer complete callback */
void (* XferErrorCallback)( struct __DMA_HandleTypeDef * hdma); /*!< DMA transfer error callback */
__IO uint32_t ErrorCode; /*!< DMA Error code */
} DMA_HandleTypeDef;
/* Exported constants --------------------------------------------------------*/
/** @defgroup DMA_Exported_Constants
* @{
*/
/** @defgroup DMA_Error_Code
* @{
*/
#define HAL_DMA_ERROR_NONE ((uint32_t)0x00000000) /*!< No error */
#define HAL_DMA_ERROR_TE ((uint32_t)0x00000001) /*!< Transfer error */
#define HAL_DMA_ERROR_TIMEOUT ((uint32_t)0x00000020) /*!< Timeout error */
/**
* @}
*/
#define IS_DMA_ALL_PERIPH(PERIPH) (((PERIPH) == DMA1_Channel1) || \
((PERIPH) == DMA1_Channel2) || \
((PERIPH) == DMA1_Channel3) || \
((PERIPH) == DMA1_Channel4) || \
((PERIPH) == DMA1_Channel5) || \
((PERIPH) == DMA1_Channel6) || \
((PERIPH) == DMA1_Channel7))
#define IS_DMA_ALL_CONTROLLER(CONTROLLER) (((CONTROLLER) == DMA1))
/**
* @}
*/
/** @defgroup DMA_request
* @{
*/
#define DMA_REQUEST_0 ((uint32_t)0x00000000)
#define DMA_REQUEST_1 ((uint32_t)0x00000001)
#define DMA_REQUEST_2 ((uint32_t)0x00000002)
#define DMA_REQUEST_3 ((uint32_t)0x00000003)
#define DMA_REQUEST_4 ((uint32_t)0x00000004)
#define DMA_REQUEST_5 ((uint32_t)0x00000005)
#define DMA_REQUEST_6 ((uint32_t)0x00000006)
#define DMA_REQUEST_7 ((uint32_t)0x00000007)
#define DMA_REQUEST_8 ((uint32_t)0x00000008)
#define DMA_REQUEST_9 ((uint32_t)0x00000009)
#define DMA_REQUEST_11 ((uint32_t)0x0000000B)
#define IS_DMA_ALL_REQUEST(REQUEST) (((REQUEST) == DMA_REQUEST_0) || \
((REQUEST) == DMA_REQUEST_1) || \
((REQUEST) == DMA_REQUEST_2) || \
((REQUEST) == DMA_REQUEST_3) || \
((REQUEST) == DMA_REQUEST_4) || \
((REQUEST) == DMA_REQUEST_5) || \
((REQUEST) == DMA_REQUEST_6) || \
((REQUEST) == DMA_REQUEST_7) || \
((REQUEST) == DMA_REQUEST_8) || \
((REQUEST) == DMA_REQUEST_9) || \
((REQUEST) == DMA_REQUEST_11))
/**
* @}
*/
/** @defgroup DMA_Data_transfer_direction
* @{
*/
#define DMA_PERIPH_TO_MEMORY ((uint32_t)0x00000000) /*!< Peripheral to memory direction */
#define DMA_MEMORY_TO_PERIPH ((uint32_t)DMA_CCR_DIR) /*!< Memory to peripheral direction */
#define DMA_MEMORY_TO_MEMORY ((uint32_t)(DMA_CCR_MEM2MEM)) /*!< Memory to memory direction */
#define IS_DMA_DIRECTION(DIRECTION) (((DIRECTION) == DMA_PERIPH_TO_MEMORY ) || \
((DIRECTION) == DMA_MEMORY_TO_PERIPH) || \
((DIRECTION) == DMA_MEMORY_TO_MEMORY))
/**
* @}
*/
/** @defgroup DMA_Data_buffer_size
* @{
*/
#define IS_DMA_BUFFER_SIZE(SIZE) (((SIZE) >= 0x1) && ((SIZE) < 0x10000))
/**
* @}
*/
/** @defgroup DMA_Peripheral_incremented_mode
* @{
*/
#define DMA_PINC_ENABLE ((uint32_t)DMA_CCR_PINC) /*!< Peripheral increment mode Enable */
#define DMA_PINC_DISABLE ((uint32_t)0x00000000) /*!< Peripheral increment mode Disable */
#define IS_DMA_PERIPHERAL_INC_STATE(STATE) (((STATE) == DMA_PINC_ENABLE) || \
((STATE) == DMA_PINC_DISABLE))
/**
* @}
*/
/** @defgroup DMA_Memory_incremented_mode
* @{
*/
#define DMA_MINC_ENABLE ((uint32_t)DMA_CCR_MINC) /*!< Memory increment mode Enable */
#define DMA_MINC_DISABLE ((uint32_t)0x00000000) /*!< Memory increment mode Disable */
#define IS_DMA_MEMORY_INC_STATE(STATE) (((STATE) == DMA_MINC_ENABLE) || \
((STATE) == DMA_MINC_DISABLE))
/**
* @}
*/
/** @defgroup DMA_Peripheral_data_size
* @{
*/
#define DMA_PDATAALIGN_BYTE ((uint32_t)0x00000000) /*!< Peripheral data alignment : Byte */
#define DMA_PDATAALIGN_HALFWORD ((uint32_t)DMA_CCR_PSIZE_0) /*!< Peripheral data alignment : HalfWord */
#define DMA_PDATAALIGN_WORD ((uint32_t)DMA_CCR_PSIZE_1) /*!< Peripheral data alignment : Word */
#define IS_DMA_PERIPHERAL_DATA_SIZE(SIZE) (((SIZE) == DMA_PDATAALIGN_BYTE) || \
((SIZE) == DMA_PDATAALIGN_HALFWORD) || \
((SIZE) == DMA_PDATAALIGN_WORD))
/**
* @}
*/
/** @defgroup DMA_Memory_data_size
* @{
*/
#define DMA_MDATAALIGN_BYTE ((uint32_t)0x00000000) /*!< Memory data alignment : Byte */
#define DMA_MDATAALIGN_HALFWORD ((uint32_t)DMA_CCR_MSIZE_0) /*!< Memory data alignment : HalfWord */
#define DMA_MDATAALIGN_WORD ((uint32_t)DMA_CCR_MSIZE_1) /*!< Memory data alignment : Word */
#define IS_DMA_MEMORY_DATA_SIZE(SIZE) (((SIZE) == DMA_MDATAALIGN_BYTE) || \
((SIZE) == DMA_MDATAALIGN_HALFWORD) || \
((SIZE) == DMA_MDATAALIGN_WORD ))
/**
* @}
*/
/** @defgroup DMA_mode
* @{
*/
#define DMA_NORMAL ((uint32_t)0x00000000) /*!< Normal Mode */
#define DMA_CIRCULAR ((uint32_t)DMA_CCR_CIRC) /*!< Circular Mode */
#define IS_DMA_MODE(MODE) (((MODE) == DMA_NORMAL ) || \
((MODE) == DMA_CIRCULAR))
/**
* @}
*/
/** @defgroup DMA_Priority_level
* @{
*/
#define DMA_PRIORITY_LOW ((uint32_t)0x00000000) /*!< Priority level : Low */
#define DMA_PRIORITY_MEDIUM ((uint32_t)DMA_CCR_PL_0) /*!< Priority level : Medium */
#define DMA_PRIORITY_HIGH ((uint32_t)DMA_CCR_PL_1) /*!< Priority level : High */
#define DMA_PRIORITY_VERY_HIGH ((uint32_t)DMA_CCR_PL) /*!< Priority level : Very_High */
#define IS_DMA_PRIORITY(PRIORITY) (((PRIORITY) == DMA_PRIORITY_LOW ) || \
((PRIORITY) == DMA_PRIORITY_MEDIUM) || \
((PRIORITY) == DMA_PRIORITY_HIGH) || \
((PRIORITY) == DMA_PRIORITY_VERY_HIGH))
/**
* @}
*/
/** @defgroup DMA_interrupt_enable_definitions
* @{
*/
#define DMA_IT_TC ((uint32_t)DMA_CCR_TCIE)
#define DMA_IT_HT ((uint32_t)DMA_CCR_HTIE)
#define DMA_IT_TE ((uint32_t)DMA_CCR_TEIE)
/**
* @}
*/
/** @defgroup DMA_flag_definitions
* @{
*/
#define DMA_FLAG_GL1 ((uint32_t)0x00000001)
#define DMA_FLAG_TC1 ((uint32_t)0x00000002)
#define DMA_FLAG_HT1 ((uint32_t)0x00000004)
#define DMA_FLAG_TE1 ((uint32_t)0x00000008)
#define DMA_FLAG_GL2 ((uint32_t)0x00000010)
#define DMA_FLAG_TC2 ((uint32_t)0x00000020)
#define DMA_FLAG_HT2 ((uint32_t)0x00000040)
#define DMA_FLAG_TE2 ((uint32_t)0x00000080)
#define DMA_FLAG_GL3 ((uint32_t)0x00000100)
#define DMA_FLAG_TC3 ((uint32_t)0x00000200)
#define DMA_FLAG_HT3 ((uint32_t)0x00000400)
#define DMA_FLAG_TE3 ((uint32_t)0x00000800)
#define DMA_FLAG_GL4 ((uint32_t)0x00001000)
#define DMA_FLAG_TC4 ((uint32_t)0x00002000)
#define DMA_FLAG_HT4 ((uint32_t)0x00004000)
#define DMA_FLAG_TE4 ((uint32_t)0x00008000)
#define DMA_FLAG_GL5 ((uint32_t)0x00010000)
#define DMA_FLAG_TC5 ((uint32_t)0x00020000)
#define DMA_FLAG_HT5 ((uint32_t)0x00040000)
#define DMA_FLAG_TE5 ((uint32_t)0x00080000)
#define DMA_FLAG_GL6 ((uint32_t)0x00100000)
#define DMA_FLAG_TC6 ((uint32_t)0x00200000)
#define DMA_FLAG_HT6 ((uint32_t)0x00400000)
#define DMA_FLAG_TE6 ((uint32_t)0x00800000)
#define DMA_FLAG_GL7 ((uint32_t)0x01000000)
#define DMA_FLAG_TC7 ((uint32_t)0x02000000)
#define DMA_FLAG_HT7 ((uint32_t)0x04000000)
#define DMA_FLAG_TE7 ((uint32_t)0x08000000)
/**
* @}
*/
/* Exported macro ------------------------------------------------------------*/
/** @brief Reset DMA handle state
* @param __HANDLE__: DMA handle
* @retval None
*/
#define __HAL_DMA_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_DMA_STATE_RESET)
/**
* @brief Enable the specified DMA Channel.
* @param __HANDLE__: DMA handle
* @retval None.
*/
#define __HAL_DMA_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CCR |= DMA_CCR_EN)
/**
* @brief Disable the specified DMA Channel.
* @param __HANDLE__: DMA handle
* @retval None.
*/
#define __HAL_DMA_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CCR &= ~DMA_CCR_EN)
/* Interrupt & Flag management */
/**
* @brief Returns the current DMA Channel transfer complete flag.
* @param __HANDLE__: DMA handle
* @retval The specified transfer complete flag index.
*/
#define __HAL_DMA_GET_TC_FLAG_INDEX(__HANDLE__) \
(((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel1))? DMA_FLAG_TC1 :\
((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel2))? DMA_FLAG_TC2 :\
((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel3))? DMA_FLAG_TC3 :\
((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel4))? DMA_FLAG_TC4 :\
((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel5))? DMA_FLAG_TC5 :\
((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel6))? DMA_FLAG_TC6 :\
DMA_FLAG_TC7)
/**
* @brief Returns the current DMA Channel half transfer complete flag.
* @param __HANDLE__: DMA handle
* @retval The specified half transfer complete flag index.
*/
#define __HAL_DMA_GET_HT_FLAG_INDEX(__HANDLE__)\
(((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel1))? DMA_FLAG_HT1 :\
((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel2))? DMA_FLAG_HT2 :\
((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel3))? DMA_FLAG_HT3 :\
((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel4))? DMA_FLAG_HT4 :\
((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel5))? DMA_FLAG_HT5 :\
((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel6))? DMA_FLAG_HT6 :\
DMA_FLAG_HT7)
/**
* @brief Returns the current DMA Channel transfer error flag.
* @param __HANDLE__: DMA handle
* @retval The specified transfer error flag index.
*/
#define __HAL_DMA_GET_TE_FLAG_INDEX(__HANDLE__)\
(((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel1))? DMA_FLAG_TE1 :\
((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel2))? DMA_FLAG_TE2 :\
((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel3))? DMA_FLAG_TE3 :\
((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel4))? DMA_FLAG_TE4 :\
((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel5))? DMA_FLAG_TE5 :\
((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel6))? DMA_FLAG_TE6 :\
DMA_FLAG_TE7)
/**
* @brief Returns the current DMA Channel Global interrupt flag.
* @param __HANDLE__: DMA handle
* @retval The specified transfer error flag index.
*/
#define __HAL_DMA_GET_GI_FLAG_INDEX(__HANDLE__)\
(((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel1))? DMA_ISR_GIF1 :\
((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel2))? DMA_ISR_GIF2 :\
((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel3))? DMA_ISR_GIF3 :\
((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel4))? DMA_ISR_GIF4 :\
((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel5))? DMA_ISR_GIF5 :\
((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel6))? DMA_ISR_GIF6 :\
DMA_ISR_GIF7)
/**
* @brief Get the DMA Channel pending flags.
* @param __HANDLE__: DMA handle
* @param __FLAG__: Get the specified flag.
* This parameter can be any combination of the following values:
* @arg DMA_FLAG_TCIFx: Transfer complete flag
* @arg DMA_FLAG_HTIFx: Half transfer complete flag
* @arg DMA_FLAG_TEIFx: Transfer error flag
* @arg DMA_ISR_GIFx: Global interrupt flag
* Where x can be 0_4, 1_5, 2_6 or 3_7 to select the DMA Channel flag.
* @retval The state of FLAG (SET or RESET).
*/
#define __HAL_DMA_GET_FLAG(__HANDLE__, __FLAG__) (DMA1->ISR & (__FLAG__))
/**
* @brief Clears the DMA Channel pending flags.
* @param __HANDLE__: DMA handle
* @param __FLAG__: specifies the flag to clear.
* This parameter can be any combination of the following values:
* @arg DMA_FLAG_TCIFx: Transfer complete flag
* @arg DMA_FLAG_HTIFx: Half transfer complete flag
* @arg DMA_FLAG_TEIFx: Transfer error flag
* @arg DMA_ISR_GIFx: Global interrupt flag
* Where x can be 0_4, 1_5, 2_6 or 3_7 to select the DMA Channel flag.
* @retval None
*/
#define __HAL_DMA_CLEAR_FLAG(__HANDLE__, __FLAG__) (DMA1->IFCR = (__FLAG__))
/**
* @brief Enables the specified DMA Channel interrupts.
* @param __HANDLE__: DMA handle
* @param __INTERRUPT__: specifies the DMA interrupt sources to be enabled or disabled.
* This parameter can be any combination of the following values:
* @arg DMA_IT_TC: Transfer complete interrupt mask
* @arg DMA_IT_HT: Half transfer complete interrupt mask
* @arg DMA_IT_TE: Transfer error interrupt mask
* @retval None
*/
#define __HAL_DMA_ENABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->CCR |= (__INTERRUPT__))
/**
* @brief Disables the specified DMA Channel interrupts.
* @param __HANDLE__: DMA handle
* @param __INTERRUPT__: specifies the DMA interrupt sources to be enabled or disabled.
* This parameter can be any combination of the following values:
* @arg DMA_IT_TC: Transfer complete interrupt mask
* @arg DMA_IT_HT: Half transfer complete interrupt mask
* @arg DMA_IT_TE: Transfer error interrupt mask
* @retval None
*/
#define __HAL_DMA_DISABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->CCR &= ~(__INTERRUPT__))
/**
* @brief Checks whether the specified DMA Channel interrupt has occurred or not.
* @param __HANDLE__: DMA handle
* @param __INTERRUPT__: specifies the DMA interrupt source to check.
* This parameter can be one of the following values:
* @arg DMA_IT_TC: Transfer complete interrupt mask
* @arg DMA_IT_HT: Half transfer complete interrupt mask
* @arg DMA_IT_TE: Transfer error interrupt mask
* @retval The state of DMA_IT (SET or RESET).
*/
#define __HAL_DMA_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->CCR & (__INTERRUPT__)))
/* Exported functions --------------------------------------------------------*/
/* Initialization and de-initialization functions *****************************/
HAL_StatusTypeDef HAL_DMA_Init(DMA_HandleTypeDef *hdma);
HAL_StatusTypeDef HAL_DMA_DeInit (DMA_HandleTypeDef *hdma);
/* IO operation functions *****************************************************/
HAL_StatusTypeDef HAL_DMA_Start (DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t DataLength);
HAL_StatusTypeDef HAL_DMA_Start_IT(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t DataLength);
HAL_StatusTypeDef HAL_DMA_Abort(DMA_HandleTypeDef *hdma);
HAL_StatusTypeDef HAL_DMA_PollForTransfer(DMA_HandleTypeDef *hdma, uint32_t CompleteLevel, uint32_t Timeout);
void HAL_DMA_IRQHandler(DMA_HandleTypeDef *hdma);
/* Peripheral State and Error functions ***************************************/
HAL_DMA_StateTypeDef HAL_DMA_GetState(DMA_HandleTypeDef *hdma);
uint32_t HAL_DMA_GetError(DMA_HandleTypeDef *hdma);
/**
* @}
*/
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif /* __STM32L0xx_HAL_DMA_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,706 @@
/**
******************************************************************************
* @file stm32l0xx_hal_flash.c
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief FLASH HAL module driver.
* This file provides firmware functions to manage the following
* functionalities of the internal FLASH memory:
* + FLASH Interface configuration
* + FLASH Memory Programming
* + DATA EEPROM Programming
* + Option Bytes Programming
* + Interrupts and flags management
*
* @verbatim
==============================================================================
##### FLASH peripheral features #####
==============================================================================
[..] The Flash memory interface manages CPU accesses to the Flash memory.
It implements the erase and program Flash memory operations
and the read and write protection mechanisms.
[..] The FLASH main features are:
(+) Flash memory read operations
(+) Flash memory program/erase operations
(+) Read / write protections
(+) Option Bytes programming
##### How to use this driver #####
==============================================================================
[..]
This driver provides functions and macros to configure and program the FLASH
memory of all STM32L0xx devices.
(#) FLASH Memory IO Programming functions:
(++) Lock and Unlock the FLASH interface using HAL_FLASH_Unlock() and
HAL_FLASH_Lock() functions
(++) Program functions: byte, half word and word
(++) There Two modes of programming :
(+++) Polling mode using HAL_FLASH_Program() function
(+++) Interrupt mode using HAL_FLASH_Program_IT() function
(#) Interrupts and flags management functions :
(++) Handle FLASH interrupts by calling HAL_FLASH_IRQHandler()
(++) Wait for last FLASH operation according to its status
(++) Get error flag status by calling HAL_GetErrorCode()
[..]
In addition to these functions, this driver includes a set of macros allowing
to handle the following operations:
(+) Set the latency
(+) Enable/Disable the prefetch buffer
(+) Enable/Disable the preread buffer
(+) Enable/Disable the Flash power-down
(+) Enable/Disable the FLASH interrupts
(+) Monitor the FLASH flags status
===============================================================================
##### Programming operation functions #####
===============================================================================
[..]
This subsection provides a set of functions allowing to manage the FLASH
program operations.
[..] The FLASH Memory Programming functions, includes the following functions:
(+) HAL_FLASH_Unlock(void);
(+) HAL_FLASH_Lock(void);
(+) HAL_FLASH_Program(uint32_t TypeProgram, uint32_t Address, uint32_t Data)
(+) HAL_FLASH_Program_IT(uint32_t TypeProgram, uint32_t Address, uint32_t Data)
[..] Any operation of erase or program should follow these steps:
(#) Call the HAL_FLASH_Unlock() function to enable the flash control register and
program memory access.
(#) Call the desired function to erase page or program data.
(#) Call the HAL_FLASH_Lock() to disable the flash program memory access
(recommended to protect the FLASH memory against possible unwanted operation).
==============================================================================
##### Option Bytes Programming functions #####
==============================================================================
[..] The FLASH_Option Bytes Programming_functions, includes the following functions:
(+) HAL_FLASH_OB_Unlock(void);
(+) HAL_FLASH_OB_Lock(void);
(+) HAL_FLASH_OB_Launch(void);
(+) HAL_FLASHEx_OBProgram(FLASH_OBProgramInitTypeDef *pOBInit);
(+) HAL_FLASHEx_OBGetConfig(FLASH_OBProgramInitTypeDef *pOBInit);
[..] Any operation of erase or program should follow these steps:
(#) Call the HAL_FLASH_OB_Unlock() function to enable the Flash option control
register access.
(#) Call the following functions to program the desired option bytes.
(++) HAL_FLASHEx_OBProgram(FLASH_OBProgramInitTypeDef *pOBInit);
(#) Once all needed option bytes to be programmed are correctly written, call the
HAL_FLASH_OB_Launch(void) function to launch the Option Bytes programming process.
(#) Call the HAL_FLASH_OB_Lock() to disable the Flash option control register access (recommended
to protect the option Bytes against possible unwanted operations).
[..] Proprietary code Read Out Protection (PcROP):
(#) The PcROP sector is selected by using the same option bytes as the Write
protection (nWRPi bits). As a result, these 2 options are exclusive each other.
(#) In order to activate the PcROP (change the function of the nWRPi option bits),
the SPRMOD option bit must be activated.
(#) The active value of nWRPi bits is inverted when PCROP mode is active, this
means: if SPRMOD = 1 and nWRPi = 1 (default value), then the user page "i"
is read/write protected.
(#) To activate PCROP mode for Flash page(s), you need to follow the sequence below:
(++) For page(s) within the first 64KB of the Flash, use this function
HAL_FLASHEx_AdvOBProgram with PCROPState = PCROPSTATE_ENABLE.
* @endverbatim
*
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @defgroup FLASH
* @brief FLASH driver modules
* @{
*/
#ifdef HAL_FLASH_MODULE_ENABLED
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
#define HAL_FLASH_TIMEOUT_VALUE ((uint32_t)0xFFFF0)
/* FLASH Mask */
#define WRP01_MASK ((uint32_t)0x0000FFFF)
#define PAGESIZE ((uint32_t)0x00000080)
/* Private macro -------------------------------------------------------------*/
/*Variables used for Erase sectors under interruption*/
FLASH_ProcessTypeDef pFlash;
/* Private function prototypes -----------------------------------------------*/
static void FLASH_Program_Word(uint32_t Address, uint32_t Data);
HAL_StatusTypeDef FLASH_WaitForLastOperation(uint32_t Timeout);
static void FLASH_SetErrorCode(void);
/* Private functions ---------------------------------------------------------*/
/** @defgroup FLASH_Private_Functions
* @{
*/
/** @defgroup FLASH_Group1 Programming operation functions
* @brief Programming operation functions
*
@verbatim
@endverbatim
* @{
*/
/**
* @brief Program word at a specified address
* @param TypeProgram: Indicate the way to program at a specified address.
* This parameter can be a value of @ref FLASH_Type_Program
* @param Address: specifies the address to be programmed.
* @param Data: specifies the data to be programmed
*
* @retval HAL_StatusTypeDef HAL Status
*/
HAL_StatusTypeDef HAL_FLASH_Program(uint32_t TypeProgram, uint32_t Address, uint32_t Data)
{
HAL_StatusTypeDef status = HAL_ERROR;
/* Process Locked */
__HAL_LOCK(&pFlash);
/* Check the parameters */
assert_param(IS_TYPEPROGRAM(TypeProgram));
/* Wait for last operation to be completed */
status = FLASH_WaitForLastOperation((uint32_t)HAL_FLASH_TIMEOUT_VALUE);
if(status == HAL_OK)
{
if(TypeProgram == TYPEPROGRAM_WORD)
{
/*Program word (32-bit) at a specified address.*/
FLASH_Program_Word(Address, (uint32_t) Data);
}
/* Wait for last operation to be completed */
status = FLASH_WaitForLastOperation((uint32_t)HAL_FLASH_TIMEOUT_VALUE);
/* Reset PROG bit */
FLASH->PECR &= ~FLASH_PECR_PROG;
}
/* Process Unlocked */
__HAL_UNLOCK(&pFlash);
return status;
}
/**
* @brief Program word at a specified address with interrupt enabled.
* @param TypeProgram: Indicate the way to program at a specified address.
* This parameter can be a value of @ref FLASH_Type_Program
* @param Address: specifies the address to be programmed.
* @param Data: specifies the data to be programmed
*
* @retval HAL_StatusTypeDef HAL Status
*/
HAL_StatusTypeDef HAL_FLASH_Program_IT(uint32_t TypeProgram, uint32_t Address, uint32_t Data)
{
HAL_StatusTypeDef status = HAL_OK;
/* Process Locked */
__HAL_LOCK(&pFlash);
/* Check the parameters */
assert_param(IS_TYPEPROGRAM(TypeProgram));
/* Enable End of FLASH Operation interrupt */
__HAL_FLASH_ENABLE_IT(FLASH_IT_EOP);
/* Enable Error source interrupt */
__HAL_FLASH_ENABLE_IT(FLASH_IT_ERR);
/* Clear pending flags (if any) */
__HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_EOP | FLASH_FLAG_ENDHV | FLASH_FLAG_WRPERR |\
FLASH_FLAG_PGAERR | FLASH_FLAG_SIZERR| FLASH_FLAG_OPTVERR |\
FLASH_FLAG_RDERR | FLASH_FLAG_NOTZEROERR);
pFlash.ProcedureOnGoing = FLASH_PROC_PROGRAM;
pFlash.Address = Address;
if(TypeProgram == TYPEPROGRAM_WORD)
{
/*Program word (32-bit) at a specified address.*/
FLASH_Program_Word(Address, (uint32_t) Data);
}
/* Process Unlocked */
__HAL_UNLOCK(&pFlash);
return status;
}
/**
* @brief This function handles FLASH interrupt request.
* @param None
* @retval None
*/
void HAL_FLASH_IRQHandler(void)
{
uint32_t temp;
/* If the program operation is completed, disable the PROG Bit */
FLASH->PECR &= (~FLASH_PECR_PROG);
/* If the erase operation is completed, disable the ERASE Bit */
FLASH->PECR &= (~FLASH_PECR_ERASE);
/* Check FLASH End of Operation flag */
if(__HAL_FLASH_GET_FLAG(FLASH_FLAG_EOP))
{
if(pFlash.ProcedureOnGoing == FLASH_PROC_PAGEERASE)
{
/*Nb of sector to erased can be decreased*/
pFlash.NbPagesToErase--;
/* Check if there are still sectors to erase*/
if(pFlash.NbPagesToErase != 0)
{
temp = pFlash.Page;
/*Indicate user which sector has been erased*/
HAL_FLASH_EndOfOperationCallback(temp);
/* Clear pending flags (if any) */
__HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_EOP | FLASH_FLAG_ENDHV | FLASH_FLAG_WRPERR |\
FLASH_FLAG_PGAERR | FLASH_FLAG_SIZERR| FLASH_FLAG_OPTVERR |\
FLASH_FLAG_RDERR | FLASH_FLAG_NOTZEROERR);
/*Increment sector number*/
temp = pFlash.Page + PAGESIZE;
pFlash.Page = pFlash.Page + PAGESIZE;
FLASH_Erase_Page(temp);
}
else
{
/*No more sectors to Erase, user callback can be called.*/
/*Reset Sector and stop Erase sectors procedure*/
pFlash.Page = temp = 0xFFFFFFFF;
pFlash.ProcedureOnGoing = FLASH_PROC_NONE;
/* FLASH EOP interrupt user callback */
HAL_FLASH_EndOfOperationCallback(temp);
/* Clear FLASH End of Operation pending bit */
__HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_EOP);
}
}
else
{
if(pFlash.ProcedureOnGoing == FLASH_PROC_PROGRAM)
{
/*Program ended. Return the selected address*/
/* FLASH EOP interrupt user callback */
HAL_FLASH_EndOfOperationCallback(pFlash.Address);
}
pFlash.ProcedureOnGoing = FLASH_PROC_NONE;
/* Clear FLASH End of Operation pending bit */
__HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_EOP);
}
}
/* Check FLASH operation error flags */
if( (__HAL_FLASH_GET_FLAG(FLASH_FLAG_EOP) != RESET) || (__HAL_FLASH_GET_FLAG(FLASH_FLAG_ENDHV) != RESET) || \
(__HAL_FLASH_GET_FLAG(FLASH_FLAG_WRPERR) != RESET)|| (__HAL_FLASH_GET_FLAG(FLASH_FLAG_PGAERR) != RESET) || \
(__HAL_FLASH_GET_FLAG(FLASH_FLAG_SIZERR) != RESET)|| (__HAL_FLASH_GET_FLAG(FLASH_FLAG_OPTVERR) != RESET) || \
(__HAL_FLASH_GET_FLAG(FLASH_FLAG_RDERR) != RESET) || (__HAL_FLASH_GET_FLAG(FLASH_FLAG_NOTZEROERR) != RESET))
{
if(pFlash.ProcedureOnGoing == FLASH_PROC_PAGEERASE)
{
/*return the faulty sector*/
temp = pFlash.Page;
pFlash.Page = 0xFFFFFFFF;
}
else
{
/*retrun the faulty address*/
temp = pFlash.Address;
}
/*Save the Error code*/
FLASH_SetErrorCode();
/* FLASH error interrupt user callback */
HAL_FLASH_OperationErrorCallback(temp);
/* Clear FLASH error pending bits */
__HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_EOP | FLASH_FLAG_ENDHV | FLASH_FLAG_WRPERR |\
FLASH_FLAG_PGAERR | FLASH_FLAG_SIZERR| FLASH_FLAG_OPTVERR |\
FLASH_FLAG_RDERR | FLASH_FLAG_NOTZEROERR);
/*Stop the procedure ongoing*/
pFlash.ProcedureOnGoing = FLASH_PROC_NONE;
}
if(pFlash.ProcedureOnGoing == FLASH_PROC_NONE)
{
/* Disable End of FLASH Operation interrupt */
__HAL_FLASH_DISABLE_IT(FLASH_IT_EOP);
/* Disable Error source interrupt */
__HAL_FLASH_DISABLE_IT(FLASH_IT_ERR);
/* Process Unlocked */
__HAL_UNLOCK(&pFlash);
}
}
/**
* @brief FLASH end of operation interrupt callback
* @param ReturnValue: The value saved in this parameter depends on the ongoing procedure
* Pages_Erase: Sector which has been erased
* (if 0xFFFFFFFF, it means that all the selected sectors have been erased)
* Program: Address which was selected for data program
* @retval none
*/
__weak void HAL_FLASH_EndOfOperationCallback(uint32_t ReturnValue)
{
/* NOTE : This function Should not be modified, when the callback is needed,
the HAL_FLASH_EndOfOperationCallback could be implemented in the user file
*/
}
/**
* @brief FLASH operation error interrupt callback
* @param ReturnValue: The value saved in this parameter depends on the ongoing procedure
* Pages_Erase: Sector number which returned an error
* Program: Address which was selected for data program
* @retval none
*/
__weak void HAL_FLASH_OperationErrorCallback(uint32_t ReturnValue)
{
/* NOTE : This function Should not be modified, when the callback is needed,
the HAL_FLASH_OperationErrorCallback could be implemented in the user file
*/
}
/**
* @}
*/
/** @defgroup FLASH_Group2 Peripheral Control functions
* @brief management functions
*
@verbatim
===============================================================================
##### Peripheral Control functions #####
===============================================================================
[..]
This subsection provides a set of functions allowing to control the FLASH
memory operations.
@endverbatim
* @{
*/
/**
* @brief Unlock the FLASH control register access
* @param None
* @retval HAL_StatusTypeDef HAL Status
*/
HAL_StatusTypeDef HAL_FLASH_Unlock(void)
{
if((FLASH->PECR & FLASH_PECR_PRGLOCK) != RESET)
{
if((FLASH->PECR & FLASH_PECR_PELOCK) != RESET)
{
/* Unlocking the Data memory and FLASH_PECR register access*/
FLASH->PEKEYR = FLASH_PEKEY1;
FLASH->PEKEYR = FLASH_PEKEY2;
}
/* Unlocking the program memory access */
FLASH->PRGKEYR = FLASH_PRGKEY1;
FLASH->PRGKEYR = FLASH_PRGKEY2;
}
else
{
return HAL_ERROR;
}
return HAL_OK;
}
/**
* @brief Locks the FLASH control register access
* @param None
* @retval HAL_StatusTypeDef HAL Status
*/
HAL_StatusTypeDef HAL_FLASH_Lock(void)
{
/* Set the PRGLOCK Bit to lock the program memory access */
FLASH->PECR |= FLASH_PECR_PRGLOCK;
return HAL_OK;
}
/**
* @brief Unlock the FLASH Option Control Registers access.
* @param None
* @retval HAL_StatusTypeDef HAL Status
*/
HAL_StatusTypeDef HAL_FLASH_OB_Unlock(void)
{
if((FLASH->PECR & FLASH_PECR_OPTLOCK) != RESET)
{
if((FLASH->PECR & FLASH_PECR_PELOCK) != RESET)
{
/* Unlocking the Data memory and FLASH_PECR register access*/
FLASH->PEKEYR = FLASH_PEKEY1;
FLASH->PEKEYR = FLASH_PEKEY2;
}
/* Unlocking the option bytes block access */
FLASH->OPTKEYR = FLASH_OPTKEY1;
FLASH->OPTKEYR = FLASH_OPTKEY2;
}
else
{
return HAL_ERROR;
}
return HAL_OK;
}
/**
* @brief Lock the FLASH Option Control Registers access.
* @param None
* @retval HAL_StatusTypeDef HAL Status
*/
HAL_StatusTypeDef HAL_FLASH_OB_Lock(void)
{
/* Set the OPTLOCK Bit to lock the option bytes block access */
FLASH->PECR |= FLASH_PECR_OPTLOCK;
return HAL_OK;
}
/**
* @brief Launch the option byte loading.
* @param None
* @retval HAL_StatusTypeDef HAL Status
*/
HAL_StatusTypeDef HAL_FLASH_OB_Launch(void)
{
/* Set the OBL_Launch bit to lauch the option byte loading */
FLASH->PECR |= FLASH_PECR_OBL_LAUNCH;
/* Wait for last operation to be completed */
return(FLASH_WaitForLastOperation((uint32_t)HAL_FLASH_TIMEOUT_VALUE));
}
/**
* @}
*/
/** @defgroup FLASH_Group3 Peripheral State and Errors functions
* @brief Peripheral Errors functions
*
@verbatim
===============================================================================
##### Peripheral Errors functions #####
===============================================================================
[..]
This subsection permit to get in run-time Errors of the FLASH peripheral.
@endverbatim
* @{
*/
/**
* @brief Get the specific FLASH error flag.
* @param None
* @retval FLASH_ErrorCode: The returned value can be:
* @arg FLASH_ERROR_RD: FLASH Read Protection error flag (PCROP)
* @arg FLASH_ERROR_ENDHV: FLASH Programming Sequence error flag
* @arg FLASH_ERROR_SIZE: FLASH Programming Parallelism error flag
* @arg FLASH_ERROR_PGA: FLASH Programming Alignment error flag
* @arg FLASH_ERROR_WRP: FLASH Write protected error flag
* @arg FLASH_ERROR_OPTV: FLASH Option valid error flag
* @arg FLASH_ERROR_NOTZERO: FLASH write operation is done in a not-erased region
*/
FLASH_ErrorTypeDef HAL_FLASH_GetError(void)
{
return pFlash.ErrorCode;
}
/**
* @}
*/
/**
* @}
*/
/**
* @brief Wait for a FLASH operation to complete.
* @param Timeout: maximum flash operationtimeout
* @retval HAL_StatusTypeDef HAL Status
*/
HAL_StatusTypeDef FLASH_WaitForLastOperation(uint32_t Timeout)
{
uint32_t tickstart = 0;
/* Wait for the FLASH operation to complete by polling on BUSY flag to be reset.
Even if the FLASH operation fails, the BUSY flag will be reset and an error
flag will be set */
tickstart = HAL_GetTick();
while(__HAL_FLASH_GET_FLAG(FLASH_FLAG_BSY))
{
if(Timeout != HAL_MAX_DELAY)
{
if((Timeout == 0)||((HAL_GetTick() - tickstart ) > Timeout))
{
return HAL_TIMEOUT;
}
}
}
if( (__HAL_FLASH_GET_FLAG(FLASH_FLAG_WRPERR) != RESET) ||(__HAL_FLASH_GET_FLAG(FLASH_FLAG_PGAERR) != RESET) || \
(__HAL_FLASH_GET_FLAG(FLASH_FLAG_SIZERR) != RESET)||(__HAL_FLASH_GET_FLAG(FLASH_FLAG_OPTVERR) != RESET) || \
(__HAL_FLASH_GET_FLAG(FLASH_FLAG_RDERR) != RESET) ||(__HAL_FLASH_GET_FLAG(FLASH_FLAG_NOTZEROERR) != RESET))
{
/*Save the error code*/
FLASH_SetErrorCode();
return HAL_ERROR;
}
/* If there is an error flag set */
return HAL_OK;
}
/**
* @brief Set the specific FLASH error flag.
* @param None
* @retval None
*/
static void FLASH_SetErrorCode(void)
{
if(__HAL_FLASH_GET_FLAG(FLASH_FLAG_ENDHV))
{
pFlash.ErrorCode = FLASH_ERROR_ENDHV;
}
if(__HAL_FLASH_GET_FLAG(FLASH_FLAG_WRPERR))
{
pFlash.ErrorCode = FLASH_ERROR_WRP;
}
if(__HAL_FLASH_GET_FLAG(FLASH_FLAG_PGAERR))
{
pFlash.ErrorCode = FLASH_ERROR_PGA;
}
if(__HAL_FLASH_GET_FLAG(FLASH_FLAG_SIZERR))
{
pFlash.ErrorCode = FLASH_ERROR_SIZE;
}
if(__HAL_FLASH_GET_FLAG(FLASH_FLAG_OPTVERR))
{
pFlash.ErrorCode = FLASH_ERROR_OPTV;
}
if(__HAL_FLASH_GET_FLAG(FLASH_FLAG_RDERR))
{
pFlash.ErrorCode = FLASH_ERROR_RD;
}
if(__HAL_FLASH_GET_FLAG(FLASH_FLAG_NOTZEROERR))
{
pFlash.ErrorCode = FLASH_ERROR_NOTZERO;
}
}
/**
* @brief Erases a specified page in program memory.
* @note To correctly run this function, the HAL_FLASH_Unlock() function
* must be called before.
* Call the HAL_FLASH_Lock() to disable the flash memory access
* (recommended to protect the FLASH memory against possible unwanted operation)
* @param Page_Address: The page address in program memory to be erased.
* @note A Page is erased in the Program memory only if the address to load
* is the start address of a page (multiple of 256 bytes).
* @retval HAL_StatusTypeDef HAL Status
*/
void FLASH_Erase_Page(uint32_t Page_Address)
{
/* Set the ERASE bit */
FLASH->PECR |= FLASH_PECR_ERASE;
/* Set PROG bit */
FLASH->PECR |= FLASH_PECR_PROG;
/* Write 00000000h to the first word of the program page to erase */
*(__IO uint32_t *)Page_Address = 0x00000000;
}
/**
* @brief Program word (32-bit) at a specified address.
* @param Address: specifies the address to be programmed.
* @param Data: specifies the data to be programmed.
* @retval None
*/
static void FLASH_Program_Word(uint32_t Address, uint32_t Data)
{
/* Check the parameters */
assert_param(IS_FLASH_PROGRAM_ADDRESS(Address));
/* Set PROG bit */
FLASH->PECR |= FLASH_PECR_PROG;
*(__IO uint32_t*)Address = Data;
}
#endif /* HAL_FLASH_MODULE_ENABLED */
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,503 @@
/**
******************************************************************************
* @file stm32l0xx_hal_flash.h
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief This file contains all the functions prototypes for the FLASH
* firmware library.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32L0XX_HAL_FLASH_H
#define __STM32L0XX_HAL_FLASH_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal_def.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @addtogroup FLASH
* @{
*/
/* Exported types ------------------------------------------------------------*/
/**
* @brief FLASH Error structure definition
*/
typedef enum
{
FLASH_ERROR_RD = 0x01,
FLASH_ERROR_ENDHV = 0x02,
FLASH_ERROR_SIZE = 0x04,
FLASH_ERROR_PGA = 0x08,
FLASH_ERROR_WRP = 0x10,
FLASH_ERROR_OPTV = 0x20,
FLASH_ERROR_NOTZERO = 0x40
}FLASH_ErrorTypeDef;
/**
* @brief FLASH Procedure structure definition
*/
typedef enum
{
FLASH_PROC_NONE = 0,
FLASH_PROC_PAGEERASE,
FLASH_PROC_PROGRAM
} FLASH_ProcedureTypeDef;
/**
* @brief FLASH Erase structure definition
*/
typedef struct
{
uint32_t TypeErase; /*!< TypeErase: Mass erase or sector Erase.
This parameter can be a value of @ref FLASH_Type_Erase */
uint32_t Page; /*!< Sector: Initial FLASH sector to erase when Mass erase is disabled
This parameter must be an address value between 0x08000000 and 0x0800FFFF */
uint32_t NbPages; /*!< NbSectors: Number of sectors to be erased.
This parameter must be a value between 1 and (max number of sectors - initial sector value) */
} FLASH_EraseInitTypeDef;
/**
* @brief FLASH Option Bytes PROGRAM structure definition
*/
typedef struct
{
uint32_t OptionType; /*!< OptionType: Option byte to be configured.
This parameter can be a value of @ref FLASH_Option_Type */
uint32_t WRPState; /*!< WRPState: Write protection activation or deactivation.
This parameter can be a value of @ref FLASH_WRP_State */
uint32_t WRPSector; /*!< WRPSector: specifies the sector(s) to be write protected.
The value of this parameter depends on device used within the same series */
uint32_t RDPLevel; /*!< RDPLevel: Set the read protection level..
This parameter can be a value of @ref FLASH_Option_Bytes_Read_Protection */
uint32_t BORLevel; /*!< BORLevel: Set the BOR Level.
This parameter can be a value of @ref FLASH_Option_Bytes_BOR_Level */
uint8_t USERConfig; /*!< USERConfig: Program the FLASH User Option Byte: IWDG_SW / RST_STOP / RST_STDBY.
This parameter can be a combination of @ref FLASH_Option_Bytes_IWatchdog, @ref FLASH_Option_Bytes_nRST_STOP and @ref FLASH_Option_Bytes_nRST_STDBY*/
} FLASH_OBProgramInitTypeDef;
/**
* @brief FLASH handle Structure definition
*/
typedef struct
{
__IO FLASH_ProcedureTypeDef ProcedureOnGoing; /*Internal variable to indicate which procedure is ongoing or not in IT context*/
__IO uint32_t NbPagesToErase; /*Internal variable to save the remaining sectors to erase in IT context*/
__IO uint32_t Page; /*Internal variable to define the current sector which is erasing*/
__IO uint32_t Address; /*Internal variable to save address selected for program*/
HAL_LockTypeDef Lock; /* FLASH locking object */
__IO FLASH_ErrorTypeDef ErrorCode; /* FLASH error code */
}FLASH_ProcessTypeDef;
/*Variables used for Erase sectors under interruption*/
extern FLASH_ProcessTypeDef pFlash;
/* Exported constants --------------------------------------------------------*/
/** @defgroup FLASH_Exported_Constants FLASH Exported Constants
* @{
*/
/** @defgroup FLASH_Type_Erase
* @{
*/
#define TYPEERASE_PAGEERASE ((uint32_t)0x00) /*!<Page erase only*/
#define TYPEERASE_WORD ((uint32_t)0x01) /*!<Data erase word activation*/
#define IS_TYPEERASE(VALUE)(((VALUE) == TYPEERASE_PAGEERASE) || \
((VALUE) == TYPEERASE_WORD))
/**
* @}
*/
/** @defgroup FLASH_Type_Program
* @{
*/
#define TYPEPROGRAM_BYTE ((uint32_t)0x00) /*!<Program byte (8-bit) at a specified address.*/
#define TYPEPROGRAM_HALFWORD ((uint32_t)0x01) /*!<Program a half-word (16-bit) at a specified address.*/
#define TYPEPROGRAM_WORD ((uint32_t)0x02) /*!<Program a word (32-bit) at a specified address.*/
#define TYPEPROGRAM_FASTBYTE ((uint32_t)0x04) /*!<Fast Program byte (8-bit) at a specified address.*/
#define TYPEPROGRAM_FASTHALFWORD ((uint32_t)0x08) /*!<Fast Program a half-word (16-bit) at a specified address.*/
#define TYPEPROGRAM_FASTWORD ((uint32_t)0x10) /*!<Fast Program a word (32-bit) at a specified address.*/
#define IS_TYPEPROGRAM(VALUE)(((VALUE) == TYPEPROGRAM_BYTE) || \
((VALUE) == TYPEPROGRAM_HALFWORD) || \
((VALUE) == TYPEPROGRAM_WORD) || \
((VALUE) == TYPEPROGRAM_FASTBYTE) || \
((VALUE) == TYPEPROGRAM_FASTHALFWORD) || \
((VALUE) == TYPEPROGRAM_FASTWORD))
/**
* @}
*/
/** @defgroup FLASH_WRP_State
* @{
*/
#define WRPSTATE_DISABLE ((uint32_t)0x00) /*!<Disable the write protection of the desired bank 1 sectors*/
#define WRPSTATE_ENABLE ((uint32_t)0x01) /*!<Enable the write protection of the desired bank 1 sectors*/
#define IS_WRPSTATE(VALUE)(((VALUE) == WRPSTATE_DISABLE) || \
((VALUE) == WRPSTATE_ENABLE))
/**
* @}
*/
/** @defgroup FLASH_Option_Type
* @{
*/
#define OPTIONBYTE_WRP ((uint32_t)0x01) /*!<WRP option byte configuration*/
#define OPTIONBYTE_RDP ((uint32_t)0x02) /*!<RDP option byte configuration*/
#define OPTIONBYTE_USER ((uint32_t)0x04) /*!<USER option byte configuration*/
#define OPTIONBYTE_BOR ((uint32_t)0x08) /*!<BOR option byte configuration*/
#define IS_OPTIONBYTE(VALUE)(((VALUE) < (OPTIONBYTE_WRP|OPTIONBYTE_RDP|OPTIONBYTE_USER|OPTIONBYTE_BOR)))
/**
* @}
*/
/** @defgroup FLASH_Interrupts
* @{
*/
#define FLASH_IT_EOP FLASH_PECR_EOPIE /*!< End of programming interrupt source */
#define FLASH_IT_ERR FLASH_PECR_ERRIE /*!< Error interrupt source */
#define IS_FLASH_IT(IT) ((((IT) & (uint32_t)0xFFFCFFFF) == 0x00000000) && (((IT) != 0x00000000)))
/**
* @}
*/
/** @defgroup FLASH_Address
* @{
*/
#define IS_FLASH_DATA_ADDRESS(ADDRESS) (((ADDRESS) >= DATA_EEPROM_BASE) && ((ADDRESS) <= DATA_EEPROM_END)) /* 2K */
#define IS_FLASH_PROGRAM_ADDRESS(ADDRESS) (((ADDRESS) >= FLASH_BASE) && ((ADDRESS) <= FLASH_END)) /* 64K */
#define IS_NBPAGES(PAGES) (((PAGES) >= 1) && ((PAGES) <= 512)) /* 512 pages from page0 to page 511 */
/**
* @}
*/
/** @defgroup FLASH_Option_Bytes_Write_Protection
* @{
*/
#define OB_WRP_Pages0to31 ((uint32_t)0x00000001) /* Write protection of Sector0 */
#define OB_WRP_Pages32to63 ((uint32_t)0x00000002) /* Write protection of Sector1 */
#define OB_WRP_Pages64to95 ((uint32_t)0x00000004) /* Write protection of Sector2 */
#define OB_WRP_Pages96to127 ((uint32_t)0x00000008) /* Write protection of Sector3 */
#define OB_WRP_Pages128to159 ((uint32_t)0x00000010) /* Write protection of Sector4 */
#define OB_WRP_Pages160to191 ((uint32_t)0x00000020) /* Write protection of Sector5 */
#define OB_WRP_Pages192to223 ((uint32_t)0x00000040) /* Write protection of Sector6 */
#define OB_WRP_Pages224to255 ((uint32_t)0x00000080) /* Write protection of Sector7 */
#define OB_WRP_Pages256to287 ((uint32_t)0x00000100) /* Write protection of Sector8 */
#define OB_WRP_Pages288to319 ((uint32_t)0x00000200) /* Write protection of Sector9 */
#define OB_WRP_Pages320to351 ((uint32_t)0x00000400) /* Write protection of Sector10 */
#define OB_WRP_Pages352to383 ((uint32_t)0x00000800) /* Write protection of Sector11 */
#define OB_WRP_Pages384to415 ((uint32_t)0x00001000) /* Write protection of Sector12 */
#define OB_WRP_Pages416to447 ((uint32_t)0x00002000) /* Write protection of Sector13 */
#define OB_WRP_Pages448to479 ((uint32_t)0x00004000) /* Write protection of Sector14 */
#define OB_WRP_Pages480to511 ((uint32_t)0x00008000) /* Write protection of Sector15 */
#define OB_WRP_AllPages ((uint32_t)0x0000FFFF) /*!< Write protection of all Sectors */
#define IS_OB_WRP(PAGE) (((PAGE) != 0x0000000))
/**
* @}
*/
/** @defgroup FLASH_Option_Bytes_Read_Protection
* @{
*/
/**
* @brief FLASH_Option_Bytes_Read_Protection
*/
#define OB_RDP_Level_0 ((uint8_t)0xAA)
#define OB_RDP_Level_1 ((uint8_t)0xBB)
/*#define OB_RDP_Level_2 ((uint8_t)0xCC)*/ /* Warning: When enabling read protection level 2
it's no more possible to go back to level 1 or 0 */
#define IS_OB_RDP(LEVEL) (((LEVEL) == OB_RDP_Level_0)||\
((LEVEL) == OB_RDP_Level_1))/*||\
((LEVEL) == OB_RDP_Level_2))*/
/**
* @}
*/
/** @defgroup FLASH_Option_Bytes_IWatchdog
* @{
*/
#define OB_IWDG_SW ((uint8_t)0x10) /*!< Software WDG selected */
#define OB_IWDG_HW ((uint8_t)0x00) /*!< Hardware WDG selected */
#define IS_OB_IWDG_SOURCE(SOURCE) (((SOURCE) == OB_IWDG_SW) || ((SOURCE) == OB_IWDG_HW))
/**
* @}
*/
/** @defgroup FLASH_Option_Bytes_nRST_STOP
* @{
*/
#define OB_STOP_NoRST ((uint8_t)0x20) /*!< No reset generated when entering in STOP */
#define OB_STOP_RST ((uint8_t)0x00) /*!< Reset generated when entering in STOP */
#define IS_OB_STOP_SOURCE(SOURCE) (((SOURCE) == OB_STOP_NoRST) || ((SOURCE) == OB_STOP_RST))
/**
* @}
*/
/** @defgroup FLASH_Option_Bytes_nRST_STDBY
* @{
*/
#define OB_STDBY_NoRST ((uint8_t)0x40) /*!< No reset generated when entering in STANDBY */
#define OB_STDBY_RST ((uint8_t)0x00) /*!< Reset generated when entering in STANDBY */
#define IS_OB_STDBY_SOURCE(SOURCE) (((SOURCE) == OB_STDBY_NoRST) || ((SOURCE) == OB_STDBY_RST))
/**
* @}
*/
/** @defgroup FLASH_Option_Bytes_BOR_Level
* @{
*/
#define OB_BOR_OFF ((uint8_t)0x00) /*!< BOR is disabled at power down, the reset is asserted when the VDD
power supply reaches the PDR(Power Down Reset) threshold (1.5V) */
#define OB_BOR_LEVEL1 ((uint8_t)0x08) /*!< BOR Reset threshold levels for 1.7V - 1.8V VDD power supply */
#define OB_BOR_LEVEL2 ((uint8_t)0x09) /*!< BOR Reset threshold levels for 1.9V - 2.0V VDD power supply */
#define OB_BOR_LEVEL3 ((uint8_t)0x0A) /*!< BOR Reset threshold levels for 2.3V - 2.4V VDD power supply */
#define OB_BOR_LEVEL4 ((uint8_t)0x0B) /*!< BOR Reset threshold levels for 2.55V - 2.65V VDD power supply */
#define OB_BOR_LEVEL5 ((uint8_t)0x0C) /*!< BOR Reset threshold levels for 2.8V - 2.9V VDD power supply */
#define IS_OB_BOR_LEVEL(LEVEL) (((LEVEL) == OB_BOR_OFF) || \
((LEVEL) == OB_BOR_LEVEL1) || \
((LEVEL) == OB_BOR_LEVEL2) || \
((LEVEL) == OB_BOR_LEVEL3) || \
((LEVEL) == OB_BOR_LEVEL4) || \
((LEVEL) == OB_BOR_LEVEL5))
/**
* @}
*/
/** @defgroup FLASH_Flags
* @{
*/
#define FLASH_FLAG_BSY FLASH_SR_BSY /*!< FLASH Busy flag */
#define FLASH_FLAG_EOP FLASH_SR_EOP /*!< FLASH End of Programming flag */
#define FLASH_FLAG_ENDHV FLASH_SR_ENHV /*!< FLASH End of High Voltage flag */
#define FLASH_FLAG_READY FLASH_SR_READY /*!< FLASH Ready flag after low power mode */
#define FLASH_FLAG_WRPERR FLASH_SR_WRPERR /*!< FLASH Write protected error flag */
#define FLASH_FLAG_PGAERR FLASH_SR_PGAERR /*!< FLASH Programming Alignment error flag */
#define FLASH_FLAG_SIZERR FLASH_SR_SIZERR /*!< FLASH Size error flag */
#define FLASH_FLAG_OPTVERR FLASH_SR_OPTVERR /*!< FLASH Option Validity error flag */
#define FLASH_FLAG_RDERR FLASH_SR_RDERR /*!< FLASH Read protected error flag */
#define FLASH_FLAG_NOTZEROERR FLASH_SR_NOTZEROERR /*!< FLASH Read protected error flag */
#define IS_FLASH_CLEAR_FLAG(FLAG) ((((FLAG) & (uint32_t)0xFFFED0FF) == 0x00000000) && ((FLAG) != 0x00000000))
#define IS_FLASH_GET_FLAG(FLAG) (((FLAG) == FLASH_FLAG_BSY) || ((FLAG) == FLASH_FLAG_EOP) || \
((FLAG) == FLASH_FLAG_ENDHV) || ((FLAG) == FLASH_FLAG_READY ) || \
((FLAG) == FLASH_FLAG_WRPERR) || ((FLAG) == FLASH_FLAG_PGAERR ) || \
((FLAG) == FLASH_FLAG_SIZERR) || ((FLAG) == FLASH_FLAG_OPTVERR) || \
((FLAG) == FLASH_FLAG_RDERR) || ((FLAG) == FLASH_FLAG_NOTZEROERR))
/**
* @}
*/
/** @defgroup FLASH_Keys
* @{
*/
#define FLASH_PDKEY1 ((uint32_t)0x04152637) /*!< Flash power down key1 */
#define FLASH_PDKEY2 ((uint32_t)0xFAFBFCFD) /*!< Flash power down key2: used with FLASH_PDKEY1
to unlock the RUN_PD bit in FLASH_ACR */
#define FLASH_PEKEY1 ((uint32_t)0x89ABCDEF) /*!< Flash program erase key1 */
#define FLASH_PEKEY2 ((uint32_t)0x02030405) /*!< Flash program erase key: used with FLASH_PEKEY2
to unlock the write access to the FLASH_PECR register and
data EEPROM */
#define FLASH_PRGKEY1 ((uint32_t)0x8C9DAEBF) /*!< Flash program memory key1 */
#define FLASH_PRGKEY2 ((uint32_t)0x13141516) /*!< Flash program memory key2: used with FLASH_PRGKEY2
to unlock the program memory */
#define FLASH_OPTKEY1 ((uint32_t)0xFBEAD9C8) /*!< Flash option key1 */
#define FLASH_OPTKEY2 ((uint32_t)0x24252627) /*!< Flash option key2: used with FLASH_OPTKEY1 to
unlock the write access to the option byte block */
/**
* @}
*/
/* CMSIS_Legacy */
#if defined ( __ICCARM__ )
#define InterruptType_ACTLR_DISMCYCINT_Msk IntType_ACTLR_DISMCYCINT_Msk
#endif
/**
* @}
*/
/* Exported macro ------------------------------------------------------------*/
/** @defgroup FLASH_Interrupt FLASH Interrupt
* @brief macros to handle FLASH interrupts
* @{
*/
/**
* @brief Enables or disables the specified FLASH interrupts.
* @param __INTERRUPT__: specifies the FLASH interrupt sources to be enabled or
* disabled.
* This parameter can be any combination of the following values:
* @arg FLASH_IT_EOP: FLASH end of programming Interrupt
* @arg FLASH_IT_ERR: FLASH Error Interrupt
* @retval None
*/
#define __HAL_FLASH_ENABLE_IT(__INTERRUPT__) (FLASH->PECR |= (__INTERRUPT__))
/**
* @brief Disable the specified FLASH interrupt.
* @param __INTERRUPT__ : FLASH interrupt
* This parameter can be any combination of the following values:
* @arg FLASH_IT_EOP: End of FLASH Operation Interrupt
* @arg FLASH_IT_ERR: Error Interrupt
* @retval none
*/
#define __HAL_FLASH_DISABLE_IT(__INTERRUPT__) (FLASH->PECR &= ~(uint32_t)(__INTERRUPT__))
/**
* @brief Checks whether the specified FLASH flag is set or not.
* @param __FLAG__: specifies the FLASH flag to check.
* This parameter can be one of the following values:
* @arg FLASH_FLAG_BSY: FLASH write/erase operations in progress flag
* @arg FLASH_FLAG_EOP: FLASH End of Operation flag
* @arg FLASH_FLAG_READY: FLASH Ready flag after low power mode
* @arg FLASH_FLAG_ENDHV: FLASH End of high voltage flag
* @arg FLASH_FLAG_WRPERR: FLASH Write protected error flag
* @arg FLASH_FLAG_PGAERR: FLASH Programming Alignment error flag
* @arg FLASH_FLAG_SIZERR: FLASH size error flag
* @arg FLASH_FLAG_OPTVERR: FLASH Option validity error flag
* @arg FLASH_FLAG_OPTVERRUSR: FLASH Option User validity error flag
* @arg FLASH_FLAG_RDERR: FLASH Read protected error flag
* @arg FLASH_FLAG_NOTZEROERR: Not Zero area error flag
* @retval The new state of FLASH_FLAG (SET or RESET).
*/
#define __HAL_FLASH_GET_FLAG(__FLAG__) ((FLASH->SR & (__FLAG__)) == (__FLAG__))
/**
* @brief Clears the FLASH's pending flags.
* @param __FLAG__: specifies the FLASH flags to clear.
* This parameter can be any combination of the following values:
* @arg FLASH_FLAG_EOP: FLASH End of Operation flag
* @arg FLASH_FLAG_WRPERR: FLASH Write protected error flag
* @arg FLASH_FLAG_PGAERR: FLASH Programming Alignment error flag
* @arg FLASH_FLAG_SIZERR: FLASH size error flag
* @arg FLASH_FLAG_OPTVERR: FLASH Option validity error flag
* @arg FLASH_FLAG_OPTVERRUSR: FLASH Option User validity error flag
* @arg FLASH_FLAG_RDERR: FLASH Read protected error flag
* @arg FLASH_FLAG_NOTZEROERR: Not Zero area error flag
* @retval None
*/
#define __HAL_FLASH_CLEAR_FLAG(__FLAG__) (FLASH->SR = (__FLAG__))
/**
* @}
*/
/* Include FLASH HAL Extension module */
#include "stm32l0xx_hal_flash_ex.h"
#include "stm32l0xx_hal_flash_ramfunc.h"
/* Exported functions ------------------------------------------------------- */
/**
* @brief FLASH memory functions that can be executed from FLASH.
*/
/* Program operation functions ***********************************************/
HAL_StatusTypeDef HAL_FLASH_Program(uint32_t TypeProgram, uint32_t Address, uint32_t Data);
HAL_StatusTypeDef HAL_FLASH_Program_IT(uint32_t TypeProgram, uint32_t Address, uint32_t Data);
/* FLASH IRQ handler function */
void HAL_FLASH_IRQHandler(void);
/* Callbacks in non blocking modes */
void HAL_FLASH_EndOfOperationCallback(uint32_t ReturnValue);
void HAL_FLASH_OperationErrorCallback(uint32_t ReturnValue);
/* Peripheral Control functions **********************************************/
HAL_StatusTypeDef HAL_FLASH_Unlock(void);
HAL_StatusTypeDef HAL_FLASH_Lock(void);
HAL_StatusTypeDef HAL_FLASH_OB_Unlock(void);
HAL_StatusTypeDef HAL_FLASH_OB_Lock(void);
/* Option bytes control */
HAL_StatusTypeDef HAL_FLASH_OB_Launch(void);
/* Peripheral State functions ************************************************/
FLASH_ErrorTypeDef HAL_FLASH_GetError(void);
/* Non-User functions ********************************************************/
HAL_StatusTypeDef FLASH_WaitForLastOperation(uint32_t Timeout);
void FLASH_Erase_Page(uint32_t Page_Address);
#ifdef __cplusplus
}
#endif
#endif /* __STM32L0XX_HAL_FLASH_H */
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,297 @@
/**
******************************************************************************
* @file stm32l0xx_hal_flash_ex.h
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief Header file of FLASH HAL Extension module.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32L0xx_HAL_FLASH_EX_H
#define __STM32L0xx_HAL_FLASH_EX_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal_def.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @addtogroup FLASHEx
* @{
*/
/* Exported types ------------------------------------------------------------*/
/**
* @brief FLASH Advanced Option Bytes Program structure definition
*/
typedef struct
{
uint32_t OptionType; /*!< OptionType: Option byte to be configured for extension .
This parameter can be a value of @ref FLASHEx_Option_Type */
uint32_t PCROPState; /*!< PCROPState: PCROP activation or deactivation.
This parameter can be a value of @ref FLASHEx_PCROP_State */
uint16_t Pages; /*!< Sectors: specifies the sector(s) set for PCROP
This parameter can be a value of @ref FLASHEx_Option_Bytes_PC_ReadWrite_Protection */
uint16_t BootConfig; /*!< BootConfig: specifies Option bytes for boot config
This parameter can be a value of @ref FLASHEx_Option_Bytes_BOOT1 */
} FLASH_AdvOBProgramInitTypeDef;
/* Exported constants --------------------------------------------------------*/
/** @defgroup FLASHEx_Exported_Constants
* @{
*/
/** @defgroup FLASHEx_PCROP_State
* @{
*/
#define PCROPSTATE_DISABLE ((uint32_t)0x00) /*!<Disable PCROP */
#define PCROPSTATE_ENABLE ((uint32_t)0x01) /*!<Enable PCROP */
#define IS_PCROPSTATE(VALUE)(((VALUE) == PCROPSTATE_DISABLE) || \
((VALUE) == PCROPSTATE_ENABLE))
/**
* @}
*/
/** @defgroup FLASHEx_Option_Type
* @{
*/
#define OBEX_PCROP ((uint32_t)0x01) /*!<PCROP option byte configuration*/
#define OBEX_BOOTCONFIG ((uint32_t)0x02) /*!<BOOTConfig option byte configuration*/
#define IS_OBEX(VALUE)(((VALUE) == OBEX_PCROP) || \
((VALUE) == OBEX_BOOTCONFIG))
/**
* @}
*/
/** @defgroup FLASHEx_Latency
* @{
*/
#define FLASH_LATENCY_0 ((uint8_t)0x00) /*!< FLASH Zero Latency cycle */
#define FLASH_LATENCY_1 FLASH_ACR_LATENCY /*!< FLASH One Latency cycle */
#define IS_FLASH_LATENCY(LATENCY) (((LATENCY) == FLASH_LATENCY_0) || \
((LATENCY) == FLASH_LATENCY_1))
/**
* @}
*/
/** @defgroup FLASHEx_Option_Bytes_PC_ReadWrite_Protection
* @{
*/
#define OB_PCROP_Pages0to31 ((uint32_t)0x00000001) /* PC Read/Write protection of Sector0 */
#define OB_PCROP_Pages32to63 ((uint32_t)0x00000002) /* PC Read/Write protection of Sector1 */
#define OB_PCROP_Pages64to95 ((uint32_t)0x00000004) /* PC Read/Write protection of Sector2 */
#define OB_PCROP_Pages96to127 ((uint32_t)0x00000008) /* PC Read/Write protection of Sector3 */
#define OB_PCROP_Pages128to159 ((uint32_t)0x00000010) /* PC Read/Write protection of Sector4 */
#define OB_PCROP_Pages160to191 ((uint32_t)0x00000020) /* PC Read/Write protection of Sector5 */
#define OB_PCROP_Pages192to223 ((uint32_t)0x00000040) /* PC Read/Write protection of Sector6 */
#define OB_PCROP_Pages224to255 ((uint32_t)0x00000080) /* PC Read/Write protection of Sector7 */
#define OB_PCROP_Pages256to287 ((uint32_t)0x00000100) /* PC Read/Write protection of Sector8 */
#define OB_PCROP_Pages288to319 ((uint32_t)0x00000200) /* PC Read/Write protection of Sector9 */
#define OB_PCROP_Pages320to351 ((uint32_t)0x00000400) /* PC Read/Write protection of Sector10 */
#define OB_PCROP_Pages352to383 ((uint32_t)0x00000800) /* PC Read/Write protection of Sector11 */
#define OB_PCROP_Pages384to415 ((uint32_t)0x00001000) /* PC Read/Write protection of Sector12 */
#define OB_PCROP_Pages416to447 ((uint32_t)0x00002000) /* PC Read/Write protection of Sector13 */
#define OB_PCROP_Pages448to479 ((uint32_t)0x00004000) /* PC Read/Write protection of Sector14 */
#define OB_PCROP_Pages480to511 ((uint32_t)0x00008000) /* PC Read/Write protection of Sector15 */
#define OB_PCROP_AllPages ((uint32_t)0x0000FFFF) /*!< PC Read/Write protection of all Sectors */
#define IS_OB_PCROP(PAGE) (((PAGE) != 0x0000000))
/**
* @}
*/
/** @defgroup FLASHEx_Option_Bytes_BOOT1
* @{
*/
#define OB_BOOT1_RESET ((uint16_t)0x0000) /*!< BOOT1 Reset */
#define OB_BOOT1_SET ((uint16_t)0x8000) /*!< BOOT1 Set */
#define IS_OB_BOOT1(BOOT1) (((BOOT1) == OB_BOOT1_RESET) || ((BOOT1) == OB_BOOT1_SET))
/**
* @}
*/
/** @defgroup FLASHEx_Selection_Protection_Mode
* @{
*/
#define OB_PCROP_DESELECTED ((uint16_t)0x0000) /*!< Disabled PcROP, nWPRi bits used for Write Protection on sector i */
#define OB_PCROP_SELECTED ((uint16_t)0x0100) /*!< Enable PcROP, nWPRi bits used for PCRoP Protection on sector i */
#define IS_OB_PCROP_SELECT(PCROP) (((PCROP) == OB_PCROP_SELECTED) || ((PCROP) == OB_PCROP_DESELECTED))
/**
* @}
*/
/**
* @}
*/
/* Exported macro ------------------------------------------------------------*/
/** @defgroup FLASHEx_Macros
* @brief macros to control FLASH features
* @{
*/
/**
* @brief Set the FLASH Latency.
* @param __LATENCY__: FLASH Latency
* The value of this parameter depend on device used within the same series
* @retval none
*/
#define __HAL_FLASH_SET_LATENCY(__LATENCY__) \
MODIFY_REG(FLASH->ACR, FLASH_ACR_LATENCY, (uint32_t)(__LATENCY__))
/**
* @brief Enable the FLASH prefetch buffer.
* @retval none
*/
#define __HAL_FLASH_PREFETCH_BUFFER_ENABLE() (FLASH->ACR |= FLASH_ACR_PRFTEN)
/**
* @brief Disable the FLASH prefetch buffer.
* @retval none
*/
#define __HAL_FLASH_PREFETCH_BUFFER_DISABLE() (FLASH->ACR &= (~FLASH_ACR_PRFTEN))
/**
* @brief Enable the FLASH Buffer cache.
* @retval none
*/
#define __HAL_FLASH_BUFFER_CACHE_ENABLE() (FLASH->ACR &= (~FLASH_ACR_DISAB_BUF))
/**
* @brief Disable the FLASH Buffer cache.
* @retval none
*/
#define __HAL_FLASH_BUFFER_CACHE_DISABLE() (FLASH->ACR |= FLASH_ACR_DISAB_BUF)
/**
* @brief Enable the FLASH preread buffer
* @retval none
*/
#define __HAL_FLASH_PREREAD_BUFFER_ENABLE() (FLASH->ACR |= FLASH_ACR_PRE_READ)
/**
* @brief Disable the FLASH preread buffer
* @retval none
*/
#define __HAL_FLASH_PREREAD_BUFFER_DISABLE() (FLASH->ACR &= (~FLASH_ACR_PRE_READ))
/**
* @brief Enable the FLASH power down during Sleep mode
* @retval none
*/
#define __HAL_FLASH_SLEEP_POWERDOWN_ENABLE() SET_BIT(FLASH->ACR, FLASH_ACR_SLEEP_PD)
/**
* @brief Disable the FLASH power down during Sleep mode
* @retval none
*/
#define __HAL_FLASH_SLEEP_POWERDOWN_DISABLE() CLEAR_BIT(FLASH->ACR, FLASH_ACR_SLEEP_PD)
/**
* @brief Macro to enable or disable the Flash Run power down mode.
* @note Writing this bit to 0 this bit, automatically the keys are
* loss and a new unlock sequence is necessary to re-write it to 1.
*/
#define __HAL_FLASH_POWER_DOWN_ENABLE() do { FLASH->PDKEYR = FLASH_PDKEY1; \
FLASH->PDKEYR = FLASH_PDKEY2; \
SET_BIT(FLASH->ACR, FLASH_ACR_RUN_PD); \
} while (0)
#define __HAL_FLASH_POWER_DOWN_DISABLE() do { FLASH->PDKEYR = FLASH_PDKEY1; \
FLASH->PDKEYR = FLASH_PDKEY2; \
CLEAR_BIT(FLASH->ACR, FLASH_ACR_RUN_PD); \
} while (0)
/**
* @}
*/
/* Exported functions --------------------------------------------------------*/
/* I/O operation functions *****************************************************/
/* Peripheral Control functions ************************************************/
HAL_StatusTypeDef HAL_FLASHEx_DATAEEPROM_Unlock(void);
HAL_StatusTypeDef HAL_FLASHEx_DATAEEPROM_Lock(void);
HAL_StatusTypeDef HAL_FLASHEx_DATAEEPROM_Erase(uint32_t Address);
HAL_StatusTypeDef HAL_FLASHEx_DATAEEPROM_Program(uint32_t TypeProgram, uint32_t Address, uint32_t Data);
/* Aliases for legacy HAL versions compatibility */
#define HAL_DATA_EEPROMEx_Unlock HAL_FLASHEx_DATAEEPROM_Unlock
#define HAL_DATA_EEPROMEx_Lock HAL_FLASHEx_DATAEEPROM_Lock
#define HAL_DATA_EEPROMEx_Erase HAL_FLASHEx_DATAEEPROM_Erase
#define HAL_DATA_EEPROMEx_Program HAL_FLASHEx_DATAEEPROM_Program
HAL_StatusTypeDef HAL_FLASHEx_Erase(FLASH_EraseInitTypeDef *pEraseInit, uint32_t *PageError);
HAL_StatusTypeDef HAL_FLASHEx_Erase_IT(FLASH_EraseInitTypeDef *pEraseInit);
HAL_StatusTypeDef HAL_FLASHEx_OB_SelectPCROP(void);
HAL_StatusTypeDef HAL_FLASHEx_OB_DeSelectPCROP(void);
HAL_StatusTypeDef HAL_FLASHEx_OBProgram(FLASH_OBProgramInitTypeDef *pOBInit);
void HAL_FLASHEx_OBGetConfig(FLASH_OBProgramInitTypeDef *pOBInit);
HAL_StatusTypeDef HAL_FLASHEx_AdvOBProgram (FLASH_AdvOBProgramInitTypeDef *pAdvOBInit);
void HAL_FLASHEx_AdvOBGetConfig(FLASH_AdvOBProgramInitTypeDef *pAdvOBInit);
/**
* @}
*/
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif /* __STM32L0xx_HAL_FLASH_EX_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,216 @@
/**
******************************************************************************
* @file stm32l0xx_hal_flash_ramfunc.c
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief FLASH RAMFUNC driver.
* This file provides a Flash firmware functions which should be
* executed from internal SRAM
* + FLASH HalfPage Programming
* + FLASH Power Down in Run mode
*
* @verbatim
*** 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(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal.h"
/** @addtogroup STM32L0XX_HAL_Driver
* @{
*/
/** @defgroup FLASHRamfunc Driver
* @brief FLASH functions executed from RAM
* @{
*/
#ifdef HAL_FLASH_MODULE_ENABLED
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
static __RAM_FUNC FLASH_Program_HalfPage(uint32_t Address, uint32_t *Data);
/* Private functions ---------------------------------------------------------*/
/** @defgroup FLASHRamfunc_Private_Functions
* @{
*/
/** @defgroup FLASHRamfunc_Group1 Peripheral features functions
* @brief Data transfers functions
*
@verbatim
===============================================================================
##### ramfunc functions #####
===============================================================================
[..]
This subsection provides a set of functions that should be executed from RAM
transfers.
@endverbatim
* @{
*/
/**
* @brief Program a half page word at a specified address,
* @note This function should be executed from RAM
* @param Address: specifies the address to be programmed,
* the address should be half page aligned.
* @param *Data: specifies the buffer of data to be programmed,
* the size of the buffer is 16 words.
*
* @retval HAL_StatusTypeDef HAL Status
*/
__RAM_FUNC HAL_FLASHEx_HalfPageProgram(uint32_t Address, uint32_t *Data)
{
HAL_StatusTypeDef status = HAL_OK;
uint32_t timeout = 0xFFFFFFFF;
/*Program word (32-bit) at a specified address.*/
FLASH_Program_HalfPage(Address, Data);
/* Wait for a FLASH operation to complete or a TIMEOUT to occur */
while(((FLASH->SR & FLASH_FLAG_BSY) != 0x00) && (timeout != 0x00))
{
timeout--;
}
if(timeout == 0x00 )
{
return HAL_TIMEOUT;
}
/* Reset PROG bit */
FLASH->PECR &= ~FLASH_PECR_PROG;
FLASH->PECR &= ~FLASH_PECR_FPRG;
return status;
}
/**
* @brief Enable the Power down in Run Mode
* @note This function should be called and executed from SRAM memory
* @param None
* @retval None
*/
__RAM_FUNC HAL_FLASHEx_EnableRunPowerDown(void)
{
/* Enable the Power Down in Run mode*/
__HAL_FLASH_POWER_DOWN_ENABLE();
return HAL_OK;
}
/**
* @brief Disable the Power down in Run Mode
* @note This function should be called and executed from SRAM memory
* @param None
* @retval None
*/
__RAM_FUNC HAL_FLASHEx_DisableRunPowerDown(void)
{
/* Disable the Power Down in Run mode*/
__HAL_FLASH_POWER_DOWN_DISABLE();
return HAL_OK;
}
/**
* @}
*/
/**
* @brief Program a half page in program memory.
* @param Address: The Half page address in program memory to be written.
* @param Data:
* @retval None
*/
static __RAM_FUNC FLASH_Program_HalfPage(uint32_t Address, uint32_t *Data)
{
HAL_StatusTypeDef status = HAL_OK;
uint32_t i =0;
/* Set PROG bit */
FLASH->PECR |= FLASH_PECR_PROG;
/* Set FPRG bit */
FLASH->PECR |= FLASH_PECR_FPRG;
*(__IO uint32_t*)Address = Data[0];
for(i = 1; i <= 15; i++)
{
*(__IO uint32_t*)(Address + 4) = Data[i];
}
return status;
}
/**
* @}
*/
#endif /* HAL_FLASH_MODULE_ENABLED */
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,89 @@
/**
******************************************************************************
* @file stm32l0xx_hal_flash_ramfunc.h
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief Header file of FLASH RAMFUNC driver.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32L0xx_FLASH_RAMFUNC_H
#define __STM32L0xx_FLASH_RAMFUNC_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal_def.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @addtogroup FLASHRamfunc
* @{
*/
/* Exported types ------------------------------------------------------------*/
/* Exported functions --------------------------------------------------------*/
/* I/O operation functions *****************************************************/
/* Peripheral Control functions ************************************************/
__RAM_FUNC HAL_FLASHEx_HalfPageProgram(uint32_t Address, uint32_t *Data);
__RAM_FUNC HAL_FLASHEx_EnableRunPowerDown(void);
__RAM_FUNC HAL_FLASHEx_DisableRunPowerDown(void);
/* Aliases for legacy compatibility */
#define FLASH_HalfPageProgram HAL_FLASHEx_HalfPageProgram
#define FLASH_EnableRunPowerDown HAL_FLASHEx_EnableRunPowerDown
#define FLASH_DisableRunPowerDown HAL_FLASHEx_DisableRunPowerDown
/**
* @}
*/
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif /* __STM32L0xx_FLASH_RAMFUNC_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,528 @@
/**
******************************************************************************
* @file stm32l0xx_hal_gpio.c
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief GPIO HAL module driver.
* This file provides firmware functions to manage the following
* functionalities of the General Purpose Input/Output (GPIO) peripheral:
* + Initialization and de-initialization functions
* + IO operation functions
*
@verbatim
==============================================================================
##### GPIO Peripheral features #####
==============================================================================
[..]
(+) Each port bit of the general-purpose I/O (GPIO) ports can be individually
configured by software in several modes:
(++) Input mode
(++) Analog mode
(++) Output mode
(++) Alternate function mode
(++) External interrupt/event lines
(+) During and just after reset, the alternate functions and external interrupt
lines are not active and the I/O ports are configured in input floating mode.
(+) All GPIO pins have weak internal pull-up and pull-down resistors, which can be
activated or not.
(+) In Output or Alternate mode, each IO can be configured on open-drain or push-pull
type and the IO speed can be selected depending on the VDD value.
(+) The microcontroller IO pins are connected to onboard peripherals/modules through a
multiplexer that allows only one peripheral alternate function (AF) connected
to an IO pin at a time. In this way, there can be no conflict between peripherals
sharing the same IO pin.
(+) All ports have external interrupt/event capability. To use external interrupt
lines, the port must be configured in input mode. All available GPIO pins are
connected to the 16 external interrupt/event lines from EXTI0 to EXTI15.
(+) The external interrupt/event controller consists of up to 23 edge detectors
(16 lines are connected to GPIO) for generating event/interrupt requests (each
input line can be independently configured to select the type (interrupt or event)
and the corresponding trigger event (rising or falling or both). Each line can
also be masked independently.
##### How to use this driver #####
==============================================================================
[..]
(#) Enable the GPIO IOPORT clock using the following function: __GPIOx_CLK_ENABLE().
(#) In case of external interrupt/event mode selection, enable the SYSCFG clock
using the following function __SYSCFG_CLK_ENABLE().
(#) Configure the GPIO pin(s) using HAL_GPIO_Init().
(++) Configure the IO mode using "Mode" member from GPIO_InitTypeDef structure
(++) Activate Pull-up, Pull-down resistor using "Pull" member from GPIO_InitTypeDef
structure.
(++) In case of Output or alternate function mode selection: the speed is
configured through "Speed" member from GPIO_InitTypeDef structure.
(++) In alternate mode is selection, the alternate function connected to the IO
is configured through "Alternate" member from GPIO_InitTypeDef structure.
(++) Analog mode is required when a pin is to be used as ADC channel
or DAC output.
(++) In case of external interrupt/event selection the "Mode" member from
GPIO_InitTypeDef structure select the type (interrupt or event) and
the corresponding trigger event (rising or falling or both).
(#) In case of external interrupt/event mode selection, configure NVIC IRQ priority
mapped to the EXTI line using HAL_NVIC_SetPriority() and enable it using
HAL_NVIC_EnableIRQ().
(#) To get the level of a pin configured in input mode use HAL_GPIO_ReadPin().
(#) To set/reset the level of a pin configured in output mode use
HAL_GPIO_WritePin()/HAL_GPIO_TogglePin().
(#) 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(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @defgroup GPIO
* @brief GPIO HAL module driver
* @{
*/
#ifdef HAL_GPIO_MODULE_ENABLED
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
#define GET_GPIO_SOURCE(__GPIOx__) \
(((uint32_t)(__GPIOx__) == ((uint32_t)GPIOA_BASE))? 0 :\
((uint32_t)(__GPIOx__) == ((uint32_t)(GPIOA_BASE + 0x0400)))? (uint32_t)1 :\
((uint32_t)(__GPIOx__) == ((uint32_t)(GPIOA_BASE + 0x0800)))? (uint32_t)2 :\
((uint32_t)(__GPIOx__) == ((uint32_t)(GPIOA_BASE + 0x0C00)))? (uint32_t)3 :\
((uint32_t)(__GPIOx__) == ((uint32_t)(GPIOA_BASE + 0x1C00)))? (uint32_t)4 : (uint32_t)5)
#define GPIO_MODE ((uint32_t)0x00000003)
#define EXTI_MODE ((uint32_t)0x10000000)
#define GPIO_MODE_IT ((uint32_t)0x00010000)
#define GPIO_MODE_EVT ((uint32_t)0x00020000)
#define RISING_EDGE ((uint32_t)0x00100000)
#define FALLING_EDGE ((uint32_t)0x00200000)
#define GPIO_OUTPUT_TYPE ((uint32_t)0x00000010)
#define GPIO_NUMBER ((uint32_t)16)
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/** @defgroup GPIO_Private_Functions
* @{
*/
/** @defgroup GPIO_Group1 Initialization and de-initialization functions
* @brief Initialization and Configuration functions
*
@verbatim
===============================================================================
##### Initialization and de-initialization functions #####
===============================================================================
@endverbatim
* @{
*/
/**
* @brief Initializes the GPIOx peripheral according to the specified parameters in the GPIO_Init.
* @param GPIOx: where x can be (A..D and H) to select the GPIO peripheral for STM32L0XX family devices.
* @param GPIO_Init: pointer to a GPIO_InitTypeDef structure that contains
* the configuration information for the specified GPIO peripheral.
* @retval None
*/
void HAL_GPIO_Init(GPIO_TypeDef *GPIOx, GPIO_InitTypeDef *GPIO_Init)
{
uint32_t position;
uint32_t ioposition = 0x00;
uint32_t iocurrent = 0x00;
uint32_t temp = 0x00;
/* Check the parameters */
assert_param(IS_GPIO_PIN(GPIO_Init->Pin));
assert_param(IS_GPIO_MODE(GPIO_Init->Mode));
assert_param(IS_GPIO_PULL(GPIO_Init->Pull));
/* Configure the port pins */
for(position = 0; position < GPIO_NUMBER; position++)
{
/* Get the IO position */
ioposition = ((uint32_t)0x01) << position;
/* Get the current IO position */
iocurrent = (uint32_t)(GPIO_Init->Pin) & ioposition;
if(iocurrent == ioposition)
{
/*--------------------- GPIO Mode Configuration ------------------------*/
/* In case of Alternate function mode selection */
if((GPIO_Init->Mode == GPIO_MODE_AF_PP) || (GPIO_Init->Mode == GPIO_MODE_AF_OD))
{
/* Check the Alternate function parameter */
assert_param(IS_GPIO_AF(GPIO_Init->Alternate));
/* Configure Alternate function mapped with the current IO */
temp = GPIOx->AFR[position >> 3];
temp &= ~((uint32_t)0xF << ((uint32_t)(position & (uint32_t)0x07) * 4)) ;
temp |= ((uint32_t)(GPIO_Init->Alternate) << (((uint32_t)position & (uint32_t)0x07) * 4)) ;
GPIOx->AFR[position >> 3] = temp;
}
/* In case of Output or Alternate function mode selection */
if((GPIO_Init->Mode == GPIO_MODE_OUTPUT_PP) || (GPIO_Init->Mode == GPIO_MODE_AF_PP) ||
(GPIO_Init->Mode == GPIO_MODE_OUTPUT_OD) || (GPIO_Init->Mode == GPIO_MODE_AF_OD))
{
/* Check the Speed parameter */
assert_param(IS_GPIO_SPEED(GPIO_Init->Speed));
/* Configure the IO Speed */
temp = GPIOx->OSPEEDR;
temp &= ~(GPIO_OSPEEDER_OSPEED0 << (position * 2));
temp |= (GPIO_Init->Speed << (position * 2));
GPIOx->OSPEEDR = temp;
/* Configure the IO Output Type */
temp= GPIOx->OTYPER;
temp &= ~(GPIO_OTYPER_OT_0 << position) ;
temp |= (((GPIO_Init->Mode & GPIO_OUTPUT_TYPE) >> 4) << position);
GPIOx->OTYPER = temp;
}
/* Configure IO Direction mode (Input, Output, Alternate or Analog) */
temp = GPIOx->MODER;
temp &= ~(GPIO_MODER_MODE0 << (position * 2));
temp |= ((GPIO_Init->Mode & GPIO_MODE) << (position * 2));
GPIOx->MODER = temp;
/* Activate the Pull-up or Pull down resistor for the current IO */
temp = GPIOx->PUPDR;
temp &= ~(GPIO_PUPDR_PUPD0 << (position * 2));
temp |= ((GPIO_Init->Pull) << (position * 2));
GPIOx->PUPDR = temp;
/*--------------------- EXTI Mode Configuration ------------------------*/
/* Configure the External Interrupt or event for the current IO */
if((GPIO_Init->Mode & EXTI_MODE) == EXTI_MODE)
{
/* Enable SYSCFG Clock */
__SYSCFG_CLK_ENABLE();
temp = SYSCFG->EXTICR[position >> 2];
temp &= ~((uint32_t)0x0F) << (4 * (position & 0x03));
temp |= ((uint32_t)(GET_GPIO_SOURCE(GPIOx)) << (4 * (position & 0x03)));
SYSCFG->EXTICR[position >> 2] = temp;
/* Clear EXTI line configuration */
temp = EXTI->IMR;
temp &= ~((uint32_t)iocurrent);
if((GPIO_Init->Mode & GPIO_MODE_IT) == GPIO_MODE_IT)
{
temp |= iocurrent;
}
EXTI->IMR = temp;
temp = EXTI->EMR;
temp &= ~((uint32_t)iocurrent);
if((GPIO_Init->Mode & GPIO_MODE_EVT) == GPIO_MODE_EVT)
{
temp |= iocurrent;
}
EXTI->EMR = temp;
/* Clear Rising Falling edge configuration */
temp = EXTI->RTSR;
temp &= ~((uint32_t)iocurrent);
if((GPIO_Init->Mode & RISING_EDGE) == RISING_EDGE)
{
temp |= iocurrent;
}
EXTI->RTSR = temp;
temp = EXTI->FTSR;
temp &= ~((uint32_t)iocurrent);
if((GPIO_Init->Mode & FALLING_EDGE) == FALLING_EDGE)
{
temp |= iocurrent;
}
EXTI->FTSR = temp;
}
}
}
}
/**
* @brief De-initializes the GPIOx peripheral registers to their default reset values.
* @param GPIOx: where x can be (A..D and H) to select the GPIO peripheral for STM32L0XX family 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) except for GPIOD(2) and GPIOH(1:0).
* @retval None
*/
void HAL_GPIO_DeInit(GPIO_TypeDef *GPIOx, uint32_t GPIO_Pin)
{
uint32_t position;
uint32_t ioposition = 0x00;
uint32_t iocurrent = 0x00;
uint32_t tmp = 0x00;
/* Configure the port pins */
for(position = 0; position < GPIO_NUMBER; position++)
{
/* Get the IO position */
ioposition = ((uint32_t)0x01) << position;
/* Get the current IO position */
iocurrent = (GPIO_Pin) & ioposition;
if(iocurrent == ioposition)
{
/*------------------------- GPIO Mode Configuration --------------------*/
/* Configure IO Direction in Input Floting Mode */
GPIOx->MODER &= ~(GPIO_MODER_MODE0 << (position * 2));
/* Configure the default Alternate Function in current IO */
GPIOx->AFR[position >> 3] &= ~((uint32_t)0xF << ((uint32_t)(position & (uint32_t)0x07) * 4)) ;
/* Configure the default value for IO Speed */
GPIOx->OSPEEDR &= ~(GPIO_OSPEEDER_OSPEED0 << (position * 2));
/* Configure the default value IO Output Type */
GPIOx->OTYPER &= ~(GPIO_OTYPER_OT_0 << position) ;
/* Deactivate the Pull-up oand Pull-down resistor for the current IO */
GPIOx->PUPDR &= ~(GPIO_PUPDR_PUPD0 << (position * 2));
/*------------------------- EXTI Mode Configuration --------------------*/
/* Configure the External Interrupt or event for the current IO */
tmp = ((uint32_t)0x0F) << (4 * (position & 0x03));
SYSCFG->EXTICR[position >> 2] &= ~tmp;
/* Clear EXTI line configuration */
EXTI->IMR &= ~((uint32_t)iocurrent);
EXTI->EMR &= ~((uint32_t)iocurrent);
/* Clear Rising Falling edge configuration */
EXTI->RTSR &= ~((uint32_t)iocurrent);
EXTI->FTSR &= ~((uint32_t)iocurrent);
}
}
}
/**
* @}
*/
/** @defgroup GPIO_Group2 IO operation functions
* @brief GPIO Read and Write
*
@verbatim
===============================================================================
##### IO operation functions #####
===============================================================================
@endverbatim
* @{
*/
/**
* @brief Reads the specified input port pin.
* @param GPIOx: where x can be (A..D and H) to select the GPIO peripheral for STM32L0xx family devices.
* @param GPIO_Pin: specifies the port bit to read.
* This parameter can be GPIO_PIN_x where x can be (0..15) except for GPIOD(2) and GPIOH(1:0).
* @retval The input port pin value.
*/
GPIO_PinState HAL_GPIO_ReadPin(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin)
{
GPIO_PinState bitstatus;
/* Check the parameters */
assert_param(IS_GPIO_PIN(GPIO_Pin));
if((GPIOx->IDR & GPIO_Pin) != (uint32_t)GPIO_PIN_RESET)
{
bitstatus = GPIO_PIN_SET;
}
else
{
bitstatus = GPIO_PIN_RESET;
}
return bitstatus;
}
/**
* @brief Sets or clears the selected data port bit.
*
* @note This function 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..D and H) to select the GPIO peripheral for STM32L0xx family 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) except for GPIOD(2) and GPIOH(1:0).
* @param PinState: specifies the value to be written to the selected bit.
* This parameter can be one of the GPIO_PinState enum values:
* GPIO_PIN_RESET: to clear the port pin
* GPIO_PIN_SET: to set the port pin
* @retval None
*/
void HAL_GPIO_WritePin(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin, GPIO_PinState PinState)
{
/* Check the parameters */
assert_param(IS_GPIO_PIN(GPIO_Pin));
assert_param(IS_GPIO_PIN_ACTION(PinState));
if(PinState != GPIO_PIN_RESET)
{
GPIOx->BSRR = GPIO_Pin;
}
else
{
GPIOx->BRR = GPIO_Pin ;
}
}
/**
* @brief Toggles the specified GPIO pins.
* @param GPIOx: Where x can be (A..D and H) to select the GPIO peripheral for STM32L0xx family devices.
* @param GPIO_Pin: Specifies the pins to be toggled.
* @retval None
*/
void HAL_GPIO_TogglePin(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin)
{
/* Check the parameters */
assert_param(IS_GPIO_PIN(GPIO_Pin));
GPIOx->ODR ^= GPIO_Pin;
}
/**
* @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..D and H) to select the GPIO peripheral for STM32F3 family
* @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
*/
HAL_StatusTypeDef HAL_GPIO_LockPin(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin)
{
__IO uint32_t tmp = GPIO_LCKR_LCKK;
/* Check the parameters */
assert_param(IS_GPIO_PIN(GPIO_Pin));
/* Apply lock key write sequence */
tmp |= GPIO_Pin;
/* Set LCKx bit(s): LCKK='1' + LCK[15-0] */
GPIOx->LCKR = tmp;
/* Reset LCKx bit(s): LCKK='0' + LCK[15-0] */
GPIOx->LCKR = GPIO_Pin;
/* Set LCKx bit(s): LCKK='1' + LCK[15-0] */
GPIOx->LCKR = tmp;
/* Read LCKK bit*/
tmp = GPIOx->LCKR;
if((GPIOx->LCKR & GPIO_LCKR_LCKK) != RESET)
{
return HAL_OK;
}
else
{
return HAL_ERROR;
}
}
/**
* @brief This function handles EXTI interrupt request.
* @param GPIO_Pin: Specifies the pins connected EXTI line
* @retval None
*/
void HAL_GPIO_EXTI_IRQHandler(uint16_t GPIO_Pin)
{
/* EXTI line interrupt detected */
if(__HAL_GPIO_EXTI_GET_IT(GPIO_Pin) != RESET)
{
__HAL_GPIO_EXTI_CLEAR_IT(GPIO_Pin);
HAL_GPIO_EXTI_Callback(GPIO_Pin);
}
}
/**
* @brief EXTI line detection callbacks.
* @param GPIO_Pin: Specifies the pins connected EXTI line
* @retval None
*/
__weak void HAL_GPIO_EXTI_Callback(uint16_t GPIO_Pin)
{
/* NOTE: This function Should not be modified, when the callback is needed,
the HAL_GPIO_EXTI_Callback could be implemented in the user file
*/
}
/**
* @}
*/
/**
* @}
*/
#endif /* HAL_GPIO_MODULE_ENABLED */
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,271 @@
/**
******************************************************************************
* @file stm32l0xx_hal_gpio.h
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief Header file of GPIO HAL module.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32L0xx_HAL_GPIO_H
#define __STM32L0xx_HAL_GPIO_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal_def.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @addtogroup GPIO
* @{
*/
/* Exported types ------------------------------------------------------------*/
/**
* @brief GPIO Init structure definition
*/
typedef struct
{
uint32_t Pin; /*!< Specifies the GPIO pins to be configured.
This parameter can be any value of @ref GPIO_pins_define */
uint32_t Mode; /*!< Specifies the operating mode for the selected pins.
This parameter can be a value of @ref GPIO_mode_define */
uint32_t Pull; /*!< Specifies the Pull-up or Pull-Down activation for the selected pins.
This parameter can be a value of @ref GPIO_pull_define */
uint32_t Speed; /*!< Specifies the speed for the selected pins.
This parameter can be a value of @ref GPIO_speed_define */
uint32_t Alternate; /*!< Peripheral to be connected to the selected pins
This parameter can be a value of @ref GPIOEx_Alternate_function_selection */
}GPIO_InitTypeDef;
/**
* @brief GPIO Bit SET and Bit RESET enumeration
*/
typedef enum
{
GPIO_PIN_RESET = 0,
GPIO_PIN_SET
}GPIO_PinState;
#define IS_GPIO_PIN_ACTION(ACTION) (((ACTION) == GPIO_PIN_RESET) || ((ACTION) == GPIO_PIN_SET))
/* Exported constants --------------------------------------------------------*/
/** @defgroup GPIO_Exported_Constants
* @{
*/
/** @defgroup GPIO_pins_define
* @{
*/
#define GPIO_PIN_0 ((uint16_t)0x0001) /* Pin 0 selected */
#define GPIO_PIN_1 ((uint16_t)0x0002) /* Pin 1 selected */
#define GPIO_PIN_2 ((uint16_t)0x0004) /* Pin 2 selected */
#define GPIO_PIN_3 ((uint16_t)0x0008) /* Pin 3 selected */
#define GPIO_PIN_4 ((uint16_t)0x0010) /* Pin 4 selected */
#define GPIO_PIN_5 ((uint16_t)0x0020) /* Pin 5 selected */
#define GPIO_PIN_6 ((uint16_t)0x0040) /* Pin 6 selected */
#define GPIO_PIN_7 ((uint16_t)0x0080) /* Pin 7 selected */
#define GPIO_PIN_8 ((uint16_t)0x0100) /* Pin 8 selected */
#define GPIO_PIN_9 ((uint16_t)0x0200) /* Pin 9 selected */
#define GPIO_PIN_10 ((uint16_t)0x0400) /* Pin 10 selected */
#define GPIO_PIN_11 ((uint16_t)0x0800) /* Pin 11 selected */
#define GPIO_PIN_12 ((uint16_t)0x1000) /* Pin 12 selected */
#define GPIO_PIN_13 ((uint16_t)0x2000) /* Pin 13 selected */
#define GPIO_PIN_14 ((uint16_t)0x4000) /* Pin 14 selected */
#define GPIO_PIN_15 ((uint16_t)0x8000) /* Pin 15 selected */
#define GPIO_PIN_All ((uint16_t)0xFFFF) /* All pins selected */
#define GPIO_PIN_MASK ((uint32_t)0x0000FFFF) /* PIN mask for assert test */
#define IS_GPIO_PIN(PIN) (((PIN) & GPIO_PIN_MASK ) != (uint32_t)0x00)
/**
* @}
*/
/** @defgroup GPIO_mode_define
* @brief GPIO Configuration Mode
* Elements values convention: 0xX0yz00YZ
* - X : GPIO mode or EXTI Mode
* - y : External IT or Event trigger detection
* - z : IO configuration on External IT or Event
* - Y : Output type (Push Pull or Open Drain)
* - Z : IO Direction mode (Input, Output, Alternate or Analog)
* @{
*/
#define GPIO_MODE_INPUT ((uint32_t)0x00000000) /*!< Input Floating Mode */
#define GPIO_MODE_OUTPUT_PP ((uint32_t)0x00000001) /*!< Output Push Pull Mode */
#define GPIO_MODE_OUTPUT_OD ((uint32_t)0x00000011) /*!< Output Open Drain Mode */
#define GPIO_MODE_AF_PP ((uint32_t)0x00000002) /*!< Alternate Function Push Pull Mode */
#define GPIO_MODE_AF_OD ((uint32_t)0x00000012) /*!< Alternate Function Open Drain Mode */
#define GPIO_MODE_ANALOG ((uint32_t)0x00000003) /*!< Analog Mode */
#define GPIO_MODE_IT_RISING ((uint32_t)0x10110000) /*!< External Interrupt Mode with Rising edge trigger detection */
#define GPIO_MODE_IT_FALLING ((uint32_t)0x10210000) /*!< External Interrupt Mode with Falling edge trigger detection */
#define GPIO_MODE_IT_RISING_FALLING ((uint32_t)0x10310000) /*!< External Interrupt Mode with Rising/Falling edge trigger detection */
#define GPIO_MODE_EVT_RISING ((uint32_t)0x10120000) /*!< External Event Mode with Rising edge trigger detection */
#define GPIO_MODE_EVT_FALLING ((uint32_t)0x10220000) /*!< External Event Mode with Falling edge trigger detection */
#define GPIO_MODE_EVT_RISING_FALLING ((uint32_t)0x10320000) /*!< External Event Mode with Rising/Falling edge trigger detection */
#define IS_GPIO_MODE(MODE) (((MODE) == GPIO_MODE_INPUT) ||\
((MODE) == GPIO_MODE_OUTPUT_PP) ||\
((MODE) == GPIO_MODE_OUTPUT_OD) ||\
((MODE) == GPIO_MODE_AF_PP) ||\
((MODE) == GPIO_MODE_AF_OD) ||\
((MODE) == GPIO_MODE_IT_RISING) ||\
((MODE) == GPIO_MODE_IT_FALLING) ||\
((MODE) == GPIO_MODE_IT_RISING_FALLING) ||\
((MODE) == GPIO_MODE_EVT_RISING) ||\
((MODE) == GPIO_MODE_EVT_FALLING) ||\
((MODE) == GPIO_MODE_EVT_RISING_FALLING) ||\
((MODE) == GPIO_MODE_ANALOG))
/**
* @}
*/
/** @defgroup GPIO_speed_define
* @brief GPIO Output Maximum frequency
* @{
*/
#define GPIO_SPEED_LOW ((uint32_t)0x00000000) /*!< Low speed */
#define GPIO_SPEED_MEDIUM ((uint32_t)0x00000001) /*!< Medium speed */
#define GPIO_SPEED_FAST ((uint32_t)0x00000002) /*!< Fast speed */
#define GPIO_SPEED_HIGH ((uint32_t)0x00000003) /*!< High speed */
#define IS_GPIO_SPEED(SPEED) (((SPEED) == GPIO_SPEED_LOW) || ((SPEED) == GPIO_SPEED_MEDIUM) || \
((SPEED) == GPIO_SPEED_FAST) || ((SPEED) == GPIO_SPEED_HIGH))
/**
* @}
*/
/** @defgroup GPIO_pull_define
* @brief GPIO Pull-Up or Pull-Down Activation
* @{
*/
#define GPIO_NOPULL ((uint32_t)0x00000000) /*!< No Pull-up or Pull-down activation */
#define GPIO_PULLUP ((uint32_t)0x00000001) /*!< Pull-up activation */
#define GPIO_PULLDOWN ((uint32_t)0x00000002) /*!< Pull-down activation */
#define IS_GPIO_PULL(PULL) (((PULL) == GPIO_NOPULL) || ((PULL) == GPIO_PULLUP) || \
((PULL) == GPIO_PULLDOWN))
/**
* @}
*/
/**
* @}
*/
/* Exported macro ------------------------------------------------------------*/
/**
* @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 GPIO_PIN_x where x can be(0..15)
* @retval The new state of __EXTI_LINE__ (SET or RESET).
*/
#define __HAL_GPIO_EXTI_GET_FLAG(__EXTI_LINE__) (EXTI->PR & (__EXTI_LINE__))
/**
* @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 GPIO_PIN_x where x can be (0..15)
* @retval None
*/
#define __HAL_GPIO_EXTI_CLEAR_FLAG(__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 GPIO_PIN_x where x can be(0..15)
* @retval The new state of __EXTI_LINE__ (SET or RESET).
*/
#define __HAL_GPIO_EXTI_GET_IT(__EXTI_LINE__) (EXTI->PR & (__EXTI_LINE__))
/**
* @brief Clears the EXTI's line pending bits.
* @param __EXTI_LINE__: specifies the EXTI lines to clear.
* This parameter can be any combination of GPIO_PIN_x where x can be (0..15)
* @retval None
*/
#define __HAL_GPIO_EXTI_CLEAR_IT(__EXTI_LINE__) (EXTI->PR = (__EXTI_LINE__))
/**
* @brief Generates a Software interrupt on selected EXTI line.
* @param __EXTI_LINE__: specifies the EXTI line to check.
* This parameter can be GPIO_PIN_x where x can be(0..15)
* @retval None
*/
#define __HAL_GPIO_EXTI_GENERATE_SWIT(__EXTI_LINE__) (EXTI->SWIER |= (__EXTI_LINE__))
/* Include GPIO HAL Extension module */
#include "stm32l0xx_hal_gpio_ex.h"
/* Exported functions --------------------------------------------------------*/
/* Initialization and de-initialization functions *******************************/
void HAL_GPIO_Init(GPIO_TypeDef *GPIOx, GPIO_InitTypeDef *GPIO_Init);
void HAL_GPIO_DeInit(GPIO_TypeDef *GPIOx, uint32_t GPIO_Pin);
/* IO operation functions *******************************************************/
GPIO_PinState HAL_GPIO_ReadPin(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin);
void HAL_GPIO_WritePin(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin, GPIO_PinState PinState);
void HAL_GPIO_TogglePin(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin);
HAL_StatusTypeDef HAL_GPIO_LockPin(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin);
void HAL_GPIO_EXTI_IRQHandler(uint16_t GPIO_Pin);
void HAL_GPIO_EXTI_Callback(uint16_t GPIO_Pin);
/**
* @}
*/
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif /* __STM32L0xx_HAL_GPIO_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,428 @@
/**
******************************************************************************
* @file stm32l0xx_hal_gpio_ex.h
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief Header file of GPIO HAL Extension module.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32L0xx_HAL_GPIO_EX_H
#define __STM32L0xx_HAL_GPIO_EX_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal_def.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @addtogroup GPIOEx
* @{
*/
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
/** @defgroup GPIOEx_Exported_Constants
* @{
*/
/** @defgroup GPIOEx_Alternate_function_selection
* @{
*/
/*------------------------- STM32L053xx/STM32L063xx---------------------------*/
#if defined (STM32L053xx) || defined (STM32L063xx)
/**
* @brief AF 0 selection
*/
#define GPIO_AF0_SPI1 ((uint8_t)0x00) /* SPI1 Alternate Function mapping */
#define GPIO_AF0_SPI2 ((uint8_t)0x00) /* SPI2 Alternate Function mapping */
#define GPIO_AF0_USART1 ((uint8_t)0x00) /* USART1 Alternate Function mapping */
#define GPIO_AF0_USART2 ((uint8_t)0x00) /* USART2 Alternate Function mapping */
#define GPIO_AF0_LPUART1 ((uint8_t)0x00) /* LPUART1 Alternate Function mapping */
#define GPIO_AF0_USB ((uint8_t)0x00) /* USB Alternate Function mapping */
#define GPIO_AF0_LPTIM ((uint8_t)0x00) /* LPTIM Alternate Function mapping */
#define GPIO_AF0_TSC ((uint8_t)0x00) /* TSC Alternate Function mapping */
#define GPIO_AF0_TIM2 ((uint8_t)0x00) /* TIM2 Alternate Function mapping */
#define GPIO_AF0_TIM21 ((uint8_t)0x00) /* TIM21 Alternate Function mapping */
#define GPIO_AF0_TIM22 ((uint8_t)0x00) /* TIM22 Alternate Function mapping */
#define GPIO_AF0_EVENTOUT ((uint8_t)0x00) /* EVENTOUT Alternate Function mapping */
#define GPIO_AF0_MCO ((uint8_t)0x00) /* MCO Alternate Function mapping */
#define GPIO_AF0_SWDIO ((uint8_t)0x00) /* SWDIO Alternate Function mapping */
#define GPIO_AF0_SWCLK ((uint8_t)0x00) /* SWCLK Alternate Function mapping */
/**
* @brief AF 1 selection
*/
#define GPIO_AF1_SPI1 ((uint8_t)0x01) /* SPI1 Alternate Function mapping */
#define GPIO_AF1_SPI2 ((uint8_t)0x01) /* SPI2 Alternate Function mapping */
#define GPIO_AF1_I2C1 ((uint8_t)0x01) /* I2C1 Alternate Function mapping */
#define GPIO_AF1_LCD ((uint8_t)0x01) /* LCD Alternate Function mapping */
#define GPIO_AF1_TIM2 ((uint8_t)0x01) /* TIM2 Alternate Function mapping */
#define GPIO_AF1_TIM21 ((uint8_t)0x01) /* TIM21 Alternate Function mapping */
/**
* @brief AF 2 selection
*/
#define GPIO_AF2_SPI2 ((uint8_t)0x02) /* SPI2 Alternate Function mapping */
#define GPIO_AF2_LPUART1 ((uint8_t)0x02) /* LPUART1 Alternate Function mapping */
#define GPIO_AF2_USB ((uint8_t)0x02) /* USB Alternate Function mapping */
#define GPIO_AF2_LPTIM ((uint8_t)0x02) /* LPTIM Alternate Function mapping */
#define GPIO_AF2_TIM2 ((uint8_t)0x02) /* TIM2 Alternate Function mapping */
#define GPIO_AF2_TIM22 ((uint8_t)0x02) /* TIM22 Alternate Function mapping */
#define GPIO_AF2_EVENTOUT ((uint8_t)0x02) /* EVENTOUT Alternate Function mapping */
#define GPIO_AF2_RTC_50Hz ((uint8_t)0x02) /* RTC_OUT Alternate Function mapping */
/**
* @brief AF 3 selection
*/
#define GPIO_AF3_I2C1 ((uint8_t)0x03) /* I2C1 Alternate Function mapping */
#define GPIO_AF3_TSC ((uint8_t)0x03) /* TSC Alternate Function mapping */
#define GPIO_AF3_EVENTOUT ((uint8_t)0x03) /* EVENTOUT Alternate Function mapping */
/**
* @brief AF 4 selection
*/
#define GPIO_AF4_I2C1 ((uint8_t)0x04) /* I2C1 Alternate Function mapping */
#define GPIO_AF4_USART1 ((uint8_t)0x04) /* USART1 Alternate Function mapping */
#define GPIO_AF4_USART2 ((uint8_t)0x04) /* USART2 Alternate Function mapping */
#define GPIO_AF4_LPUART1 ((uint8_t)0x04) /* LPUART1 Alternate Function mapping */
#define GPIO_AF4_TIM22 ((uint8_t)0x04) /* TIM22 Alternate Function mapping */
#define GPIO_AF4_EVENTOUT ((uint8_t)0x04) /* EVENTOUT Alternate Function mapping */
/**
* @brief AF 5 selection
*/
#define GPIO_AF5_SPI2 ((uint8_t)0x05) /* SPI2 Alternate Function mapping */
#define GPIO_AF5_I2C2 ((uint8_t)0x05) /* I2C2 Alternate Function mapping */
#define GPIO_AF5_TIM2 ((uint8_t)0x05) /* TIM2 Alternate Function mapping */
#define GPIO_AF5_TIM21 ((uint8_t)0x05) /* TIM21 Alternate Function mapping */
#define GPIO_AF5_TIM22 ((uint8_t)0x05) /* TIM22 Alternate Function mapping */
/**
* @brief AF 6 selection
*/
#define GPIO_AF6_I2C2 ((uint8_t)0x06) /* I2C2 Alternate Function mapping */
#define GPIO_AF6_TIM21 ((uint8_t)0x06) /* TIM21 Alternate Function mapping */
#define GPIO_AF6_EVENTOUT ((uint8_t)0x06) /* EVENTOUT Alternate Function mapping */
/**
* @brief AF 7 selection
*/
#define GPIO_AF7_COMP1 ((uint8_t)0x07) /* COMP1 Alternate Function mapping */
#define GPIO_AF7_COMP2 ((uint8_t)0x07) /* COMP2 Alternate Function mapping */
#define IS_GPIO_AF(AF) (((AF) == GPIO_AF0_SPI1) || ((AF) == GPIO_AF2_SPI2) || \
((AF) == GPIO_AF0_SPI2) || ((AF) == GPIO_AF2_LPUART1) || \
((AF) == GPIO_AF0_USART1) || ((AF) == GPIO_AF2_USB) || \
((AF) == GPIO_AF0_USART2) || ((AF) == GPIO_AF2_LPTIM) || \
((AF) == GPIO_AF0_LPUART1) || ((AF) == GPIO_AF2_TIM2) || \
((AF) == GPIO_AF0_USB) || ((AF) == GPIO_AF2_TIM22) || \
((AF) == GPIO_AF0_LPTIM) || ((AF) == GPIO_AF2_EVENTOUT) || \
((AF) == GPIO_AF0_TSC) || ((AF) == GPIO_AF2_RTC_50Hz) || \
((AF) == GPIO_AF0_TIM2) || ((AF) == GPIO_AF3_I2C1) || \
((AF) == GPIO_AF0_TIM21) || ((AF) == GPIO_AF3_TSC) || \
((AF) == GPIO_AF0_TIM22) || ((AF) == GPIO_AF3_EVENTOUT) || \
((AF) == GPIO_AF0_EVENTOUT) || ((AF) == GPIO_AF4_I2C1) || \
((AF) == GPIO_AF0_MCO) || ((AF) == GPIO_AF4_USART1) || \
((AF) == GPIO_AF0_SWDIO) || ((AF) == GPIO_AF0_SWCLK) || \
((AF) == GPIO_AF1_SPI1) || ((AF) == GPIO_AF4_USART2) || \
((AF) == GPIO_AF1_SPI2) || ((AF) == GPIO_AF4_LPUART1) || \
((AF) == GPIO_AF1_TIM2) || ((AF) == GPIO_AF4_TIM22) || \
((AF) == GPIO_AF1_I2C1) || ((AF) == GPIO_AF4_EVENTOUT) || \
((AF) == GPIO_AF1_LCD) || ((AF) == GPIO_AF5_SPI2) || \
((AF) == GPIO_AF5_I2C2) || ((AF) == GPIO_AF5_TIM2) || \
((AF) == GPIO_AF5_TIM21) || ((AF) == GPIO_AF5_TIM22) || \
((AF) == GPIO_AF6_I2C2) || ((AF) == GPIO_AF6_TIM21) || \
((AF) == GPIO_AF6_EVENTOUT) || ((AF) == GPIO_AF7_COMP1) || \
((AF) == GPIO_AF7_COMP2) || ((AF) == GPIO_AF1_TIM21))
#endif /* STM32L053xx || STM32L063xx */
/*------------------------------------------------------------------------------------------*/
/*------------------------- STM32L052xx/STM32L062xx---------------------------*/
#if defined (STM32L052xx) || defined (STM32L062xx)
/**
* @brief AF 0 selection
*/
#define GPIO_AF0_SPI1 ((uint8_t)0x00) /* SPI1 Alternate Function mapping */
#define GPIO_AF0_SPI2 ((uint8_t)0x00) /* SPI2 Alternate Function mapping */
#define GPIO_AF0_USART1 ((uint8_t)0x00) /* USART1 Alternate Function mapping */
#define GPIO_AF0_USART2 ((uint8_t)0x00) /* USART2 Alternate Function mapping */
#define GPIO_AF0_LPUART1 ((uint8_t)0x00) /* LPUART1 Alternate Function mapping */
#define GPIO_AF0_USB ((uint8_t)0x00) /* USB Alternate Function mapping */
#define GPIO_AF0_LPTIM ((uint8_t)0x00) /* LPTIM Alternate Function mapping */
#define GPIO_AF0_TSC ((uint8_t)0x00) /* TSC Alternate Function mapping */
#define GPIO_AF0_TIM2 ((uint8_t)0x00) /* TIM2 Alternate Function mapping */
#define GPIO_AF0_TIM21 ((uint8_t)0x00) /* TIM21 Alternate Function mapping */
#define GPIO_AF0_TIM22 ((uint8_t)0x00) /* TIM22 Alternate Function mapping */
#define GPIO_AF0_EVENTOUT ((uint8_t)0x00) /* EVENTOUT Alternate Function mapping */
#define GPIO_AF0_MCO ((uint8_t)0x00) /* MCO Alternate Function mapping */
#define GPIO_AF0_SWDIO ((uint8_t)0x00) /* SWDIO Alternate Function mapping */
#define GPIO_AF0_SWCLK ((uint8_t)0x00) /* SWCLK Alternate Function mapping */
/**
* @brief AF 1 selection
*/
#define GPIO_AF1_SPI1 ((uint8_t)0x01) /* SPI1 Alternate Function mapping */
#define GPIO_AF1_SPI2 ((uint8_t)0x01) /* SPI2 Alternate Function mapping */
#define GPIO_AF1_I2C1 ((uint8_t)0x01) /* I2C1 Alternate Function mapping */
#define GPIO_AF1_TIM2 ((uint8_t)0x01) /* TIM2 Alternate Function mapping */
#define GPIO_AF1_TIM21 ((uint8_t)0x01) /* TIM21 Alternate Function mapping */
/**
* @brief AF 2 selection
*/
#define GPIO_AF2_SPI2 ((uint8_t)0x02) /* SPI2 Alternate Function mapping */
#define GPIO_AF2_LPUART1 ((uint8_t)0x02) /* LPUART1 Alternate Function mapping */
#define GPIO_AF2_USB ((uint8_t)0x02) /* USB Alternate Function mapping */
#define GPIO_AF2_LPTIM ((uint8_t)0x02) /* LPTIM Alternate Function mapping */
#define GPIO_AF2_TIM2 ((uint8_t)0x02) /* TIM2 Alternate Function mapping */
#define GPIO_AF2_TIM22 ((uint8_t)0x02) /* TIM22 Alternate Function mapping */
#define GPIO_AF2_EVENTOUT ((uint8_t)0x02) /* EVENTOUT Alternate Function mapping */
#define GPIO_AF2_RTC_50Hz ((uint8_t)0x02) /* RTC_OUT Alternate Function mapping */
/**
* @brief AF 3 selection
*/
#define GPIO_AF3_I2C1 ((uint8_t)0x03) /* I2C1 Alternate Function mapping */
#define GPIO_AF3_TSC ((uint8_t)0x03) /* TSC Alternate Function mapping */
#define GPIO_AF3_EVENTOUT ((uint8_t)0x03) /* EVENTOUT Alternate Function mapping */
/**
* @brief AF 4 selection
*/
#define GPIO_AF4_I2C1 ((uint8_t)0x04) /* I2C1 Alternate Function mapping */
#define GPIO_AF4_USART1 ((uint8_t)0x04) /* USART1 Alternate Function mapping */
#define GPIO_AF4_USART2 ((uint8_t)0x04) /* USART2 Alternate Function mapping */
#define GPIO_AF4_LPUART1 ((uint8_t)0x04) /* LPUART1 Alternate Function mapping */
#define GPIO_AF4_TIM22 ((uint8_t)0x04) /* TIM22 Alternate Function mapping */
#define GPIO_AF4_EVENTOUT ((uint8_t)0x04) /* EVENTOUT Alternate Function mapping */
/**
* @brief AF 5 selection
*/
#define GPIO_AF5_SPI2 ((uint8_t)0x05) /* SPI2 Alternate Function mapping */
#define GPIO_AF5_I2C2 ((uint8_t)0x05) /* I2C2 Alternate Function mapping */
#define GPIO_AF5_TIM2 ((uint8_t)0x05) /* TIM2 Alternate Function mapping */
#define GPIO_AF5_TIM21 ((uint8_t)0x05) /* TIM21 Alternate Function mapping */
#define GPIO_AF5_TIM22 ((uint8_t)0x05) /* TIM22 Alternate Function mapping */
/**
* @brief AF 6 selection
*/
#define GPIO_AF6_I2C2 ((uint8_t)0x06) /* I2C2 Alternate Function mapping */
#define GPIO_AF6_TIM21 ((uint8_t)0x06) /* TIM21 Alternate Function mapping */
#define GPIO_AF6_EVENTOUT ((uint8_t)0x06) /* EVENTOUT Alternate Function mapping */
/**
* @brief AF 7 selection
*/
#define GPIO_AF7_COMP1 ((uint8_t)0x07) /* COMP1 Alternate Function mapping */
#define GPIO_AF7_COMP2 ((uint8_t)0x07) /* COMP2 Alternate Function mapping */
#define IS_GPIO_AF(AF) (((AF) == GPIO_AF0_SPI1) || ((AF) == GPIO_AF2_SPI2) || \
((AF) == GPIO_AF0_SPI2) || ((AF) == GPIO_AF2_LPUART1) || \
((AF) == GPIO_AF0_USART1) || ((AF) == GPIO_AF2_USB) || \
((AF) == GPIO_AF0_USART2) || ((AF) == GPIO_AF2_LPTIM) || \
((AF) == GPIO_AF0_LPUART1) || ((AF) == GPIO_AF2_TIM2) || \
((AF) == GPIO_AF0_USB) || ((AF) == GPIO_AF2_TIM22) || \
((AF) == GPIO_AF0_LPTIM) || ((AF) == GPIO_AF2_EVENTOUT) || \
((AF) == GPIO_AF0_TSC) || ((AF) == GPIO_AF2_RTC_50Hz) || \
((AF) == GPIO_AF0_TIM2) || ((AF) == GPIO_AF3_I2C1) || \
((AF) == GPIO_AF0_TIM21) || ((AF) == GPIO_AF3_TSC) || \
((AF) == GPIO_AF0_TIM22) || ((AF) == GPIO_AF3_EVENTOUT) || \
((AF) == GPIO_AF0_EVENTOUT) || ((AF) == GPIO_AF4_I2C1) || \
((AF) == GPIO_AF0_MCO) || ((AF) == GPIO_AF4_USART1) || \
((AF) == GPIO_AF0_SWDIO) || ((AF) == GPIO_AF0_SWCLK) || \
((AF) == GPIO_AF1_SPI1) || ((AF) == GPIO_AF4_USART2) || \
((AF) == GPIO_AF1_SPI2) || ((AF) == GPIO_AF4_LPUART1) || \
((AF) == GPIO_AF1_TIM2) || ((AF) == GPIO_AF4_TIM22) || \
((AF) == GPIO_AF1_I2C1) || ((AF) == GPIO_AF4_EVENTOUT) || \
((AF) == GPIO_AF6_EVENTOUT) || ((AF) == GPIO_AF5_SPI2) || \
((AF) == GPIO_AF5_I2C2) || ((AF) == GPIO_AF5_TIM2) || \
((AF) == GPIO_AF5_TIM21) || ((AF) == GPIO_AF5_TIM22) || \
((AF) == GPIO_AF6_I2C2) || ((AF) == GPIO_AF6_TIM21) || \
((AF) == GPIO_AF7_COMP2) || ((AF) == GPIO_AF7_COMP1) || \
((AF) == GPIO_AF1_TIM21))
#endif /* STM32L052xx || STM32L062xx */
/*------------------------------------------------------------------------------------------*/
/*------------------------- STM32L051xx/STM32L061xx---------------------------*/
#if defined (STM32L051xx)|| defined (STM32L061xx)
/**
* @brief AF 0 selection
*/
#define GPIO_AF0_SPI1 ((uint8_t)0x00) /* SPI1 Alternate Function mapping */
#define GPIO_AF0_SPI2 ((uint8_t)0x00) /* SPI2 Alternate Function mapping */
#define GPIO_AF0_USART1 ((uint8_t)0x00) /* USART1 Alternate Function mapping */
#define GPIO_AF0_USART2 ((uint8_t)0x00) /* USART2 Alternate Function mapping */
#define GPIO_AF0_LPUART1 ((uint8_t)0x00) /* LPUART1 Alternate Function mapping */
#define GPIO_AF0_LPTIM ((uint8_t)0x00) /* LPTIM Alternate Function mapping */
#define GPIO_AF0_TSC ((uint8_t)0x00) /* TSC Alternate Function mapping */
#define GPIO_AF0_TIM2 ((uint8_t)0x00) /* TIM2 Alternate Function mapping */
#define GPIO_AF0_TIM21 ((uint8_t)0x00) /* TIM21 Alternate Function mapping */
#define GPIO_AF0_TIM22 ((uint8_t)0x00) /* TIM22 Alternate Function mapping */
#define GPIO_AF0_EVENTOUT ((uint8_t)0x00) /* EVENTOUT Alternate Function mapping */
#define GPIO_AF0_MCO ((uint8_t)0x00) /* MCO Alternate Function mapping */
#define GPIO_AF0_SWDIO ((uint8_t)0x00) /* SWDIO Alternate Function mapping */
#define GPIO_AF0_SWCLK ((uint8_t)0x00) /* SWCLK Alternate Function mapping */
/**
* @brief AF 1 selection
*/
#define GPIO_AF1_SPI1 ((uint8_t)0x01) /* SPI1 Alternate Function mapping */
#define GPIO_AF1_SPI2 ((uint8_t)0x01) /* SPI2 Alternate Function mapping */
#define GPIO_AF1_I2C1 ((uint8_t)0x01) /* I2C1 Alternate Function mapping */
#define GPIO_AF1_TIM2 ((uint8_t)0x01) /* TIM2 Alternate Function mapping */
#define GPIO_AF1_TIM21 ((uint8_t)0x01) /* TIM21 Alternate Function mapping */
/**
* @brief AF 2 selection
*/
#define GPIO_AF2_SPI2 ((uint8_t)0x02) /* SPI2 Alternate Function mapping */
#define GPIO_AF2_LPUART1 ((uint8_t)0x02) /* LPUART1 Alternate Function mapping */
#define GPIO_AF2_LPTIM ((uint8_t)0x02) /* LPTIM Alternate Function mapping */
#define GPIO_AF2_TIM2 ((uint8_t)0x02) /* TIM2 Alternate Function mapping */
#define GPIO_AF2_TIM22 ((uint8_t)0x02) /* TIM22 Alternate Function mapping */
#define GPIO_AF2_EVENTOUT ((uint8_t)0x02) /* EVENTOUT Alternate Function mapping */
#define GPIO_AF2_RTC_50Hz ((uint8_t)0x02) /* RTC_OUT Alternate Function mapping */
/**
* @brief AF 3 selection
*/
#define GPIO_AF3_I2C1 ((uint8_t)0x03) /* I2C1 Alternate Function mapping */
#define GPIO_AF3_TSC ((uint8_t)0x03) /* TSC Alternate Function mapping */
#define GPIO_AF3_EVENTOUT ((uint8_t)0x03) /* EVENTOUT Alternate Function mapping */
/**
* @brief AF 4 selection
*/
#define GPIO_AF4_I2C1 ((uint8_t)0x04) /* I2C1 Alternate Function mapping */
#define GPIO_AF4_USART1 ((uint8_t)0x04) /* USART1 Alternate Function mapping */
#define GPIO_AF4_USART2 ((uint8_t)0x04) /* USART2 Alternate Function mapping */
#define GPIO_AF4_LPUART1 ((uint8_t)0x04) /* LPUART1 Alternate Function mapping */
#define GPIO_AF4_TIM22 ((uint8_t)0x04) /* TIM22 Alternate Function mapping */
#define GPIO_AF4_EVENTOUT ((uint8_t)0x04) /* EVENTOUT Alternate Function mapping */
/**
* @brief AF 5 selection
*/
#define GPIO_AF5_SPI2 ((uint8_t)0x05) /* SPI2 Alternate Function mapping */
#define GPIO_AF5_I2C2 ((uint8_t)0x05) /* I2C2 Alternate Function mapping */
#define GPIO_AF5_TIM2 ((uint8_t)0x05) /* TIM2 Alternate Function mapping */
#define GPIO_AF5_TIM21 ((uint8_t)0x05) /* TIM21 Alternate Function mapping */
#define GPIO_AF5_TIM22 ((uint8_t)0x05) /* TIM22 Alternate Function mapping */
/**
* @brief AF 6 selection
*/
#define GPIO_AF6_I2C2 ((uint8_t)0x06) /* I2C2 Alternate Function mapping */
#define GPIO_AF6_TIM21 ((uint8_t)0x06) /* TIM21 Alternate Function mapping */
#define GPIO_AF6_EVENTOUT ((uint8_t)0x06) /* EVENTOUT Alternate Function mapping */
/**
* @brief AF 7 selection
*/
#define GPIO_AF7_COMP1 ((uint8_t)0x07) /* COMP1 Alternate Function mapping */
#define GPIO_AF7_COMP2 ((uint8_t)0x07) /* COMP2 Alternate Function mapping */
#define IS_GPIO_AF(AF) (((AF) == GPIO_AF0_SPI1) || ((AF) == GPIO_AF2_SPI2) || \
((AF) == GPIO_AF0_SPI2) || ((AF) == GPIO_AF2_LPUART1) || \
((AF) == GPIO_AF0_USART1) || ((AF) == GPIO_AF2_TIM22) || \
((AF) == GPIO_AF0_USART2) || ((AF) == GPIO_AF2_LPTIM) || \
((AF) == GPIO_AF0_LPUART1) || ((AF) == GPIO_AF2_TIM2) || \
((AF) == GPIO_AF0_LPTIM) || ((AF) == GPIO_AF2_EVENTOUT) || \
((AF) == GPIO_AF1_TIM21) || ((AF) == GPIO_AF2_RTC_50Hz) || \
((AF) == GPIO_AF0_TIM2) || ((AF) == GPIO_AF3_I2C1) || \
((AF) == GPIO_AF0_TIM21) || ((AF) == GPIO_AF3_TSC) || \
((AF) == GPIO_AF0_TIM22) || ((AF) == GPIO_AF3_EVENTOUT) || \
((AF) == GPIO_AF0_EVENTOUT) || ((AF) == GPIO_AF4_I2C1) || \
((AF) == GPIO_AF0_MCO) || ((AF) == GPIO_AF4_USART1) || \
((AF) == GPIO_AF0_SWDIO) || ((AF) == GPIO_AF0_SWCLK) || \
((AF) == GPIO_AF1_SPI1) || ((AF) == GPIO_AF4_USART2) || \
((AF) == GPIO_AF1_SPI2) || ((AF) == GPIO_AF4_LPUART1) || \
((AF) == GPIO_AF1_TIM2) || ((AF) == GPIO_AF4_TIM22) || \
((AF) == GPIO_AF1_I2C1) || ((AF) == GPIO_AF4_EVENTOUT) || \
((AF) == GPIO_AF6_EVENTOUT) || ((AF) == GPIO_AF5_SPI2) || \
((AF) == GPIO_AF5_I2C2) || ((AF) == GPIO_AF5_TIM2) || \
((AF) == GPIO_AF5_TIM21) || ((AF) == GPIO_AF5_TIM22) || \
((AF) == GPIO_AF6_I2C2) || ((AF) == GPIO_AF6_TIM21) || \
((AF) == GPIO_AF7_COMP2) || ((AF) == GPIO_AF7_COMP1))
#endif /* STM32L051xx/STM32L061xx*/
/* Aliases define maintained for legacy */
#define GPIO_AF0_EVENOUT GPIO_AF0_EVENTOUT
#define GPIO_AF2_EVENOUT GPIO_AF2_EVENTOUT
#define GPIO_AF3_EVENOUT GPIO_AF3_EVENTOUT
#define GPIO_AF6_EVENOUT GPIO_AF6_EVENTOUT
/*------------------------------------------------------------------------------------------*/
/**
* @}
*/
/**
* @}
*/
/* Exported macro ------------------------------------------------------------*/
/* Exported functions --------------------------------------------------------*/
/**
* @}
*/
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif /* __STM32L0xx_HAL_GPIO_EX_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,496 @@
/**
******************************************************************************
* @file stm32l0xx_hal_i2c.h
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief Header file of I2C HAL module.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32L0xx_HAL_I2C_H
#define __STM32L0xx_HAL_I2C_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal_def.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @addtogroup I2C
* @{
*/
/* Exported types ------------------------------------------------------------*/
/**
* @brief I2C Configuration Structure definition
*/
typedef struct
{
uint32_t Timing; /*!< Specifies the I2C_TIMINGR_register value.
This parameter calculated by referring to I2C initialization
section in Reference manual */
uint32_t OwnAddress1; /*!< Specifies the first device own address.
This parameter can be a 7-bit or 10-bit address. */
uint32_t AddressingMode; /*!< Specifies if 7-bit or 10-bit addressing mode is selected.
This parameter can be a value of @ref I2C_addressing_mode */
uint32_t DualAddressMode; /*!< Specifies if dual addressing mode is selected.
This parameter can be a value of @ref I2C_dual_addressing_mode */
uint32_t OwnAddress2; /*!< Specifies the second device own address if dual addressing mode is selected
This parameter can be a 7-bit address. */
uint32_t OwnAddress2Masks; /*!< Specifies the acknoledge mask address second device own address if dual addressing mode is selected
This parameter can be a value of @ref I2C_own_address2_masks */
uint32_t GeneralCallMode; /*!< Specifies if general call mode is selected.
This parameter can be a value of @ref I2C_general_call_addressing_mode */
uint32_t NoStretchMode; /*!< Specifies if nostretch mode is selected.
This parameter can be a value of @ref I2C_nostretch_mode */
}I2C_InitTypeDef;
/**
* @brief HAL State structures definition
*/
typedef enum
{
HAL_I2C_STATE_RESET = 0x00, /*!< I2C not yet initialized or disabled */
HAL_I2C_STATE_READY = 0x01, /*!< I2C initialized and ready for use */
HAL_I2C_STATE_BUSY = 0x02, /*!< I2C internal process is ongoing */
HAL_I2C_STATE_MASTER_BUSY_TX = 0x12, /*!< Master Data Transmission process is ongoing */
HAL_I2C_STATE_MASTER_BUSY_RX = 0x22, /*!< Master Data Reception process is ongoing */
HAL_I2C_STATE_SLAVE_BUSY_TX = 0x32, /*!< Slave Data Transmission process is ongoing */
HAL_I2C_STATE_SLAVE_BUSY_RX = 0x42, /*!< Slave Data Reception process is ongoing */
HAL_I2C_STATE_MEM_BUSY_TX = 0x52, /*!< Memory Data Transmission process is ongoing */
HAL_I2C_STATE_MEM_BUSY_RX = 0x62, /*!< Memory Data Reception process is ongoing */
HAL_I2C_STATE_TIMEOUT = 0x03, /*!< Timeout state */
HAL_I2C_STATE_ERROR = 0x04 /*!< Reception process is ongoing */
}HAL_I2C_StateTypeDef;
/**
* @brief HAL I2C Error Code structure definition
*/
typedef enum
{
HAL_I2C_ERROR_NONE = 0x00, /*!< No error */
HAL_I2C_ERROR_BERR = 0x01, /*!< BERR error */
HAL_I2C_ERROR_ARLO = 0x02, /*!< ARLO error */
HAL_I2C_ERROR_AF = 0x04, /*!< ACKF error */
HAL_I2C_ERROR_OVR = 0x08, /*!< OVR error */
HAL_I2C_ERROR_DMA = 0x10, /*!< DMA transfer error */
HAL_I2C_ERROR_TIMEOUT = 0x20, /*!< Timeout error */
HAL_I2C_ERROR_SIZE = 0x40 /*!< Size Management error */
}HAL_I2C_ErrorTypeDef;
/**
* @brief I2C handle Structure definition
*/
typedef struct
{
I2C_TypeDef *Instance; /*!< I2C registers base address */
I2C_InitTypeDef Init; /*!< I2C communication parameters */
uint8_t *pBuffPtr; /*!< Pointer to I2C transfer buffer */
uint16_t XferSize; /*!< I2C transfer size */
__IO uint16_t XferCount; /*!< I2C transfer counter */
DMA_HandleTypeDef *hdmatx; /*!< I2C Tx DMA handle parameters */
DMA_HandleTypeDef *hdmarx; /*!< I2C Rx DMA handle parameters */
HAL_LockTypeDef Lock; /*!< I2C locking object */
__IO HAL_I2C_StateTypeDef State; /*!< I2C communication state */
__IO HAL_I2C_ErrorTypeDef ErrorCode; /* I2C Error code */
}I2C_HandleTypeDef;
/* Exported constants --------------------------------------------------------*/
/** @defgroup I2C_Exported_Constants
* @{
*/
/** @defgroup I2C_addressing_mode
* @{
*/
#define I2C_ADDRESSINGMODE_7BIT ((uint32_t)0x00000001)
#define I2C_ADDRESSINGMODE_10BIT ((uint32_t)0x00000002)
#define IS_I2C_ADDRESSING_MODE(MODE) (((MODE) == I2C_ADDRESSINGMODE_7BIT) || \
((MODE) == I2C_ADDRESSINGMODE_10BIT))
/**
* @}
*/
/** @defgroup I2C_dual_addressing_mode
* @{
*/
#define I2C_DUALADDRESS_DISABLED ((uint32_t)0x00000000)
#define I2C_DUALADDRESS_ENABLED I2C_OAR2_OA2EN
#define IS_I2C_DUAL_ADDRESS(ADDRESS) (((ADDRESS) == I2C_DUALADDRESS_DISABLED) || \
((ADDRESS) == I2C_DUALADDRESS_ENABLED))
/**
* @}
*/
/** @defgroup I2C_own_address2_masks
* @{
*/
#define I2C_OA2_NOMASK ((uint8_t)0x00)
#define I2C_OA2_MASK01 ((uint8_t)0x01)
#define I2C_OA2_MASK02 ((uint8_t)0x02)
#define I2C_OA2_MASK03 ((uint8_t)0x03)
#define I2C_OA2_MASK04 ((uint8_t)0x04)
#define I2C_OA2_MASK05 ((uint8_t)0x05)
#define I2C_OA2_MASK06 ((uint8_t)0x06)
#define I2C_OA2_MASK07 ((uint8_t)0x07)
#define IS_I2C_OWN_ADDRESS2_MASK(MASK) (((MASK) == I2C_OA2_NOMASK) || \
((MASK) == I2C_OA2_MASK01) || \
((MASK) == I2C_OA2_MASK02) || \
((MASK) == I2C_OA2_MASK03) || \
((MASK) == I2C_OA2_MASK04) || \
((MASK) == I2C_OA2_MASK05) || \
((MASK) == I2C_OA2_MASK06) || \
((MASK) == I2C_OA2_MASK07))
/**
* @}
*/
/** @defgroup I2C_general_call_addressing_mode
* @{
*/
#define I2C_GENERALCALL_DISABLED ((uint32_t)0x00000000)
#define I2C_GENERALCALL_ENABLED I2C_CR1_GCEN
#define IS_I2C_GENERAL_CALL(CALL) (((CALL) == I2C_GENERALCALL_DISABLED) || \
((CALL) == I2C_GENERALCALL_ENABLED))
/**
* @}
*/
/** @defgroup I2C_nostretch_mode
* @{
*/
#define I2C_NOSTRETCH_DISABLED ((uint32_t)0x00000000)
#define I2C_NOSTRETCH_ENABLED I2C_CR1_NOSTRETCH
#define IS_I2C_NO_STRETCH(STRETCH) (((STRETCH) == I2C_NOSTRETCH_DISABLED) || \
((STRETCH) == I2C_NOSTRETCH_ENABLED))
/**
* @}
*/
/** @defgroup I2C_Memory_Address_Size
* @{
*/
#define I2C_MEMADD_SIZE_8BIT ((uint32_t)0x00000001)
#define I2C_MEMADD_SIZE_16BIT ((uint32_t)0x00000002)
#define IS_I2C_MEMADD_SIZE(SIZE) (((SIZE) == I2C_MEMADD_SIZE_8BIT) || \
((SIZE) == I2C_MEMADD_SIZE_16BIT))
/**
* @}
*/
/** @defgroup I2C_ReloadEndMode_definition
* @{
*/
#define I2C_RELOAD_MODE I2C_CR2_RELOAD
#define I2C_AUTOEND_MODE I2C_CR2_AUTOEND
#define I2C_SOFTEND_MODE ((uint32_t)0x00000000)
#define IS_TRANSFER_MODE(MODE) (((MODE) == I2C_RELOAD_MODE) || \
((MODE) == I2C_AUTOEND_MODE) || \
((MODE) == I2C_SOFTEND_MODE))
/**
* @}
*/
/** @defgroup I2C_StartStopMode_definition
* @{
*/
#define I2C_NO_STARTSTOP ((uint32_t)0x00000000)
#define I2C_GENERATE_STOP I2C_CR2_STOP
#define I2C_GENERATE_START_READ (uint32_t)(I2C_CR2_START | I2C_CR2_RD_WRN)
#define I2C_GENERATE_START_WRITE I2C_CR2_START
#define IS_TRANSFER_REQUEST(REQUEST) (((REQUEST) == I2C_GENERATE_STOP) || \
((REQUEST) == I2C_GENERATE_START_READ) || \
((REQUEST) == I2C_GENERATE_START_WRITE) || \
((REQUEST) == I2C_NO_STARTSTOP))
/**
* @}
*/
/** @defgroup I2C_Interrupt_configuration_definition
* @brief I2C Interrupt definition
* Elements values convention: 0xXXXXXXXX
* - XXXXXXXX : Interrupt control mask
* @{
*/
#define I2C_IT_ERRI I2C_CR1_ERRIE
#define I2C_IT_TCI I2C_CR1_TCIE
#define I2C_IT_STOPI I2C_CR1_STOPIE
#define I2C_IT_NACKI I2C_CR1_NACKIE
#define I2C_IT_ADDRI I2C_CR1_ADDRIE
#define I2C_IT_RXI I2C_CR1_RXIE
#define I2C_IT_TXI I2C_CR1_TXIE
/**
* @}
*/
/** @defgroup I2C_Flag_definition
* @{
*/
#define I2C_FLAG_TXE I2C_ISR_TXE
#define I2C_FLAG_TXIS I2C_ISR_TXIS
#define I2C_FLAG_RXNE I2C_ISR_RXNE
#define I2C_FLAG_ADDR I2C_ISR_ADDR
#define I2C_FLAG_AF I2C_ISR_NACKF
#define I2C_FLAG_STOPF I2C_ISR_STOPF
#define I2C_FLAG_TC I2C_ISR_TC
#define I2C_FLAG_TCR I2C_ISR_TCR
#define I2C_FLAG_BERR I2C_ISR_BERR
#define I2C_FLAG_ARLO I2C_ISR_ARLO
#define I2C_FLAG_OVR I2C_ISR_OVR
#define I2C_FLAG_PECERR I2C_ISR_PECERR
#define I2C_FLAG_TIMEOUT I2C_ISR_TIMEOUT
#define I2C_FLAG_ALERT I2C_ISR_ALERT
#define I2C_FLAG_BUSY I2C_ISR_BUSY
#define I2C_FLAG_DIR I2C_ISR_DIR
/**
* @}
*/
/**
* @}
*/
/* Exported macro ------------------------------------------------------------*/
/** @brief Reset I2C handle state
* @param __HANDLE__: specifies the I2C Handle.
* This parameter can be I2C where x: 1 or 2 to select the I2C peripheral.
* @retval None
*/
#define __HAL_I2C_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_I2C_STATE_RESET)
/** @brief Enables or disables the specified I2C interrupts.
* @param __HANDLE__: specifies the I2C Handle.
* This parameter can be I2C where x: 1 or 2 to select the I2C peripheral.
* @param __INTERRUPT__: specifies the interrupt source to enable or disable.
* This parameter can be one of the following values:
* @arg I2C_IT_ERRI: Errors interrupt enable
* @arg I2C_IT_TCI: Transfer complete interrupt enable
* @arg I2C_IT_STOPI: STOP detection interrupt enable
* @arg I2C_IT_NACKI: NACK received interrupt enable
* @arg I2C_IT_ADDRI: Address match interrupt enable
* @arg I2C_IT_RXI: RX interrupt enable
* @arg I2C_IT_TXI: TX interrupt enable
*
* @retval None
*/
#define __HAL_I2C_ENABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->CR1 |= (__INTERRUPT__))
#define __HAL_I2C_DISABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->CR1 &= (~(__INTERRUPT__)))
/** @brief Checks if the specified I2C interrupt source is enabled or disabled.
* @param __HANDLE__: specifies the I2C Handle.
* This parameter can be I2C where x: 1 or 2 to select the I2C peripheral.
* @param __INTERRUPT__: specifies the I2C interrupt source to check.
* This parameter can be one of the following values:
* @arg I2C_IT_ERRI: Errors interrupt enable
* @arg I2C_IT_TCI: Transfer complete interrupt enable
* @arg I2C_IT_STOPI: STOP detection interrupt enable
* @arg I2C_IT_NACKI: NACK received interrupt enable
* @arg I2C_IT_ADDRI: Address match interrupt enable
* @arg I2C_IT_RXI: RX interrupt enable
* @arg I2C_IT_TXI: TX interrupt enable
*
* @retval The new state of __IT__ (TRUE or FALSE).
*/
#define __HAL_I2C_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) ((((__HANDLE__)->Instance->CR1 & (__INTERRUPT__)) == (__INTERRUPT__)) ? SET : RESET)
/** @brief Checks whether the specified I2C flag is set or not.
* @param __HANDLE__: specifies the I2C Handle.
* This parameter can be I2C where x: 1 or 2 to select the I2C peripheral.
* @param __FLAG__: specifies the flag to check.
* This parameter can be one of the following values:
* @arg I2C_FLAG_TXE: Transmit data register empty
* @arg I2C_FLAG_TXIS: Transmit interrupt status
* @arg I2C_FLAG_RXNE: Receive data register not empty
* @arg I2C_FLAG_ADDR: Address matched (slave mode)
* @arg I2C_FLAG_AF: Acknowledge failure received flag
* @arg I2C_FLAG_STOPF: STOP detection flag
* @arg I2C_FLAG_TC: Transfer complete (master mode)
* @arg I2C_FLAG_TCR: Transfer complete reload
* @arg I2C_FLAG_BERR: Bus error
* @arg I2C_FLAG_ARLO: Arbitration lost
* @arg I2C_FLAG_OVR: Overrun/Underrun
* @arg I2C_FLAG_PECERR: PEC error in reception
* @arg I2C_FLAG_TIMEOUT: Timeout or Tlow detection flag
* @arg I2C_FLAG_ALERT: SMBus alert
* @arg I2C_FLAG_BUSY: Bus busy
* @arg I2C_FLAG_DIR: Transfer direction (slave mode)
*
* @retval The new state of __FLAG__ (TRUE or FALSE).
*/
#define I2C_FLAG_MASK ((uint32_t)0x0001FFFF)
#define __HAL_I2C_GET_FLAG(__HANDLE__, __FLAG__) (((((__HANDLE__)->Instance->ISR) & ((__FLAG__) & I2C_FLAG_MASK)) == ((__FLAG__) & I2C_FLAG_MASK)))
/** @brief Clears the I2C pending flags which are cleared by writing 1 in a specific bit.
* @param __HANDLE__: specifies the I2C Handle.
* This parameter can be I2C where x: 1 or 2 to select the I2C peripheral.
* @param __FLAG__: specifies the flag to clear.
* This parameter can be any combination of the following values:
* @arg I2C_FLAG_ADDR: Address matched (slave mode)
* @arg I2C_FLAG_AF: Acknowledge failure received flag
* @arg I2C_FLAG_STOPF: STOP detection flag
* @arg I2C_FLAG_BERR: Bus error
* @arg I2C_FLAG_ARLO: Arbitration lost
* @arg I2C_FLAG_OVR: Overrun/Underrun
* @arg I2C_FLAG_PECERR: PEC error in reception
* @arg I2C_FLAG_TIMEOUT: Timeout or Tlow detection flag
* @arg I2C_FLAG_ALERT: SMBus alert
*
* @retval None
*/
#define __HAL_I2C_CLEAR_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->ICR = ((__FLAG__) & I2C_FLAG_MASK))
#define __HAL_I2C_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR1 |= I2C_CR1_PE)
#define __HAL_I2C_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR1 &= ~I2C_CR1_PE)
#define __HAL_I2C_RESET_CR2(__HANDLE__) ((__HANDLE__)->Instance->CR2 &= (uint32_t)~((uint32_t)(I2C_CR2_SADD | I2C_CR2_HEAD10R | I2C_CR2_NBYTES | I2C_CR2_RELOAD | I2C_CR2_RD_WRN)))
#define __HAL_I2C_MEM_ADD_MSB(__ADDRESS__) ((uint8_t)((uint16_t)(((uint16_t)((__ADDRESS__) & (uint16_t)(0xFF00))) >> 8)))
#define __HAL_I2C_MEM_ADD_LSB(__ADDRESS__) ((uint8_t)((uint16_t)((__ADDRESS__) & (uint16_t)(0x00FF))))
#define __HAL_I2C_GENERATE_START(__ADDMODE__,__ADDRESS__) (((__ADDMODE__) == I2C_ADDRESSINGMODE_7BIT) ? (uint32_t)((((uint32_t)(__ADDRESS__) & (I2C_CR2_SADD)) | (I2C_CR2_START) | (I2C_CR2_AUTOEND)) & (~I2C_CR2_RD_WRN)) : \
(uint32_t)((((uint32_t)(__ADDRESS__) & (I2C_CR2_SADD)) | (I2C_CR2_ADD10) | (I2C_CR2_START)) & (~I2C_CR2_RD_WRN)))
#define IS_I2C_OWN_ADDRESS1(ADDRESS1) ((ADDRESS1) <= (uint32_t)0x000003FF)
#define IS_I2C_OWN_ADDRESS2(ADDRESS2) ((ADDRESS2) <= (uint16_t)0x00FF)
/* Include I2C HAL Extension module */
#include "stm32l0xx_hal_i2c_ex.h"
/* Exported functions --------------------------------------------------------*/
/* Initialization/de-initialization functions**********************************/
HAL_StatusTypeDef HAL_I2C_Init(I2C_HandleTypeDef *hi2c);
HAL_StatusTypeDef HAL_I2C_DeInit (I2C_HandleTypeDef *hi2c);
void HAL_I2C_MspInit(I2C_HandleTypeDef *hi2c);
void HAL_I2C_MspDeInit(I2C_HandleTypeDef *hi2c);
/* I/O operation functions ***************************************************/
/******* Blocking mode: Polling */
HAL_StatusTypeDef HAL_I2C_Master_Transmit(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t Timeout);
HAL_StatusTypeDef HAL_I2C_Master_Receive(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t Timeout);
HAL_StatusTypeDef HAL_I2C_Slave_Transmit(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size, uint32_t Timeout);
HAL_StatusTypeDef HAL_I2C_Slave_Receive(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size, uint32_t Timeout);
HAL_StatusTypeDef HAL_I2C_Mem_Write(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint8_t *pData, uint16_t Size, uint32_t Timeout);
HAL_StatusTypeDef HAL_I2C_Mem_Read(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint8_t *pData, uint16_t Size, uint32_t Timeout);
HAL_StatusTypeDef HAL_I2C_IsDeviceReady(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint32_t Trials, uint32_t Timeout);
/******* Non-Blocking mode: Interrupt */
HAL_StatusTypeDef HAL_I2C_Master_Transmit_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size);
HAL_StatusTypeDef HAL_I2C_Master_Receive_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size);
HAL_StatusTypeDef HAL_I2C_Slave_Transmit_IT(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size);
HAL_StatusTypeDef HAL_I2C_Slave_Receive_IT(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size);
HAL_StatusTypeDef HAL_I2C_Mem_Write_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint8_t *pData, uint16_t Size);
HAL_StatusTypeDef HAL_I2C_Mem_Read_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint8_t *pData, uint16_t Size);
/******* Non-Blocking mode: DMA */
HAL_StatusTypeDef HAL_I2C_Master_Transmit_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size);
HAL_StatusTypeDef HAL_I2C_Master_Receive_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size);
HAL_StatusTypeDef HAL_I2C_Slave_Transmit_DMA(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size);
HAL_StatusTypeDef HAL_I2C_Slave_Receive_DMA(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size);
HAL_StatusTypeDef HAL_I2C_Mem_Write_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint8_t *pData, uint16_t Size);
HAL_StatusTypeDef HAL_I2C_Mem_Read_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint8_t *pData, uint16_t Size);
/******* I2C IRQHandler and Callbacks used in non blocking modes (Interrupt and DMA) */
void HAL_I2C_EV_IRQHandler(I2C_HandleTypeDef *hi2c);
void HAL_I2C_ER_IRQHandler(I2C_HandleTypeDef *hi2c);
void HAL_I2C_MasterTxCpltCallback(I2C_HandleTypeDef *hi2c);
void HAL_I2C_MasterRxCpltCallback(I2C_HandleTypeDef *hi2c);
void HAL_I2C_SlaveTxCpltCallback(I2C_HandleTypeDef *hi2c);
void HAL_I2C_SlaveRxCpltCallback(I2C_HandleTypeDef *hi2c);
void HAL_I2C_MemTxCpltCallback(I2C_HandleTypeDef *hi2c);
void HAL_I2C_MemRxCpltCallback(I2C_HandleTypeDef *hi2c);
void HAL_I2C_ErrorCallback(I2C_HandleTypeDef *hi2c);
/* Peripheral State functions ************************************************/
HAL_I2C_StateTypeDef HAL_I2C_GetState(I2C_HandleTypeDef *hi2c);
uint32_t HAL_I2C_GetError(I2C_HandleTypeDef *hi2c);
/**
* @}
*/
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif /* __STM32L0xx_HAL_I2C_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,288 @@
/**
******************************************************************************
* @file stm32l0xx_hal_i2c_ex.c
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief Extended I2C HAL module driver.
*
* This file provides firmware functions to manage the following
* functionalities of the Inter Integrated Circuit (I2C) peripheral:
* + Extended Control methods
*
@verbatim
==============================================================================
##### I2C peripheral extended features #####
==============================================================================
[..] Comparing to other previous devices, the I2C interface for STM32L0XX
devices contains the following additional features
(+) Possibility to disable or enable Analog Noise Filter
(+) Use of a configured Digital Noise Filter
(+) Disable or enable wakeup from Stop mode
##### How to use this driver #####
==============================================================================
[..] This driver provides functions to configure Noise Filter
@endverbatim
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @defgroup I2CEx
* @brief I2C HAL module driver
* @{
*/
#ifdef HAL_I2C_MODULE_ENABLED
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/** @defgroup I2CEX_Private_Functions
* @{
*/
/** @defgroup I2CEX_Group1 Peripheral Control methods
* @brief management functions
*
@verbatim
===============================================================================
##### Peripheral Control methods #####
===============================================================================
[..] This section provides functions allowing to:
(+) Configure Noise Filters
@endverbatim
* @{
*/
/**
* @brief Configures I2C Analog noise filter.
* @param hi2c : pointer to a I2C_HandleTypeDef structure that contains
* the configuration information for the specified I2Cx peripheral.
* @param AnalogFilter : new state of the Analog filter.
* @retval HAL status
*/
HAL_StatusTypeDef HAL_I2CEx_AnalogFilter_Config(I2C_HandleTypeDef *hi2c, uint32_t AnalogFilter)
{
/* Check the parameters */
assert_param(IS_I2C_ALL_INSTANCE(hi2c->Instance));
assert_param(IS_I2C_ANALOG_FILTER(AnalogFilter));
if((hi2c->State == HAL_I2C_STATE_BUSY) || (hi2c->State == HAL_I2C_STATE_MASTER_BUSY_TX) || (hi2c->State == HAL_I2C_STATE_MASTER_BUSY_RX)
|| (hi2c->State == HAL_I2C_STATE_SLAVE_BUSY_TX) || (hi2c->State == HAL_I2C_STATE_SLAVE_BUSY_RX))
{
return HAL_BUSY;
}
/* Process Locked */
__HAL_LOCK(hi2c);
hi2c->State = HAL_I2C_STATE_BUSY;
/* Disable the selected I2C peripheral */
__HAL_I2C_DISABLE(hi2c);
/* Reset I2Cx ANOFF bit */
hi2c->Instance->CR1 &= ~(I2C_CR1_ANFOFF);
/* Set analog filter bit*/
hi2c->Instance->CR1 |= AnalogFilter;
__HAL_I2C_ENABLE(hi2c);
hi2c->State = HAL_I2C_STATE_READY;
/* Process Unlocked */
__HAL_UNLOCK(hi2c);
return HAL_OK;
}
/**
* @brief Configures I2C Digital noise filter.
* @param hi2c : pointer to a I2C_HandleTypeDef structure that contains
* the configuration information for the specified I2Cx peripheral.
* @param DigitalFilter : Coefficient of digital noise filter between 0x00 and 0x0F.
* @retval HAL status
*/
HAL_StatusTypeDef HAL_I2CEx_DigitalFilter_Config(I2C_HandleTypeDef *hi2c, uint32_t DigitalFilter)
{
uint32_t tmpreg = 0;
/* Check the parameters */
assert_param(IS_I2C_ALL_INSTANCE(hi2c->Instance));
assert_param(IS_I2C_DIGITAL_FILTER(DigitalFilter));
if((hi2c->State == HAL_I2C_STATE_BUSY) || (hi2c->State == HAL_I2C_STATE_MASTER_BUSY_TX) || (hi2c->State == HAL_I2C_STATE_MASTER_BUSY_RX)
|| (hi2c->State == HAL_I2C_STATE_SLAVE_BUSY_TX) || (hi2c->State == HAL_I2C_STATE_SLAVE_BUSY_RX))
{
return HAL_BUSY;
}
/* Process Locked */
__HAL_LOCK(hi2c);
hi2c->State = HAL_I2C_STATE_BUSY;
/* Disable the selected I2C peripheral */
__HAL_I2C_DISABLE(hi2c);
/* Get the old register value */
tmpreg = hi2c->Instance->CR1;
/* Reset I2Cx DNF bits [11:8] */
tmpreg &= ~(I2C_CR1_DFN);
/* Set I2Cx DNF coefficient */
tmpreg |= DigitalFilter << 8;
/* Store the new register value */
hi2c->Instance->CR1 = tmpreg;
__HAL_I2C_ENABLE(hi2c);
hi2c->State = HAL_I2C_STATE_READY;
/* Process Unlocked */
__HAL_UNLOCK(hi2c);
return HAL_OK;
}
/**
* @brief Enables I2C wakeup from stop mode.
* @param hi2c : pointer to a I2C_HandleTypeDef structure that contains
* the configuration information for the specified I2Cx peripheral.
* @retval HAL status
*/
HAL_StatusTypeDef HAL_I2CEx_EnableWakeUp (I2C_HandleTypeDef *hi2c)
{
/* Check the parameters */
assert_param(IS_I2C_ALL_INSTANCE(hi2c->Instance));
if((hi2c->State == HAL_I2C_STATE_BUSY) || (hi2c->State == HAL_I2C_STATE_MASTER_BUSY_TX) || (hi2c->State == HAL_I2C_STATE_MASTER_BUSY_RX)
|| (hi2c->State == HAL_I2C_STATE_SLAVE_BUSY_TX) || (hi2c->State == HAL_I2C_STATE_SLAVE_BUSY_RX))
{
return HAL_BUSY;
}
/* Process Locked */
__HAL_LOCK(hi2c);
hi2c->State = HAL_I2C_STATE_BUSY;
/* Disable the selected I2C peripheral */
__HAL_I2C_DISABLE(hi2c);
/* Enable wakeup from stop mode */
hi2c->Instance->CR1 |= I2C_CR1_WUPEN;
__HAL_I2C_ENABLE(hi2c);
hi2c->State = HAL_I2C_STATE_READY;
/* Process Unlocked */
__HAL_UNLOCK(hi2c);
return HAL_OK;
}
/**
* @brief Disables I2C wakeup from stop mode.
* @param hi2c : pointer to a I2C_HandleTypeDef structure that contains
* the configuration information for the specified I2Cx peripheral.
* @retval HAL status
*/
HAL_StatusTypeDef HAL_I2CEx_DisableWakeUp (I2C_HandleTypeDef *hi2c)
{
/* Check the parameters */
assert_param(IS_I2C_ALL_INSTANCE(hi2c->Instance));
if((hi2c->State == HAL_I2C_STATE_BUSY) || (hi2c->State == HAL_I2C_STATE_MASTER_BUSY_TX) || (hi2c->State == HAL_I2C_STATE_MASTER_BUSY_RX)
|| (hi2c->State == HAL_I2C_STATE_SLAVE_BUSY_TX) || (hi2c->State == HAL_I2C_STATE_SLAVE_BUSY_RX))
{
return HAL_BUSY;
}
/* Process Locked */
__HAL_LOCK(hi2c);
hi2c->State = HAL_I2C_STATE_BUSY;
/* Disable the selected I2C peripheral */
__HAL_I2C_DISABLE(hi2c);
/* Enable wakeup from stop mode */
hi2c->Instance->CR1 &= ~(I2C_CR1_WUPEN);
__HAL_I2C_ENABLE(hi2c);
hi2c->State = HAL_I2C_STATE_READY;
/* Process Unlocked */
__HAL_UNLOCK(hi2c);
return HAL_OK;
}
/**
* @}
*/
/**
* @}
*/
#endif /* HAL_I2C_MODULE_ENABLED */
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,112 @@
/**
******************************************************************************
* @file stm32l0xx_hal_i2c_ex.h
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief Header file of I2C HAL Extension module.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32L0xx_HAL_I2C_EX_H
#define __STM32L0xx_HAL_I2C_EX_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal_def.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @addtogroup I2CEx
* @{
*/
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
/** @defgroup I2CEx_Exported_Constants
* @{
*/
/** @defgroup I2CEx_Analog_Filter
* @{
*/
#define I2C_ANALOGFILTER_ENABLED ((uint32_t)0x00000000)
#define I2C_ANALOGFILTER_DISABLED I2C_CR1_ANFOFF
#define IS_I2C_ANALOG_FILTER(FILTER) (((FILTER) == I2C_ANALOGFILTER_ENABLED) || \
((FILTER) == I2C_ANALOGFILTER_DISABLED))
/**
* @}
*/
/** @defgroup I2CEx_Digital_Filter
* @{
*/
#define IS_I2C_DIGITAL_FILTER(FILTER) ((FILTER) <= 0x0000000F)
/**
* @}
*/
/**
* @}
*/
/* Exported macro ------------------------------------------------------------*/
/* Exported functions --------------------------------------------------------*/
/* Peripheral Control methods ************************************************/
HAL_StatusTypeDef HAL_I2CEx_AnalogFilter_Config(I2C_HandleTypeDef *hi2c, uint32_t AnalogFilter);
HAL_StatusTypeDef HAL_I2CEx_DigitalFilter_Config(I2C_HandleTypeDef *hi2c, uint32_t DigitalFilter);
HAL_StatusTypeDef HAL_I2CEx_EnableWakeUp (I2C_HandleTypeDef *hi2c);
HAL_StatusTypeDef HAL_I2CEx_DisableWakeUp (I2C_HandleTypeDef *hi2c);
/**
* @}
*/
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif /* __STM32L0xx_HAL_I2C_EX_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,399 @@
/**
******************************************************************************
* @file stm32l0xx_hal_i2s.h
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief Header file of I2S HAL module.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32L0xx_HAL_I2S_H
#define __STM32L0xx_HAL_I2S_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal_def.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @addtogroup I2S
* @{
*/
/* Exported types ------------------------------------------------------------*/
/**
* @brief I2S Init structure definition
*/
typedef struct
{
uint32_t Mode; /*!< Specifies the I2S operating mode.
This parameter can be a value of @ref I2S_Mode */
uint32_t Standard; /*!< Specifies the standard used for the I2S communication.
This parameter can be a value of @ref I2S_Standard */
uint32_t DataFormat; /*!< Specifies the data format for the I2S communication.
This parameter can be a value of @ref I2S_Data_Format */
uint32_t MCLKOutput; /*!< Specifies whether the I2S MCLK output is enabled or not.
This parameter can be a value of @ref I2S_MCLK_Output */
uint32_t AudioFreq; /*!< Specifies the frequency selected for the I2S communication.
This parameter can be a value of @ref I2S_Audio_Frequency */
uint32_t CPOL; /*!< Specifies the idle state of the I2S clock.
This parameter can be a value of @ref I2S_Clock_Polarity */
}I2S_InitTypeDef;
/**
* @brief HAL State structures definition
*/
typedef enum
{
HAL_I2S_STATE_RESET = 0x00, /*!< I2S not yet initialized or disabled */
HAL_I2S_STATE_READY = 0x01, /*!< I2S initialized and ready for use */
HAL_I2S_STATE_BUSY = 0x02, /*!< I2S internal process is ongoing */
HAL_I2S_STATE_BUSY_TX = 0x12, /*!< Data Transmission process is ongoing */
HAL_I2S_STATE_BUSY_RX = 0x22, /*!< Data Reception process is ongoing */
HAL_I2S_STATE_TIMEOUT = 0x03, /*!< I2S timeout state */
HAL_I2S_STATE_ERROR = 0x04 /*!< I2S error state */
}HAL_I2S_StateTypeDef;
/**
* @brief HAL I2S Error Code structure definition
*/
typedef enum
{
HAL_I2S_ERROR_NONE = 0x00, /*!< No error */
HAL_I2S_ERROR_UDR = 0x01, /*!< I2S Underrun error */
HAL_I2S_ERROR_OVR = 0x02, /*!< I2S Overrun error */
HAL_I2S_ERROR_FRE = 0x10, /*!< I2S Frame format error */
HAL_I2S_ERROR_DMA = 0x20 /*!< DMA transfer error */
}HAL_I2S_ErrorTypeDef;
/**
* @brief I2S handle Structure definition
*/
typedef struct
{
SPI_TypeDef *Instance; /* I2S registers base address */
I2S_InitTypeDef Init; /* I2S communication parameters */
uint16_t *pTxBuffPtr; /* Pointer to I2S Tx transfer buffer*/
__IO uint16_t TxXferSize; /* I2S Tx transfer size */
__IO uint16_t TxXferCount; /* I2S Tx transfer Counter */
uint16_t *pRxBuffPtr; /* Pointer to I2S Rx transfer buffer*/
__IO uint16_t RxXferSize; /* I2S Rx transfer size */
__IO uint16_t RxXferCount; /* I2S Rx transfer counter */
DMA_HandleTypeDef *hdmatx; /* I2S Tx DMA handle parameters */
DMA_HandleTypeDef *hdmarx; /* I2S Rx DMA handle parameters */
__IO HAL_LockTypeDef Lock; /* I2S locking object */
__IO HAL_I2S_StateTypeDef State; /* I2S communication state */
__IO HAL_I2S_ErrorTypeDef ErrorCode; /* I2S Error code */
}I2S_HandleTypeDef;
/* Exported constants --------------------------------------------------------*/
/** @defgroup I2S_Exported_Constants
* @{
*/
/** @defgroup I2S_Mode
* @{
*/
#define I2S_MODE_SLAVE_TX ((uint32_t)0x00000000)
#define I2S_MODE_SLAVE_RX ((uint32_t)0x00000100)
#define I2S_MODE_MASTER_TX ((uint32_t)0x00000200)
#define I2S_MODE_MASTER_RX ((uint32_t)0x00000300)
#define IS_I2S_MODE(MODE) (((MODE) == I2S_MODE_SLAVE_TX) || \
((MODE) == I2S_MODE_SLAVE_RX) || \
((MODE) == I2S_MODE_MASTER_TX) || \
((MODE) == I2S_MODE_MASTER_RX))
/**
* @}
*/
/** @defgroup I2S_Standard
* @{
*/
#define I2S_STANDARD_PHILIPS ((uint32_t)0x00000000)
#define I2S_STANDARD_MSB ((uint32_t)0x00000010)
#define I2S_STANDARD_LSB ((uint32_t)0x00000020)
#define I2S_STANDARD_PCM_SHORT ((uint32_t)0x00000030)
#define I2S_STANDARD_PCM_LONG ((uint32_t)0x000000B0)
#define IS_I2S_STANDARD(STANDARD) (((STANDARD) == I2S_STANDARD_PHILIPS) || \
((STANDARD) == I2S_STANDARD_MSB) || \
((STANDARD) == I2S_STANDARD_LSB) || \
((STANDARD) == I2S_STANDARD_PCM_SHORT) || \
((STANDARD) == I2S_STANDARD_PCM_LONG))
/**
* @}
*/
/** @defgroup I2S_Data_Format
* @{
*/
#define I2S_DATAFORMAT_16B ((uint32_t)0x00000000)
#define I2S_DATAFORMAT_16B_EXTENDED ((uint32_t)0x00000001)
#define I2S_DATAFORMAT_24B ((uint32_t)0x00000003)
#define I2S_DATAFORMAT_32B ((uint32_t)0x00000005)
#define IS_I2S_DATA_FORMAT(FORMAT) (((FORMAT) == I2S_DATAFORMAT_16B) || \
((FORMAT) == I2S_DATAFORMAT_16B_EXTENDED) || \
((FORMAT) == I2S_DATAFORMAT_24B) || \
((FORMAT) == I2S_DATAFORMAT_32B))
/**
* @}
*/
/** @defgroup I2S_MCLK_Output
* @{
*/
#define I2S_MCLKOUTPUT_ENABLE ((uint32_t)SPI_I2SPR_MCKOE)
#define I2S_MCLKOUTPUT_DISABLE ((uint32_t)0x00000000)
#define IS_I2S_MCLK_OUTPUT(OUTPUT) (((OUTPUT) == I2S_MCLKOUTPUT_ENABLE) || \
((OUTPUT) == I2S_MCLKOUTPUT_DISABLE))
/**
* @}
*/
/** @defgroup I2S_Audio_Frequency
* @{
*/
#define I2S_AUDIOFREQ_192K ((uint32_t)192000)
#define I2S_AUDIOFREQ_96K ((uint32_t)96000)
#define I2S_AUDIOFREQ_48K ((uint32_t)48000)
#define I2S_AUDIOFREQ_44K ((uint32_t)44100)
#define I2S_AUDIOFREQ_32K ((uint32_t)32000)
#define I2S_AUDIOFREQ_22K ((uint32_t)22050)
#define I2S_AUDIOFREQ_16K ((uint32_t)16000)
#define I2S_AUDIOFREQ_11K ((uint32_t)11025)
#define I2S_AUDIOFREQ_8K ((uint32_t)8000)
#define I2S_AUDIOFREQ_DEFAULT ((uint32_t)2)
#define IS_I2S_AUDIO_FREQ(FREQ) ((((FREQ) >= I2S_AUDIOFREQ_8K) && \
((FREQ) <= I2S_AUDIOFREQ_192K)) || \
((FREQ) == I2S_AUDIOFREQ_DEFAULT))
/**
* @}
*/
/** @defgroup I2S_Clock_Polarity
* @{
*/
#define I2S_CPOL_LOW ((uint32_t)0x00000000)
#define I2S_CPOL_HIGH ((uint32_t)SPI_I2SCFGR_CKPOL)
#define IS_I2S_CPOL(CPOL) (((CPOL) == I2S_CPOL_LOW) || \
((CPOL) == I2S_CPOL_HIGH))
/**
* @}
*/
/** @defgroup I2S_Interrupt_configuration_definition
* @{
*/
#define I2S_IT_TXE SPI_CR2_TXEIE
#define I2S_IT_RXNE SPI_CR2_RXNEIE
#define I2S_IT_ERR SPI_CR2_ERRIE
/**
* @}
*/
/** @defgroup I2S_Flag_definition
* @{
*/
#define I2S_FLAG_TXE SPI_SR_TXE
#define I2S_FLAG_RXNE SPI_SR_RXNE
#define I2S_FLAG_UDR SPI_SR_UDR
#define I2S_FLAG_OVR SPI_SR_OVR
#define I2S_FLAG_FRE SPI_SR_FRE
#define I2S_FLAG_CHSIDE SPI_SR_CHSIDE
#define I2S_FLAG_BSY SPI_SR_BSY
/**
* @}
*/
/**
* @}
*/
/* Exported macro ------------------------------------------------------------*/
/** @brief Reset I2S handle state
* @param __HANDLE__: specifies the I2S Handle.
* @retval None
*/
#define __HAL_I2S_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_I2S_STATE_RESET)
/** @brief Enable or disable the specified SPI peripheral (in I2S mode).
* @param __HANDLE__: specifies the I2S Handle.
* @retval None
*/
#define __HAL_I2S_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->I2SCFGR |= SPI_I2SCFGR_I2SE)
#define __HAL_I2S_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->I2SCFGR &= (uint32_t)~((uint32_t)SPI_I2SCFGR_I2SE))
/** @brief Enable or disable the specified I2S interrupts.
* @param __HANDLE__: specifies the I2S Handle.
* @param __INTERRUPT__: specifies the interrupt source to enable or disable.
* This parameter can be one of the following values:
* @arg I2S_IT_TXE: Tx buffer empty interrupt enable
* @arg I2S_IT_RXNE: RX buffer not empty interrupt enable
* @arg I2S_IT_ERR: Error interrupt enable
* @retval None
*/
#define __HAL_I2S_ENABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->CR2 |= (__INTERRUPT__))
#define __HAL_I2S_DISABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->CR2 &= ~(__INTERRUPT__))
/** @brief Checks if the specified I2S interrupt source is enabled or disabled.
* @param __HANDLE__: specifies the I2S Handle.
* This parameter can be I2S where x: 1, 2, or 3 to select the I2S peripheral.
* @param __INTERRUPT__: specifies the I2S interrupt source to check.
* This parameter can be one of the following values:
* @arg I2S_IT_TXE: Tx buffer empty interrupt enable
* @arg I2S_IT_RXNE: RX buffer not empty interrupt enable
* @arg I2S_IT_ERR: Error interrupt enable
* @retval The new state of __IT__ (TRUE or FALSE).
*/
#define __HAL_I2S_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) ((((__HANDLE__)->Instance->CR2 & (__INTERRUPT__)) == (__INTERRUPT__)) ? SET : RESET)
/** @brief Checks whether the specified I2S flag is set or not.
* @param __HANDLE__: specifies the I2S Handle.
* @param __FLAG__: specifies the flag to check.
* This parameter can be one of the following values:
* @arg I2S_FLAG_RXNE: Receive buffer not empty flag
* @arg I2S_FLAG_TXE: Transmit buffer empty flag
* @arg I2S_FLAG_UDR: Underrun flag
* @arg I2S_FLAG_OVR: Overrun flag
* @arg I2S_FLAG_FRE: Frame error flag
* @arg I2S_FLAG_CHSIDE: Channel Side flag
* @arg I2S_FLAG_BSY: Busy flag
* @retval The new state of __FLAG__ (TRUE or FALSE).
*/
#define __HAL_I2S_GET_FLAG(__HANDLE__, __FLAG__) ((((__HANDLE__)->Instance->SR) & (__FLAG__)) == (__FLAG__))
/** @brief Clears the I2S OVR pending flag.
* @param __HANDLE__: specifies the I2S Handle.
* @retval None
*/
#define __HAL_I2S_CLEAR_OVRFLAG(__HANDLE__) do{(__HANDLE__)->Instance->DR;\
(__HANDLE__)->Instance->SR;}while(0)
/** @brief Clears the I2S UDR pending flag.
* @param __HANDLE__: specifies the I2S Handle.
* @retval None
*/
#define __HAL_I2S_CLEAR_UDRFLAG(__HANDLE__)((__HANDLE__)->Instance->SR)
/* Exported functions --------------------------------------------------------*/
/* Initialization/de-initialization functions **********************************/
HAL_StatusTypeDef HAL_I2S_Init(I2S_HandleTypeDef *hi2s);
HAL_StatusTypeDef HAL_I2S_DeInit (I2S_HandleTypeDef *hi2s);
void HAL_I2S_MspInit(I2S_HandleTypeDef *hi2s);
void HAL_I2S_MspDeInit(I2S_HandleTypeDef *hi2s);
/* I/O operation functions *****************************************************/
/* Blocking mode: Polling */
HAL_StatusTypeDef HAL_I2S_Transmit(I2S_HandleTypeDef *hi2s, uint16_t *pData, uint16_t Size, uint32_t Timeout);
HAL_StatusTypeDef HAL_I2S_Receive(I2S_HandleTypeDef *hi2s, uint16_t *pData, uint16_t Size, uint32_t Timeout);
/* Non-Blocking mode: Interrupt */
HAL_StatusTypeDef HAL_I2S_Transmit_IT(I2S_HandleTypeDef *hi2s, uint16_t *pData, uint16_t Size);
HAL_StatusTypeDef HAL_I2S_Receive_IT(I2S_HandleTypeDef *hi2s, uint16_t *pData, uint16_t Size);
void HAL_I2S_IRQHandler(I2S_HandleTypeDef *hi2s);
/* Non-Blocking mode: DMA */
HAL_StatusTypeDef HAL_I2S_Transmit_DMA(I2S_HandleTypeDef *hi2s, uint16_t *pData, uint16_t Size);
HAL_StatusTypeDef HAL_I2S_Receive_DMA(I2S_HandleTypeDef *hi2s, uint16_t *pData, uint16_t Size);
HAL_StatusTypeDef HAL_I2S_DMAPause(I2S_HandleTypeDef *hi2s);
HAL_StatusTypeDef HAL_I2S_DMAResume(I2S_HandleTypeDef *hi2s);
HAL_StatusTypeDef HAL_I2S_DMAStop(I2S_HandleTypeDef *hi2s);
/* Peripheral Control and State functions **************************************/
HAL_I2S_StateTypeDef HAL_I2S_GetState(I2S_HandleTypeDef *hi2s);
HAL_I2S_ErrorTypeDef HAL_I2S_GetError(I2S_HandleTypeDef *hi2s);
/* Callbacks used in non blocking modes (Interrupt and DMA) *******************/
void HAL_I2S_TxHalfCpltCallback(I2S_HandleTypeDef *hi2s);
void HAL_I2S_TxCpltCallback(I2S_HandleTypeDef *hi2s);
void HAL_I2S_RxHalfCpltCallback(I2S_HandleTypeDef *hi2s);
void HAL_I2S_RxCpltCallback(I2S_HandleTypeDef *hi2s);
void HAL_I2S_ErrorCallback(I2S_HandleTypeDef *hi2s);
void I2S_DMATxCplt(DMA_HandleTypeDef *hdma);
void I2S_DMATxHalfCplt(DMA_HandleTypeDef *hdma);
void I2S_DMARxCplt(DMA_HandleTypeDef *hdma);
void I2S_DMARxHalfCplt(DMA_HandleTypeDef *hdma);
void I2S_DMAError(DMA_HandleTypeDef *hdma);
HAL_StatusTypeDef I2S_WaitFlagStateUntilTimeout(I2S_HandleTypeDef *hi2s, uint32_t Flag, uint32_t Status, uint32_t Timeout);
/**
* @}
*/
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif /* __STM32L0xx_HAL_I2S_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,572 @@
/**
******************************************************************************
* @file stm32l0xx_hal_irda.h
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief Header file of IRDA HAL module.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32L0xx_HAL_IRDA_H
#define __STM32L0xx_HAL_IRDA_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal_def.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @addtogroup IRDA
* @{
*/
/* Exported types ------------------------------------------------------------*/
/**
* @brief IRDA Init Structure definition
*/
typedef struct
{
uint32_t BaudRate; /*!< This member configures the IRDA communication baud rate.
The baud rate register is computed using the following formula:
Baud Rate Register = ((PCLKx) / ((hirda->Init.BaudRate))) */
uint32_t WordLength; /*!< Specifies the number of data bits transmitted or received in a frame.
This parameter can be a value of @ref IRDAEx_Word_Length */
uint32_t Parity; /*!< Specifies the parity mode.
This parameter can be a value of @ref IRDA_Parity
@note When parity is enabled, the computed parity is inserted
at the MSB position of the transmitted data (9th bit when
the word length is set to 9 data bits; 8th bit when the
word length is set to 8 data bits). */
uint16_t Mode; /*!< Specifies wether the Receive or Transmit mode is enabled or disabled.
This parameter can be a value of @ref IRDA_Mode */
uint8_t Prescaler; /*!< Specifies the Prescaler value for dividing the UART/USART source clock
to achieve low-power frequency.
@note Prescaler value 0 is forbidden */
uint16_t PowerMode; /*!< Specifies the IRDA power mode.
This parameter can be a value of @ref IRDA_Low_Power */
}IRDA_InitTypeDef;
/**
* @brief HAL IRDA State structures definition
*/
typedef enum
{
HAL_IRDA_STATE_RESET = 0x00, /*!< Peripheral is not yet Initialized */
HAL_IRDA_STATE_READY = 0x01, /*!< Peripheral Initialized and ready for use */
HAL_IRDA_STATE_BUSY = 0x02, /*!< an internal process is ongoing */
HAL_IRDA_STATE_BUSY_TX = 0x12, /*!< Data Transmission process is ongoing */
HAL_IRDA_STATE_BUSY_RX = 0x22, /*!< Data Reception process is ongoing */
HAL_IRDA_STATE_BUSY_TX_RX = 0x32, /*!< Data Transmission and Reception process is ongoing */
HAL_IRDA_STATE_TIMEOUT = 0x03, /*!< Timeout state */
HAL_IRDA_STATE_ERROR = 0x04 /*!< Error */
}HAL_IRDA_StateTypeDef;
/**
* @brief HAL IRDA Error Code structure definition
*/
typedef enum
{
HAL_IRDA_ERROR_NONE = 0x00, /*!< No error */
HAL_IRDA_ERROR_PE = 0x01, /*!< Parity error */
HAL_IRDA_ERROR_NE = 0x02, /*!< Noise error */
HAL_IRDA_ERROR_FE = 0x04, /*!< frame error */
HAL_IRDA_ERROR_ORE = 0x08, /*!< Overrun error */
HAL_IRDA_ERROR_DMA = 0x10 /*!< DMA transfer error */
}HAL_IRDA_ErrorTypeDef;
/**
* @brief IRDA clock sources definition
*/
typedef enum
{
IRDA_CLOCKSOURCE_PCLK1 = 0x00, /*!< PCLK1 clock source */
IRDA_CLOCKSOURCE_PCLK2 = 0x01, /*!< PCLK2 clock source */
IRDA_CLOCKSOURCE_HSI = 0x02, /*!< HSI clock source */
IRDA_CLOCKSOURCE_SYSCLK = 0x04, /*!< SYSCLK clock source */
IRDA_CLOCKSOURCE_LSE = 0x08 /*!< LSE clock source */
}IRDA_ClockSourceTypeDef;
/**
* @brief IRDA handle Structure definition
*/
typedef struct
{
USART_TypeDef *Instance; /* IRDA registers base address */
IRDA_InitTypeDef Init; /* IRDA communication parameters */
uint8_t *pTxBuffPtr; /* Pointer to IRDA Tx transfer Buffer */
uint16_t TxXferSize; /* IRDA Tx Transfer size */
uint16_t TxXferCount; /* IRDA Tx Transfer Counter */
uint8_t *pRxBuffPtr; /* Pointer to IRDA Rx transfer Buffer */
uint16_t RxXferSize; /* IRDA Rx Transfer size */
uint16_t RxXferCount; /* IRDA Rx Transfer Counter */
uint16_t Mask; /* IRDA RX RDR register mask */
DMA_HandleTypeDef *hdmatx; /* IRDA Tx DMA Handle parameters */
DMA_HandleTypeDef *hdmarx; /* IRDA Rx DMA Handle parameters */
HAL_LockTypeDef Lock; /* Locking object */
__IO HAL_IRDA_StateTypeDef State; /* IRDA communication state */
__IO HAL_IRDA_ErrorTypeDef ErrorCode; /* IRDA Error code */
}IRDA_HandleTypeDef;
/**
* @brief IRDA Configuration enumeration values definition
*/
/* Exported constants --------------------------------------------------------*/
/** @defgroup IRDA_Exported_Constants IRDA Exported Constants
* @{
*/
/** @defgroup IRDA_Parity
* @{
*/
#define IRDA_PARITY_NONE ((uint32_t)0x0000)
#define IRDA_PARITY_EVEN ((uint32_t)USART_CR1_PCE)
#define IRDA_PARITY_ODD ((uint32_t)(USART_CR1_PCE | USART_CR1_PS))
#define IS_IRDA_PARITY(PARITY) (((PARITY) == IRDA_PARITY_NONE) || \
((PARITY) == IRDA_PARITY_EVEN) || \
((PARITY) == IRDA_PARITY_ODD))
/**
* @}
*/
/** @defgroup IRDA_Transfer_Mode
* @{
*/
#define IRDA_MODE_RX ((uint32_t)USART_CR1_RE)
#define IRDA_MODE_TX ((uint32_t)USART_CR1_TE)
#define IRDA_MODE_TX_RX ((uint32_t)(USART_CR1_TE |USART_CR1_RE))
#define IS_IRDA_TX_RX_MODE(MODE) ((((MODE) & (~((uint32_t)(IRDA_MODE_TX_RX)))) == (uint32_t)0x00) && ((MODE) != (uint32_t)0x00))
/**
* @}
*/
/** @defgroup IRDA_Low_Power
* @{
*/
#define IRDA_POWERMODE_NORMAL ((uint32_t)0x0000)
#define IRDA_POWERMODE_LOWPOWER ((uint32_t)USART_CR3_IRLP)
#define IS_IRDA_POWERMODE(MODE) (((MODE) == IRDA_POWERMODE_LOWPOWER) || \
((MODE) == IRDA_POWERMODE_NORMAL))
/**
* @}
*/
/** @defgroup IRDA_State
* @{
*/
#define IRDA_STATE_DISABLE ((uint32_t)0x0000)
#define IRDA_STATE_ENABLE ((uint32_t)USART_CR1_UE)
#define IS_IRDA_STATE(STATE) (((STATE) == IRDA_STATE_DISABLE) || \
((STATE) == IRDA_STATE_ENABLE))
/**
* @}
*/
/** @defgroup IRDA_Mode
* @{
*/
#define IRDA_MODE_DISABLE ((uint32_t)0x0000)
#define IRDA_MODE_ENABLE ((uint32_t)USART_CR3_IREN)
#define IS_IRDA_MODE(STATE) (((STATE) == IRDA_MODE_DISABLE) || \
((STATE) == IRDA_MODE_ENABLE))
/**
* @}
*/
/** @defgroup IRDA_One_Bit
* @{
*/
#define IRDA_ONE_BIT_SAMPLE_DISABLED ((uint32_t)0x00000000)
#define IRDA_ONE_BIT_SAMPLE_ENABLED ((uint32_t)USART_CR3_ONEBIT)
#define IS_IRDA_ONEBIT_SAMPLE(ONEBIT) (((ONEBIT) == IRDA_ONE_BIT_SAMPLE_DISABLED) || \
((ONEBIT) == IRDA_ONE_BIT_SAMPLE_ENABLED))
/**
* @}
*/
/** @defgroup IRDA_DMA_Tx
* @{
*/
#define IRDA_DMA_TX_DISABLE ((uint32_t)0x00000000)
#define IRDA_DMA_TX_ENABLE ((uint32_t)USART_CR3_DMAT)
#define IS_IRDA_DMA_TX(DMATX) (((DMATX) == IRDA_DMA_TX_DISABLE) || \
((DMATX) == IRDA_DMA_TX_ENABLE))
/**
* @}
*/
/** @defgroup IRDA_DMA_Rx
* @{
*/
#define IRDA_DMA_RX_DISABLE ((uint32_t)0x0000)
#define IRDA_DMA_RX_ENABLE ((uint32_t)USART_CR3_DMAR)
#define IS_IRDA_DMA_RX(DMARX) (((DMARX) == IRDA_DMA_RX_DISABLE) || \
((DMARX) == IRDA_DMA_RX_ENABLE))
/**
* @}
*/
/** @defgroup IRDA_Flags
* Elements values convention: 0xXXXX
* - 0xXXXX : Flag mask in the ISR register
* @{
*/
#define IRDA_FLAG_REACK ((uint32_t)0x00400000)
#define IRDA_FLAG_TEACK ((uint32_t)0x00200000)
#define IRDA_FLAG_BUSY ((uint32_t)0x00010000)
#define IRDA_FLAG_ABRF ((uint32_t)0x00008000)
#define IRDA_FLAG_ABRE ((uint32_t)0x00004000)
#define IRDA_FLAG_TXE ((uint32_t)0x00000080)
#define IRDA_FLAG_TC ((uint32_t)0x00000040)
#define IRDA_FLAG_RXNE ((uint32_t)0x00000020)
#define IRDA_FLAG_ORE ((uint32_t)0x00000008)
#define IRDA_FLAG_NE ((uint32_t)0x00000004)
#define IRDA_FLAG_FE ((uint32_t)0x00000002)
#define IRDA_FLAG_PE ((uint32_t)0x00000001)
/**
* @}
*/
/** @defgroup IRDA_Interrupt_definition
* Elements values convention: 0000ZZZZ0XXYYYYYb
* - YYYYY : Interrupt source position in the XX register (5bits)
* - XX : Interrupt source register (2bits)
* - 01: CR1 register
* - 10: CR2 register
* - 11: CR3 register
* - ZZZZ : Flag position in the ISR register(4bits)
* @{
*/
#define IRDA_IT_PE ((uint16_t)0x0028)
#define IRDA_IT_TXE ((uint16_t)0x0727)
#define IRDA_IT_TC ((uint16_t)0x0626)
#define IRDA_IT_RXNE ((uint16_t)0x0525)
#define IRDA_IT_IDLE ((uint16_t)0x0424)
/** Elements values convention: 000000000XXYYYYYb
* - YYYYY : Interrupt source position in the XX register (5bits)
* - XX : Interrupt source register (2bits)
* - 01: CR1 register
* - 10: CR2 register
* - 11: CR3 register
*/
#define IRDA_IT_ERR ((uint16_t)0x0060)
/** Elements values convention: 0000ZZZZ00000000b
* - ZZZZ : Flag position in the ISR register(4bits)
*/
#define IRDA_IT_ORE ((uint16_t)0x0300)
#define IRDA_IT_NE ((uint16_t)0x0200)
#define IRDA_IT_FE ((uint16_t)0x0100)
/**
* @}
*/
/** @defgroup IRDA_IT_CLEAR_Flags
* @{
*/
#define IRDA_CLEAR_PEF USART_ICR_PECF /*!< Parity Error Clear Flag */
#define IRDA_CLEAR_FEF USART_ICR_FECF /*!< Framing Error Clear Flag */
#define IRDA_CLEAR_NEF USART_ICR_NCF /*!< Noise detected Clear Flag */
#define IRDA_CLEAR_OREF USART_ICR_ORECF /*!< OverRun Error Clear Flag */
#define IRDA_CLEAR_TCF USART_ICR_TCCF /*!< Transmission Complete Clear Flag */
/**
* @}
*/
/** @defgroup IRDA_Request_Parameters
* @{
*/
#define IRDA_AUTOBAUD_REQUEST ((uint16_t)USART_RQR_ABRRQ) /*!< Auto-Baud Rate Request */
#define IRDA_RXDATA_FLUSH_REQUEST ((uint16_t)USART_RQR_RXFRQ) /*!< Receive Data flush Request */
#define IRDA_TXDATA_FLUSH_REQUEST ((uint16_t)USART_RQR_TXFRQ) /*!< Transmit data flush Request */
#define IS_IRDA_REQUEST_PARAMETER(PARAM) (((PARAM) == IRDA_AUTOBAUD_REQUEST) || \
((PARAM) == IRDA_SENDBREAK_REQUEST) || \
((PARAM) == IRDA_MUTE_MODE_REQUEST) || \
((PARAM) == IRDA_RXDATA_FLUSH_REQUEST) || \
((PARAM) == IRDA_TXDATA_FLUSH_REQUEST))
/**
* @}
*/
/** @defgroup IRDA_Interruption_Mask
* @{
*/
#define IRDA_IT_MASK ((uint16_t)0x001F)
/**
* @}
*/
/**
* @}
*/
/* Exported macro ------------------------------------------------------------*/
/** @defgroup IRDA_Exported_Macros
* @{
*/
/** @brief Reset IRDA handle state
* @param __HANDLE__: specifies the IRDA Handle.
* The Handle Instance which can be USART1 or USART2.
* @retval None
*/
#define __HAL_IRDA_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_IRDA_STATE_RESET)
/** @brief Check whether the specified IRDA flag is set or not.
* @param __HANDLE__: specifies the IRDA Handle.
* The Handle Instance which can be USART1 or USART2.
* UART peripheral
* @param __FLAG__: specifies the flag to check.
* This parameter can be one of the following values:
* @arg IRDA_FLAG_REACK: Receive enable ackowledge flag
* @arg IRDA_FLAG_TEACK: Transmit enable ackowledge flag
* @arg IRDA_FLAG_BUSY: Busy flag
* @arg IRDA_FLAG_ABRF: Auto Baud rate detection flag
* @arg IRDA_FLAG_ABRE: Auto Baud rate detection error flag
* @arg IRDA_FLAG_TXE: Transmit data register empty flag
* @arg IRDA_FLAG_TC: Transmission Complete flag
* @arg IRDA_FLAG_RXNE: Receive data register not empty flag
* @arg IRDA_FLAG_IDLE: Idle Line detection flag
* @arg IRDA_FLAG_ORE: OverRun Error flag
* @arg IRDA_FLAG_NE: Noise Error flag
* @arg IRDA_FLAG_FE: Framing Error flag
* @arg IRDA_FLAG_PE: Parity Error flag
* @retval The new state of __FLAG__ (TRUE or FALSE).
*/
#define __HAL_IRDA_GET_FLAG(__HANDLE__, __FLAG__) (((__HANDLE__)->Instance->ISR & (__FLAG__)) == (__FLAG__))
/** @brief Enable the specified IRDA interrupt.
* @param __HANDLE__: specifies the IRDA Handle.
* The Handle Instance which can be USART1 or USART2.
* UART peripheral
* @param __INTERRUPT__: specifies the IRDA interrupt source to enable.
* This parameter can be one of the following values:
* @arg IRDA_IT_TXE: Transmit Data Register empty interrupt
* @arg IRDA_IT_TC: Transmission complete interrupt
* @arg IRDA_IT_RXNE: Receive Data register not empty interrupt
* @arg IRDA_IT_IDLE: Idle line detection interrupt
* @arg IRDA_IT_PE: Parity Error interrupt
* @arg IRDA_IT_ERR: Error interrupt(Frame error, noise error, overrun error)
* @retval None
*/
#define __HAL_IRDA_ENABLE_IT(__HANDLE__, __INTERRUPT__) (((((uint8_t)(__INTERRUPT__)) >> 5) == 1)? ((__HANDLE__)->Instance->CR1 |= (1 << ((__INTERRUPT__) & IRDA_IT_MASK))): \
((((uint8_t)(__INTERRUPT__)) >> 5) == 2)? ((__HANDLE__)->Instance->CR2 |= (1 << ((__INTERRUPT__) & IRDA_IT_MASK))): \
((__HANDLE__)->Instance->CR3 |= (1 << ((__INTERRUPT__) & IRDA_IT_MASK))))
/** @brief Disable the specified IRDA interrupt.
* @param __HANDLE__: specifies the IRDA Handle.
* The Handle Instance which can be USART1 or USART2.
* @param __INTERRUPT__: specifies the IRDA interrupt source to disable.
* This parameter can be one of the following values:
* @arg IRDA_IT_TXE: Transmit Data Register empty interrupt
* @arg IRDA_IT_TC: Transmission complete interrupt
* @arg IRDA_IT_RXNE: Receive Data register not empty interrupt
* @arg IRDA_IT_IDLE: Idle line detection interrupt
* @arg IRDA_IT_PE: Parity Error interrupt
* @arg IRDA_IT_ERR: Error interrupt(Frame error, noise error, overrun error)
* @retval None
*/
#define __HAL_IRDA_DISABLE_IT(__HANDLE__, __INTERRUPT__) (((((uint8_t)(__INTERRUPT__)) >> 5) == 1)? ((__HANDLE__)->Instance->CR1 &= ~ ((uint32_t)1 << ((__INTERRUPT__) & IRDA_IT_MASK))): \
((((uint8_t)(__INTERRUPT__)) >> 5) == 2)? ((__HANDLE__)->Instance->CR2 &= ~ ((uint32_t)1 << ((__INTERRUPT__) & IRDA_IT_MASK))): \
((__HANDLE__)->Instance->CR3 &= ~ ((uint32_t)1 << ((__INTERRUPT__) & IRDA_IT_MASK))))
/** @brief Check whether the specified IRDA interrupt has occurred or not.
* @param __HANDLE__: specifies the IRDA Handle.
* The Handle Instance which can be USART1 or USART2.
* @param __IT__: specifies the IRDA interrupt source to check.
* This parameter can be one of the following values:
* @arg IRDA_IT_TXE: Transmit Data Register empty interrupt
* @arg IRDA_IT_TC: Transmission complete interrupt
* @arg IRDA_IT_RXNE: Receive Data register not empty interrupt
* @arg IRDA_IT_IDLE: Idle line detection interrupt
* @arg IRDA_IT_ORE: OverRun Error interrupt
* @arg IRDA_IT_NE: Noise Error interrupt
* @arg IRDA_IT_FE: Framing Error interrupt
* @arg IRDA_IT_PE: Parity Error interrupt
* @retval The new state of __IT__ (TRUE or FALSE).
*/
#define __HAL_IRDA_GET_IT(__HANDLE__, __IT__) ((__HANDLE__)->Instance->ISR & ((uint32_t)1 << ((__IT__)>> 0x08)))
/** @brief Check whether the specified IRDA interrupt source is enabled.
* @param __HANDLE__: specifies the IRDA Handle.
* The Handle Instance which can be USART1 or USART2.
* @param __IT__: specifies the IRDA interrupt source to check.
* This parameter can be one of the following values:
* @arg IRDA_IT_TXE: Transmit Data Register empty interrupt
* @arg IRDA_IT_TC: Transmission complete interrupt
* @arg IRDA_IT_RXNE: Receive Data register not empty interrupt
* @arg IRDA_IT_IDLE: Idle line detection interrupt
* @arg IRDA_IT_ORE: OverRun Error interrupt
* @arg IRDA_IT_NE: Noise Error interrupt
* @arg IRDA_IT_FE: Framing Error interrupt
* @arg IRDA_IT_PE: Parity Error interrupt
* @retval The new state of __IT__ (TRUE or FALSE).
*/
#define __HAL_IRDA_GET_IT_SOURCE(__HANDLE__, __IT__) ((((((uint8_t)(__IT__)) >> 5) == 1)? (__HANDLE__)->Instance->CR1:(((((uint8_t)(__IT__)) >> 5) == 2)? \
(__HANDLE__)->Instance->CR2 : (__HANDLE__)->Instance->CR3)) & ((uint32_t)1 << (((uint16_t)(__IT__)) & IRDA_IT_MASK)))
/** @brief Clear the specified IRDA ISR flag, in setting the proper ICR register flag.
* @param __HANDLE__: specifies the IRDA Handle.
* The Handle Instance which can be USART1 or USART2.
* @param __IT_CLEAR__: specifies the interrupt clear register flag that needs to be set
* to clear the corresponding interrupt
* This parameter can be one of the following values:
* @arg IRDA_CLEAR_PEF: Parity Error Clear Flag
* @arg IRDA_CLEAR_FEF: Framing Error Clear Flag
* @arg IRDA_CLEAR_NEF: Noise detected Clear Flag
* @arg IRDA_CLEAR_OREF: OverRun Error Clear Flag
* @arg IRDA_CLEAR_TCF: Transmission Complete Clear Flag
* @retval None
*/
#define __HAL_IRDA_CLEAR_IT(__HANDLE__, __IT_CLEAR__) ((__HANDLE__)->Instance->ICR |= (uint32_t)(__IT_CLEAR__))
/** @brief Set a specific IRDA request flag.
* @param __HANDLE__: specifies the IRDA Handle.
* The Handle Instance which can be USART1 or USART2.
* @param __REQ__: specifies the request flag to set
* This parameter can be one of the following values:
* @arg IRDA_AUTOBAUD_REQUEST: Auto-Baud Rate Request
* @arg IRDA_RXDATA_FLUSH_REQUEST: Receive Data flush Request
* @arg IRDA_TXDATA_FLUSH_REQUEST: Transmit data flush Request
*
* @retval None
*/
#define __HAL_IRDA_SEND_REQ(__HANDLE__, __REQ__) ((__HANDLE__)->Instance->RQR |= (uint16_t)(__REQ__))
/** @brief Enable UART/USART associated to IRDA Handle
* @param __HANDLE__: specifies the IRDA Handle.
* The Handle Instance which can be USART1 or USART2.
* @retval None
*/
#define __HAL_IRDA_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR1 |= USART_CR1_UE)
/** @brief Disable UART/USART associated to IRDA Handle
* @param __HANDLE__: specifies the IRDA Handle.
* The Handle Instance which can be USART1 or USART2.
* @retval None
*/
#define __HAL_IRDA_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR1 &= ~USART_CR1_UE)
/** @brief Ensure that IRDA Baud rate is less or equal to maximum value
* @param __BAUDRATE__: specifies the IRDA Baudrate set by the user.
* @retval True or False
*/
#define IS_IRDA_BAUDRATE(__BAUDRATE__) ((__BAUDRATE__) < 115201)
/** @brief Ensure that IRDA prescaler value is strictly larger than 0
* @param __PRESCALER__: specifies the IRDA prescaler value set by the user.
* @retval True or False
*/
#define IS_IRDA_PRESCALER(__PRESCALER__) ((__PRESCALER__) > 0)
/**
* @}
*/
/* Include IRDA HAL Extension module */
#include "stm32l0xx_hal_irda_ex.h"
/* Exported functions --------------------------------------------------------*/
/* Initialization/de-initialization methods **********************************/
HAL_StatusTypeDef HAL_IRDA_Init(IRDA_HandleTypeDef *hirda);
HAL_StatusTypeDef HAL_IRDA_DeInit(IRDA_HandleTypeDef *hirda);
void HAL_IRDA_MspInit(IRDA_HandleTypeDef *hirda);
void HAL_IRDA_MspDeInit(IRDA_HandleTypeDef *hirda);
/* IO operation methods *******************************************************/
HAL_StatusTypeDef HAL_IRDA_Transmit(IRDA_HandleTypeDef *hirda, uint8_t *pData, uint16_t Size, uint32_t Timeout);
HAL_StatusTypeDef HAL_IRDA_Receive(IRDA_HandleTypeDef *hirda, uint8_t *pData, uint16_t Size, uint32_t Timeout);
HAL_StatusTypeDef HAL_IRDA_Transmit_IT(IRDA_HandleTypeDef *hirda, uint8_t *pData, uint16_t Size);
HAL_StatusTypeDef HAL_IRDA_Receive_IT(IRDA_HandleTypeDef *hirda, uint8_t *pData, uint16_t Size);
HAL_StatusTypeDef HAL_IRDA_Transmit_DMA(IRDA_HandleTypeDef *hirda, uint8_t *pData, uint16_t Size);
HAL_StatusTypeDef HAL_IRDA_Receive_DMA(IRDA_HandleTypeDef *hirda, uint8_t *pData, uint16_t Size);
HAL_StatusTypeDef HAL_IRDA_DMAPause(IRDA_HandleTypeDef *hirda);
HAL_StatusTypeDef HAL_IRDA_DMAResume(IRDA_HandleTypeDef *hirda);
HAL_StatusTypeDef HAL_IRDA_DMAStop(IRDA_HandleTypeDef *hirda);
void HAL_IRDA_IRQHandler(IRDA_HandleTypeDef *hirda);
void HAL_IRDA_TxCpltCallback(IRDA_HandleTypeDef *hirda);
void HAL_IRDA_RxCpltCallback(IRDA_HandleTypeDef *hirda);
void HAL_IRDA_TxHalfCpltCallback(IRDA_HandleTypeDef *hirda);
void HAL_IRDA_RxHalfCpltCallback(IRDA_HandleTypeDef *hirda);
void HAL_IRDA_ErrorCallback(IRDA_HandleTypeDef *hirda);
/* Peripheral State methods **************************************************/
HAL_IRDA_StateTypeDef HAL_IRDA_GetState(IRDA_HandleTypeDef *hirda);
uint32_t HAL_IRDA_GetError(IRDA_HandleTypeDef *hirda);
/**
* @}
*/
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif /* __STM32L0xx_HAL_IRDA_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,221 @@
/**
******************************************************************************
* @file stm32l0xx_hal_irda_ex.h
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief Header file of IRDA HAL Extension module.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2013 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32L0xx_HAL_IRDA_EX_H
#define __STM32L0xx_HAL_IRDA_EX_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal_def.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @addtogroup IRDAEx
* @{
*/
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
/** @defgroup IRDAEx_Extended_Exported_Constants
* @{
*/
/** @defgroup IRDAEx_Word_Length
* @{
*/
#define IRDA_WORDLENGTH_7B ((uint32_t)USART_CR1_M_1)
#define IRDA_WORDLENGTH_8B ((uint32_t)0x00000000)
#define IRDA_WORDLENGTH_9B ((uint32_t)USART_CR1_M_0)
#define IS_IRDA_WORD_LENGTH(LENGTH) (((LENGTH) == IRDA_WORDLENGTH_7B) || \
((LENGTH) == IRDA_WORDLENGTH_8B) || \
((LENGTH) == IRDA_WORDLENGTH_9B))
/**
* @}
*/
/**
* @}
*/
/* Exported macro ------------------------------------------------------------*/
/** @defgroup IRDAEx_Extended_Exported_Macros
* @{
*/
/** @brief Reports the IRDA clock source.
* @param __HANDLE__: specifies the UART Handle
* @param __CLOCKSOURCE__ : output variable
* @retval IRDA clocking source, written in __CLOCKSOURCE__.
*/
#define __HAL_IRDA_GETCLOCKSOURCE(__HANDLE__,__CLOCKSOURCE__) \
do { \
if((__HANDLE__)->Instance == USART1) \
{ \
switch(__HAL_RCC_GET_USART1_SOURCE()) \
{ \
case RCC_USART1CLKSOURCE_PCLK2: \
(__CLOCKSOURCE__) = IRDA_CLOCKSOURCE_PCLK2; \
break; \
case RCC_USART1CLKSOURCE_HSI: \
(__CLOCKSOURCE__) = IRDA_CLOCKSOURCE_HSI; \
break; \
case RCC_USART1CLKSOURCE_SYSCLK: \
(__CLOCKSOURCE__) = IRDA_CLOCKSOURCE_SYSCLK; \
break; \
case RCC_USART1CLKSOURCE_LSE: \
(__CLOCKSOURCE__) = IRDA_CLOCKSOURCE_LSE; \
break; \
default: \
break; \
} \
} \
else if((__HANDLE__)->Instance == USART2) \
{ \
switch(__HAL_RCC_GET_USART2_SOURCE()) \
{ \
case RCC_USART2CLKSOURCE_PCLK1: \
(__CLOCKSOURCE__) = IRDA_CLOCKSOURCE_PCLK1; \
break; \
case RCC_USART2CLKSOURCE_HSI: \
(__CLOCKSOURCE__) = IRDA_CLOCKSOURCE_HSI; \
break; \
case RCC_USART2CLKSOURCE_SYSCLK: \
(__CLOCKSOURCE__) = IRDA_CLOCKSOURCE_SYSCLK; \
break; \
case RCC_USART2CLKSOURCE_LSE: \
(__CLOCKSOURCE__) = IRDA_CLOCKSOURCE_LSE; \
break; \
default: \
break; \
} \
} \
else if((__HANDLE__)->Instance == LPUART1) \
{ \
switch(__HAL_RCC_GET_LPUART1_SOURCE()) \
{ \
case RCC_LPUART1CLKSOURCE_PCLK1: \
(__CLOCKSOURCE__) = IRDA_CLOCKSOURCE_PCLK1; \
break; \
case RCC_LPUART1CLKSOURCE_HSI: \
(__CLOCKSOURCE__) = IRDA_CLOCKSOURCE_HSI; \
break; \
case RCC_LPUART1CLKSOURCE_SYSCLK: \
(__CLOCKSOURCE__) = IRDA_CLOCKSOURCE_SYSCLK; \
break; \
case RCC_LPUART1CLKSOURCE_LSE: \
(__CLOCKSOURCE__) = IRDA_CLOCKSOURCE_LSE; \
break; \
default: \
break; \
} \
} \
} while(0)
/** @brief Reports the mask to apply to retrieve the received data
* according to the word length and to the parity bits activation.
* @param __HANDLE__: specifies the IRDA Handle
* @retval mask to apply to USART RDR register value.
*/
#define __HAL_IRDA_MASK_COMPUTATION(__HANDLE__) \
do { \
if ((__HANDLE__)->Init.WordLength == IRDA_WORDLENGTH_9B) \
{ \
if ((__HANDLE__)->Init.Parity == IRDA_PARITY_NONE) \
{ \
(__HANDLE__)->Mask = 0x01FF ; \
} \
else \
{ \
(__HANDLE__)->Mask = 0x00FF ; \
} \
} \
else if ((__HANDLE__)->Init.WordLength == IRDA_WORDLENGTH_8B) \
{ \
if ((__HANDLE__)->Init.Parity == IRDA_PARITY_NONE) \
{ \
(__HANDLE__)->Mask = 0x00FF ; \
} \
else \
{ \
(__HANDLE__)->Mask = 0x007F ; \
} \
} \
else if ((__HANDLE__)->Init.WordLength == IRDA_WORDLENGTH_7B) \
{ \
if ((__HANDLE__)->Init.Parity == IRDA_PARITY_NONE) \
{ \
(__HANDLE__)->Mask = 0x007F ; \
} \
else \
{ \
(__HANDLE__)->Mask = 0x003F ; \
} \
} \
} while(0)
/**
* @}
*/
/* Exported functions --------------------------------------------------------*/
/* Initialization/de-initialization methods **********************************/
/* IO operation methods *******************************************************/
/* Peripheral Control methods ************************************************/
/* Peripheral State methods **************************************************/
/**
* @}
*/
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif /* __STM32L0xx_HAL_IRDA_EX_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,410 @@
/**
******************************************************************************
* @file stm32l0xx_hal_iwdg.c
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief IWDG HAL module driver.
* This file provides firmware functions to manage the following
* functionalities of the Independent Watchdog (IWDG) peripheral:
* + Initialization and de-initialization functions
* + IO operation functions
* + Peripheral State functions
*
@verbatim
==============================================================================
##### IWDG Generic 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 refreshed at regular intervals, otherwise the
watchdog generates an MCU reset when the counter reaches 0.
(+) 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 an IWDG
reset occurs.
[..] Min-max timeout value @32KHz (LSI): ~0.512ms / ~32.0s
The IWDG timeout may vary due to LSI frequency dispersion. STM32L0xx
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.
##### How to use this driver #####
==============================================================================
[..]
If Window option is disabled
(+) Use IWDG using HAL_IWDG_Init() function to :
(++) Enable write access to IWDG_PR, IWDG_RLR.
(++) Configure the IWDG prescaler, counter reload value.
This reload value will be loaded in the IWDG counter each time the counter
is reloaded, then the IWDG will start counting down from this value.
(+) Use IWDG using HAL_IWDG_Start() function to :
(++) Reload IWDG counter with value defined in the IWDG_RLR register.
(++) Start the IWDG, 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 refresh the IWDG counter at regular
intervals during normal operation to prevent an MCU reset, using
HAL_IWDG_Refresh() function.
[..]
if Window option is enabled:
(+) Use IWDG using HAL_IWDG_Start() function to enable IWDG downcounter
(+) Use IWDG using HAL_IWDG_Init() function to :
(++) Enable write access to IWDG_PR, IWDG_RLR and IWDG_WINR registers.
(++) Configure the IWDG prescaler, reload value and window value.
(+) Then the application program must refresh the IWDG counter at regular
intervals during normal operation to prevent an MCU reset, using
HAL_IWDG_Refresh() function.
*** IWDG HAL driver macros list ***
====================================
[..]
Below the list of most used macros in IWDG HAL driver.
(+) __HAL_IWDG_START: Enable the IWDG peripheral
(+) __HAL_IWDG_RELOAD_COUNTER: Reloads IWDG counter with value defined in the reload register
(+) __HAL_IWDG_ENABLE_WRITE_ACCESS : Enable write access to IWDG_PR and IWDG_RLR registers
(+) __HAL_IWDG_DISABLE_WRITE_ACCESS : Disable write access to IWDG_PR and IWDG_RLR registers
(+) __HAL_IWDG_GET_FLAG: Get the selected IWDG's flag status
@endverbatim
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @defgroup IWDG
* @brief IWDG HAL module driver.
* @{
*/
#ifdef HAL_IWDG_MODULE_ENABLED
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/** @defgroup IWDG_Private_Functions
* @{
*/
/** @defgroup IWDG_Group1 Initialization and de-initialization functions
* @brief Initialization and Configuration functions.
*
@verbatim
===============================================================================
##### Initialization and de-initialization functions #####
===============================================================================
[..] This section provides functions allowing to:
(+) Initialize the IWDG according to the specified parameters
in the IWDG_InitTypeDef and create the associated handle
(+) Manage Window option
(+) Initialize the IWDG MSP
@endverbatim
* @{
*/
/**
* @brief Initializes the IWDG according to the specified
* parameters in the IWDG_InitTypeDef and creates the associated handle.
* @param hiwdg: pointer to a IWDG_HandleTypeDef structure that contains
* the configuration information for the specified IWDG module.
* @retval HAL status
*/
HAL_StatusTypeDef HAL_IWDG_Init(IWDG_HandleTypeDef *hiwdg)
{
uint32_t tickstart = 0;
/* Check the IWDG handle allocation */
if(hiwdg == NULL)
{
return HAL_ERROR;
}
/* Check the parameters */
assert_param(IS_IWDG_PRESCALER(hiwdg->Init.Prescaler));
assert_param(IS_IWDG_RELOAD(hiwdg->Init.Reload));
assert_param(IS_IWDG_WINDOW(hiwdg->Init.Window));
/* Check pending flag, if previous update not done, return error */
if((__HAL_IWDG_GET_FLAG(hiwdg, IWDG_FLAG_PVU) != RESET)
&&(__HAL_IWDG_GET_FLAG(hiwdg, IWDG_FLAG_RVU) != RESET)
&&(__HAL_IWDG_GET_FLAG(hiwdg, IWDG_FLAG_WVU) != RESET))
{
return HAL_ERROR;
}
if(hiwdg->State == HAL_IWDG_STATE_RESET)
{
/* Init the low level hardware */
HAL_IWDG_MspInit(hiwdg);
}
/* Change IWDG peripheral state */
hiwdg->State = HAL_IWDG_STATE_BUSY;
/* Enable write access to IWDG_PR, IWDG_RLR and IWDG_WINR registers */
/* by writing 0x5555 in KR */
__HAL_IWDG_ENABLE_WRITE_ACCESS(hiwdg);
/* Write to IWDG registers the IWDG_Prescaler & IWDG_Reload values to work with */
MODIFY_REG(hiwdg->Instance->PR, (uint32_t)IWDG_PR_PR, hiwdg->Init.Prescaler);
MODIFY_REG(hiwdg->Instance->RLR, (uint32_t)IWDG_RLR_RL, hiwdg->Init.Reload);
/* check if window option is enabled */
if (((hiwdg->Init.Window) != IWDG_WINDOW_DISABLE) || ((hiwdg->Instance->WINR) != IWDG_WINDOW_DISABLE))
{
tickstart = HAL_GetTick();
/* Wait for register to be updated */
while((uint32_t)(hiwdg->Instance->SR) != RESET)
{
if((HAL_GetTick() - tickstart ) > 1000)
{
/* Set IWDG state */
hiwdg->State = HAL_IWDG_STATE_TIMEOUT;
return HAL_TIMEOUT;
}
}
/* Write to IWDG WINR the IWDG_Window value to compare with */
MODIFY_REG(hiwdg->Instance->WINR, (uint32_t)IWDG_WINR_WIN, hiwdg->Init.Window);
}
/* Change IWDG peripheral state */
hiwdg->State = HAL_IWDG_STATE_READY;
/* Return function status */
return HAL_OK;
}
/**
* @brief Initializes the IWDG MSP.
* @param hiwdg: pointer to a IWDG_HandleTypeDef structure that contains
* the configuration information for the specified IWDG module.
* @retval None
*/
__weak void HAL_IWDG_MspInit(IWDG_HandleTypeDef *hiwdg)
{
/* NOTE : This function Should not be modified, when the callback is needed,
the HAL_IWDG_MspInit could be implemented in the user file
*/
}
/**
* @}
*/
/** @defgroup IWDG_Group2 IO operation functions
* @brief IO operation functions
*
@verbatim
===============================================================================
##### IO operation functions #####
===============================================================================
[..] This section provides functions allowing to:
(+) Start the IWDG.
(+) Refresh the IWDG.
@endverbatim
* @{
*/
/**
* @brief Starts the IWDG.
* @param hiwdg: pointer to a IWDG_HandleTypeDef structure that contains
* the configuration information for the specified IWDG module.
* @retval HAL status
*/
HAL_StatusTypeDef HAL_IWDG_Start(IWDG_HandleTypeDef *hiwdg)
{
uint32_t tickstart = 0;
/* Process locked */
__HAL_LOCK(hiwdg);
/* Change IWDG peripheral state */
hiwdg->State = HAL_IWDG_STATE_BUSY;
/* Reload IWDG counter with value defined in the RLR register */
if ((hiwdg->Init.Window) == IWDG_WINDOW_DISABLE)
{
__HAL_IWDG_RELOAD_COUNTER(hiwdg);
}
/* Enable the IWDG peripheral */
__HAL_IWDG_START(hiwdg);
tickstart = HAL_GetTick();
/* Wait until PVU, RVU, WVU flag are RESET */
while( (__HAL_IWDG_GET_FLAG(hiwdg, IWDG_FLAG_PVU) != RESET)
&&(__HAL_IWDG_GET_FLAG(hiwdg, IWDG_FLAG_RVU) != RESET)
&&(__HAL_IWDG_GET_FLAG(hiwdg, IWDG_FLAG_WVU) != RESET) )
{
if((HAL_GetTick() - tickstart ) > 1000)
{
/* Set IWDG state */
hiwdg->State = HAL_IWDG_STATE_TIMEOUT;
/* Process unlocked */
__HAL_UNLOCK(hiwdg);
return HAL_TIMEOUT;
}
}
/* Change IWDG peripheral state */
hiwdg->State = HAL_IWDG_STATE_READY;
/* Process Unlocked */
__HAL_UNLOCK(hiwdg);
/* Return function status */
return HAL_OK;
}
/**
* @brief Refreshes the IWDG.
* @param hiwdg: pointer to a IWDG_HandleTypeDef structure that contains
* the configuration information for the specified IWDG module.
* @retval HAL status
*/
HAL_StatusTypeDef HAL_IWDG_Refresh(IWDG_HandleTypeDef *hiwdg)
{
uint32_t tickstart = 0;
/* Process Locked */
__HAL_LOCK(hiwdg);
/* Change IWDG peripheral state */
hiwdg->State = HAL_IWDG_STATE_BUSY;
tickstart = HAL_GetTick();
/* Wait until RVU flag is RESET */
while(__HAL_IWDG_GET_FLAG(hiwdg, IWDG_FLAG_RVU) != RESET)
{
if((HAL_GetTick() - tickstart ) > 1000)
{
/* Set IWDG state */
hiwdg->State = HAL_IWDG_STATE_TIMEOUT;
/* Process unlocked */
__HAL_UNLOCK(hiwdg);
return HAL_TIMEOUT;
}
}
/* Reload IWDG counter with value defined in the reload register */
__HAL_IWDG_RELOAD_COUNTER(hiwdg);
/* Change IWDG peripheral state */
hiwdg->State = HAL_IWDG_STATE_READY;
/* Process Unlocked */
__HAL_UNLOCK(hiwdg);
/* Return function status */
return HAL_OK;
}
/**
* @}
*/
/** @defgroup IWDG_Group3 Peripheral State functions
* @brief Peripheral State functions.
*
@verbatim
===============================================================================
##### Peripheral State functions #####
===============================================================================
[..]
This subsection permits to get in run-time the status of the peripheral
and the data flow.
@endverbatim
* @{
*/
/**
* @brief Returns the IWDG state.
* @param hiwdg: pointer to a IWDG_HandleTypeDef structure that contains
* the configuration information for the specified IWDG module.
* @retval HAL state
*/
HAL_IWDG_StateTypeDef HAL_IWDG_GetState(IWDG_HandleTypeDef *hiwdg)
{
return hiwdg->State;
}
/**
* @}
*/
/**
* @}
*/
#endif /* HAL_IWDG_MODULE_ENABLED */
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,296 @@
/**
******************************************************************************
* @file stm32l0xx_hal_iwdg.h
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief Header file of IWDG HAL module.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32L0xx_HAL_IWDG_H
#define __STM32L0xx_HAL_IWDG_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal_def.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @addtogroup IWDG
* @{
*/
/* Exported types ------------------------------------------------------------*/
/** @defgroup IWDG_Exported_Types IWDG Exported Types
* @{
*/
/**
* @brief IWDG HAL State Structure definition
*/
typedef enum
{
HAL_IWDG_STATE_RESET = 0x00, /*!< IWDG not yet initialized or disabled */
HAL_IWDG_STATE_READY = 0x01, /*!< IWDG initialized and ready for use */
HAL_IWDG_STATE_BUSY = 0x02, /*!< IWDG internal process is ongoing */
HAL_IWDG_STATE_TIMEOUT = 0x03, /*!< IWDG timeout state */
HAL_IWDG_STATE_ERROR = 0x04 /*!< IWDG error state */
}HAL_IWDG_StateTypeDef;
/**
* @brief IWDG Init structure definition
*/
typedef struct
{
uint32_t Prescaler; /*!< Select the prescaler of the IWDG.
This parameter can be a value of @ref IWDG_Prescaler */
uint32_t Reload; /*!< Specifies the IWDG down-counter reload value.
This parameter must be a number between Min_Data = 0 and Max_Data = 0x0FFF */
uint32_t Window; /*!< Specifies the window value to be compared to the down-counter.
This parameter must be a number between Min_Data = 0 and Max_Data = 0x0FFF */
} IWDG_InitTypeDef;
/**
* @brief IWDG Handle Structure definition
*/
typedef struct
{
IWDG_TypeDef *Instance; /*!< Register base address */
IWDG_InitTypeDef Init; /*!< IWDG required parameters */
HAL_LockTypeDef Lock; /*!< IWDG Locking object */
__IO HAL_IWDG_StateTypeDef State; /*!< IWDG communication state */
}IWDG_HandleTypeDef;
/**
* @}
*/
/* Exported constants --------------------------------------------------------*/
/** @defgroup IWDG_Exported_Constants IWDG Exported Constants
* @{
*/
/** @defgroup IWDG_Registers_BitMask IWDG_Registers_BitMask
* @brief IWDG registers bit mask
* @{
*/
/* --- KR Register ---*/
/* KR register bit mask */
#define KR_KEY_RELOAD ((uint32_t)0xAAAA) /*!< IWDG Reload Counter Enable */
#define KR_KEY_ENABLE ((uint32_t)0xCCCC) /*!< IWDG Peripheral Enable */
#define KR_KEY_EWA ((uint32_t)0x5555) /*!< IWDG KR Write Access Enable */
#define KR_KEY_DWA ((uint32_t)0x0000) /*!< IWDG KR Write Access Disable */
#define IS_IWDG_KR(__KR__) (((__KR__) == KR_KEY_RELOAD) || \
((__KR__) == KR_KEY_ENABLE))|| \
((__KR__) == KR_KEY_EWA)) || \
((__KR__) == KR_KEY_DWA))
/**
* @}
*/
/** @defgroup IWDG_Flag_definition IWDG_Flag_definition
* @{
*/
#define IWDG_FLAG_PVU ((uint32_t)IWDG_SR_PVU) /*!< Watchdog counter prescaler value update flag */
#define IWDG_FLAG_RVU ((uint32_t)IWDG_SR_RVU) /*!< Watchdog counter reload value update flag */
#define IWDG_FLAG_WVU ((uint32_t)IWDG_SR_WVU) /*!< Watchdog counter window value update Flag */
#define IS_IWDG_FLAG(FLAG) (((FLAG) == IWDG_FLAG_PVU) || \
((FLAG) == IWDG_FLAG_RVU) || \
((FLAG) == IWDG_FLAG_WVU))
/**
* @}
*/
/** @defgroup IWDG_Prescaler IWDG_Prescaler
* @{
*/
#define IWDG_PRESCALER_4 ((uint8_t)0x00) /*!< IWDG prescaler set to 4 */
#define IWDG_PRESCALER_8 ((uint8_t)(IWDG_PR_PR_0)) /*!< IWDG prescaler set to 8 */
#define IWDG_PRESCALER_16 ((uint8_t)(IWDG_PR_PR_1)) /*!< IWDG prescaler set to 16 */
#define IWDG_PRESCALER_32 ((uint8_t)(IWDG_PR_PR_1 | IWDG_PR_PR_0)) /*!< IWDG prescaler set to 32 */
#define IWDG_PRESCALER_64 ((uint8_t)(IWDG_PR_PR_2)) /*!< IWDG prescaler set to 64 */
#define IWDG_PRESCALER_128 ((uint8_t)(IWDG_PR_PR_2 | IWDG_PR_PR_0)) /*!< IWDG prescaler set to 128 */
#define IWDG_PRESCALER_256 ((uint8_t)(IWDG_PR_PR_2 | IWDG_PR_PR_1)) /*!< IWDG prescaler set to 256 */
#define IS_IWDG_PRESCALER(__PRESCALER__) (((__PRESCALER__) == IWDG_PRESCALER_4) || \
((__PRESCALER__) == IWDG_PRESCALER_8) || \
((__PRESCALER__) == IWDG_PRESCALER_16) || \
((__PRESCALER__) == IWDG_PRESCALER_32) || \
((__PRESCALER__) == IWDG_PRESCALER_64) || \
((__PRESCALER__) == IWDG_PRESCALER_128)|| \
((__PRESCALER__) == IWDG_PRESCALER_256))
/**
* @}
*/
/** @defgroup IWDG_Reload_Value IWDG_Reload_Value
* @{
*/
#define IS_IWDG_RELOAD(__RELOAD__) ((__RELOAD__) <= 0xFFF)
/**
* @}
*/
/** @defgroup IWDG_CounterWindow_Value
* @{
*/
#define IS_IWDG_WINDOW(VALUE) ((VALUE) <= 0xFFF)
/**
* @}
*/
/** @defgroup IWDG_Window
* @{
*/
#define IWDG_WINDOW_DISABLE 0xFFF
/**
* @}
*/
/**
* @}
*/
/* Exported macro ------------------------------------------------------------*/
/** @defgroup IWDG_Exported_Macro
* @{
*/
/** @brief Reset IWDG handle state
* @param __HANDLE__: IWDG handle
* @retval None
*/
#define __HAL_IWDG_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_IWDG_STATE_RESET)
/**
* @brief Enables the IWDG peripheral.
* @param __HANDLE__: IWDG handle
* @retval None
*/
#define __HAL_IWDG_START(__HANDLE__) WRITE_REG((__HANDLE__)->Instance->KR, KR_KEY_ENABLE)
/**
* @brief Reloads IWDG counter with value defined in the reload register
* (write access to IWDG_PR and IWDG_RLR registers disabled).
* @param __HANDLE__: IWDG handle
* @retval None
*/
#define __HAL_IWDG_RELOAD_COUNTER(__HANDLE__) WRITE_REG((__HANDLE__)->Instance->KR, KR_KEY_RELOAD)
/**
* @brief Enables write access to IWDG_PR, IWDG_RLR and IWDG_WINR registers.
* @param __HANDLE__: IWDG handle
* @retval None
*/
#define __HAL_IWDG_ENABLE_WRITE_ACCESS(__HANDLE__) WRITE_REG((__HANDLE__)->Instance->KR, KR_KEY_EWA)
/**
* @brief Disables write access to IWDG_PR, IWDG_RLR and IWDG_WINR registers.
* @param __HANDLE__: IWDG handle
* @retval None
*/
#define __HAL_IWDG_DISABLE_WRITE_ACCESS(__HANDLE__) WRITE_REG((__HANDLE__)->Instance->KR, KR_KEY_DWA)
/**
* @brief Gets the selected IWDG's flag status.
* @param __HANDLE__: IWDG handle
* @param __FLAG__: specifies the flag to check.
* This parameter can be one of the following values:
* @arg IWDG_FLAG_PVU: Watchdog counter reload value update flag
* @arg IWDG_FLAG_RVU: Watchdog counter prescaler value flag
* @arg IWDG_FLAG_WVU: Watchdog counter window value flag
* @retval The new state of __FLAG__ (TRUE or FALSE) .
*/
#define __HAL_IWDG_GET_FLAG(__HANDLE__, __FLAG__) (((__HANDLE__)->Instance->SR & (__FLAG__)) == (__FLAG__))
/**
* @}
*/
/* Exported functions --------------------------------------------------------*/
/** @addtogroup IWDG_Exported_Functions
* @{
*/
/* Initialization/de-initialization functions ********************************/
HAL_StatusTypeDef HAL_IWDG_Init(IWDG_HandleTypeDef *hiwdg);
void HAL_IWDG_MspInit(IWDG_HandleTypeDef *hiwdg);
/* I/O operation functions ****************************************************/
HAL_StatusTypeDef HAL_IWDG_Start(IWDG_HandleTypeDef *hiwdg);
HAL_StatusTypeDef HAL_IWDG_Refresh(IWDG_HandleTypeDef *hiwdg);
/* Peripheral State functions ************************************************/
HAL_IWDG_StateTypeDef HAL_IWDG_GetState(IWDG_HandleTypeDef *hiwdg);
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif /* __STM32L0xx_HAL_IWDG_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,577 @@
/**
******************************************************************************
* @file stm32l0xx_hal_lcd.c
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief LCD Controller HAL module driver.
* This file provides firmware functions to manage the following
* functionalities of the LCD Controller (LCD) peripheral:
* + Initialization/de-initialization methods
* + I/O operation methods
* + Peripheral State methods
*
@verbatim
==============================================================================
##### How to use this driver #####
==============================================================================
[..] The LCD HAL driver can be used as follows:
(#) Declare a LCD_HandleTypeDef handle structure.
(#) Initialize the LCD low level resources by implement the HAL_LCD_MspInit() API:
(##) Enable the LCDCLK (same as RTCCLK): to configure the RTCCLK/LCDCLK, proceed as follows:
(+) Enable the Power Controller (PWR) APB1 interface clock using the
__PWR_CLK_ENABLE() macro.
(+) Enable access to RTC domain using the HAL_PWR_EnableBkUpAccess() function.
(+) Select the RTC clock source using the __HAL_RCC_RTC_CONFIG() function.
-@- The frequency generator allows you to achieve various LCD frame rates
starting from an LCD input clock frequency (LCDCLK) which can vary
from 32 kHz up to 1 MHz.
(##) LCD pins configuration:
(+) Enable the clock for the LCD GPIOs.
(+) Configure these LCD pins as alternate function no-pull.
(##) Enable the LCD interface clock.
(#) Program the Prescaler, Divider, Blink mode, Blink Frequency Duty, Bias,
Voltage Source, Dead Time, Pulse On Duration and Contrast in the hlcd Init structure.
(#) Initialize the LCD registers by calling the HAL_LCD_Init() API.
-@- The HAL_LCD_Init() API configures also the low level Hardware GPIO, CLOCK, ...etc)
by calling the custumed HAL_LCD_MspInit() API.
-@- After calling the HAL_LCD_Init() the LCD RAM memory is cleared
(#) Optionally you can update the LCD configuration using these macros:
(+) LCD High Drive using the __HAL_LCD_HIGHDRIVER_ENABLE() and __HAL_LCD_HIGHDRIVER_DISABLE() macros
(+) LCD Pulse ON Duration using the __HAL_LCD_PULSEONDURATION_CONFIG() macro
(+) LCD Dead Time using the __HAL_LCD_DEADTIME_CONFIG() macro
(+) The LCD Blink mode and frequency using the __HAL_LCD_BLINK_CONFIG() macro
(+) The LCD Contrast using the __HAL_LCD_CONTRAST_CONFIG() macro
(#) Write to the LCD RAM memory using the HAL_LCD_Write() API, this API can be called
more time to update the different LCD RAM registers before calling
HAL_LCD_UpdateDisplayRequest() API.
(#) The HAL_LCD_Clear() API can be used to clear the LCD RAM memory.
(#) When LCD RAM memory is updated enable the update display request using
the HAL_LCD_UpdateDisplayRequest() API.
[..] LCD and low power modes:
(#) The LCD remain active during STOP mode.
@endverbatim
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @defgroup LCD
* @brief LCD HAL module driver
* @{
*/
#ifdef HAL_LCD_MODULE_ENABLED
#if !defined (STM32L051xx) && !defined (STM32L052xx) && !defined (STM32L062xx) && !defined (STM32L061xx)
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
#define LCD_TIMEOUT_VALUE 1000
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/** @defgroup LCD_Private_Functions
* @{
*/
/** @defgroup LCD_Group1 Initialization/de-initialization methods
* @brief Initialization and Configuration functions
*
@verbatim
===============================================================================
##### Initialization and Configuration functions #####
===============================================================================
[..]
@endverbatim
* @{
*/
/**
* @brief DeInitializes the LCD peripheral.
* @param hlcd: LCD handle
* @retval HAL status
*/
HAL_StatusTypeDef HAL_LCD_DeInit(LCD_HandleTypeDef *hlcd)
{
/* Check the LCD handle allocation */
if(hlcd == NULL)
{
return HAL_ERROR;
}
/* Check the parameters */
assert_param(IS_LCD_ALL_INSTANCE(hlcd->Instance));
hlcd->State = HAL_LCD_STATE_BUSY;
/* DeInit the low level hardware */
HAL_LCD_MspDeInit(hlcd);
hlcd->ErrorCode = HAL_LCD_ERROR_NONE;
hlcd->State = HAL_LCD_STATE_RESET;
/* Release Lock */
__HAL_UNLOCK(hlcd);
return HAL_OK;
}
/**
* @brief Initializes the LCD peripheral according to the specified parameters
* in the LCD_InitStruct.
* @note This function can be used only when the LCD is disabled.
* @param hlcd: LCD handle
* @retval None
*/
HAL_StatusTypeDef HAL_LCD_Init(LCD_HandleTypeDef *hlcd)
{
uint32_t tickstart = 0x00;
uint8_t counter = 0;
/* Check the LCD handle allocation */
if(hlcd == NULL)
{
return HAL_ERROR;
}
/* Check function parameters */
assert_param(IS_LCD_ALL_INSTANCE(hlcd->Instance));
assert_param(IS_LCD_PRESCALER(hlcd->Init.Prescaler));
assert_param(IS_LCD_DIVIDER(hlcd->Init.Divider));
assert_param(IS_LCD_DUTY(hlcd->Init.Duty));
assert_param(IS_LCD_BIAS(hlcd->Init.Bias));
assert_param(IS_LCD_VOLTAGE_SOURCE(hlcd->Init.VoltageSource));
assert_param(IS_LCD_PULSE_ON_DURATION(hlcd->Init.PulseOnDuration));
assert_param(IS_LCD_DEAD_TIME(hlcd->Init.DeadTime));
assert_param(IS_LCD_CONTRAST(hlcd->Init.Contrast));
assert_param(IS_LCD_BLINK_FREQUENCY(hlcd->Init.BlinkFrequency));
assert_param(IS_LCD_BLINK_MODE(hlcd->Init.BlinkMode));
if(hlcd->State == HAL_LCD_STATE_RESET)
{
/* Initialize the low level hardware (MSP) */
HAL_LCD_MspInit(hlcd);
}
hlcd->State = HAL_LCD_STATE_BUSY;
/* Disable the peripheral */
__HAL_LCD_DISABLE(hlcd);
/* Clear the LCD_RAM registers and enable the display request by setting the UDR bit
in the LCD_SR register */
for(counter = LCD_RAM_REGISTER0; counter <= LCD_RAM_REGISTER15; counter++)
{
hlcd->Instance->RAM[counter] = 0;
}
/* Enable the display request */
hlcd->Instance->SR |= LCD_SR_UDR;
/* Configure the LCD Prescaler, Divider, Blink mode and Blink Frequency:
Set PS[3:0] bits according to hlcd->Init.Prescaler value
Set DIV[3:0] bits according to hlcd->Init.Divider value
Set BLINK[1:0] bits according to hlcd->Init.BlinkMode value
Set BLINKF[2:0] bits according to hlcd->Init.BlinkFrequency value
Set DEAD[2:0] bits according to hlcd->Init.DeadTime value
Set PON[2:0] bits according to hlcd->Init.PulseOnDuration value
Set CC[2:0] bits according to hlcd->Init.Contrast value */
hlcd->Instance->FCR = (uint32_t)(hlcd->Init.Prescaler | hlcd->Init.Divider | \
hlcd->Init.BlinkMode | hlcd->Init.BlinkFrequency | \
hlcd->Init.DeadTime | hlcd->Init.PulseOnDuration | \
hlcd->Init.Contrast);
/* Wait until LCD Frame Control Register Synchronization flag (FCRSF) is set in the LCD_SR register
This bit is set by hardware each time the LCD_FCR register is updated in the LCDCLK
domain. It is cleared by hardware when writing to the LCD_FCR register.*/
LCD_WaitForSynchro(hlcd);
/* Configure the LCD Duty, Bias, Voltage Source, Dead Time, Pulse On Duration and Contrast:
Set DUTY[2:0] bits according to hlcd->Init.Duty value
Set BIAS[1:0] bits according to hlcd->Init.Bias value
Set VSEL bits according to hlcd->Init.VoltageSource value */
hlcd->Instance->CR = (uint32_t)(hlcd->Init.Duty | hlcd->Init.Bias | \
hlcd->Init.VoltageSource);
/* Enable the peripheral */
__HAL_LCD_ENABLE(hlcd);
/* Get timeout */
tickstart = HAL_GetTick();
/* Wait Until the LCD is enabled */
while((hlcd->Instance->SR & LCD_FLAG_ENS) == (uint32_t)RESET)
{
if((HAL_GetTick() - tickstart ) > LCD_TIMEOUT_VALUE)
{
hlcd->ErrorCode = HAL_LCD_ERROR_ENS;
return HAL_TIMEOUT;
}
}
/* Get timeout */
tickstart = HAL_GetTick();
/*!< Wait Until the LCD Booster is ready */
while((hlcd->Instance->SR & LCD_FLAG_RDY) == (uint32_t)RESET)
{
if((HAL_GetTick() - tickstart ) > LCD_TIMEOUT_VALUE)
{
hlcd->ErrorCode = HAL_LCD_ERROR_RDY;
return HAL_TIMEOUT;
}
}
/* Initialize the LCD state */
hlcd->ErrorCode = HAL_LCD_ERROR_NONE;
hlcd->State= HAL_LCD_STATE_READY;
return HAL_OK;
}
/**
* @brief LCD MSP DeInit.
* @param hlcd: LCD handle
* @retval None
*/
__weak void HAL_LCD_MspDeInit(LCD_HandleTypeDef *hlcd)
{
/* NOTE: This function Should not be modified, when the callback is needed,
the HAL_LCD_MspDeInit could be implemented in the user file
*/
}
/**
* @brief LCD MSP Init.
* @param hlcd: LCD handle
* @retval None
*/
__weak void HAL_LCD_MspInit(LCD_HandleTypeDef *hlcd)
{
/* NOTE: This function Should not be modified, when the callback is needed,
the HAL_LCD_MspInit could be implemented in the user file
*/
}
/**
* @}
*/
/** @defgroup LCD_Group2 IO operation methods
* @brief LCD RAM functions
*
@verbatim
===============================================================================
##### IO operation functions #####
===============================================================================
[..] Using its double buffer memory the LCD controller ensures the coherency of the
displayed information without having to use interrupts to control LCD_RAM
modification.
The application software can access the first buffer level (LCD_RAM) through
the APB interface. Once it has modified the LCD_RAM using the HAL_LCD_Write() API,
it sets the UDR flag in the LCD_SR register using the HAL_LCD_UpdateDisplayRequest() API.
This UDR flag (update display request) requests the updated information to be
moved into the second buffer level (LCD_DISPLAY).
This operation is done synchronously with the frame (at the beginning of the
next frame), until the update is completed, the LCD_RAM is write protected and
the UDR flag stays high.
Once the update is completed another flag (UDD - Update Display Done) is set and
generates an interrupt if the UDDIE bit in the LCD_FCR register is set.
The time it takes to update LCD_DISPLAY is, in the worst case, one odd and one
even frame.
The update will not occur (UDR = 1 and UDD = 0) until the display is
enabled (LCDEN = 1).
@endverbatim
* @{
*/
/**
* @brief Writes a word in the specific LCD RAM.
* @param hlcd: LCD handle
* @param RAMRegisterIndex: specifies the LCD RAM Register.
* This parameter can be one of the following values:
* @arg LCD_RAM_REGISTER0: LCD RAM Register 0
* @arg LCD_RAM_REGISTER1: LCD RAM Register 1
* @arg LCD_RAM_REGISTER2: LCD RAM Register 2
* @arg LCD_RAM_REGISTER3: LCD RAM Register 3
* @arg LCD_RAM_REGISTER4: LCD RAM Register 4
* @arg LCD_RAM_REGISTER5: LCD RAM Register 5
* @arg LCD_RAM_REGISTER6: LCD RAM Register 6
* @arg LCD_RAM_REGISTER7: LCD RAM Register 7
* @arg LCD_RAM_REGISTER8: LCD RAM Register 8
* @arg LCD_RAM_REGISTER9: LCD RAM Register 9
* @arg LCD_RAM_REGISTER10: LCD RAM Register 10
* @arg LCD_RAM_REGISTER11: LCD RAM Register 11
* @arg LCD_RAM_REGISTER12: LCD RAM Register 12
* @arg LCD_RAM_REGISTER13: LCD RAM Register 13
* @arg LCD_RAM_REGISTER14: LCD RAM Register 14
* @arg LCD_RAM_REGISTER15: LCD RAM Register 15
* @param RAMRegisterMask: specifies the LCD RAM Register Data Mask.
* @param Data: specifies LCD Data Value to be written.
* @retval None
*/
HAL_StatusTypeDef HAL_LCD_Write(LCD_HandleTypeDef *hlcd, uint32_t RAMRegisterIndex, uint32_t RAMRegisterMask, uint32_t Data)
{
uint32_t tickstart = 0x00;
if((hlcd->State == HAL_LCD_STATE_READY) || (hlcd->State == HAL_LCD_STATE_BUSY))
{
/* Check the parameters */
assert_param(IS_LCD_RAM_REGISTER(RAMRegisterIndex));
if(hlcd->State == HAL_LCD_STATE_READY)
{
/* Process Locked */
__HAL_LOCK(hlcd);
hlcd->State = HAL_LCD_STATE_BUSY;
/* Get timeout */
tickstart = HAL_GetTick();
/*!< Wait Until the LCD is ready */
while((hlcd->Instance->SR & LCD_FLAG_UDR) != (uint32_t)RESET)
{
if((HAL_GetTick() - tickstart) > LCD_TIMEOUT_VALUE)
{
hlcd->ErrorCode = HAL_LCD_ERROR_UDR;
return HAL_TIMEOUT;
}
}
}
/* Clear the data bytes position into LCD RAM register */
hlcd->Instance->RAM[RAMRegisterIndex] &= (uint32_t)RAMRegisterMask;
/* Copy the new Data bytes to LCD RAM register */
hlcd->Instance->RAM[RAMRegisterIndex] |= (uint32_t)Data;
return HAL_OK;
}
else
{
return HAL_ERROR;
}
}
/**
* @brief Clears the LCD RAM registers.
* @param hlcd: LCD handle
* @retval None
*/
HAL_StatusTypeDef HAL_LCD_Clear(LCD_HandleTypeDef *hlcd)
{
uint32_t tickstart = 0x00;
uint32_t counter = 0;
if((hlcd->State == HAL_LCD_STATE_READY) || (hlcd->State == HAL_LCD_STATE_BUSY))
{
/* Process Locked */
__HAL_LOCK(hlcd);
hlcd->State = HAL_LCD_STATE_BUSY;
/* Get timeout */
tickstart = HAL_GetTick();
/*!< Wait Until the LCD is ready */
while((hlcd->Instance->SR & LCD_FLAG_UDR) != (uint32_t)RESET)
{
if( (HAL_GetTick() - tickstart) > LCD_TIMEOUT_VALUE)
{
hlcd->ErrorCode = HAL_LCD_ERROR_UDR;
return HAL_TIMEOUT;
}
}
/* Clear the LCD_RAM registers */
for(counter = LCD_RAM_REGISTER0; counter <= LCD_RAM_REGISTER15; counter++)
{
hlcd->Instance->RAM[counter] = 0;
}
/* Update the LCD display */
HAL_LCD_UpdateDisplayRequest(hlcd);
return HAL_OK;
}
else
{
return HAL_ERROR;
}
}
/**
* @brief Enables the Update Display Request.
* @param hlcd: LCD handle
* @note Each time software modifies the LCD_RAM it must set the UDR bit to
* transfer the updated data to the second level buffer.
* The UDR bit stays set until the end of the update and during this
* time the LCD_RAM is write protected.
* @note When the display is disabled, the update is performed for all
* LCD_DISPLAY locations.
* When the display is enabled, the update is performed only for locations
* for which commons are active (depending on DUTY). For example if
* DUTY = 1/2, only the LCD_DISPLAY of COM0 and COM1 will be updated.
* @retval None
*/
HAL_StatusTypeDef HAL_LCD_UpdateDisplayRequest(LCD_HandleTypeDef *hlcd)
{
uint32_t tickstart = 0x00;
/* Clear the Update Display Done flag before starting the update display request */
__HAL_LCD_CLEAR_FLAG(hlcd, LCD_FLAG_UDD);
/* Enable the display request */
hlcd->Instance->SR |= LCD_SR_UDR;
/* Get timeout */
tickstart = HAL_GetTick();
/*!< Wait Until the LCD display is done */
while((hlcd->Instance->SR & LCD_FLAG_UDD) == (uint32_t)RESET)
{
if( (HAL_GetTick() - tickstart) > LCD_TIMEOUT_VALUE)
{
hlcd->ErrorCode = HAL_LCD_ERROR_UDD;
return HAL_TIMEOUT;
}
}
hlcd->State = HAL_LCD_STATE_READY;
/* Process Unlocked */
__HAL_UNLOCK(hlcd);
return HAL_OK;
}
/**
* @}
*/
/** @defgroup LCD_Group3 Peripheral State methods
* @brief LCD State functions
*
@verbatim
===============================================================================
##### Peripheral State functions #####
===============================================================================
[..]
This subsection provides a set of functions allowing to control the LCD:
(+) HAL_LCD_GetState() API can be helpful to check in run-time the state of the LCD peripheral State.
(+) HAL_LCD_GetError() API to return the LCD error code.
@endverbatim
* @{
*/
/**
* @brief Returns the LCD state.
* @param hlcd: LCD handle
* @retval HAL state
*/
HAL_LCD_StateTypeDef HAL_LCD_GetState(LCD_HandleTypeDef *hlcd)
{
return hlcd->State;
}
/**
* @brief Return the LCD error code
* @param hlcd: LCD handle
* @retval LCD Error Code
*/
uint32_t HAL_LCD_GetError(LCD_HandleTypeDef *hlcd)
{
return hlcd->ErrorCode;
}
/**
* @}
*/
/**
* @brief Waits until the LCD FCR register is synchronized in the LCDCLK domain.
* This function must be called after any write operation to LCD_FCR register.
* @param None
* @retval None
*/
HAL_StatusTypeDef LCD_WaitForSynchro(LCD_HandleTypeDef *hlcd)
{
uint32_t tickstart = 0x00;
/* Get timeout */
tickstart = HAL_GetTick();
/* Loop until FCRSF flag is set */
while((hlcd->Instance->SR & LCD_FLAG_FCRSF) == (uint32_t)RESET)
{
if((HAL_GetTick() - tickstart) > LCD_TIMEOUT_VALUE)
{
hlcd->ErrorCode = HAL_LCD_ERROR_FCRSF;
return HAL_TIMEOUT;
}
}
return HAL_OK;
}
/**
* @}
*/
#endif /* STM32L051xx && STM32L052xx && STM32L062xx && STM32L061xx*/
#endif /* HAL_LCD_MODULE_ENABLED */
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,707 @@
/**
******************************************************************************
* @file stm32l0xx_hal_lcd.h
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief Header file of LCD Controller HAL module.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32L0xx_HAL_LCD_H
#define __STM32L0xx_HAL_LCD_H
#ifdef __cplusplus
extern "C" {
#endif
#if !defined (STM32L051xx) && !defined (STM32L052xx) && !defined (STM32L062xx) && !defined (STM32L061xx)
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal_def.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @addtogroup LCD
* @{
*/
/* Exported types ------------------------------------------------------------*/
/**
* @brief LCD Init structure definition
*/
typedef struct
{
uint32_t Prescaler; /*!< Configures the LCD Prescaler.
This parameter can be one value of @ref LCD_Prescaler */
uint32_t Divider; /*!< Configures the LCD Divider.
This parameter can be one value of @ref LCD_Divider */
uint32_t Duty; /*!< Configures the LCD Duty.
This parameter can be one value of @ref LCD_Duty */
uint32_t Bias; /*!< Configures the LCD Bias.
This parameter can be one value of @ref LCD_Bias */
uint32_t VoltageSource; /*!< Selects the LCD Voltage source.
This parameter can be one value of @ref LCD_Voltage_Source */
uint32_t Contrast; /*!< Configures the LCD Contrast.
This parameter can be one value of @ref LCD_Contrast */
uint32_t DeadTime; /*!< Configures the LCD Dead Time.
This parameter can be one value of @ref LCD_DeadTime */
uint32_t PulseOnDuration; /*!< Configures the LCD Pulse On Duration.
This parameter can be one value of @ref LCD_PulseOnDuration */
uint32_t HighDrive; /*!< Enable or disable the low resistance divider.
This parameter can be set to ENABLE or DISABLE. */
uint32_t BlinkMode; /*!< Configures the LCD Blink Mode.
This parameter can be one value of @ref LCD_BlinkMode */
uint32_t BlinkFrequency; /*!< Configures the LCD Blink frequency.
This parameter can be one value of @ref LCD_BlinkFrequency */
}LCD_InitTypeDef;
/**
* @brief HAL LCD State structures definition
*/
typedef enum
{
HAL_LCD_STATE_RESET = 0x00, /*!< Peripheral is not yet Initialized */
HAL_LCD_STATE_READY = 0x01, /*!< Peripheral Initialized and ready for use */
HAL_LCD_STATE_BUSY = 0x02, /*!< an internal process is ongoing */
HAL_LCD_STATE_TIMEOUT = 0x03, /*!< Timeout state */
HAL_LCD_STATE_ERROR = 0x04 /*!< Error */
}HAL_LCD_StateTypeDef;
/**
* @brief HAL LCD Error Code structure definition
*/
typedef enum
{
HAL_LCD_ERROR_NONE = 0x00, /*!< No error */
HAL_LCD_ERROR_FCRSF = 0x01, /*!< Synchro flag timeout error */
HAL_LCD_ERROR_UDR = 0x02, /*!< Update display request flag timeout error */
HAL_LCD_ERROR_UDD = 0x04, /*!< Update display done flag timeout error */
HAL_LCD_ERROR_ENS = 0x08, /*!< LCD enabled status flag timeout error */
HAL_LCD_ERROR_RDY = 0x10 /*!< LCD Booster ready timeout error */
}HAL_LCD_ErrorTypeDef;
/**
* @brief UART handle Structure definition
*/
typedef struct
{
LCD_TypeDef *Instance; /* LCD registers base address */
LCD_InitTypeDef Init; /* LCD communication parameters */
HAL_LockTypeDef Lock; /* Locking object */
__IO HAL_LCD_StateTypeDef State; /* LCD communication state */
__IO HAL_LCD_ErrorTypeDef ErrorCode; /* LCD Error code */
}LCD_HandleTypeDef;
/* Exported constants --------------------------------------------------------*/
/** @defgroup LCD_Exported_Constants
* @{
*/
#define IS_LCD_ALL_INSTANCE(INSTANCE) ((INSTANCE) == LCD)
/** @defgroup LCD_Prescaler
* @{
*/
#define LCD_PRESCALER_1 ((uint32_t)0x00000000) /*!< CLKPS = LCDCLK */
#define LCD_PRESCALER_2 ((uint32_t)0x00400000) /*!< CLKPS = LCDCLK/2 */
#define LCD_PRESCALER_4 ((uint32_t)0x00800000) /*!< CLKPS = LCDCLK/4 */
#define LCD_PRESCALER_8 ((uint32_t)0x00C00000) /*!< CLKPS = LCDCLK/8 */
#define LCD_PRESCALER_16 ((uint32_t)0x01000000) /*!< CLKPS = LCDCLK/16 */
#define LCD_PRESCALER_32 ((uint32_t)0x01400000) /*!< CLKPS = LCDCLK/32 */
#define LCD_PRESCALER_64 ((uint32_t)0x01800000) /*!< CLKPS = LCDCLK/64 */
#define LCD_PRESCALER_128 ((uint32_t)0x01C00000) /*!< CLKPS = LCDCLK/128 */
#define LCD_PRESCALER_256 ((uint32_t)0x02000000) /*!< CLKPS = LCDCLK/256 */
#define LCD_PRESCALER_512 ((uint32_t)0x02400000) /*!< CLKPS = LCDCLK/512 */
#define LCD_PRESCALER_1024 ((uint32_t)0x02800000) /*!< CLKPS = LCDCLK/1024 */
#define LCD_PRESCALER_2048 ((uint32_t)0x02C00000) /*!< CLKPS = LCDCLK/2048 */
#define LCD_PRESCALER_4096 ((uint32_t)0x03000000) /*!< CLKPS = LCDCLK/4096 */
#define LCD_PRESCALER_8192 ((uint32_t)0x03400000) /*!< CLKPS = LCDCLK/8192 */
#define LCD_PRESCALER_16384 ((uint32_t)0x03800000) /*!< CLKPS = LCDCLK/16384 */
#define LCD_PRESCALER_32768 ((uint32_t)0x03C00000) /*!< CLKPS = LCDCLK/32768 */
#define IS_LCD_PRESCALER(PRESCALER) (((PRESCALER) == LCD_PRESCALER_1) || \
((PRESCALER) == LCD_PRESCALER_2) || \
((PRESCALER) == LCD_PRESCALER_4) || \
((PRESCALER) == LCD_PRESCALER_8) || \
((PRESCALER) == LCD_PRESCALER_16) || \
((PRESCALER) == LCD_PRESCALER_32) || \
((PRESCALER) == LCD_PRESCALER_64) || \
((PRESCALER) == LCD_PRESCALER_128) || \
((PRESCALER) == LCD_PRESCALER_256) || \
((PRESCALER) == LCD_PRESCALER_512) || \
((PRESCALER) == LCD_PRESCALER_1024) || \
((PRESCALER) == LCD_PRESCALER_2048) || \
((PRESCALER) == LCD_PRESCALER_4096) || \
((PRESCALER) == LCD_PRESCALER_8192) || \
((PRESCALER) == LCD_PRESCALER_16384) || \
((PRESCALER) == LCD_PRESCALER_32768))
/**
* @}
*/
/** @defgroup LCD_Divider
* @{
*/
#define LCD_DIVIDER_16 ((uint32_t)0x00000000) /*!< LCD frequency = CLKPS/16 */
#define LCD_DIVIDER_17 ((uint32_t)0x00040000) /*!< LCD frequency = CLKPS/17 */
#define LCD_DIVIDER_18 ((uint32_t)0x00080000) /*!< LCD frequency = CLKPS/18 */
#define LCD_DIVIDER_19 ((uint32_t)0x000C0000) /*!< LCD frequency = CLKPS/19 */
#define LCD_DIVIDER_20 ((uint32_t)0x00100000) /*!< LCD frequency = CLKPS/20 */
#define LCD_DIVIDER_21 ((uint32_t)0x00140000) /*!< LCD frequency = CLKPS/21 */
#define LCD_DIVIDER_22 ((uint32_t)0x00180000) /*!< LCD frequency = CLKPS/22 */
#define LCD_DIVIDER_23 ((uint32_t)0x001C0000) /*!< LCD frequency = CLKPS/23 */
#define LCD_DIVIDER_24 ((uint32_t)0x00200000) /*!< LCD frequency = CLKPS/24 */
#define LCD_DIVIDER_25 ((uint32_t)0x00240000) /*!< LCD frequency = CLKPS/25 */
#define LCD_DIVIDER_26 ((uint32_t)0x00280000) /*!< LCD frequency = CLKPS/26 */
#define LCD_DIVIDER_27 ((uint32_t)0x002C0000) /*!< LCD frequency = CLKPS/27 */
#define LCD_DIVIDER_28 ((uint32_t)0x00300000) /*!< LCD frequency = CLKPS/28 */
#define LCD_DIVIDER_29 ((uint32_t)0x00340000) /*!< LCD frequency = CLKPS/29 */
#define LCD_DIVIDER_30 ((uint32_t)0x00380000) /*!< LCD frequency = CLKPS/30 */
#define LCD_DIVIDER_31 ((uint32_t)0x003C0000) /*!< LCD frequency = CLKPS/31 */
#define IS_LCD_DIVIDER(DIVIDER) (((DIVIDER) == LCD_DIVIDER_16) || \
((DIVIDER) == LCD_DIVIDER_17) || \
((DIVIDER) == LCD_DIVIDER_18) || \
((DIVIDER) == LCD_DIVIDER_19) || \
((DIVIDER) == LCD_DIVIDER_20) || \
((DIVIDER) == LCD_DIVIDER_21) || \
((DIVIDER) == LCD_DIVIDER_22) || \
((DIVIDER) == LCD_DIVIDER_23) || \
((DIVIDER) == LCD_DIVIDER_24) || \
((DIVIDER) == LCD_DIVIDER_25) || \
((DIVIDER) == LCD_DIVIDER_26) || \
((DIVIDER) == LCD_DIVIDER_27) || \
((DIVIDER) == LCD_DIVIDER_28) || \
((DIVIDER) == LCD_DIVIDER_29) || \
((DIVIDER) == LCD_DIVIDER_30) || \
((DIVIDER) == LCD_DIVIDER_31))
/**
* @}
*/
/** @defgroup LCD_Duty
* @{
*/
#define LCD_DUTY_STATIC ((uint32_t)0x00000000) /*!< Static duty */
#define LCD_DUTY_1_2 ((uint32_t)0x00000004) /*!< 1/2 duty */
#define LCD_DUTY_1_3 ((uint32_t)0x00000008) /*!< 1/3 duty */
#define LCD_DUTY_1_4 ((uint32_t)0x0000000C) /*!< 1/4 duty */
#define LCD_DUTY_1_8 ((uint32_t)0x00000010) /*!< 1/4 duty */
#define IS_LCD_DUTY(DUTY) (((DUTY) == LCD_DUTY_STATIC) || \
((DUTY) == LCD_DUTY_1_2) || \
((DUTY) == LCD_DUTY_1_3) || \
((DUTY) == LCD_DUTY_1_4) || \
((DUTY) == LCD_DUTY_1_8))
/**
* @}
*/
/** @defgroup LCD_Bias
* @{
*/
#define LCD_BIAS_1_4 ((uint32_t)0x00000000) /*!< 1/4 Bias */
#define LCD_BIAS_1_2 LCD_CR_BIAS_0 /*!< 1/2 Bias */
#define LCD_BIAS_1_3 LCD_CR_BIAS_1 /*!< 1/3 Bias */
#define IS_LCD_BIAS(BIAS) (((BIAS) == LCD_BIAS_1_4) || \
((BIAS) == LCD_BIAS_1_2) || \
((BIAS) == LCD_BIAS_1_3))
/**
* @}
*/
/** @defgroup LCD_Voltage_Source
* @{
*/
#define LCD_VOLTAGESOURCE_INTERNAL ((uint32_t)0x00000000) /*!< Internal voltage source for the LCD */
#define LCD_VOLTAGESOURCE_EXTERNAL LCD_CR_VSEL /*!< External voltage source for the LCD */
#define IS_LCD_VOLTAGE_SOURCE(SOURCE) (((SOURCE) == LCD_VOLTAGESOURCE_INTERNAL) || \
((SOURCE) == LCD_VOLTAGESOURCE_EXTERNAL))
/**
* @}
*/
/** @defgroup LCD_Interrupts
* @{
*/
#define LCD_IT_SOF LCD_FCR_SOFIE
#define LCD_IT_UDD LCD_FCR_UDDIE
#define IS_LCD_IT(IT) ((((IT) & (uint32_t)0xFFFFFFF5) == 0x00) && ((IT) != 0x00))
#define IS_LCD_GET_IT(IT) (((IT) == LCD_IT_SOF) || ((IT) == LCD_IT_UDD))
/**
* @}
*/
/** @defgroup LCD_PulseOnDuration
* @{
*/
#define LCD_PULSEONDURATION_0 ((uint32_t)0x00000000) /*!< Pulse ON duration = 0 pulse */
#define LCD_PULSEONDURATION_1 ((uint32_t)0x00000010) /*!< Pulse ON duration = 1/CK_PS */
#define LCD_PULSEONDURATION_2 ((uint32_t)0x00000020) /*!< Pulse ON duration = 2/CK_PS */
#define LCD_PULSEONDURATION_3 ((uint32_t)0x00000030) /*!< Pulse ON duration = 3/CK_PS */
#define LCD_PULSEONDURATION_4 ((uint32_t)0x00000040) /*!< Pulse ON duration = 4/CK_PS */
#define LCD_PULSEONDURATION_5 ((uint32_t)0x00000050) /*!< Pulse ON duration = 5/CK_PS */
#define LCD_PULSEONDURATION_6 ((uint32_t)0x00000060) /*!< Pulse ON duration = 6/CK_PS */
#define LCD_PULSEONDURATION_7 ((uint32_t)0x00000070) /*!< Pulse ON duration = 7/CK_PS */
#define IS_LCD_PULSE_ON_DURATION(DURATION) (((DURATION) == LCD_PULSEONDURATION_0) || \
((DURATION) == LCD_PULSEONDURATION_1) || \
((DURATION) == LCD_PULSEONDURATION_2) || \
((DURATION) == LCD_PULSEONDURATION_3) || \
((DURATION) == LCD_PULSEONDURATION_4) || \
((DURATION) == LCD_PULSEONDURATION_5) || \
((DURATION) == LCD_PULSEONDURATION_6) || \
((DURATION) == LCD_PULSEONDURATION_7))
/**
* @}
*/
/** @defgroup LCD_DeadTime
* @{
*/
#define LCD_DEADTIME_0 ((uint32_t)0x00000000) /*!< No dead Time */
#define LCD_DEADTIME_1 ((uint32_t)0x00000080) /*!< One Phase between different couple of Frame */
#define LCD_DEADTIME_2 ((uint32_t)0x00000100) /*!< Two Phase between different couple of Frame */
#define LCD_DEADTIME_3 ((uint32_t)0x00000180) /*!< Three Phase between different couple of Frame */
#define LCD_DEADTIME_4 ((uint32_t)0x00000200) /*!< Four Phase between different couple of Frame */
#define LCD_DEADTIME_5 ((uint32_t)0x00000280) /*!< Five Phase between different couple of Frame */
#define LCD_DEADTIME_6 ((uint32_t)0x00000300) /*!< Six Phase between different couple of Frame */
#define LCD_DEADTIME_7 ((uint32_t)0x00000380) /*!< Seven Phase between different couple of Frame */
#define IS_LCD_DEAD_TIME(TIME) (((TIME) == LCD_DEADTIME_0) || \
((TIME) == LCD_DEADTIME_1) || \
((TIME) == LCD_DEADTIME_2) || \
((TIME) == LCD_DEADTIME_3) || \
((TIME) == LCD_DEADTIME_4) || \
((TIME) == LCD_DEADTIME_5) || \
((TIME) == LCD_DEADTIME_6) || \
((TIME) == LCD_DEADTIME_7))
/**
* @}
*/
/** @defgroup LCD_BlinkMode
* @{
*/
#define LCD_BLINKMODE_OFF ((uint32_t)0x00000000) /*!< Blink disabled */
#define LCD_BLINKMODE_SEG0_COM0 ((uint32_t)0x00010000) /*!< Blink enabled on SEG[0], COM[0] (1 pixel) */
#define LCD_BLINKMODE_SEG0_ALLCOM ((uint32_t)0x00020000) /*!< Blink enabled on SEG[0], all COM (up to
8 pixels according to the programmed duty) */
#define LCD_BLINKMODE_ALLSEG_ALLCOM ((uint32_t)0x00030000) /*!< Blink enabled on all SEG and all COM (all pixels) */
#define IS_LCD_BLINK_MODE(MODE) (((MODE) == LCD_BLINKMODE_OFF) || \
((MODE) == LCD_BLINKMODE_SEG0_COM0) || \
((MODE) == LCD_BLINKMODE_SEG0_ALLCOM) || \
((MODE) == LCD_BLINKMODE_ALLSEG_ALLCOM))
/**
* @}
*/
/** @defgroup LCD_BlinkFrequency
* @{
*/
#define LCD_BLINKFREQUENCY_DIV8 ((uint32_t)0x00000000) /*!< The Blink frequency = fLCD/8 */
#define LCD_BLINKFREQUENCY_DIV16 ((uint32_t)0x00002000) /*!< The Blink frequency = fLCD/16 */
#define LCD_BLINKFREQUENCY_DIV32 ((uint32_t)0x00004000) /*!< The Blink frequency = fLCD/32 */
#define LCD_BLINKFREQUENCY_DIV64 ((uint32_t)0x00006000) /*!< The Blink frequency = fLCD/64 */
#define LCD_BLINKFREQUENCY_DIV128 ((uint32_t)0x00008000) /*!< The Blink frequency = fLCD/128 */
#define LCD_BLINKFREQUENCY_DIV256 ((uint32_t)0x0000A000) /*!< The Blink frequency = fLCD/256 */
#define LCD_BLINKFREQUENCY_DIV512 ((uint32_t)0x0000C000) /*!< The Blink frequency = fLCD/512 */
#define LCD_BLINKFREQUENCY_DIV1024 ((uint32_t)0x0000E000) /*!< The Blink frequency = fLCD/1024 */
#define IS_LCD_BLINK_FREQUENCY(FREQUENCY) (((FREQUENCY) == LCD_BLINKFREQUENCY_DIV8) || \
((FREQUENCY) == LCD_BLINKFREQUENCY_DIV16) || \
((FREQUENCY) == LCD_BLINKFREQUENCY_DIV32) || \
((FREQUENCY) == LCD_BLINKFREQUENCY_DIV64) || \
((FREQUENCY) == LCD_BLINKFREQUENCY_DIV128) || \
((FREQUENCY) == LCD_BLINKFREQUENCY_DIV256) || \
((FREQUENCY) == LCD_BLINKFREQUENCY_DIV512) || \
((FREQUENCY) == LCD_BLINKFREQUENCY_DIV1024))
/**
* @}
*/
/** @defgroup LCD_Contrast
* @{
*/
#define LCD_CONTRASTLEVEL_0 ((uint32_t)0x00000000) /*!< Maximum Voltage = 2.60V */
#define LCD_CONTRASTLEVEL_1 ((uint32_t)0x00000400) /*!< Maximum Voltage = 2.73V */
#define LCD_CONTRASTLEVEL_2 ((uint32_t)0x00000800) /*!< Maximum Voltage = 2.86V */
#define LCD_CONTRASTLEVEL_3 ((uint32_t)0x00000C00) /*!< Maximum Voltage = 2.99V */
#define LCD_CONTRASTLEVEL_4 ((uint32_t)0x00001000) /*!< Maximum Voltage = 3.12V */
#define LCD_CONTRASTLEVEL_5 ((uint32_t)0x00001400) /*!< Maximum Voltage = 3.25V */
#define LCD_CONTRASTLEVEL_6 ((uint32_t)0x00001800) /*!< Maximum Voltage = 3.38V */
#define LCD_CONTRASTLEVEL_7 ((uint32_t)0x00001C00) /*!< Maximum Voltage = 3.51V */
#define IS_LCD_CONTRAST(CONTRAST) (((CONTRAST) == LCD_CONTRASTLEVEL_0) || \
((CONTRAST) == LCD_CONTRASTLEVEL_1) || \
((CONTRAST) == LCD_CONTRASTLEVEL_2) || \
((CONTRAST) == LCD_CONTRASTLEVEL_3) || \
((CONTRAST) == LCD_CONTRASTLEVEL_4) || \
((CONTRAST) == LCD_CONTRASTLEVEL_5) || \
((CONTRAST) == LCD_CONTRASTLEVEL_6) || \
((CONTRAST) == LCD_CONTRASTLEVEL_7))
/**
* @}
*/
/** @defgroup LCD_Flag
* @{
*/
#define LCD_FLAG_ENS LCD_SR_ENS
#define LCD_FLAG_SOF LCD_SR_SOF
#define LCD_FLAG_UDR LCD_SR_UDR
#define LCD_FLAG_UDD LCD_SR_UDD
#define LCD_FLAG_RDY LCD_SR_RDY
#define LCD_FLAG_FCRSF LCD_SR_FCRSR
#define IS_LCD_GET_FLAG(FLAG) (((FLAG) == LCD_FLAG_ENS) || ((FLAG) == LCD_FLAG_SOF) || \
((FLAG) == LCD_FLAG_UDR) || ((FLAG) == LCD_FLAG_UDD) || \
((FLAG) == LCD_FLAG_RDY) || ((FLAG) == LCD_FLAG_FCRSF))
#define IS_LCD_CLEAR_FLAG(FLAG) ((((FLAG) & (uint32_t)0xFFFFFFF5) == 0x00) && ((FLAG) != 0x00))
/**
* @}
*/
/** @defgroup LCD_RAMRegister
* @{
*/
#define LCD_RAM_REGISTER0 ((uint32_t)0x00000000) /*!< LCD RAM Register 0 */
#define LCD_RAM_REGISTER1 ((uint32_t)0x00000001) /*!< LCD RAM Register 1 */
#define LCD_RAM_REGISTER2 ((uint32_t)0x00000002) /*!< LCD RAM Register 2 */
#define LCD_RAM_REGISTER3 ((uint32_t)0x00000003) /*!< LCD RAM Register 3 */
#define LCD_RAM_REGISTER4 ((uint32_t)0x00000004) /*!< LCD RAM Register 4 */
#define LCD_RAM_REGISTER5 ((uint32_t)0x00000005) /*!< LCD RAM Register 5 */
#define LCD_RAM_REGISTER6 ((uint32_t)0x00000006) /*!< LCD RAM Register 6 */
#define LCD_RAM_REGISTER7 ((uint32_t)0x00000007) /*!< LCD RAM Register 7 */
#define LCD_RAM_REGISTER8 ((uint32_t)0x00000008) /*!< LCD RAM Register 8 */
#define LCD_RAM_REGISTER9 ((uint32_t)0x00000009) /*!< LCD RAM Register 9 */
#define LCD_RAM_REGISTER10 ((uint32_t)0x0000000A) /*!< LCD RAM Register 10 */
#define LCD_RAM_REGISTER11 ((uint32_t)0x0000000B) /*!< LCD RAM Register 11 */
#define LCD_RAM_REGISTER12 ((uint32_t)0x0000000C) /*!< LCD RAM Register 12 */
#define LCD_RAM_REGISTER13 ((uint32_t)0x0000000D) /*!< LCD RAM Register 13 */
#define LCD_RAM_REGISTER14 ((uint32_t)0x0000000E) /*!< LCD RAM Register 14 */
#define LCD_RAM_REGISTER15 ((uint32_t)0x0000000F) /*!< LCD RAM Register 15 */
#define IS_LCD_RAM_REGISTER(REGISTER) (((REGISTER) == LCD_RAM_REGISTER0) || \
((REGISTER) == LCD_RAM_REGISTER1) || \
((REGISTER) == LCD_RAM_REGISTER2) || \
((REGISTER) == LCD_RAM_REGISTER3) || \
((REGISTER) == LCD_RAM_REGISTER4) || \
((REGISTER) == LCD_RAM_REGISTER5) || \
((REGISTER) == LCD_RAM_REGISTER6) || \
((REGISTER) == LCD_RAM_REGISTER7) || \
((REGISTER) == LCD_RAM_REGISTER8) || \
((REGISTER) == LCD_RAM_REGISTER9) || \
((REGISTER) == LCD_RAM_REGISTER10) || \
((REGISTER) == LCD_RAM_REGISTER11) || \
((REGISTER) == LCD_RAM_REGISTER12) || \
((REGISTER) == LCD_RAM_REGISTER13) || \
((REGISTER) == LCD_RAM_REGISTER14) || \
((REGISTER) == LCD_RAM_REGISTER15))
/**
* @}
*/
/**
* @}
*/
/* Exported macro ------------------------------------------------------------*/
/** @defgroup LCD_Exported_Macros
* @{
*/
/** @brief Reset LCD handle state
* @param __HANDLE__: specifies the LCD Handle.
* @retval None
*/
#define __HAL_LCD_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_LCD_STATE_RESET)
/** @brief macros to enables or disables the LCD
* @param __HANDLE__: specifies the LCD Handle.
* @retval None
*/
#define __HAL_LCD_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR |= LCD_CR_LCDEN)
#define __HAL_LCD_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR &= ~LCD_CR_LCDEN)
/** @brief Macros to enable or disable the low resistance divider. Displays with high
* internal resistance may need a longer drive time to achieve
* satisfactory contrast. This function is useful in this case if some
* additional power consumption can be tolerated.
* @param __HANDLE__: specifies the LCD Handle.
* @note When this mode is enabled, the PulseOn Duration (PON) have to be
* programmed to 1/CK_PS (LCD_PULSEONDURATION_1).
* @retval None
*/
#define __HAL_LCD_HIGHDRIVER_ENABLE(__HANDLE__) \
do{ \
((__HANDLE__)->Instance->FCR |= LCD_FCR_HD); \
LCD_WaitForSynchro(__HANDLE__); \
}while(0)
#define __HAL_LCD_HIGHDRIVER_DISABLE(__HANDLE__) \
do{ \
((__HANDLE__)->Instance->FCR &= ~LCD_FCR_HD); \
LCD_WaitForSynchro(__HANDLE__); \
}while(0)
/**
* @brief Macro to configure the LCD pulses on duration.
* @param __HANDLE__: specifies the LCD Handle.
* @param __DURATION__: specifies the LCD pulse on duration in terms of
* CK_PS (prescaled LCD clock period) pulses.
* This parameter can be one of the following values:
* @arg LCD_PULSEONDURATION_0: 0 pulse
* @arg LCD_PULSEONDURATION_1: Pulse ON duration = 1/CK_PS
* @arg LCD_PULSEONDURATION_2: Pulse ON duration = 2/CK_PS
* @arg LCD_PULSEONDURATION_3: Pulse ON duration = 3/CK_PS
* @arg LCD_PULSEONDURATION_4: Pulse ON duration = 4/CK_PS
* @arg LCD_PULSEONDURATION_5: Pulse ON duration = 5/CK_PS
* @arg LCD_PULSEONDURATION_6: Pulse ON duration = 6/CK_PS
* @arg LCD_PULSEONDURATION_7: Pulse ON duration = 7/CK_PS
* @retval None
*/
#define __HAL_LCD_PULSEONDURATION_CONFIG(__HANDLE__, __DURATION__) \
do{ \
MODIFY_REG((__HANDLE__)->Instance->FCR, LCD_FCR_PON, (__DURATION__)); \
LCD_WaitForSynchro(__HANDLE__); \
}while(0)
/**
* @brief Macro to configure the LCD dead time.
* @param __HANDLE__: specifies the LCD Handle.
* @param __DEADTIME__: specifies the LCD dead time.
* This parameter can be one of the following values:
* @arg LCD_DEADTIME_0: No dead Time
* @arg LCD_DEADTIME_1: One Phase between different couple of Frame
* @arg LCD_DEADTIME_2: Two Phase between different couple of Frame
* @arg LCD_DEADTIME_3: Three Phase between different couple of Frame
* @arg LCD_DEADTIME_4: Four Phase between different couple of Frame
* @arg LCD_DEADTIME_5: Five Phase between different couple of Frame
* @arg LCD_DEADTIME_6: Six Phase between different couple of Frame
* @arg LCD_DEADTIME_7: Seven Phase between different couple of Frame
* @retval None
*/
#define __HAL_LCD_DEADTIME_CONFIG(__HANDLE__, __DEADTIME__) \
do{ \
MODIFY_REG((__HANDLE__)->Instance->FCR, LCD_FCR_DEAD, (__DEADTIME__)); \
LCD_WaitForSynchro(__HANDLE__); \
}while(0)
/**
* @brief Macro to configure the LCD Contrast.
* @param __HANDLE__: specifies the LCD Handle.
* @param __CONTRAST__: specifies the LCD Contrast.
* This parameter can be one of the following values:
* @arg LCD_CONTRASTLEVEL_0: Maximum Voltage = 2.60V
* @arg LCD_CONTRASTLEVEL_1: Maximum Voltage = 2.73V
* @arg LCD_CONTRASTLEVEL_2: Maximum Voltage = 2.86V
* @arg LCD_CONTRASTLEVEL_3: Maximum Voltage = 2.99V
* @arg LCD_CONTRASTLEVEL_4: Maximum Voltage = 3.12V
* @arg LCD_CONTRASTLEVEL_5: Maximum Voltage = 3.25V
* @arg LCD_CONTRASTLEVEL_6: Maximum Voltage = 3.38V
* @arg LCD_CONTRASTLEVEL_7: Maximum Voltage = 3.51V
* @retval None
*/
#define __HAL_LCD_CONTRAST_CONFIG(__HANDLE__, __CONTRAST__) \
do{ \
MODIFY_REG((__HANDLE__)->Instance->FCR, LCD_FCR_CC, (__CONTRAST__)); \
LCD_WaitForSynchro(__HANDLE__); \
} while(0)
/**
* @brief Macro to configure the LCD Blink mode and Blink frequency.
* @param __HANDLE__: specifies the LCD Handle.
* @param __BLINKMODE__: specifies the LCD blink mode.
* This parameter can be one of the following values:
* @arg LCD_BLINKMODE_OFF: Blink disabled
* @arg LCD_BLINKMODE_SEG0_COM0: Blink enabled on SEG[0], COM[0] (1 pixel)
* @arg LCD_BLINKMODE_SEG0_ALLCOM: Blink enabled on SEG[0], all COM (up to 8
* pixels according to the programmed duty)
* @arg LCD_BLINKMODE_ALLSEG_ALLCOM: Blink enabled on all SEG and all COM
* (all pixels)
* @param __BLINKFREQUENCY__: specifies the LCD blink frequency.
* @arg LCD_BLINKFREQUENCY_DIV8: The Blink frequency = fLcd/8
* @arg LCD_BLINKFREQUENCY_DIV16: The Blink frequency = fLcd/16
* @arg LCD_BLINKFREQUENCY_DIV32: The Blink frequency = fLcd/32
* @arg LCD_BLINKFREQUENCY_DIV64: The Blink frequency = fLcd/64
* @arg LCD_BLINKFREQUENCY_DIV128: The Blink frequency = fLcd/128
* @arg LCD_BLINKFREQUENCY_DIV256: The Blink frequency = fLcd/256
* @arg LCD_BLINKFREQUENCY_DIV512: The Blink frequency = fLcd/512
* @arg LCD_BLINKFREQUENCY_DIV1024: The Blink frequency = fLcd/1024
* @retval None
*/
#define __HAL_LCD_BLINK_CONFIG(__HANDLE__, __BLINKMODE__, __BLINKFREQUENCY__) \
do{ \
MODIFY_REG((__HANDLE__)->Instance->FCR, (LCD_FCR_BLINKF | LCD_FCR_BLINK), ((__BLINKMODE__) | (__BLINKFREQUENCY__))); \
LCD_WaitForSynchro(__HANDLE__); \
}while(0)
/** @brief Enables or disables the specified LCD interrupt.
* @param __HANDLE__: specifies the LCD Handle.
* @param __INTERRUPT__: specifies the LCD interrupt source to be enabled or disabled.
* This parameter can be one of the following values:
* @arg LCD_IT_SOF: Start of Frame Interrupt
* @arg LCD_IT_UDD: Update Display Done Interrupt
* @retval None
*/
#define __HAL_LCD_ENABLE_IT(__HANDLE__, __INTERRUPT__) \
do{ \
((__HANDLE__)->Instance->FCR |= (__INTERRUPT__)); \
LCD_WaitForSynchro(__HANDLE__); \
}while(0)
#define __HAL_LCD_DISABLE_IT(__HANDLE__, __INTERRUPT__) \
do{ \
((__HANDLE__)->Instance->FCR &= ~(__INTERRUPT__));\
LCD_WaitForSynchro(__HANDLE__); \
}while(0)
/** @brief Checks whether the specified LCD interrupt is enabled or not.
* @param __HANDLE__: specifies the LCD Handle.
* @param __IT__: specifies the LCD interrupt source to check.
* This parameter can be one of the following values:
* @arg LCD_IT_SOF: Start of Frame Interrupt
* @arg LCD_IT_UDD: Update Display Done Interrupt.
* @note If the device is in STOP mode (PCLK not provided) UDD will not
* generate an interrupt even if UDDIE = 1.
* If the display is not enabled the UDD interrupt will never occur.
* @retval The state of __IT__ (TRUE or FALSE).
*/
#define __HAL_LCD_GET_IT_SOURCE(__HANDLE__, __IT__) (((__HANDLE__)->Instance->FCR) & (__IT__))
/** @brief Checks whether the specified LCD flag is set or not.
* @param __HANDLE__: specifies the LCD Handle.
* @param __FLAG__: specifies the flag to check.
* This parameter can be one of the following values:
* @arg LCD_FLAG_ENS: LCD Enabled flag. It indicates the LCD controller status.
* @note The ENS bit is set immediately when the LCDEN bit in the LCD_CR
* goes from 0 to 1. On deactivation it reflects the real status of
* LCD so it becomes 0 at the end of the last displayed frame.
* @arg LCD_FLAG_SOF: Start of Frame flag. This flag is set by hardware at
* the beginning of a new frame, at the same time as the display data is
* updated.
* @arg LCD_FLAG_UDR: Update Display Request flag.
* @arg LCD_FLAG_UDD: Update Display Done flag.
* @arg LCD_FLAG_RDY: Step_up converter Ready flag. It indicates the status
* of the step-up converter.
* @arg LCD_FLAG_FCRSF: LCD Frame Control Register Synchronization Flag.
* This flag is set by hardware each time the LCD_FCR register is updated
* in the LCDCLK domain.
* @retval The new state of __FLAG__ (TRUE or FALSE).
*/
#define __HAL_LCD_GET_FLAG(__HANDLE__, __FLAG__) (((__HANDLE__)->Instance->SR & (__FLAG__)) == (__FLAG__))
/** @brief Clears the specified LCD pending flag.
* @param __HANDLE__: specifies the LCD Handle.
* @param __FLAG__: specifies the flag to check.
* This parameter can be any combination of the following values:
* @arg LCD_FLAG_SOF: Start of Frame Interrupt
* @arg LCD_FLAG_UDD: Update Display Done Interrupt
* @retval None
*/
#define __HAL_LCD_CLEAR_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->CLR = (__FLAG__))
/**
* @}
*/
/* Exported functions ------------------------------------------------------- */
/* Initialization/de-initialization methods **********************************/
HAL_StatusTypeDef HAL_LCD_DeInit(LCD_HandleTypeDef *hlcd);
HAL_StatusTypeDef HAL_LCD_Init(LCD_HandleTypeDef *hlcd);
void HAL_LCD_MspInit(LCD_HandleTypeDef *hlcd);
void HAL_LCD_MspDeInit(LCD_HandleTypeDef *hlcd);
/* IO operation methods *******************************************************/
HAL_StatusTypeDef HAL_LCD_Write(LCD_HandleTypeDef *hlcd, uint32_t RAMRegisterIndex, uint32_t RAMRegisterMask, uint32_t Data);
HAL_StatusTypeDef HAL_LCD_Clear(LCD_HandleTypeDef *hlcd);
HAL_StatusTypeDef HAL_LCD_UpdateDisplayRequest(LCD_HandleTypeDef *hlcd);
/* Peripheral State methods **************************************************/
HAL_LCD_StateTypeDef HAL_LCD_GetState(LCD_HandleTypeDef *hlcd);
uint32_t HAL_LCD_GetError(LCD_HandleTypeDef *hlcd);
/* Private functions ---------------------------------------------------------*/
HAL_StatusTypeDef LCD_WaitForSynchro(LCD_HandleTypeDef *hlcd);
#endif /* STM32L051xx && STM32L052xx && STM32L062xx && STM32L061xx*/
#ifdef __cplusplus
}
#endif
#endif /* __STM32L0xx_HAL_LCD_H */
/**
* @}
*/
/**
* @}
*/
/******************* (C) COPYRIGHT 2014 STMicroelectronics *****END OF FILE****/

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,624 @@
/**
******************************************************************************
* @file stm32l0xx_hal_lptim.h
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief Header file of LPTIM HAL module.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32L0xx_HAL_LPTIM_H
#define __STM32L0xx_HAL_LPTIM_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal_def.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @addtogroup LPTIM
* @{
*/
/* Exported types ------------------------------------------------------------*/
/**
* @brief LPTIM Clock configuration definition
*/
typedef struct
{
uint32_t Source; /*!< Selects the clock source.
This parameter can be a value of @ref LPTIM_Clock_Source */
uint32_t Prescaler; /*!< Specifies the counter clock Prescaler.
This parameter can be a value of @ref LPTIM_Clock_Prescaler */
}LPTIM_ClockConfigTypeDef;
/**
* @brief LPTIM Clock configuration definition
*/
typedef struct
{
uint32_t Polarity; /*!< Selects the polarity of the active edge for the counter unit
if the ULPTIM input is selected.
Note: This parameter is used only when Ultra low power clock source is used.
Note: If the polarity is configured on 'both edges', an auxiliary clock
(one of the Low power oscillator) must be active.
This parameter can be a value of @ref LPTIM_Clock_Polarity */
uint32_t SampleTime; /*!< Selects the clock sampling time to configure the clock glitch filter.
Note: This parameter is used only when Ultra low power clock source is used.
This parameter can be a value of @ref LPTIM_Clock_Sample_Time */
}LPTIM_ULPClockConfigTypeDef;
/**
* @brief LPTIM Trigger configuration definition
*/
typedef struct
{
uint32_t Source; /*!< Selects the Trigger source.
This parameter can be a value of @ref LPTIM_Trigger_Source */
uint32_t ActiveEdge; /*!< Selects the Trigger active edge.
Note: This parameter is used only when an external trigger is used.
This parameter can be a value of @ref LPTIM_External_Trigger_Polarity */
uint32_t SampleTime; /*!< Selects the trigger sampling time to configure the clock glitch filter.
Note: This parameter is used only when an external trigger is used.
This parameter can be a value of @ref LPTIM_Trigger_Sample_Time */
}LPTIM_TriggerConfigTypeDef;
/**
* @brief LPTIM Initialization Structure definition
*/
typedef struct
{
LPTIM_ClockConfigTypeDef Clock; /*!< Specifies the clock parameters */
LPTIM_ULPClockConfigTypeDef UltraLowPowerClock; /*!< Specifies the Ultra Low Power clock parameters */
LPTIM_TriggerConfigTypeDef Trigger; /*!< Specifies the Trigger parameters */
uint32_t OutputPolarity; /*!< Specifies the Output polarity.
This parameter can be a value of @ref LPTIM_Output_Polarity */
uint32_t UpdateMode; /*!< Specifies whether the update of the autorelaod and the compare
values is done immediately or after the end of current period.
This parameter can be a value of @ref LPTIM_Updating_Mode */
uint32_t CounterSource; /*!< Specifies whether the counter is incremented each internal event
or each external event.
This parameter can be a value of @ref LPTIM_Counter_Source */
}LPTIM_InitTypeDef;
/**
* @brief HAL LPTIM State structure definition
*/
typedef enum __HAL_LPTIM_StateTypeDef
{
HAL_LPTIM_STATE_RESET = 0x00, /*!< Peripheral not yet initialized or disabled */
HAL_LPTIM_STATE_READY = 0x01, /*!< Peripheral Initialized and ready for use */
HAL_LPTIM_STATE_BUSY = 0x02, /*!< An internal process is ongoing */
HAL_LPTIM_STATE_TIMEOUT = 0x03, /*!< Timeout state */
HAL_LPTIM_STATE_ERROR = 0x04 /*!< Internal Process is ongoing */
}HAL_LPTIM_StateTypeDef;
/**
* @brief LPTIM handle Structure definition
*/
typedef struct
{
LPTIM_TypeDef *Instance; /*!< Register base address */
LPTIM_InitTypeDef Init; /*!< LPTIM required parameters */
HAL_StatusTypeDef Status; /*!< LPTIM peripheral status */
HAL_LockTypeDef Lock; /*!< LPTIM locking object */
__IO HAL_LPTIM_StateTypeDef State; /*!< LPTIM peripheral state */
}LPTIM_HandleTypeDef;
/* Exported constants --------------------------------------------------------*/
/** @defgroup LPTIM_Exported_Constants
* @{
*/
/** @defgroup LPTIM_Autorelaod_Value
* @{
*/
#define IS_LPTIM_AUTORELOAD(AUTORELOAD) ((AUTORELOAD) <= 0x0000FFFF)
/**
* @}
*/
/** @defgroup LPTIM_Compare_Value
* @{
*/
#define IS_LPTIM_COMPARE(COMPARE) ((COMPARE) <= 0x0000FFFF)
/**
* @}
*/
/** @defgroup LPTIM_Clock_Source
* @{
*/
#define LPTIM_CLOCKSOURCE_APBCLOCK_LPOSC ((uint32_t)0x00)
#define LPTIM_CLOCKSOURCE_ULPTIM LPTIM_CFGR_CKSEL
#define IS_LPTIM_CLOCK_SOURCE(SOURCE) (((SOURCE) == LPTIM_CLOCKSOURCE_ULPTIM) || \
((SOURCE) == LPTIM_CLOCKSOURCE_APBCLOCK_LPOSC))
/**
* @}
*/
/** @defgroup LPTIM_Clock_Prescaler
* @{
*/
#define LPTIM_PRESCALER_DIV1 ((uint32_t)0x000000)
#define LPTIM_PRESCALER_DIV2 LPTIM_CFGR_PRESC_0
#define LPTIM_PRESCALER_DIV4 LPTIM_CFGR_PRESC_1
#define LPTIM_PRESCALER_DIV8 ((uint32_t)(LPTIM_CFGR_PRESC_0 | LPTIM_CFGR_PRESC_1))
#define LPTIM_PRESCALER_DIV16 LPTIM_CFGR_PRESC_2
#define LPTIM_PRESCALER_DIV32 ((uint32_t)(LPTIM_CFGR_PRESC_0 | LPTIM_CFGR_PRESC_2))
#define LPTIM_PRESCALER_DIV64 ((uint32_t)(LPTIM_CFGR_PRESC_1 | LPTIM_CFGR_PRESC_2))
#define LPTIM_PRESCALER_DIV128 ((uint32_t)LPTIM_CFGR_PRESC)
#define IS_LPTIM_CLOCK_PRESCALER(PRESCALER) (((PRESCALER) == LPTIM_PRESCALER_DIV1 ) || \
((PRESCALER) == LPTIM_PRESCALER_DIV2 ) || \
((PRESCALER) == LPTIM_PRESCALER_DIV4 ) || \
((PRESCALER) == LPTIM_PRESCALER_DIV8 ) || \
((PRESCALER) == LPTIM_PRESCALER_DIV16 ) || \
((PRESCALER) == LPTIM_PRESCALER_DIV32 ) || \
((PRESCALER) == LPTIM_PRESCALER_DIV64 ) || \
((PRESCALER) == LPTIM_PRESCALER_DIV128))
#define IS_LPTIM_CLOCK_PRESCALERDIV1(PRESCALER) ((PRESCALER) == LPTIM_PRESCALER_DIV1)
/**
* @}
*/
/** @defgroup LPTIM_Output_Polarity
* @{
*/
#define LPTIM_OUTPUTPOLARITY_HIGH ((uint32_t)0x00000000)
#define LPTIM_OUTPUTPOLARITY_LOW (LPTIM_CFGR_WAVPOL)
#define IS_LPTIM_OUTPUT_POLARITY(POLARITY) (((POLARITY) == LPTIM_OUTPUTPOLARITY_LOW ) || \
((POLARITY) == LPTIM_OUTPUTPOLARITY_HIGH))
/**
* @}
*/
/** @defgroup LPTIM_Clock_Sample_Time
* @{
*/
#define LPTIM_CLOCKSAMPLETIME_DIRECTTRANSISTION ((uint32_t)0x00000000)
#define LPTIM_CLOCKSAMPLETIME_2TRANSISTIONS LPTIM_CFGR_CKFLT_0
#define LPTIM_CLOCKSAMPLETIME_4TRANSISTIONS LPTIM_CFGR_CKFLT_1
#define LPTIM_CLOCKSAMPLETIME_8TRANSISTIONS LPTIM_CFGR_CKFLT
#define IS_LPTIM_CLOCK_SAMPLE_TIME(SAMPLETIME) (((SAMPLETIME) == LPTIM_CLOCKSAMPLETIME_DIRECTTRANSISTION) || \
((SAMPLETIME) == LPTIM_CLOCKSAMPLETIME_2TRANSISTIONS) || \
((SAMPLETIME) == LPTIM_CLOCKSAMPLETIME_4TRANSISTIONS) || \
((SAMPLETIME) == LPTIM_CLOCKSAMPLETIME_8TRANSISTIONS))
/**
* @}
*/
/** @defgroup LPTIM_Clock_Polarity
* @{
*/
#define LPTIM_CLOCKPOLARITY_RISINGEDGE ((uint32_t)0x00000000)
#define LPTIM_CLOCKPOLARITY_FALLINGEDGE LPTIM_CFGR_CKPOL_0
#define LPTIM_CLOCKPOLARITY_BOTHEDGES LPTIM_CFGR_CKPOL_1
#define IS_LPTIM_CLOCK_POLARITY(POLARITY) (((POLARITY) == LPTIM_CLOCKPOLARITY_RISINGEDGE) || \
((POLARITY) == LPTIM_CLOCKPOLARITY_FALLINGEDGE) || \
((POLARITY) == LPTIM_CLOCKPOLARITY_BOTHEDGES))
/**
* @}
*/
/** @defgroup LPTIM_Trigger_Source
* @{
*/
#define LPTIM_TRIGSOURCE_SOFTWARE ((uint32_t)0x0000FFFF)
#define LPTIM_TRIGSOURCE_0 ((uint32_t)0x00000000)
#define LPTIM_TRIGSOURCE_1 ((uint32_t)LPTIM_CFGR_TRIGSEL_0)
#define LPTIM_TRIGSOURCE_2 LPTIM_CFGR_TRIGSEL_1
#define LPTIM_TRIGSOURCE_3 ((uint32_t)LPTIM_CFGR_TRIGSEL_0 | LPTIM_CFGR_TRIGSEL_1)
#define LPTIM_TRIGSOURCE_4 LPTIM_CFGR_TRIGSEL_2
#define LPTIM_TRIGSOURCE_6 ((uint32_t)LPTIM_CFGR_TRIGSEL_1 | LPTIM_CFGR_TRIGSEL_2)
#define LPTIM_TRIGSOURCE_7 LPTIM_CFGR_TRIGSEL
#define IS_LPTIM_TRG_SOURCE(TRIG) (((TRIG) == LPTIM_TRIGSOURCE_SOFTWARE) || \
((TRIG) == LPTIM_TRIGSOURCE_0) || \
((TRIG) == LPTIM_TRIGSOURCE_1) || \
((TRIG) == LPTIM_TRIGSOURCE_2) || \
((TRIG) == LPTIM_TRIGSOURCE_3) || \
((TRIG) == LPTIM_TRIGSOURCE_4) || \
((TRIG) == LPTIM_TRIGSOURCE_6) || \
((TRIG) == LPTIM_TRIGSOURCE_7))
/**
* @}
*/
/** @defgroup LPTIM_External_Trigger_Polarity
* @{
*/
#define LPTIM_ACTIVEEDGE_RISING LPTIM_CFGR_TRIGEN_0
#define LPTIM_ACTIVEEDGE_FALLING LPTIM_CFGR_TRIGEN_1
#define LPTIM_ACTIVEEDGE_RISING_FALLING LPTIM_CFGR_TRIGEN
#define IS_LPTIM_EXT_TRG_POLARITY(POLAR) (((POLAR) == LPTIM_ACTIVEEDGE_RISING ) || \
((POLAR) == LPTIM_ACTIVEEDGE_FALLING ) || \
((POLAR) == LPTIM_ACTIVEEDGE_RISING_FALLING ))
/**
* @}
*/
/** @defgroup LPTIM_Trigger_Sample_Time
* @{
*/
#define LPTIM_TRIGSAMPLETIME_DIRECTTRANSISTION ((uint32_t)0x00000000)
#define LPTIM_TRIGSAMPLETIME_2TRANSISTIONS LPTIM_CFGR_TRGFLT_0
#define LPTIM_TRIGSAMPLETIME_4TRANSISTIONS LPTIM_CFGR_TRGFLT_1
#define LPTIM_TRIGSAMPLETIME_8TRANSISTIONS LPTIM_CFGR_TRGFLT
#define IS_LPTIM_TRIG_SAMPLE_TIME(SAMPLETIME) (((SAMPLETIME) == LPTIM_TRIGSAMPLETIME_DIRECTTRANSISTION) || \
((SAMPLETIME) == LPTIM_TRIGSAMPLETIME_2TRANSISTIONS ) || \
((SAMPLETIME) == LPTIM_TRIGSAMPLETIME_4TRANSISTIONS ) || \
((SAMPLETIME) == LPTIM_TRIGSAMPLETIME_8TRANSISTIONS ))
/**
* @}
*/
/** @defgroup LPTIM_Updating_Mode
* @{
*/
#define LPTIM_UPDATE_IMMEDIATE ((uint32_t)0x00000000)
#define LPTIM_UPDATE_ENDOFPERIOD LPTIM_CFGR_PRELOAD
#define IS_LPTIM_UPDATE_MODE(MODE) (((MODE) == LPTIM_UPDATE_IMMEDIATE) || \
((MODE) == LPTIM_UPDATE_ENDOFPERIOD))
/**
* @}
*/
/** @defgroup LPTIM_Counter_Source
* @{
*/
#define LPTIM_COUNTERSOURCE_INTERNAL ((uint32_t)0x00000000)
#define LPTIM_COUNTERSOURCE_EXTERNAL LPTIM_CFGR_COUNTMODE
#define IS_LPTIM_COUNTER_SOURCE(SOURCE) (((SOURCE) == LPTIM_COUNTERSOURCE_INTERNAL) || \
((SOURCE) == LPTIM_COUNTERSOURCE_EXTERNAL))
/**
* @}
*/
/** @defgroup LPTIM_Autorelaod_Value
* @{
*/
#define IS_LPTIM_PERIOD(PERIOD) ((PERIOD) <= 0x0000FFFF)
/**
* @}
*/
/** @defgroup LPTIM_Compare_Value
* @{
*/
#define IS_LPTIM_PULSE(PULSE) ((PULSE) <= 0x0000FFFF)
/**
* @}
*/
/** @defgroup LPTIM_Flag_Definition
* @{
*/
#define LPTIM_FLAG_DOWN LPTIM_ISR_DOWN
#define LPTIM_FLAG_UP LPTIM_ISR_UP
#define LPTIM_FLAG_ARROK LPTIM_ISR_ARROK
#define LPTIM_FLAG_CMPOK LPTIM_ISR_CMPOK
#define LPTIM_FLAG_EXTTRIG LPTIM_ISR_EXTTRIG
#define LPTIM_FLAG_ARRM LPTIM_ISR_ARRM
#define LPTIM_FLAG_CMPM LPTIM_ISR_CMPM
#define IS_LPTIM_FLAG_(FLAG) (((FLAG) == LPTIM_FLAG_DOWN) || \
((FLAG) == LPTIM_FLAG_UP) || \
((FLAG) == LPTIM_FLAG_ARROK) || \
((FLAG) == LPTIM_FLAG_CMPOK) || \
((FLAG) == LPTIM_FLAG_EXTTRIG) || \
((FLAG) == LPTIM_FLAG_ARRM) || \
((FLAG) == LPTIM_FLAG_CMPM))
/**
* @}
*/
/** @defgroup LPTIM_Interrupts_Definition
* @{
*/
#define LPTIM_IT_DOWN LPTIM_IER_DOWNIE
#define LPTIM_IT_UP LPTIM_IER_UPIE
#define LPTIM_IT_ARROK LPTIM_IER_ARROKIE
#define LPTIM_IT_CMPOK LPTIM_IER_CMPOKIE
#define LPTIM_IT_EXTTRIG LPTIM_IER_EXTTRIGIE
#define LPTIM_IT_ARRM LPTIM_IER_ARRMIE
#define LPTIM_IT_CMPM LPTIM_IER_CMPMIE
#define IS_LPTIM_IT(IT) (((IT) == LPTIM_IT_DOWN) || \
((IT) == LPTIM_IT_UP) || \
((IT) == LPTIM_IT_ARROK) || \
((IT) == LPTIM_IT_CMPOK) || \
((IT) == LPTIM_IT_EXTTRIG) || \
((IT) == LPTIM_IT_ARRM) || \
((IT) == LPTIM_IT_CMPM))
/**
* @}
*/
/**
* @}
*/
/* Exported macro ------------------------------------------------------------*/
/** @defgroup LPTIM_Exported_Macros
* @{
*/
/** @brief Reset LPTIM handle state
* @param __HANDLE__: LPTIM handle
* @retval None
*/
#define __HAL_LPTIM_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_LPTIM_STATE_RESET)
/**
* @brief Enable/Disable the LPTIM peripheral.
* @param __HANDLE__: LPTIM handle
* @retval None
*/
#define __HAL_LPTIM_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR |= (LPTIM_CR_ENABLE))
#define __HAL_LPTIM_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR &= ~(LPTIM_CR_ENABLE))
/**
* @brief Starts the LPTIM peripheral in Continuous or in single mode.
* @param __HANDLE__: DMA handle
* @retval None
*/
#define __HAL_LPTIM_START_CONTINUOUS(__HANDLE__) ((__HANDLE__)->Instance->CR |= LPTIM_CR_CNTSTRT)
#define __HAL_LPTIM_START_SINGLE(__HANDLE__) ((__HANDLE__)->Instance->CR |= LPTIM_CR_SNGSTRT)
/**
* @brief Writes the passed parameter in the Autoreload register.
* @param __HANDLE__: LPTIM handle
* @param __VALUE__ : Autoreload value
* @retval None
*/
#define __HAL_LPTIM_AUTORELOAD_SET(__HANDLE__ , __VALUE__) ((__HANDLE__)->Instance->ARR = (__VALUE__))
/**
* @brief Writes the passed parameter in the Compare register.
* @param __HANDLE__: LPTIM handle
* @param __VALUE__ : Compare value
* @retval None
*/
#define __HAL_LPTIM_COMPARE_SET(__HANDLE__ , __VALUE__) ((__HANDLE__)->Instance->CMP = (__VALUE__))
/**
* @brief Checks whether the specified LPTIM flag is set or not.
* @param __HANDLE__: LPTIM handle
* @param __FLAG__ : LPTIM flag to check
* This parameter can be a value of:
* @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.
* @retval The state of the specified flag (SET or RESET).
*/
#define __HAL_LPTIM_GET_FLAG(__HANDLE__, __FLAG__) (((__HANDLE__)->Instance->ISR &(__FLAG__)) == (__FLAG__))
/**
* @brief Clears the specified LPTIM flag.
* @param __HANDLE__: LPTIM handle.
* @param __FLAG__ : LPTIM flag to clear.
* This parameter can be a value of:
* @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.
* @retval None.
*/
#define __HAL_LPTIM_CLEAR_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->ICR = (__FLAG__))
/**
* @brief Enable the specified LPTIM interrupt.
* @param __HANDLE__ : LPTIM handle.
* @param __INTERRUPT__ : LPTIM interrupt to set.
* This parameter can be a value of:
* @arg LPTIM_IT_DOWN : Counter direction change up Interrupt.
* @arg LPTIM_IT_UP : Counter direction change down to up Interrupt.
* @arg LPTIM_IT_ARROK : Autoreload register update OK Interrupt.
* @arg LPTIM_IT_CMPOK : Compare register update OK Interrupt.
* @arg LPTIM_IT_EXTTRIG : External trigger edge event Interrupt.
* @arg LPTIM_IT_ARRM : Autoreload match Interrupt.
* @arg LPTIM_IT_CMPM : Compare match Interrupt.
* @retval None.
*/
#define __HAL_LPTIM_ENABLE_INTERRUPT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->IER |= (__INTERRUPT__))
/**
* @brief Disable the specified LPTIM interrupt.
* @param __HANDLE__ : LPTIM handle.
* @param __INTERRUPT__ : LPTIM interrupt to set.
* This parameter can be a value of:
* @arg LPTIM_IT_DOWN : Counter direction change up Interrupt.
* @arg LPTIM_IT_UP : Counter direction change down to up Interrupt.
* @arg LPTIM_IT_ARROK : Autoreload register update OK Interrupt.
* @arg LPTIM_IT_CMPOK : Compare register update OK Interrupt.
* @arg LPTIM_IT_EXTTRIG : External trigger edge event Interrupt.
* @arg LPTIM_IT_ARRM : Autoreload match Interrupt.
* @arg LPTIM_IT_CMPM : Compare match Interrupt.
* @retval None.
*/
#define __HAL_LPTIM_DISABLE_INTERRUPT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->IER &= (~(__INTERRUPT__)))
/**
* @brief Checks whether the specified LPTIM interrupt is set or not.
* @param __HANDLE__ : LPTIM handle.
* @param __INTERRUPT__ : LPTIM interrupt to check.
* This parameter can be a value of:
* @arg LPTIM_IT_DOWN : Counter direction change up Interrupt.
* @arg LPTIM_IT_UP : Counter direction change down to up Interrupt.
* @arg LPTIM_IT_ARROK : Autoreload register update OK Interrupt.
* @arg LPTIM_IT_CMPOK : Compare register update OK Interrupt.
* @arg LPTIM_IT_EXTTRIG : External trigger edge event Interrupt.
* @arg LPTIM_IT_ARRM : Autoreload match Interrupt.
* @arg LPTIM_IT_CMPM : Compare match Interrupt.
* @retval Interrupt status.
*/
#define __HAL_LPTIM_GET_ITSTATUS(__HANDLE__, __INTERRUPT__) ((((__HANDLE__)->Instance->IER & (__INTERRUPT__)) == (__INTERRUPT__)) ? SET : RESET)
/**
* @}
*/
/* Exported functions --------------------------------------------------------*/
/* Initialization/de-initialization functions ********************************/
HAL_StatusTypeDef HAL_LPTIM_Init(LPTIM_HandleTypeDef *hlptim);
HAL_StatusTypeDef HAL_LPTIM_DeInit(LPTIM_HandleTypeDef *hlptim);
/* MSP functions *************************************************************/
void HAL_LPTIM_MspInit(LPTIM_HandleTypeDef *hlptim);
void HAL_LPTIM_MspDeInit(LPTIM_HandleTypeDef *hlptim);
/* Start/Stop operation functions *********************************************/
/* ################################# PWM Mode ################################*/
/* Blocking mode: Polling */
HAL_StatusTypeDef HAL_LPTIM_PWM_Start(LPTIM_HandleTypeDef *hlptim, uint32_t Period, uint32_t Pulse);
HAL_StatusTypeDef HAL_LPTIM_PWM_Stop(LPTIM_HandleTypeDef *hlptim);
/* Non-Blocking mode: Interrupt */
HAL_StatusTypeDef HAL_LPTIM_PWM_Start_IT(LPTIM_HandleTypeDef *hlptim, uint32_t Period, uint32_t Pulse);
HAL_StatusTypeDef HAL_LPTIM_PWM_Stop_IT(LPTIM_HandleTypeDef *hlptim);
/* ############################# One Pulse Mode ##############################*/
/* Blocking mode: Polling */
HAL_StatusTypeDef HAL_LPTIM_OnePulse_Start(LPTIM_HandleTypeDef *hlptim, uint32_t Period, uint32_t Pulse);
HAL_StatusTypeDef HAL_LPTIM_OnePulse_Stop(LPTIM_HandleTypeDef *hlptim);
/* Non-Blocking mode: Interrupt */
HAL_StatusTypeDef HAL_LPTIM_OnePulse_Start_IT(LPTIM_HandleTypeDef *hlptim, uint32_t Period, uint32_t Pulse);
HAL_StatusTypeDef HAL_LPTIM_OnePulse_Stop_IT(LPTIM_HandleTypeDef *hlptim);
/* ############################## Set once Mode ##############################*/
/* Blocking mode: Polling */
HAL_StatusTypeDef HAL_LPTIM_SetOnce_Start(LPTIM_HandleTypeDef *hlptim, uint32_t Period, uint32_t Pulse);
HAL_StatusTypeDef HAL_LPTIM_SetOnce_Stop(LPTIM_HandleTypeDef *hlptim);
/* Non-Blocking mode: Interrupt */
HAL_StatusTypeDef HAL_LPTIM_SetOnce_Start_IT(LPTIM_HandleTypeDef *hlptim, uint32_t Period, uint32_t Pulse);
HAL_StatusTypeDef HAL_LPTIM_SetOnce_Stop_IT(LPTIM_HandleTypeDef *hlptim);
/* ############################### Encoder Mode ##############################*/
/* Blocking mode: Polling */
HAL_StatusTypeDef HAL_LPTIM_Encoder_Start(LPTIM_HandleTypeDef *hlptim, uint32_t Period);
HAL_StatusTypeDef HAL_LPTIM_Encoder_Stop(LPTIM_HandleTypeDef *hlptim);
/* Non-Blocking mode: Interrupt */
HAL_StatusTypeDef HAL_LPTIM_Encoder_Start_IT(LPTIM_HandleTypeDef *hlptim, uint32_t Period);
HAL_StatusTypeDef HAL_LPTIM_Encoder_Stop_IT(LPTIM_HandleTypeDef *hlptim);
/* ############################# Time out Mode ##############################*/
/* Blocking mode: Polling */
HAL_StatusTypeDef HAL_LPTIM_TimeOut_Start(LPTIM_HandleTypeDef *hlptim, uint32_t Period, uint32_t Timeout);
HAL_StatusTypeDef HAL_LPTIM_TimeOut_Stop(LPTIM_HandleTypeDef *hlptim);
/* Non-Blocking mode: Interrupt */
HAL_StatusTypeDef HAL_LPTIM_TimeOut_Start_IT(LPTIM_HandleTypeDef *hlptim, uint32_t Period, uint32_t Timeout);
HAL_StatusTypeDef HAL_LPTIM_TimeOut_Stop_IT(LPTIM_HandleTypeDef *hlptim);
/* ############################## Counter Mode ###############################*/
/* Blocking mode: Polling */
HAL_StatusTypeDef HAL_LPTIM_Counter_Start(LPTIM_HandleTypeDef *hlptim, uint32_t Period);
HAL_StatusTypeDef HAL_LPTIM_Counter_Stop(LPTIM_HandleTypeDef *hlptim);
/* Non-Blocking mode: Interrupt */
HAL_StatusTypeDef HAL_LPTIM_Counter_Start_IT(LPTIM_HandleTypeDef *hlptim, uint32_t Period);
HAL_StatusTypeDef HAL_LPTIM_Counter_Stop_IT(LPTIM_HandleTypeDef *hlptim);
/* Reading operation functions ************************************************/
uint32_t HAL_LPTIM_ReadCounter(LPTIM_HandleTypeDef *hlptim);
uint32_t HAL_LPTIM_ReadAutoReload(LPTIM_HandleTypeDef *hlptim);
uint32_t HAL_LPTIM_ReadCompare(LPTIM_HandleTypeDef *hlptim);
/* LPTIM IRQ functions *******************************************************/
void HAL_LPTIM_IRQHandler(LPTIM_HandleTypeDef *hlptim);
/* CallBack functions ********************************************************/
void HAL_LPTIM_CompareMatchCallback(LPTIM_HandleTypeDef *hlptim);
void HAL_LPTIM_AutoReloadMatchCallback(LPTIM_HandleTypeDef *hlptim);
void HAL_LPTIM_TriggerCallback(LPTIM_HandleTypeDef *hlptim);
void HAL_LPTIM_CompareWriteCallback(LPTIM_HandleTypeDef *hlptim);
void HAL_LPTIM_AutoReloadWriteCallback(LPTIM_HandleTypeDef *hlptim);
void HAL_LPTIM_DirectionUpCallback(LPTIM_HandleTypeDef *hlptim);
void HAL_LPTIM_DirectionDownCallback(LPTIM_HandleTypeDef *hlptim);
/* Peripheral State functions ************************************************/
HAL_LPTIM_StateTypeDef HAL_LPTIM_GetState(LPTIM_HandleTypeDef *hlptim);
/**
* @}
*/
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif /* __STM32L0xx_HAL_LPTIM_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,133 @@
/**
******************************************************************************
* @file stm32l0xx_hal_bsp_template.c
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief HAL BSP module.
* This file template is located in the HAL folder and should be copied
* to the user folder.
*
@verbatim
===============================================================================
##### How to use this driver #####
===============================================================================
[..]
This file is generated automatically by MicroXplorer and eventually modified
by the user
@endverbatim
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @defgroup HAL_MSP
* @brief HAL MSP module.
* @{
*/
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/** @defgroup HAL_MSP_Private_Functions
* @{
*/
/**
* @brief Initializes the Global BSP.
* @param None
* @retval None
*/
void HAL_MspInit(void)
{
/* NOTE : This function is generated automatically by STM32CubeMX and eventually
modified by the user
*/
}
/**
* @brief DeInitializes the Global MSP.
* @param None
* @retval None
*/
void HAL_MspDeInit(void)
{
/* NOTE : This function is generated automatically by STM32CubeMX and eventually
modified by the user
*/
}
/**
* @brief Initializes the PPP MSP.
* @param None
* @retval None
*/
void HAL_PPP_MspInit(void)
{
/* NOTE : This function is generated automatically by STM32CubeMX and eventually
modified by the user
*/
}
/**
* @brief DeInitializes the PPP MSP.
* @param None
* @retval None
*/
void HAL_PPP_MspDeInit(void)
{
/* NOTE : This function is generated automatically by STM32CubeMX and eventually
modified by the user
*/
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,690 @@
/**
******************************************************************************
* @file stm32l0xx_hal_pcd.h
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief Header file of PCD HAL module.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32L0xx_HAL_PCD_H
#define __STM32L0xx_HAL_PCD_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal_def.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @addtogroup PCD
* @{
*/
/* Exported types ------------------------------------------------------------*/
/**
* @brief PCD State structures definition
*/
typedef enum
{
PCD_READY = 0x00,
PCD_ERROR = 0x01,
PCD_BUSY = 0x02,
PCD_TIMEOUT = 0x03
} PCD_StateTypeDef;
typedef enum
{
/* double buffered endpoint direction */
PCD_EP_DBUF_OUT,
PCD_EP_DBUF_IN,
PCD_EP_DBUF_ERR,
}PCD_EP_DBUF_DIR;
/* endpoint buffer number */
typedef enum
{
PCD_EP_NOBUF,
PCD_EP_BUF0,
PCD_EP_BUF1
}PCD_EP_BUF_NUM;
#define PCD_ENDP0 ((uint8_t)0)
#define PCD_ENDP1 ((uint8_t)1)
#define PCD_ENDP2 ((uint8_t)2)
#define PCD_ENDP3 ((uint8_t)3)
#define PCD_ENDP4 ((uint8_t)4)
#define PCD_ENDP5 ((uint8_t)5)
#define PCD_ENDP6 ((uint8_t)6)
#define PCD_ENDP7 ((uint8_t)7)
/* Endpoint Kind */
#define PCD_SNG_BUF 0
#define PCD_DBL_BUF 1
#define IS_PCD_ALL_INSTANCE IS_USB_ALL_INSTANCE
/**
* @brief PCD Initialization Structure definition
*/
typedef struct
{
uint32_t dev_endpoints; /*!< Device Endpoints number.
This parameter depends on the used USB core.
This parameter must be a number between Min_Data = 1 and Max_Data = 15 */
uint32_t speed; /*!< USB Core speed.
This parameter can be any value of @ref PCD_Speed */
uint32_t ep0_mps; /*!< Set the Endpoint 0 Max Packet size.
This parameter can be any value of @ref PCD_USB_EP0_MPS */
uint32_t phy_itface; /*!< Select the used PHY interface.
This parameter can be any value of @ref PCD_USB_Core_PHY */
uint32_t Sof_enable; /*!< Enable or disable the output of the SOF signal.
This parameter can be set to ENABLE or DISABLE */
uint32_t low_power_enable; /*!< Enable or disable Low Power mode
This parameter can be set to ENABLE or DISABLE */
uint32_t lpm_enable; /*!< Enable or disable Link Power Management.
This parameter can be set to ENABLE or DISABLE */
uint32_t battery_charging_enable; /*!< Enable or disable Battery charging.
This parameter can be set to ENABLE or DISABLE */
}PCD_InitTypeDef;
typedef struct
{
uint8_t num; /*!< Endpoint number
This parameter must be a number between Min_Data = 1 and Max_Data = 15 */
uint8_t is_in; /*!< Endpoint direction
This parameter must be a number between Min_Data = 0 and Max_Data = 1 */
uint8_t is_stall; /*!< Endpoint stall condition
This parameter must be a number between Min_Data = 0 and Max_Data = 1 */
uint8_t type; /*!< Endpoint type
This parameter can be any value of @ref PCD_USB_EP_Type */
uint16_t pmaadress; /*!< PMA Address
This parameter can be any value between Min_addr = 0 and Max_addr = 1K */
uint16_t pmaaddr0; /*!< PMA Address0
This parameter can be any value between Min_addr = 0 and Max_addr = 1K */
uint16_t pmaaddr1; /*!< PMA Address1
This parameter can be any value between Min_addr = 0 and Max_addr = 1K */
uint8_t doublebuffer; /*!< Double buffer enable
This parameter can be 0 or 1 */
uint32_t maxpacket; /*!< Endpoint Max packet size
This parameter must be a number between Min_Data = 0 and Max_Data = 64KB */
uint8_t *xfer_buff; /*!< Pointer to transfer buffer */
uint32_t xfer_len; /*!< Current transfer length */
uint32_t xfer_count; /*!< Partial transfer length in case of multi packet transfer */
}PCD_EPTypeDef;
typedef USB_TypeDef PCD_TypeDef;
/**
* @brief PCD Handle Structure definition
*/
typedef struct
{
PCD_TypeDef *Instance; /*!< Register base address */
PCD_InitTypeDef Init; /*!< PCD required parameters */
__IO uint8_t USB_Address; /*!< USB Address */
PCD_EPTypeDef IN_ep[5]; /*!< IN endpoint parameters */
PCD_EPTypeDef OUT_ep[5]; /*!< OUT endpoint parameters */
HAL_LockTypeDef Lock; /*!< PCD peripheral status */
__IO PCD_StateTypeDef State; /*!< PCD communication state */
uint32_t Setup[12]; /*!< Setup packet buffer */
void *pData; /*!< Pointer to upper stack Handler */
} PCD_HandleTypeDef;
#include "stm32l0xx_hal_pcd_ex.h"
/* Exported constants --------------------------------------------------------*/
/** @defgroup PCD_Exported_Constants
* @{
*/
/** @defgroup PCD_Speed
* @{
*/
#define PCD_SPEED_HIGH 0 /* Not Supported */
#define PCD_SPEED_FULL 2
/**
* @}
*/
/** @defgroup PCD_USB_Core_PHY
* @{
*/
#define PCD_PHY_EMBEDDED 2
/**
* @}
*/
/** @defgroup PCD_USB_EP0_MPS
* @{
*/
#define DEP0CTL_MPS_64 0
#define DEP0CTL_MPS_32 1
#define DEP0CTL_MPS_16 2
#define DEP0CTL_MPS_8 3
#define PCD_EP0MPS_64 DEP0CTL_MPS_64
#define PCD_EP0MPS_32 DEP0CTL_MPS_32
#define PCD_EP0MPS_16 DEP0CTL_MPS_16
#define PCD_EP0MPS_08 DEP0CTL_MPS_8
/**
* @}
*/
/** @defgroup PCD_USB_EP_Type
* @{
*/
#define PCD_EP_TYPE_CTRL 0
#define PCD_EP_TYPE_ISOC 1
#define PCD_EP_TYPE_BULK 2
#define PCD_EP_TYPE_INTR 3
/**
* @}
*/
/**
* @}
*/
/* Exported macros -----------------------------------------------------------*/
/** @defgroup PCD_Interrupt_Clock
* @brief macros to handle interrupts and specific clock configurations
* @{
*/
#define __HAL_PCD_GET_FLAG(__HANDLE__, __INTERRUPT__) ((((__HANDLE__)->Instance->ISTR) & (__INTERRUPT__)) == (__INTERRUPT__))
#define __HAL_PCD_CLEAR_FLAG(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->ISTR) = ~(__INTERRUPT__))
#define USB_EXTI_LINE_WAKEUP ((uint32_t)0x00040000) /*!< External interrupt line 18 Connected to the USB FS EXTI Line */
#define __HAL_USB_EXTI_ENABLE_IT() EXTI->IMR |= USB_EXTI_LINE_WAKEUP
#define __HAL_USB_EXTI_DISABLE_IT() EXTI->IMR &= ~(USB_EXTI_LINE_WAKEUP)
#define __HAL_USB_EXTI_GENERATE_SWIT() (EXTI->SWIER |= USB_EXTI_LINE_WAKEUP)
/* Internal macros -----------------------------------------------------------*/
/* SetENDPOINT */
#define PCD_SET_ENDPOINT(USBx, bEpNum,wRegValue) (*(&USBx->EP0R + bEpNum * 2)= (uint16_t)wRegValue)
/* GetENDPOINT */
#define PCD_GET_ENDPOINT(USBx, bEpNum) (*(&USBx->EP0R + bEpNum * 2))
/**
* @brief sets the type in the endpoint register(bits EP_TYPE[1:0])
* @param bEpNum: Endpoint Number.
* @param wType: Endpoint Type.
* @retval None
*/
#define PCD_SET_EPTYPE(USBx, bEpNum,wType) (PCD_SET_ENDPOINT(USBx, bEpNum,\
((PCD_GET_ENDPOINT(USBx, bEpNum) & USB_EP_T_MASK) | wType )))
/**
* @brief gets the type in the endpoint register(bits EP_TYPE[1:0])
* @param bEpNum: Endpoint Number.
* @retval Endpoint Type
*/
#define PCD_GET_EPTYPE(USBx, bEpNum) (PCD_GET_ENDPOINT(USBx, bEpNum) & USB_EP_T_FIELD)
/**
* @brief free buffer used from the application realizing it to the line
toggles bit SW_BUF in the double buffered endpoint register
* @param bEpNum, bDir
* @retval None
*/
#define PCD_FreeUserBuffer(USBx, bEpNum, bDir)\
{\
if (bDir == PCD_EP_DBUF_OUT)\
{ /* OUT double buffered endpoint */\
PCD_TX_DTOG(USBx, bEpNum);\
}\
else if (bDir == PCD_EP_DBUF_IN)\
{ /* IN double buffered endpoint */\
PCD_RX_DTOG(USBx, bEpNum);\
}\
}
/**
* @brief gets direction of the double buffered endpoint
* @param bEpNum: Endpoint Number.
* @retval EP_DBUF_OUT, EP_DBUF_IN,
* EP_DBUF_ERR if the endpoint counter not yet programmed.
*/
#define PCD_GET_DB_DIR(USBx, bEpNum)\
{\
if ((uint16_t)(*PCD_EP_RX_CNT(USBx, bEpNum) & 0xFC00) != 0)\
return(PCD_EP_DBUF_OUT);\
else if (((uint16_t)(*PCD_EP_TX_CNT(USBx, bEpNum)) & 0x03FF) != 0)\
return(PCD_EP_DBUF_IN);\
else\
return(PCD_EP_DBUF_ERR);\
}
/**
* @brief sets the status for tx transfer (bits STAT_TX[1:0]).
* @param bEpNum: Endpoint Number.
* @param wState: new state
* @retval None
*/
#define PCD_SET_EP_TX_STATUS(USBx, bEpNum, wState) {\
register uint16_t _wRegVal; \
\
_wRegVal = PCD_GET_ENDPOINT(USBx, bEpNum) & USB_EPTX_DTOGMASK;\
/* toggle first bit ? */ \
if((USB_EPTX_DTOG1 & wState)!= 0) \
_wRegVal ^= USB_EPTX_DTOG1; \
/* toggle second bit ? */ \
if((USB_EPTX_DTOG2 & wState)!= 0) \
_wRegVal ^= USB_EPTX_DTOG2; \
PCD_SET_ENDPOINT(USBx, bEpNum, (_wRegVal | USB_EP_CTR_RX|USB_EP_CTR_TX)); \
} /* PCD_SET_EP_TX_STATUS */
/**
* @brief sets the status for rx transfer (bits STAT_TX[1:0])
* @param bEpNum: Endpoint Number.
* @param wState: new state
* @retval None
*/
#define PCD_SET_EP_RX_STATUS(USBx, bEpNum,wState) {\
register uint16_t _wRegVal; \
\
_wRegVal = PCD_GET_ENDPOINT(USBx, bEpNum) & USB_EPRX_DTOGMASK;\
/* toggle first bit ? */ \
if((USB_EPRX_DTOG1 & wState)!= 0) \
_wRegVal ^= USB_EPRX_DTOG1; \
/* toggle second bit ? */ \
if((USB_EPRX_DTOG2 & wState)!= 0) \
_wRegVal ^= USB_EPRX_DTOG2; \
PCD_SET_ENDPOINT(USBx, bEpNum, (_wRegVal | USB_EP_CTR_RX|USB_EP_CTR_TX)); \
} /* PCD_SET_EP_RX_STATUS */
/**
* @brief sets the status for rx & tx (bits STAT_TX[1:0] & STAT_RX[1:0])
* @param bEpNum: Endpoint Number.
* @param wStaterx: new state.
* @param wStatetx: new state.
* @retval None
*/
#define PCD_SET_EP_TXRX_STATUS(USBx,bEpNum,wStaterx,wStatetx) {\
register uint32_t _wRegVal; \
\
_wRegVal = PCD_GET_ENDPOINT(USBx, bEpNum) & (USB_EPRX_DTOGMASK |USB_EPTX_STAT) ;\
/* toggle first bit ? */ \
if((USB_EPRX_DTOG1 & wStaterx)!= 0) \
_wRegVal ^= USB_EPRX_DTOG1; \
/* toggle second bit ? */ \
if((USB_EPRX_DTOG2 & wStaterx)!= 0) \
_wRegVal ^= USB_EPRX_DTOG2; \
/* toggle first bit ? */ \
if((USB_EPTX_DTOG1 & wStatetx)!= 0) \
_wRegVal ^= USB_EPTX_DTOG1; \
/* toggle second bit ? */ \
if((USB_EPTX_DTOG2 & wStatetx)!= 0) \
_wRegVal ^= USB_EPTX_DTOG2; \
PCD_SET_ENDPOINT(USBx, bEpNum, _wRegVal | USB_EP_CTR_RX|USB_EP_CTR_TX); \
} /* PCD_SET_EP_TXRX_STATUS */
/**
* @brief gets the status for tx/rx transfer (bits STAT_TX[1:0]
* /STAT_RX[1:0])
* @param bEpNum: Endpoint Number.
* @retval status
*/
#define PCD_GET_EP_TX_STATUS(USBx, bEpNum) ((uint16_t)PCD_GET_ENDPOINT(USBx, bEpNum) & USB_EPTX_STAT)
#define PCD_GET_EP_RX_STATUS(USBx, bEpNum) ((uint16_t)PCD_GET_ENDPOINT(USBx, bEpNum) & USB_EPRX_STAT)
/**
* @brief sets directly the VALID tx/rx-status into the endpoint register
* @param bEpNum: Endpoint Number.
* @retval None
*/
#define PCD_SET_EP_TX_VALID(USBx, bEpNum) (PCD_SET_EP_TX_STATUS(USBx, bEpNum, USB_EP_TX_VALID))
#define PCD_SET_EP_RX_VALID(USBx, bEpNum) (PCD_SET_EP_RX_STATUS(USBx, bEpNum, USB_EP_RX_VALID))
/**
* @brief checks stall condition in an endpoint.
* @param bEpNum: Endpoint Number.
* @retval TRUE = endpoint in stall condition.
*/
#define PCD_GET_EP_TX_STALL_STATUS(USBx, bEpNum) (PCD_GET_EP_TX_STATUS(USBx, bEpNum) \
== USB_EP_TX_STALL)
#define PCD_GET_EP_RX_STALL_STATUS(USBx, bEpNum) (PCD_GET_EP_RX_STATUS(USBx, bEpNum) \
== USB_EP_RX_STALL)
/**
* @brief set & clear EP_KIND bit.
* @param bEpNum: Endpoint Number.
* @retval None
*/
#define PCD_SET_EP_KIND(USBx, bEpNum) (PCD_SET_ENDPOINT(USBx, bEpNum, \
(USB_EP_CTR_RX|USB_EP_CTR_TX|((PCD_GET_ENDPOINT(USBx, bEpNum) | USB_EP_KIND) & USB_EPREG_MASK))))
#define PCD_CLEAR_EP_KIND(USBx, bEpNum) (PCD_SET_ENDPOINT(USBx, bEpNum, \
(USB_EP_CTR_RX|USB_EP_CTR_TX|(PCD_GET_ENDPOINT(USBx, bEpNum) & USB_EPKIND_MASK))))
/**
* @brief Sets/clears directly STATUS_OUT bit in the endpoint register.
* @param bEpNum: Endpoint Number.
* @retval None
*/
#define PCD_SET_OUT_STATUS(USBx, bEpNum) PCD_SET_EP_KIND(USBx, bEpNum)
#define PCD_CLEAR_OUT_STATUS(USBx, bEpNum) PCD_CLEAR_EP_KIND(USBx, bEpNum)
/**
* @brief Sets/clears directly EP_KIND bit in the endpoint register.
* @param bEpNum: Endpoint Number.
* @retval None
*/
#define PCD_SET_EP_DBUF(USBx, bEpNum) PCD_SET_EP_KIND(USBx, bEpNum)
#define PCD_CLEAR_EP_DBUF(USBx, bEpNum) PCD_CLEAR_EP_KIND(USBx, bEpNum)
/**
* @brief Clears bit CTR_RX / CTR_TX in the endpoint register.
* @param bEpNum: Endpoint Number.
* @retval None
*/
#define PCD_CLEAR_RX_EP_CTR(USBx, bEpNum) (PCD_SET_ENDPOINT(USBx, bEpNum,\
PCD_GET_ENDPOINT(USBx, bEpNum) & 0x7FFF & USB_EPREG_MASK))
#define PCD_CLEAR_TX_EP_CTR(USBx, bEpNum) (PCD_SET_ENDPOINT(USBx, bEpNum,\
PCD_GET_ENDPOINT(USBx, bEpNum) & 0xFF7F & USB_EPREG_MASK))
/**
* @brief Toggles DTOG_RX / DTOG_TX bit in the endpoint register.
* @param bEpNum: Endpoint Number.
* @retval None
*/
#define PCD_RX_DTOG(USBx, bEpNum) (PCD_SET_ENDPOINT(USBx, bEpNum, \
USB_EP_CTR_RX|USB_EP_CTR_TX|USB_EP_DTOG_RX | (PCD_GET_ENDPOINT(USBx, bEpNum) & USB_EPREG_MASK)))
#define PCD_TX_DTOG(USBx, bEpNum) (PCD_SET_ENDPOINT(USBx, bEpNum, \
USB_EP_CTR_RX|USB_EP_CTR_TX|USB_EP_DTOG_TX | (PCD_GET_ENDPOINT(USBx, bEpNum) & USB_EPREG_MASK)))
/**
* @brief Clears DTOG_RX / DTOG_TX bit in the endpoint register.
* @param bEpNum: Endpoint Number.
* @retval None
*/
#define PCD_CLEAR_RX_DTOG(USBx, bEpNum) if((PCD_GET_ENDPOINT(USBx, bEpNum) & USB_EP_DTOG_RX) != 0)\
PCD_RX_DTOG(USBx, bEpNum)
#define PCD_CLEAR_TX_DTOG(USBx, bEpNum) if((PCD_GET_ENDPOINT(USBx, bEpNum) & USB_EP_DTOG_TX) != 0)\
PCD_TX_DTOG(USBx, bEpNum)
/**
* @brief Sets address in an endpoint register.
* @param bEpNum: Endpoint Number.
* @param bAddr: Address.
* @retval None
*/
#define PCD_SET_EP_ADDRESS(USBx, bEpNum,bAddr) PCD_SET_ENDPOINT(USBx, bEpNum,\
USB_EP_CTR_RX|USB_EP_CTR_TX|(PCD_GET_ENDPOINT(USBx, bEpNum) & USB_EPREG_MASK) | bAddr)
/**
* @brief Gets address in an endpoint register.
* @param bEpNum: Endpoint Number.
* @retval None
*/
#define PCD_GET_EP_ADDRESS(USBx, bEpNum) ((uint8_t)(PCD_GET_ENDPOINT(USBx, bEpNum) & USB_EPADDR_FIELD))
#define PCD_EP_TX_ADDRESS(USBx, bEpNum) ((uint16_t *)((USBx->BTABLE+bEpNum*8)+ ((uint32_t)USBx + 0x400)))
#define PCD_EP_TX_CNT(USBx, bEpNum) ((uint16_t *)((USBx->BTABLE+bEpNum*8+2)+ ((uint32_t)USBx + 0x400)))
#define PCD_EP_RX_ADDRESS(USBx, bEpNum) ((uint16_t *)((USBx->BTABLE+bEpNum*8+4)+ ((uint32_t)USBx + 0x400)))
#define PCD_EP_RX_CNT(USBx, bEpNum) ((uint16_t *)((USBx->BTABLE+bEpNum*8+6)+ ((uint32_t)USBx + 0x400)))
/**
* @brief sets address of the tx/rx buffer.
* @param bEpNum: Endpoint Number.
* @param wAddr: address to be set (must be word aligned).
* @retval None
*/
#define PCD_SET_EP_TX_ADDRESS(USBx, bEpNum,wAddr) (*PCD_EP_TX_ADDRESS(USBx, bEpNum) = ((wAddr >> 1) << 1))
#define PCD_SET_EP_RX_ADDRESS(USBx, bEpNum,wAddr) (*PCD_EP_RX_ADDRESS(USBx, bEpNum) = ((wAddr >> 1) << 1))
/**
* @brief Gets address of the tx/rx buffer.
* @param bEpNum: Endpoint Number.
* @retval address of the buffer.
*/
#define PCD_GET_EP_TX_ADDRESS(USBx, bEpNum) ((uint16_t)*PCD_EP_TX_ADDRESS(USBx, bEpNum))
#define PCD_GET_EP_RX_ADDRESS(USBx, bEpNum) ((uint16_t)*PCD_EP_RX_ADDRESS(USBx, bEpNum))
/**
* @brief Sets counter of rx buffer with no. of blocks.
* @param bEpNum: Endpoint Number.
* @param wCount: Counter.
* @retval None
*/
#define PCD_CALC_BLK32(dwReg,wCount,wNBlocks) {\
wNBlocks = wCount >> 5;\
if((wCount & 0x1f) == 0)\
wNBlocks--;\
*pdwReg = (uint16_t)((wNBlocks << 10) | 0x8000);\
}/* PCD_CALC_BLK32 */
#define PCD_CALC_BLK2(dwReg,wCount,wNBlocks) {\
wNBlocks = wCount >> 1;\
if((wCount & 0x1) != 0)\
wNBlocks++;\
*pdwReg = (uint16_t)(wNBlocks << 10);\
}/* PCD_CALC_BLK2 */
#define PCD_SET_EP_CNT_RX_REG(dwReg,wCount) {\
uint16_t wNBlocks;\
if(wCount > 62){PCD_CALC_BLK32(dwReg,wCount,wNBlocks);}\
else {PCD_CALC_BLK2(dwReg,wCount,wNBlocks);}\
}/* PCD_SET_EP_CNT_RX_REG */
#define PCD_SET_EP_RX_DBUF0_CNT(USBx, bEpNum,wCount) {\
uint16_t *pdwReg = PCD_EP_TX_CNT(USBx, bEpNum); \
PCD_SET_EP_CNT_RX_REG(pdwReg, wCount);\
}
/**
* @brief sets counter for the tx/rx buffer.
* @param bEpNum: Endpoint Number.
* @param wCount: Counter value.
* @retval None
*/
#define PCD_SET_EP_TX_CNT(USBx, bEpNum,wCount) (*PCD_EP_TX_CNT(USBx, bEpNum) = wCount)
#define PCD_SET_EP_RX_CNT(USBx, bEpNum,wCount) {\
uint16_t *pdwReg = PCD_EP_RX_CNT(USBx, bEpNum); \
PCD_SET_EP_CNT_RX_REG(pdwReg, wCount);\
}
/**
* @brief gets counter of the tx buffer.
* @param bEpNum: Endpoint Number.
* @retval Counter value
*/
#define PCD_GET_EP_TX_CNT(USBx, bEpNum)((uint16_t)(*PCD_EP_TX_CNT(USBx, bEpNum)) & 0x3ff)
#define PCD_GET_EP_RX_CNT(USBx, bEpNum)((uint16_t)(*PCD_EP_RX_CNT(USBx, bEpNum)) & 0x3ff)
/**
* @brief Sets buffer 0/1 address in a double buffer endpoint.
* @param bEpNum: Endpoint Number.
* @param wBuf0Addr: buffer 0 address.
* @retval Counter value
*/
#define PCD_SET_EP_DBUF0_ADDR(USBx, bEpNum,wBuf0Addr) {PCD_SET_EP_TX_ADDRESS(USBx, bEpNum, wBuf0Addr);}
#define PCD_SET_EP_DBUF1_ADDR(USBx, bEpNum,wBuf1Addr) {PCD_SET_EP_RX_ADDRESS(USBx, bEpNum, wBuf1Addr);}
/**
* @brief Sets addresses in a double buffer endpoint.
* @param bEpNum: Endpoint Number.
* @param wBuf0Addr: buffer 0 address.
* @param wBuf1Addr = buffer 1 address.
* @retval None
*/
#define PCD_SET_EP_DBUF_ADDR(USBx, bEpNum,wBuf0Addr,wBuf1Addr) { \
PCD_SET_EP_DBUF0_ADDR(USBx, bEpNum, wBuf0Addr);\
PCD_SET_EP_DBUF1_ADDR(USBx, bEpNum, wBuf1Addr);\
} /* PCD_SET_EP_DBUF_ADDR */
/**
* @brief Gets buffer 0/1 address of a double buffer endpoint.
* @param bEpNum: Endpoint Number.
* @retval None
*/
#define PCD_GET_EP_DBUF0_ADDR(USBx, bEpNum) (PCD_GET_EP_TX_ADDRESS(USBx, bEpNum))
#define PCD_GET_EP_DBUF1_ADDR(USBx, bEpNum) (PCD_GET_EP_RX_ADDRESS(USBx, bEpNum))
/**
* @brief Gets buffer 0/1 address of a double buffer endpoint.
* @param bEpNum: Endpoint Number.
* bDir: endpoint dir EP_DBUF_OUT = OUT
* EP_DBUF_IN = IN
* @param wCount: Counter value
* @retval None
*/
#define PCD_SET_EP_DBUF0_CNT(USBx, bEpNum, bDir, wCount) { \
if(bDir == PCD_EP_DBUF_OUT)\
/* OUT endpoint */ \
{PCD_SET_EP_RX_DBUF0_CNT(USBx, bEpNum,wCount);} \
else if(bDir == PCD_EP_DBUF_IN)\
/* IN endpoint */ \
*PCD_EP_TX_CNT(USBx, bEpNum) = (uint32_t)wCount; \
} /* SetEPDblBuf0Count*/
#define PCD_SET_EP_DBUF1_CNT(USBx, bEpNum, bDir, wCount) { \
if(bDir == PCD_EP_DBUF_OUT)\
/* OUT endpoint */ \
{PCD_SET_EP_RX_CNT(USBx, bEpNum,wCount);}\
else if(bDir == PCD_EP_DBUF_IN)\
/* IN endpoint */\
*PCD_EP_RX_CNT(USBx, bEpNum) = (uint32_t)wCount; \
} /* SetEPDblBuf1Count */
#define PCD_SET_EP_DBUF_CNT(USBx, bEpNum, bDir, wCount) {\
PCD_SET_EP_DBUF0_CNT(USBx, bEpNum, bDir, wCount); \
PCD_SET_EP_DBUF1_CNT(USBx, bEpNum, bDir, wCount); \
} /* PCD_SET_EP_DBUF_CNT */
/**
* @brief Gets buffer 0/1 rx/tx counter for double buffering.
* @param bEpNum: Endpoint Number.
* @retval None
*/
#define PCD_GET_EP_DBUF0_CNT(USBx, bEpNum) (PCD_GET_EP_TX_CNT(USBx, bEpNum))
#define PCD_GET_EP_DBUF1_CNT(USBx, bEpNum) (PCD_GET_EP_RX_CNT(USBx, bEpNum))
/**
* @}
*/
/* Exported functions --------------------------------------------------------*/
/* Initialization/de-initialization functions **********************************/
HAL_StatusTypeDef HAL_PCD_Init(PCD_HandleTypeDef *hpcd);
HAL_StatusTypeDef HAL_PCD_DeInit (PCD_HandleTypeDef *hpcd);
void HAL_PCD_MspInit(PCD_HandleTypeDef *hpcd);
void HAL_PCD_MspDeInit(PCD_HandleTypeDef *hpcd);
/* I/O operation functions *****************************************************/
/* Non-Blocking mode: Interrupt */
HAL_StatusTypeDef HAL_PCD_Start(PCD_HandleTypeDef *hpcd);
HAL_StatusTypeDef HAL_PCD_Stop(PCD_HandleTypeDef *hpcd);
void HAL_PCD_IRQHandler(PCD_HandleTypeDef *hpcd);
void HAL_PCD_DataOutStageCallback(PCD_HandleTypeDef *hpcd, uint8_t epnum);
void HAL_PCD_DataInStageCallback(PCD_HandleTypeDef *hpcd, uint8_t epnum);
void HAL_PCD_SetupStageCallback(PCD_HandleTypeDef *hpcd);
void HAL_PCD_SOFCallback(PCD_HandleTypeDef *hpcd);
void HAL_PCD_ResetCallback(PCD_HandleTypeDef *hpcd);
void HAL_PCD_SuspendCallback(PCD_HandleTypeDef *hpcd);
void HAL_PCD_ResumeCallback(PCD_HandleTypeDef *hpcd);
void HAL_PCD_ISOOUTIncompleteCallback(PCD_HandleTypeDef *hpcd, uint8_t epnum);
void HAL_PCD_ISOINIncompleteCallback(PCD_HandleTypeDef *hpcd, uint8_t epnum);
void HAL_PCD_ConnectCallback(PCD_HandleTypeDef *hpcd);
void HAL_PCD_DisconnectCallback(PCD_HandleTypeDef *hpcd);
/* Peripheral Control functions ************************************************/
HAL_StatusTypeDef HAL_PCD_DevConnect(PCD_HandleTypeDef *hpcd);
HAL_StatusTypeDef HAL_PCD_DevDisconnect(PCD_HandleTypeDef *hpcd);
HAL_StatusTypeDef HAL_PCD_SetAddress(PCD_HandleTypeDef *hpcd, uint8_t address);
HAL_StatusTypeDef HAL_PCD_EP_Open(PCD_HandleTypeDef *hpcd, uint8_t ep_addr, uint16_t ep_mps, uint8_t ep_type);
HAL_StatusTypeDef HAL_PCD_EP_Close(PCD_HandleTypeDef *hpcd, uint8_t ep_addr);
HAL_StatusTypeDef HAL_PCD_EP_Receive(PCD_HandleTypeDef *hpcd, uint8_t ep_addr, uint8_t *pBuf, uint32_t len);
HAL_StatusTypeDef HAL_PCD_EP_Transmit(PCD_HandleTypeDef *hpcd, uint8_t ep_addr, uint8_t *pBuf, uint32_t len);
uint16_t HAL_PCD_EP_GetRxCount(PCD_HandleTypeDef *hpcd, uint8_t ep_addr);
HAL_StatusTypeDef HAL_PCD_EP_SetStall(PCD_HandleTypeDef *hpcd, uint8_t ep_addr);
HAL_StatusTypeDef HAL_PCD_EP_ClrStall(PCD_HandleTypeDef *hpcd, uint8_t ep_addr);
HAL_StatusTypeDef HAL_PCD_EP_Flush(PCD_HandleTypeDef *hpcd, uint8_t ep_addr);
HAL_StatusTypeDef HAL_PCD_ActiveRemoteWakeup(PCD_HandleTypeDef *hpcd);
HAL_StatusTypeDef HAL_PCD_DeActiveRemoteWakeup(PCD_HandleTypeDef *hpcd);
/* Peripheral State functions **************************************************/
PCD_StateTypeDef HAL_PCD_GetState(PCD_HandleTypeDef *hpcd);
/**
* @}
*/
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif /* __STM32L0xx_HAL_PCD_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,151 @@
/**
******************************************************************************
* @file stm32l0xx_hal_pcd_ex.c
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief Extended PCD HAL module driver.
* This file provides firmware functions to manage the following
* functionalities of the USB Peripheral Controller:
* + Configururation of the PMA for EP
*
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @defgroup PCDEx
* @brief PCDEx HAL module driver
* @{
*/
#ifdef HAL_PCD_MODULE_ENABLED
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/** @defgroup PCDEx_Private_Functions
* @{
*/
/** @defgroup PCDEx_Group1 Initialization and de-initialization functions
* @brief Initialization and Configuration functions
*
@verbatim
===============================================================================
##### Peripheral extended features functions #####
===============================================================================
@endverbatim
* @{
*/
/**
* @brief Configure PMA for EP
* @param pdev : Device instance
* @param ep_addr: endpoint address
* @param ep_Kind: endpoint Kind
* USB_SNG_BUF: Single Buffer used
* USB_DBL_BUF: Double Buffer used
* @param pmaadress: EP address in The PMA: In case of single buffer endpoint
* this parameter is 16-bit value providing the address
* in PMA allocated to endpoint.
* In case of double buffer endpoint this parameter
* is a 32-bit value providing the endpoint buffer 0 address
* in the LSB part of 32-bit value and endpoint buffer 1 address
* in the MSB part of 32-bit value.
* @retval : status
*/
HAL_StatusTypeDef HAL_PCDEx_PMAConfig(PCD_HandleTypeDef *hpcd,
uint16_t ep_addr,
uint16_t ep_kind,
uint32_t pmaadress)
{
PCD_EPTypeDef *ep;
/* initialize ep structure*/
if ((0x80 & ep_addr) == 0x80)
{
ep = &hpcd->IN_ep[ep_addr & 0x7F];
}
else
{
ep = &hpcd->OUT_ep[ep_addr];
}
/* Here we check if the endpoint is single or double Buffer*/
if (ep_kind == PCD_SNG_BUF)
{
/*Single Buffer*/
ep->doublebuffer = 0;
/*Configure te PMA*/
ep->pmaadress = (uint16_t)pmaadress;
}
else /*USB_DBL_BUF*/
{
/*Double Buffer Endpoint*/
ep->doublebuffer = 1;
/*Configure the PMA*/
ep->pmaaddr0 = pmaadress & 0xFFFF;
ep->pmaaddr1 = (pmaadress & 0xFFFF0000) >> 16;
}
return HAL_OK;
}
/**
* @}
*/
/**
* @}
*/
#endif /* HAL_PCD_MODULE_ENABLED */
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,82 @@
/**
******************************************************************************
* @file stm32l0xx_hal_pcd.h
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief Header file of PCD HAL module.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32L0xx_HAL_PCD_EX_H
#define __STM32L0xx_HAL_PCD_EX_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal_def.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @addtogroup PCDEx
* @{
*/
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
/* Exported macros -----------------------------------------------------------*/
/* Internal macros -----------------------------------------------------------*/
/* Exported functions --------------------------------------------------------*/
HAL_StatusTypeDef HAL_PCDEx_PMAConfig(PCD_HandleTypeDef *hpcd,
uint16_t ep_addr,
uint16_t ep_kind,
uint32_t pmaadress);
/**
* @}
*/
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif /* __STM32L0xx_HAL_PCD_EX_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,643 @@
/**
******************************************************************************
* @file stm32l0xx_hal_pwr.c
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief PWR HAL module driver.
*
* This file provides firmware functions to manage the following
* functionalities of the Power Controller (PWR) peripheral:
* + Initialization/de-initialization functions
* + Peripheral Control functions
*
@verbatim
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @defgroup PWR
* @brief PWR HAL module driver
* @{
*/
#ifdef HAL_PWR_MODULE_ENABLED
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/** @defgroup PWR_Private_Functions
* @{
*/
/** @defgroup PWR_Group1 Initialization and De-initialization functions
* @brief Initialization and Configuration functions
*
@verbatim
===============================================================================
##### Initialization and de-initialization functions #####
===============================================================================
[..]
After reset, the backup domain (RTC registers, RTC backup data
registers) is protected against possible unwanted
write accesses.
To enable access to the RTC Domain and RTC registers, proceed as follows:
(+) Enable the Power Controller (PWR) APB1 interface clock using the
__PWR_CLK_ENABLE() macro.
(+) Enable access to RTC domain using the HAL_PWR_EnableBkUpAccess() function.
@endverbatim
* @{
*/
/**
* @brief Deinitializes the HAL PWR peripheral registers to their default reset values.
* @param None
* @retval None
*/
void HAL_PWR_DeInit(void)
{
__PWR_FORCE_RESET();
__PWR_RELEASE_RESET();
}
/**
* @brief Enables access to the backup domain (RTC registers, RTC
* backup data registers ).
* @note If the HSE divided by 2, 4, 8 or 16 is used as the RTC clock, the
* Backup Domain Access should be kept enabled.
* @param None
* @retval None
*/
void HAL_PWR_EnableBkUpAccess(void)
{
/* Enable access to RTC and backup registers */
PWR->CR |= PWR_CR_DBP;
}
/**
* @brief Disables access to the backup domain (RTC registers, RTC
* backup data registers).
* @note If the HSE divided by 2, 4, 8 or 16 is used as the RTC clock, the
* Backup Domain Access should be kept enabled.
* @param None
* @retval None
*/
void HAL_PWR_DisableBkUpAccess(void)
{
/* Disable access to RTC and backup registers */
PWR->CR &= (uint32_t)~((uint32_t)PWR_CR_DBP);
}
/**
* @}
*/
/** @defgroup PWR_Group2 Peripheral Control functions
* @brief Low Power modes configuration functions
*
@verbatim
===============================================================================
##### Peripheral Control functions #####
===============================================================================
*** PVD configuration ***
=========================
[..]
(+) The PVD is used to monitor the VDD power supply by comparing it to a
threshold selected by the PVD Level (PLS[2:0] bits in the PWR_CR).
(+) The PVD can use an external input analog voltage (PVD_IN) which is compared
internally to VREFINT. The PVD_IN (PB7) has to be configured in Analog mode
when PWR_PVDLevel_7 is selected (PLS[2:0] = 111).
(+) A PVDO flag is available to indicate if VDD/VDDA is higher or lower
than the PVD threshold. This event is internally connected to the EXTI
line16 and can generate an interrupt if enabled. This is done through
__HAL_PVD_EXTI_ENABLE_IT() macro.
(+) The PVD is stopped in Standby mode.
*** WakeUp pin configuration ***
================================
[..]
(+) WakeUp pin is used to wake up the system from Standby mode. This pin is
forced in input pull-down configuration and is active on rising edges.
(+) There are two WakeUp pins:
WakeUp Pin 1 on PA.00.
WakeUp Pin 2 on PC.13.
[..]
*** Main and Backup Regulators configuration ***
================================================
(+) The main internal regulator can be configured to have a tradeoff between
performance and power consumption when the device does not operate at
the maximum frequency. This is done through __HAL_PWR_VOLTAGESCALING_CONFIG()
macro which configure VOS bit in PWR_CR register:
(++) When this bit is set (Regulator voltage output Scale 1 mode selected)
the System frequency can go up to 32 MHz.
(++) When this bit is reset (Regulator voltage output Scale 2 mode selected)
the System frequency can go up to 16 MHz.
(++) When this bit is reset (Regulator voltage output Scale 3 mode selected)
the System frequency can go up to 4.2 MHz.
Refer to the datasheets for more details.
*** Low Power modes configuration ***
=====================================
[..]
The device features 5 low-power modes:
(+) Low power run mode: regulator in low power mode, limited clock frequency,
limited number of peripherals running.
(+) Sleep mode: Cortex-M0+ core stopped, peripherals kept running.
(+) Low power sleep mode: Cortex-M0+ core stopped, limited clock frequency,
limited number of peripherals running, regulator in low power mode.
(+) Stop mode: All clocks are stopped, regulator running, regulator in low power mode.
(+) Standby mode: VCORE domain powered off
*** Low power run mode ***
=========================
[..]
To further reduce the consumption when the system is in Run mode, the regulator can be
configured in low power mode. In this mode, the system frequency should not exceed
MSI frequency range1.
In Low power run mode, all I/O pins keep the same state as in Run mode.
(+) Entry:
(++) VCORE in range2
(++) Decrease the system frequency tonot exceed the frequency of MSI frequency range1.
(++) The regulator is forced in low power mode using the HAL_PWREx_EnableLowPowerRunMode()
function.
(+) Exit:
(++) The regulator is forced in Main regulator mode using the HAL_PWREx_DisableLowPowerRunMode()
function.
(++) Increase the system frequency if needed.
*** Sleep mode ***
==================
[..]
(+) Entry:
The Sleep mode is entered by using the HAL_PWR_EnterSLEEPMode(PWR_MAINREGULATOR_ON, PWR_SLEEPENTRY_WFx)
functions with
(++) PWR_SLEEPENTRY_WFI: enter SLEEP mode with WFI instruction
(++) PWR_SLEEPENTRY_WFE: enter SLEEP mode with WFE instruction
(+) Exit:
(++) Any peripheral interrupt acknowledged by the nested vectored interrupt
controller (NVIC) can wake up the device from Sleep mode.
*** Low power sleep mode ***
============================
[..]
(+) Entry:
The Low power sleep mode is entered by using the HAL_PWR_EnterSLEEPMode(PWR_LOWPOWERREGULATOR_ON, PWR_SLEEPENTRY_WFx)
functions with
(++) PWR_SLEEPENTRY_WFI: enter SLEEP mode with WFI instruction
(++) PWR_SLEEPENTRY_WFE: enter SLEEP mode with WFE instruction
(+) The Flash memory can be switched off by using the control bits (SLEEP_PD in the FLASH_ACR register.
This reduces power consumption but increases the wake-up time.
(+) Exit:
(++) If the WFI instruction was used to enter Low power sleep mode, any peripheral interrupt
acknowledged by the nested vectored interrupt controller (NVIC) can wake up the device
from Low power sleep mode. If the WFE instruction was used to enter Low power sleep mode,
the MCU exits Sleep mode as soon as an event occurs.
*** Stop mode ***
=================
[..]
The Stop mode is based on the Cortex-M0+ deepsleep mode combined with peripheral
clock gating. The voltage regulator can be configured either in normal or low-power mode.
In Stop mode, all clocks in the VCORE domain are stopped, the PLL, the MSI, the HSI and
the HSE RC oscillators are disabled. Internal SRAM and register contents are preserved.
To get the lowest consumption in Stop mode, the internal Flash memory also enters low
power mode. When the Flash memory is in power-down mode, an additional startup delay is
incurred when waking up from Stop mode.
To minimize the consumption In Stop mode, VREFINT, the BOR, PVD, and temperature
sensor can be switched off before entering Stop mode. They can be switched on again by
software after exiting Stop mode using the ULP bit in the PWR_CR register.
In Stop mode, all I/O pins keep the same state as in Run mode.
(+) Entry:
The Stop mode is entered using the HAL_PWR_EnterSTOPMode(PWR_MAINREGULATOR_ON, PWR_SLEEPENTRY_WFI )
function with:
(++) Main regulator ON.
(++) Low Power regulator ON.
(++) PWR_SLEEPENTRY_WFI: enter SLEEP mode with WFI instruction
(++) PWR_SLEEPENTRY_WFE: enter SLEEP mode with WFE instruction
(+) Exit:
(++) By issuing an interrupt or a wakeup event, the MSI or HSI16 RC
oscillator is selected as system clock depending the bit STOPWUCK in the RCC_CFGR
register
*** Standby mode ***
====================
[..]
The Standby mode allows to achieve the lowest power consumption. It is based on the
Cortex-M0+ deepsleep mode, with the voltage regulator disabled. The VCORE domain is
consequently powered off. The PLL, the MSI, the HSI oscillator and the HSE oscillator are
also switched off. SRAM and register contents are lost except for the RTC registers, RTC
backup registers and Standby circuitry.
To minimize the consumption In Standby mode, VREFINT, the BOR, PVD, and temperature
sensor can be switched off before entering the Standby mode. They can be switched
on again by software after exiting the Standby mode.
function.
(+) Entry:
(++) The Standby mode is entered using the HAL_PWR_EnterSTANDBYMode() function.
(+) Exit:
(++) WKUP pin rising edge, RTC alarm (Alarm A and Alarm B), RTC wakeup,
tamper event, time-stamp event, external reset in NRST pin, IWDG reset.
*** Auto-wakeup (AWU) from low-power mode ***
=============================================
[..]
The MCU can be woken up from low-power mode by an RTC Alarm event, an RTC
Wakeup event, a tamper event, a time-stamp event, or a comparator event,
without depending on an external interrupt (Auto-wakeup mode).
(+) RTC auto-wakeup (AWU) from the Stop mode
(++) To wake up from the Stop mode with an RTC alarm event, it is necessary to:
(+++) Configure the EXTI Line 17 to be sensitive to rising edges (Interrupt
or Event modes) using the EXTI_Init() function.
(+++) Enable the RTC Alarm Interrupt using the RTC_ITConfig() function
(+++) Configure the RTC to generate the RTC alarm using the RTC_SetAlarm()
and RTC_AlarmCmd() functions.
(++) To wake up from the Stop mode with an RTC Tamper or time stamp event, it
is necessary to:
(+++) Configure the EXTI Line 19 to be sensitive to rising edges (Interrupt
or Event modes) using the EXTI_Init() function.
(+++) Enable the RTC Tamper or time stamp Interrupt using the RTC_ITConfig()
function.
(+++) Configure the RTC to detect the tamper or time stamp event using the
RTC_TimeStampConfig(), RTC_TamperTriggerConfig() and RTC_TamperCmd()
functions.
(++) To wake up from the Stop mode with an RTC WakeUp event, it is necessary to:
(+++) Configure the EXTI Line 20 to be sensitive to rising edges (Interrupt
or Event modes) using the EXTI_Init() function.
(+++) Enable the RTC WakeUp Interrupt using the RTC_ITConfig() function.
(+++) Configure the RTC to generate the RTC WakeUp event using the RTC_WakeUpClockConfig(),
RTC_SetWakeUpCounter() and RTC_WakeUpCmd() functions.
(+) RTC auto-wakeup (AWU) from the Standby mode
(++) To wake up from the Standby mode with an RTC alarm event, it is necessary to:
(+++) Enable the RTC Alarm Interrupt using the RTC_ITConfig() function.
(+++) Configure the RTC to generate the RTC alarm using the RTC_SetAlarm()
and RTC_AlarmCmd() functions.
(++) To wake up from the Standby mode with an RTC Tamper or time stamp event, it
is necessary to:
(+++) Enable the RTC Tamper or time stamp Interrupt using the RTC_ITConfig()
function.
(+++) Configure the RTC to detect the tamper or time stamp event using the
RTC_TimeStampConfig(), RTC_TamperTriggerConfig() and RTC_TamperCmd()
functions.
(++) To wake up from the Standby mode with an RTC WakeUp event, it is necessary to:
(+++) Enable the RTC WakeUp Interrupt using the RTC_ITConfig() function
(+++) Configure the RTC to generate the RTC WakeUp event using the RTC_WakeUpClockConfig(),
RTC_SetWakeUpCounter() and RTC_WakeUpCmd() functions.
(+) Comparator auto-wakeup (AWU) from the Stop mode
(++) To wake up from the Stop mode with an comparator 1 or comparator 2 wakeup
event, it is necessary to:
(+++) Configure the EXTI Line 21 for comparator 1 or EXTI Line 22 for comparator 2
to be sensitive to to the selected edges (falling, rising or falling
and rising) (Interrupt or Event modes) using the EXTI_Init() function.
(+++) Configure the comparator to generate the event.
@endverbatim
* @{
*/
/**
* @brief Configures the voltage threshold detected by the Power Voltage Detector(PVD).
* @param sConfigPVD: pointer to an PWR_PVDTypeDef structure that contains the configuration
* information for the PVD.
* @note Refer to the electrical characteristics of your device datasheet for
* more details about the voltage threshold corresponding to each
* detection level.
* @retval None
*/
void HAL_PWR_PVDConfig(PWR_PVDTypeDef *sConfigPVD)
{
uint32_t tmpreg = 0;
/* Check the parameters */
assert_param(IS_PWR_PVD_LEVEL(sConfigPVD->PVDLevel));
tmpreg = PWR->CR;
/* Clear PLS[7:5] bits */
tmpreg &= ~ (uint32_t)PWR_CR_PLS;
/* Set PLS[7:5] bits according to PVDLevel value */
tmpreg |= sConfigPVD->PVDLevel;
/* Store the new value */
PWR->CR = tmpreg;
/* Configure the EXTI 16 interrupt */
if((sConfigPVD->Mode == PWR_MODE_IT_RISING_FALLING) ||\
(sConfigPVD->Mode == PWR_MODE_IT_FALLING) ||\
(sConfigPVD->Mode == PWR_MODE_IT_RISING))
{
__HAL_PVD_EXTI_ENABLE_IT(PWR_EXTI_LINE_PVD);
}
/* Clear the edge trigger for the EXTI Line 16 (PVD) */
EXTI->RTSR &= ~EXTI_RTSR_TR16;
EXTI->FTSR &= ~EXTI_FTSR_TR16;
/* Configure the rising edge */
if((sConfigPVD->Mode == PWR_MODE_IT_RISING_FALLING) ||\
(sConfigPVD->Mode == PWR_MODE_IT_RISING))
{
EXTI->RTSR |= PWR_EXTI_LINE_PVD;
}
/* Configure the falling edge */
if((sConfigPVD->Mode == PWR_MODE_IT_RISING_FALLING) ||\
(sConfigPVD->Mode == PWR_MODE_IT_FALLING))
{
EXTI->FTSR |= PWR_EXTI_LINE_PVD;
}
}
/**
* @brief Enables the Power Voltage Detector(PVD).
* @param None
* @retval None
*/
void HAL_PWR_EnablePVD(void)
{
/* Enable the power voltage detector */
PWR->CR |= PWR_CR_PVDE;
}
/**
* @brief Disables the Power Voltage Detector(PVD).
* @param None
* @retval None
*/
void HAL_PWR_DisablePVD(void)
{
/* Disable the power voltage detector */
PWR->CR &= (uint32_t)~((uint32_t)PWR_CR_PVDE);
}
/**
* @brief Enables the WakeUp PINx functionality.
* @param WakeUpPinx: Specifies the Power Wake-Up pin to enable.
* This parameter can be one of the following values:
* @arg PWR_WAKEUP_PIN1
* @arg PWR_WAKEUP_PIN2
* @retval None
*/
void HAL_PWR_EnableWakeUpPin(uint32_t WakeUpPinx)
{
/* Check the parameter */
assert_param(IS_PWR_WAKEUP_PIN(WakeUpPinx));
/* Enable the EWUPx pin */
PWR->CSR |= WakeUpPinx;
}
/**
* @brief Disables the WakeUp PINx functionality.
* @param WakeUpPinx: Specifies the Power Wake-Up pin to disable.
* This parameter can be one of the following values:
* @arg PWR_WAKEUP_PIN1
* @arg PWR_WAKEUP_PIN2
* @retval None
*/
void HAL_PWR_DisableWakeUpPin(uint32_t WakeUpPinx)
{
/* Check the parameter */
assert_param(IS_PWR_WAKEUP_PIN(WakeUpPinx));
/* Disable the EWUPx pin */
PWR->CSR &= ~WakeUpPinx;
}
/**
* @brief Enters Sleep mode.
* @note In Sleep mode, all I/O pins keep the same state as in Run mode.
* @param Regulator: Specifies the regulator state in SLEEP mode.
* This parameter can be one of the following values:
* @arg PWR_MAINREGULATOR_ON: SLEEP mode with regulator ON
* @arg PWR_LOWPOWERREGULATOR_ON: SLEEP mode with low power regulator ON
* @param SLEEPEntry: Specifies if SLEEP mode is entered with WFI or WFE instruction.
* When WFI entry is used, tick interrupt have to be disabled if not desired as
* the interrupt wake up source.
* This parameter can be one of the following values:
* @arg PWR_SLEEPENTRY_WFI: enter SLEEP mode with WFI instruction
* @arg PWR_SLEEPENTRY_WFE: enter SLEEP mode with WFE instruction
* @retval None
*/
void HAL_PWR_EnterSLEEPMode(uint32_t Regulator, uint8_t SLEEPEntry)
{
uint32_t tmpreg = 0;
/* Check the parameters */
assert_param(IS_PWR_REGULATOR(Regulator));
assert_param(IS_PWR_SLEEP_ENTRY(SLEEPEntry));
/* Select the regulator state in Sleep mode ---------------------------------*/
tmpreg = PWR->CR;
/* Clear PDDS and LPDS bits */
tmpreg &= (uint32_t)~(PWR_CR_PDDS | PWR_CR_LPSDSR);
/* Set LPSDSR bit according to PWR_Regulator value */
tmpreg |= Regulator;
/* Store the new value */
PWR->CR = tmpreg;
/* Clear SLEEPDEEP bit of Cortex System Control Register */
SCB->SCR &= (uint32_t)~((uint32_t)SCB_SCR_SLEEPDEEP_Msk);
/* Select SLEEP mode entry -------------------------------------------------*/
if(SLEEPEntry == PWR_SLEEPENTRY_WFI)
{
/* Request Wait For Interrupt */
__WFI();
}
else
{
/* Request Wait For Event */
__SEV();
__WFE();
__WFE();
}
}
/**
* @brief Enters Stop mode.
* @note In Stop mode, all I/O pins keep the same state as in Run mode.
* @note When exiting Stop mode by issuing an interrupt or a wakeup event,
* MSI or HSI16 RCoscillator is selected as system clock depending
* the bit STOPWUCK in the RCC_CFGR register.
* @note When the voltage regulator operates in low power mode, an additional
* startup delay is incurred when waking up from Stop mode.
* By keeping the internal regulator ON during Stop mode, the consumption
* is higher although the startup time is reduced.
* @param Regulator: Specifies the regulator state in Stop mode.
* This parameter can be one of the following values:
* @arg PWR_MAINREGULATOR_ON: Stop mode with regulator ON
* @arg PWR_LOWPOWERREGULATOR_ON: Stop mode with low power regulator ON
* @param STOPEntry: Specifies if Stop mode in entered with WFI or WFE instruction.
* This parameter can be one of the following values:
* @arg PWR_STOPENTRY_WFI: Enter Stop mode with WFI instruction
* @arg PWR_STOPENTRY_WFE: Enter Stop mode with WFE instruction
* @retval None
*/
void HAL_PWR_EnterSTOPMode(uint32_t Regulator, uint8_t STOPEntry)
{
uint32_t tmpreg = 0;
/* Check the parameters */
assert_param(IS_PWR_REGULATOR(Regulator));
assert_param(IS_PWR_STOP_ENTRY(STOPEntry));
/* Select the regulator state in Stop mode ---------------------------------*/
tmpreg = PWR->CR;
/* Clear PDDS and LPDS bits */
tmpreg &= (uint32_t)~(PWR_CR_PDDS | PWR_CR_LPSDSR);
/* Set LPSDSR bit according to PWR_Regulator value */
tmpreg |= Regulator;
/* Store the new value */
PWR->CR = tmpreg;
/* Set SLEEPDEEP bit of Cortex System Control Register */
SCB->SCR |= SCB_SCR_SLEEPDEEP_Msk;
/* Select Stop mode entry --------------------------------------------------*/
if(STOPEntry == PWR_STOPENTRY_WFI)
{
/* Request Wait For Interrupt */
__WFI();
}
else
{
/* Request Wait For Event */
__SEV();
__WFE();
__WFE();
}
/* Reset SLEEPDEEP bit of Cortex System Control Register */
SCB->SCR &= (uint32_t)~((uint32_t)SCB_SCR_SLEEPDEEP_Msk);
}
/**
* @brief Enters Standby mode.
* @note In Standby mode, all I/O pins are high impedance except for:
* - Reset pad (still available)
* - RTC_AF1 pin (PC13) if configured for tamper, time-stamp, RTC
* Alarm out, or RTC clock calibration out.
* - RTC_AF2 pin (PC13) if configured for tamper.
* - WKUP pin 1 (PA0) if enabled.
* - WKUP pin 2 (PC13) if enabled.
* @param None
* @retval None
*/
void HAL_PWR_EnterSTANDBYMode(void)
{
/* Select Standby mode */
PWR->CR |= PWR_CR_PDDS;
/* Set SLEEPDEEP bit of Cortex System Control Register */
SCB->SCR |= SCB_SCR_SLEEPDEEP_Msk;
/* This option is used to ensure that store operations are completed */
#if defined ( __CC_ARM)
__force_stores();
#endif
/* Request Wait For Interrupt */
__WFI();
}
/**
* @brief This function handles the PWR PVD interrupt request.
* @note This API should be called under the PVD_IRQHandler().
* @param None
* @retval None
*/
void HAL_PWR_PVD_IRQHandler(void)
{
/* Check PWR exti flag */
if(__HAL_PVD_EXTI_GET_FLAG(PWR_EXTI_LINE_PVD) != RESET)
{
/* PWR PVD interrupt user callback */
HAL_PWR_PVDCallback();
/* Clear PWR Exti pending bit */
__HAL_PVD_EXTI_CLEAR_FLAG(PWR_EXTI_LINE_PVD);
}
}
/**
* @brief PWR PVD interrupt callback
* @param None
* @retval None
*/
__weak void HAL_PWR_PVDCallback(void)
{
/* NOTE : This function Should not be modified, when the callback is needed,
the HAL_PWR_PVDCallback could be implemented in the user file
*/
}
/**
* @}
*/
/**
* @}
*/
#endif /* HAL_PWR_MODULE_ENABLED */
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,334 @@
/**
******************************************************************************
* @file stm32l0xx_hal_pwr.h
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief Header file of PWR HAL module.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32L0xx_HAL_PWR_H
#define __STM32L0xx_HAL_PWR_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal_def.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @addtogroup PWR
* @{
*/
/* Exported types ------------------------------------------------------------*/
/**
* @brief PWR PVD configuration structure definition
*/
typedef struct
{
uint32_t PVDLevel; /*!< PVDLevel: Specifies the PVD detection level.
This parameter can be a value of @ref PWR_PVD_detection_level */
uint32_t Mode; /*!< Mode: Specifies the operating mode for the selected pins.
This parameter can be a value of @ref PWR_PVD_Mode */
}PWR_PVDTypeDef;
/* Exported constants --------------------------------------------------------*/
/** @defgroup PWR_Exported_Constants
* @{
*/
/** @defgroup PWR_WakeUp_Pins
* @{
*/
#define PWR_WAKEUP_PIN1 PWR_CSR_EWUP1
#define PWR_WAKEUP_PIN2 PWR_CSR_EWUP2
#define IS_PWR_WAKEUP_PIN(PIN) (((PIN) == PWR_WAKEUP_PIN1) || \
((PIN) == PWR_WAKEUP_PIN2))
/**
* @}
*/
/** @defgroup PWR_PVD_detection_level
* @{
*/
#define PWR_PVDLEVEL_0 PWR_CR_PLS_LEV0
#define PWR_PVDLEVEL_1 PWR_CR_PLS_LEV1
#define PWR_PVDLEVEL_2 PWR_CR_PLS_LEV2
#define PWR_PVDLEVEL_3 PWR_CR_PLS_LEV3
#define PWR_PVDLEVEL_4 PWR_CR_PLS_LEV4
#define PWR_PVDLEVEL_5 PWR_CR_PLS_LEV5
#define PWR_PVDLEVEL_6 PWR_CR_PLS_LEV6
#define PWR_PVDLEVEL_7 PWR_CR_PLS_LEV7 /* External input analog voltage
(Compare internally to VREFINT) */
#define IS_PWR_PVD_LEVEL(LEVEL) (((LEVEL) == PWR_PVDLEVEL_0) || ((LEVEL) == PWR_PVDLEVEL_1)|| \
((LEVEL) == PWR_PVDLEVEL_2) || ((LEVEL) == PWR_PVDLEVEL_3)|| \
((LEVEL) == PWR_PVDLEVEL_4) || ((LEVEL) == PWR_PVDLEVEL_5)|| \
((LEVEL) == PWR_PVDLEVEL_6) || ((LEVEL) == PWR_PVDLEVEL_7))
/**
* @}
*/
/** @defgroup PWR_PVD_Mode
* @{
*/
#define PWR_MODE_EVT ((uint32_t)0x00000000) /*!< No Interrupt */
#define PWR_MODE_IT_RISING ((uint32_t)0x00000001) /*!< External Interrupt Mode with Rising edge trigger detection */
#define PWR_MODE_IT_FALLING ((uint32_t)0x00000002) /*!< External Interrupt Mode with Falling edge trigger detection */
#define PWR_MODE_IT_RISING_FALLING ((uint32_t)0x00000003) /*!< External Interrupt Mode with Rising/Falling edge trigger detection */
#define IS_PWR_PVD_MODE(MODE) (((MODE) == PWR_MODE_EVT) || ((MODE) == PWR_MODE_IT_RISING)|| \
((MODE) == PWR_MODE_IT_FALLING) || ((MODE) == PWR_MODE_IT_RISING_FALLING))
/**
* @}
*/
/** @defgroup PWR_Regulator_state_in_SLEEP_STOP_mode
* @{
*/
#define PWR_MAINREGULATOR_ON ((uint32_t)0x00000000)
#define PWR_LOWPOWERREGULATOR_ON PWR_CR_LPSDSR
#define IS_PWR_REGULATOR(REGULATOR) (((REGULATOR) == PWR_MAINREGULATOR_ON) || \
((REGULATOR) == PWR_LOWPOWERREGULATOR_ON))
/**
* @}
*/
/** @defgroup PWR_SLEEP_mode_entry
* @{
*/
#define PWR_SLEEPENTRY_WFI ((uint8_t)0x01)
#define PWR_SLEEPENTRY_WFE ((uint8_t)0x02)
#define IS_PWR_SLEEP_ENTRY(ENTRY) (((ENTRY) == PWR_SLEEPENTRY_WFI) || ((ENTRY) == PWR_SLEEPENTRY_WFE))
/**
* @}
*/
/** @defgroup PWR_STOP_mode_entry
* @{
*/
#define PWR_STOPENTRY_WFI ((uint8_t)0x01)
#define PWR_STOPENTRY_WFE ((uint8_t)0x02)
#define IS_PWR_STOP_ENTRY(ENTRY) (((ENTRY) == PWR_STOPENTRY_WFI) || ((ENTRY) == PWR_STOPENTRY_WFE) )
/**
* @}
*/
/** @defgroup PWR_Regulator_Voltage_Scale
* @{
*/
#define PWR_REGULATOR_VOLTAGE_SCALE1 PWR_CR_VOS_0
#define PWR_REGULATOR_VOLTAGE_SCALE2 PWR_CR_VOS_1
#define PWR_REGULATOR_VOLTAGE_SCALE3 PWR_CR_VOS
#define IS_PWR_VOLTAGE_SCALING_RANGE(RANGE) (((RANGE) == PWR_REGULATOR_VOLTAGE_SCALE1) || \
((RANGE) == PWR_REGULATOR_VOLTAGE_SCALE2) || \
((RANGE) == PWR_REGULATOR_VOLTAGE_SCALE3))
/**
* @}
*/
/** @defgroup PWR_Flag
* @{
*/
#define PWR_FLAG_WU PWR_CSR_WUF
#define PWR_FLAG_SB PWR_CSR_SBF
#define PWR_FLAG_PVDO PWR_CSR_PVDO
#define PWR_FLAG_VREFINTRDY PWR_CSR_VREFINTRDYF
#define PWR_FLAG_VOS PWR_CSR_VOSF
#define PWR_FLAG_REGLP PWR_CSR_REGLPF
/**
* @}
*/
/**
* @}
*/
/* Exported macro ------------------------------------------------------------*/
/** @defgroup PWR_Exported_Macro
* @{
*/
/** @brief macros configure the main internal regulator output voltage.
* @param __REGULATOR__: specifies the regulator output voltage to achieve
* a tradeoff between performance and power consumption when the device does
* not operate at the maximum frequency (refer to the datasheets for more details).
* This parameter can be one of the following values:
* @arg PWR_REGULATOR_VOLTAGE_SCALE1: Regulator voltage output Scale 1 mode,
* System frequency up to 32 MHz.
* @arg PWR_REGULATOR_VOLTAGE_SCALE2: Regulator voltage output Scale 2 mode,
* System frequency up to 16 MHz.
* @arg PWR_REGULATOR_VOLTAGE_SCALE3: Regulator voltage output Scale 3 mode,
* System frequency up to 4.2 MHz
* @retval None
*/
#define __HAL_PWR_VOLTAGESCALING_CONFIG(__REGULATOR__) (MODIFY_REG(PWR->CR, PWR_CR_VOS, (__REGULATOR__)))
/** @brief Check PWR flag is set or not.
* @param __FLAG__: specifies the flag to check.
* This parameter can be one of the following values:
* @arg PWR_FLAG_WU: Wake Up flag. This flag indicates that a wakeup event
* was received from the WKUP pin or from the RTC alarm (Alarm B),
* RTC Tamper event, RTC TimeStamp event or RTC Wakeup.
* An additional wakeup event is detected if the WKUP pin is enabled
* (by setting the EWUP bit) when the WKUP pin level is already high.
* @arg PWR_FLAG_SB: StandBy flag. This flag indicates that the system was
* resumed from StandBy mode.
* @arg PWR_FLAG_PVDO: PVD Output. This flag is valid only if PVD is enabled
* by the HAL_PWR_EnablePVD() function. The PVD is stopped by Standby mode
* For this reason, this bit is equal to 0 after Standby or reset
* until the PVDE bit is set.
* @arg PWR_FLAG_VREFINTRDY: Internal voltage reference (VREFINT) ready flag.
* This bit indicates the state of the internal voltage reference, VREFINT.
* @arg PWR_FLAG_VOS: Voltage Scaling select flag. A delay is required for
* the internal regulator to be ready after the voltage range is changed.
* The VOSF bit indicates that the regulator has reached the voltage level
* defined with bits VOS of PWR_CR register.
* @arg PWR_FLAG_REGLP: Regulator LP flag. When the MCU exits from Low power run
* mode, this bit stays at 1 until the regulator is ready in main mode.
* A polling on this bit is recommended to wait for the regulator main mode.
* This bit is reset by hardware when the regulator is ready.
* @retval The new state of __FLAG__ (TRUE or FALSE).
*/
#define __HAL_PWR_GET_FLAG(__FLAG__) ((PWR->CSR & (__FLAG__)) == (__FLAG__))
/** @brief Clear the PWR's pending flags.
* @param __FLAG__: specifies the flag to clear.
* This parameter can be one of the following values:
* @arg PWR_FLAG_WU: Wake Up flag
* @arg PWR_FLAG_SB: StandBy flag
*/
#define __HAL_PWR_CLEAR_FLAG(__FLAG__) (PWR->CR |= (__FLAG__) << 2)
#define PWR_EXTI_LINE_PVD ((uint32_t)0x00010000) /*!< External interrupt line 16 Connected to the PVD EXTI Line */
/**
* @brief Enable the PVD Exti Line.
* @param __EXTILINE__: specifies the PVD Exti sources to be enabled.
* This parameter can be:
* @arg PWR_EXTI_LINE_PVD
* @retval None.
*/
#define __HAL_PVD_EXTI_ENABLE_IT(__EXTILINE__) (EXTI->IMR |= (__EXTILINE__))
/**
* @brief Disable the PVD EXTI Line.
* @param __EXTILINE__: specifies the PVD EXTI sources to be disabled.
* This parameter can be:
* @arg PWR_EXTI_LINE_PVD
* @retval None.
*/
#define __HAL_PVD_EXTI_DISABLE_IT(__EXTILINE__) (EXTI->IMR &= ~(__EXTILINE__))
/**
* @brief Generates a Software interrupt on selected EXTI line.
* @param __EXTILINE__: specifies the PVD EXTI sources to be disabled.
* This parameter can be:
* @arg PWR_EXTI_LINE_PVD
* @retval None
*/
#define __HAL_PVD_EXTI_GENERATE_SWIT(__EXTI_LINE__) (EXTI->SWIER |= (__EXTI_LINE__))
/**
* @brief checks whether the specified PVD Exti interrupt flag is set or not.
* @param __EXTILINE__: specifies the PVD Exti sources to be cleared.
* This parameter can be:
* @arg PWR_EXTI_LINE_PVD
* @retval EXTI PVD Line Status.
*/
#define __HAL_PVD_EXTI_GET_FLAG(__EXTILINE__) (EXTI->PR & (__EXTILINE__))
/**
* @brief Clear the PVD Exti flag.
* @param __EXTILINE__: specifies the PVD Exti sources to be cleared.
* This parameter can be:
* @arg PWR_EXTI_LINE_PVD
* @retval None.
*/
#define __HAL_PVD_EXTI_CLEAR_FLAG(__EXTILINE__) (EXTI->PR = (__EXTILINE__))
/**
* @}
*/
/* Include PWR HAL Extension module */
#include "stm32l0xx_hal_pwr_ex.h"
/* Exported functions --------------------------------------------------------*/
/* Initialization and de-initialization functions *******************************/
void HAL_PWR_DeInit(void);
void HAL_PWR_EnableBkUpAccess(void);
void HAL_PWR_DisableBkUpAccess(void);
/* Peripheral Control functions ************************************************/
void HAL_PWR_PVDConfig(PWR_PVDTypeDef *sConfigPVD);
void HAL_PWR_EnablePVD(void);
void HAL_PWR_DisablePVD(void);
/* WakeUp pins configuration functions ****************************************/
void HAL_PWR_EnableWakeUpPin(uint32_t WakeUpPinx);
void HAL_PWR_DisableWakeUpPin(uint32_t WakeUpPinx);
/* Low Power modes configuration functions ************************************/
void HAL_PWR_EnterSTOPMode(uint32_t Regulator, uint8_t STOPEntry);
void HAL_PWR_EnterSLEEPMode(uint32_t Regulator, uint8_t SLEEPEntry);
void HAL_PWR_EnterSTANDBYMode(void);
void HAL_PWR_PVD_IRQHandler(void);
void HAL_PWR_PVDCallback(void);
/**
* @}
*/
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif /* __STM32L0xx_HAL_PWR_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,174 @@
/**
******************************************************************************
* @file stm32l0xx_hal_pwr_ex.c
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief Extended PWR HAL module driver.
* This file provides firmware functions to manage the following
* functionalities of the Power Controller (PWR) peripheral:
* + Extended Initialization and de-initialization functions
* + Extended Peripheral Control functions
*
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @defgroup PWREx
* @brief PWR HAL module driver
* @{
*/
#ifdef HAL_PWR_MODULE_ENABLED
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/** @defgroup PWREx_Private_Functions
* @{
*/
/** @defgroup PWREx_Group1 Peripheral Extended features functions
* @brief Low Power modes configuration functions
*
@verbatim
===============================================================================
##### Peripheral extended features functions #####
===============================================================================
@endverbatim
* @{
*/
/**
* @brief Enables the Fast WakeUp from Ultra Low Power mode.
* @note This bit works in conjunction with ULP bit.
* Means, when ULP = 1 and FWU = 1 :VREFINT startup time is ignored when
* exiting from low power mode.
* @param None
* @retval None
*/
void HAL_PWREx_EnableFastWakeUp(void)
{
/* Enable the fast wake up */
PWR->CR |= PWR_CR_FWU;
}
/**
* @brief Disables the Fast WakeUp from Ultra Low Power mode.
* @param None
* @retval None
*/
void HAL_PWREx_DisableFastWakeUp(void)
{
/* Disable the fast wake up */
PWR->CR &= (uint32_t)~((uint32_t)PWR_CR_FWU);
}
/**
* @brief Enables the Ultra Low Power mode
* @param None
* @retval None
*/
void HAL_PWREx_EnableUltraLowPower(void)
{
/* Enable the Ultra Low Power mode */
PWR->CR |= PWR_CR_ULP;
}
/**
* @brief Disables the Ultra Low Power mode
* @param None
* @retval None
*/
void HAL_PWREx_DisableUltraLowPower(void)
{
/* Disable the Ultra Low Power mode */
PWR->CR &= (uint32_t)~((uint32_t)PWR_CR_ULP);
}
/**
* @brief Enters the Low Power Run mode.
* @note Low power run mode can only be entered when VCORE is in range 2.
* In addition, the dynamic voltage scaling must not be used when Low
* power run mode is selected. Only Stop and Sleep modes with regulator
* configured in Low power mode is allowed when Low power run mode is
* selected.
* @note In Low power run mode, all I/O pins keep the same state as in Run mode.
* @param None
* @retval None
*/
void HAL_PWREx_EnableLowPowerRunMode(void)
{
/* Enters the Low Power Run mode */
PWR->CR |= PWR_CR_LPSDSR;
PWR->CR |= PWR_CR_LPRUN;
}
/**
* @brief Exits the Low Power Run mode.
* @param None
* @retval None
*/
void HAL_PWREx_DisableLowPowerRunMode(void)
{
/* Exits the Low Power Run mode */
PWR->CR &= (uint32_t)~((uint32_t)PWR_CR_LPRUN);
PWR->CR &= (uint32_t)~((uint32_t)PWR_CR_LPSDSR);
}
/**
* @}
*/
/**
* @}
*/
#endif /* HAL_PWR_MODULE_ENABLED */
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,102 @@
/**
******************************************************************************
* @file stm32l0xx_hal_pwr_ex.h
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief Header file of PWR HAL Extension module.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32L0xx_HAL_PWR_EX_H
#define __STM32L0xx_HAL_PWR_EX_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal_def.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @addtogroup PWREx
* @{
*/
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
/* Exported macro ------------------------------------------------------------*/
/** @defgroup PWREx_Exported macro
* @{
*/
/** @brief Macros to enable or disable the Deep-sleep mode with Flash memory kept off.
* @note When entering low power mode (stop or standby only), if DS_EE_KOFF and RUN_PD of
* FLASH_ACR register are both set , the Flash memory will not be woken up
* when exiting from deep-sleep mode.
*/
#define __HAL_PWR_FLASHWAKEUP_ENABLE() CLEAR_BIT(PWR->CR, PWR_CR_DSEEKOFF)
#define __HAL_PWR_FLASHWAKEUP_DISABLE() SET_BIT(PWR->CR, PWR_CR_DSEEKOFF)
/**
* @}
*/
/* Exported functions --------------------------------------------------------*/
/* Peripheral Control methods ************************************************/
void HAL_PWREx_EnableFastWakeUp(void);
void HAL_PWREx_DisableFastWakeUp(void);
void HAL_PWREx_EnableUltraLowPower(void);
void HAL_PWREx_DisableUltraLowPower(void);
void HAL_PWREx_EnableLowPowerRunMode(void);
void HAL_PWREx_DisableLowPowerRunMode(void);
/**
* @}
*/
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif /* __STM32L0xx_HAL_PWR_EX_H */
/************************ (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,535 @@
/**
******************************************************************************
* @file stm32l0xx_hal_rcc_ex.c
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief Extended RCC HAL module driver.
*
* This file provides firmware functions to manage the following
* functionalities RCC extension peripheral:
* + Extended Peripheral Control functions
*
@verbatim
==============================================================================
##### RCC specific features #####
==============================================================================
For CRS, RCC Extension HAL driver can be used as follows:
(#) In System clock configuration, HSI48 need to be enabled
(#] Enable CRS clock in IP MSP init which will use CRS functions
(#) Call CRS functions like this
(##) Prepare synchronization configuration necessary for HSI48 calibration
(+++) Default values can be set for frequency Error Measurement (reload and error limit)
and also HSI48 oscillator smooth trimming.
(+++) Macro __HAL_RCC_CRS_CALCULATE_RELOADVALUE can be also used to calculate
directly reload value with target and synchronization frequencies values
(##) Call function HAL_RCCEx_CRSConfig which
(+++) Reset CRS registers to their default values.
(+++) Configure CRS registers with synchronization configuration
(+++) Enable automatic calibration and frequency error counter feature
(##) A polling function is provided to wait for complete Synchronization
(+++) Call function 'HAL_RCCEx_CRSWaitSynchronization()'
(+++) According to CRS status, user can decide to adjust again the calibration or continue
application if synchronization is OK
(#) User can retrieve information related to synchronization in calling function
HAL_RCCEx_CRSGetSynchronizationInfo()
(#) Regarding synchronization status and synchronization information, user can try a new calibration
in changing synchronization configuration and call again HAL_RCCEx_CRSConfig.
Note: When the SYNC event is detected during the downcounting phase (before reaching the zero value),
it means that the actual frequency is lower than the target (and so, that the TRIM value should be
incremented), while when it is detected during the upcounting phase it means that the actual frequency
is higher (and that the TRIM value should be decremented).
(#) To use IT mode, user needs to handle it in calling different macros available to do it
(__HAL_RCC_CRS_XXX_IT). Interruptions will go through RCC Handler (RCC_IRQn/RCC_CRS_IRQHandler)
(+++) Call function HAL_RCCEx_CRSConfig()
(+++) Enable RCC_IRQn (thnaks to NVIC functions)
(+++) Enable CRS IT (__HAL_RCC_CRS_ENABLE_IT)
[+++) Implement CRS status management in RCC_CRS_IRQHandler
(#) To force a SYNC EVENT, user can use function 'HAL_RCCEx_CRSSoftwareSynchronizationGenerate()'. Function can be
called before calling HAL_RCCEx_CRSConfig (for instance in Systick handler)
@endverbatim
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @defgroup RCCEx
* @brief RCC Extension HAL module driver
* @{
*/
#ifdef HAL_RCC_MODULE_ENABLED
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Bit position in register */
#define CRS_CFGR_FELIM_BITNUMBER 16
#define CRS_CR_TRIM_BITNUMBER 8
#define CRS_ISR_FECAP_BITNUMBER 16
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/** @defgroup RCCEx_Private_Functions
* @{
*/
/** @defgroup RCCEx_Group1 Extended Peripheral Control functions
* @brief Extended Peripheral Control functions
*
@verbatim
===============================================================================
##### Extended Peripheral Control functions #####
===============================================================================
[..]
This subsection provides a set of functions allowing to control the RCC Clocks
frequencies.
@endverbatim
* @{
*/
/**
* @brief Initializes the RCC extended peripherals clocks according to the specified parameters in the
* RCC_PeriphCLKInitTypeDef.
* @param PeriphClkInit: pointer to an RCC_PeriphCLKInitTypeDef structure that
* contains the configuration information for the Extended Peripherals clocks(USART1,USART2, LPUART1,
* I2C1, RTC, USB/RNG and LPTIM1 clocks).
* @retval HAL status
*/
HAL_StatusTypeDef HAL_RCCEx_PeriphCLKConfig(RCC_PeriphCLKInitTypeDef *PeriphClkInit)
{
uint32_t tickstart = 0;
uint32_t tmpreg = 0;
/* Check the parameters */
assert_param(IS_RCC_PERIPHCLK(PeriphClkInit->PeriphClockSelection));
/*------------------------------- USART1 Configuration ------------------------*/
if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_USART1) == RCC_PERIPHCLK_USART1)
{
/* Check the parameters */
assert_param(IS_RCC_USART1CLKSOURCE(PeriphClkInit->Usart1ClockSelection));
/* Configure the USART1 clock source */
__HAL_RCC_USART1_CONFIG(PeriphClkInit->Usart1ClockSelection);
}
/*----------------------------- USART2 Configuration --------------------------*/
if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_USART2) == RCC_PERIPHCLK_USART2)
{
/* Check the parameters */
assert_param(IS_RCC_USART2CLKSOURCE(PeriphClkInit->Usart2ClockSelection));
/* Configure the USART2 clock source */
__HAL_RCC_USART2_CONFIG(PeriphClkInit->Usart2ClockSelection);
}
/*------------------------------ LPUART1 Configuration ------------------------*/
if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_LPUART1) == RCC_PERIPHCLK_LPUART1)
{
/* Check the parameters */
assert_param(IS_RCC_LPUART1CLKSOURCE(PeriphClkInit->Lpuart1ClockSelection));
/* Configure the LPUAR1 clock source */
__HAL_RCC_LPUART1_CONFIG(PeriphClkInit->Lpuart1ClockSelection);
}
/*------------------------------ I2C1 Configuration ------------------------*/
if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2C1) == RCC_PERIPHCLK_I2C1)
{
/* Check the parameters */
assert_param(IS_RCC_I2C1CLKSOURCE(PeriphClkInit->I2c1ClockSelection));
/* Configure the I2C1 clock source */
__HAL_RCC_I2C1_CONFIG(PeriphClkInit->I2c1ClockSelection);
}
/*---------------------------- RTC configuration -------------------------------*/
if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_RTC) == (RCC_PERIPHCLK_RTC))
{
/* Enable Power Clock*/
__PWR_CLK_ENABLE();
/* Enable write access to Backup domain */
PWR->CR |= PWR_CR_DBP;
/* Wait for Backup domain Write protection disable */
tickstart = HAL_GetTick();
while((PWR->CR & PWR_CR_DBP) == RESET)
{
if((HAL_GetTick() - tickstart ) > DBP_TIMEOUT_VALUE)
{
return HAL_TIMEOUT;
}
}
/* Reset the Backup domain only if the RTC Clock source selection is modified */
if((RCC->CSR & RCC_CSR_RTCSEL) != (PeriphClkInit->RTCClockSelection & RCC_CSR_RTCSEL))
{
/* Store the content of CSR register before the reset of Backup Domain */
tmpreg = (RCC->CSR & ~(RCC_CSR_RTCSEL));
/* RTC Clock selection can be changed only if the Backup Domain is reset */
__HAL_RCC_BACKUPRESET_FORCE();
__HAL_RCC_BACKUPRESET_RELEASE();
/* Restore the Content of CSR register */
RCC->CSR = tmpreg;
}
/* If LSE is selected as RTC clock source, wait for LSE reactivation */
if(PeriphClkInit->RTCClockSelection == RCC_RTCCLKSOURCE_LSE)
{
/* Get timeout */
tickstart = HAL_GetTick();
/* Wait till LSE is ready */
while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) == RESET)
{
if((HAL_GetTick() - tickstart ) > LSE_TIMEOUT_VALUE)
{
return HAL_TIMEOUT;
}
}
}
__HAL_RCC_RTC_CONFIG(PeriphClkInit->RTCClockSelection);
}
#if !defined(STM32L051xx) && !defined(STM32L061xx)
/*---------------------------- USB and RNG configuration --------------------*/
if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_USB) == (RCC_PERIPHCLK_USB))
{
assert_param(IS_RCC_USBCLKSOURCE(PeriphClkInit->UsbClockSelection));
__HAL_RCC_USB_CONFIG(PeriphClkInit->UsbClockSelection);
}
#endif /* !(STM32L051xx) && !(STM32L061xx) */
/*---------------------------- LPTIM1 configuration ------------------------*/
if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_LPTIM1) == (RCC_PERIPHCLK_LPTIM1))
{
assert_param(IS_RCC_LPTIMCLK(PeriphClkInit->LptimClockSelection));
__HAL_RCC_LPTIM1_CONFIG(PeriphClkInit->LptimClockSelection);
}
return HAL_OK;
}
/**
* @brief Get the RCC_ClkInitStruct according to the internal
* RCC configuration registers.
* @param PeriphClkInit: pointer to an RCC_PeriphCLKInitTypeDef structure that
* returns the configuration information for the Extended Peripherals clocks(USART1,USART2, LPUART1,
* I2C1, RTC, USB/RNG and LPTIM1 clocks).
* @retval None
*/
void HAL_RCCEx_GetPeriphCLKConfig(RCC_PeriphCLKInitTypeDef *PeriphClkInit)
{
/* Set all possible values for the extended clock type parameter -----------*/
/* Common part first */
#if !defined(STM32L051xx) && !defined(STM32L061xx)
PeriphClkInit->PeriphClockSelection = RCC_PERIPHCLK_USART1 | RCC_PERIPHCLK_USART2 | RCC_PERIPHCLK_LPUART1 | \
RCC_PERIPHCLK_I2C1 | RCC_PERIPHCLK_I2C2 | RCC_PERIPHCLK_RTC | \
RCC_PERIPHCLK_USB | RCC_PERIPHCLK_LPTIM1;
#else
PeriphClkInit->PeriphClockSelection = RCC_PERIPHCLK_USART1 | RCC_PERIPHCLK_USART2 | RCC_PERIPHCLK_LPUART1 | \
RCC_PERIPHCLK_I2C1 | RCC_PERIPHCLK_I2C2 | RCC_PERIPHCLK_RTC | \
RCC_PERIPHCLK_LPTIM1;
#endif /* !(STM32L051xx) && !(STM32L061xx) */
/* Get the USART1 configuration --------------------------------------------*/
PeriphClkInit->Usart1ClockSelection = __HAL_RCC_GET_USART1_SOURCE();
/* Get the USART2 clock source ---------------------------------------------*/
PeriphClkInit->Usart2ClockSelection = __HAL_RCC_GET_USART2_SOURCE();
/* Get the LPUART1 clock source ---------------------------------------------*/
PeriphClkInit->Lpuart1ClockSelection = __HAL_RCC_GET_LPUART1_SOURCE();
/* Get the I2C1 clock source -----------------------------------------------*/
PeriphClkInit->I2c1ClockSelection = __HAL_RCC_GET_I2C1_SOURCE();
/* Get the LPTIM1 clock source -----------------------------------------------*/
PeriphClkInit->LptimClockSelection = __HAL_RCC_GET_LPTIM1_SOURCE();
/* Get the RTC clock source -----------------------------------------------*/
PeriphClkInit->RTCClockSelection = __HAL_RCC_GET_RTC_SOURCE();
#if !defined(STM32L051xx) && !defined(STM32L061xx)
/* Get the USB/RNG clock source -----------------------------------------------*/
PeriphClkInit->UsbClockSelection = __HAL_RCC_GET_USB_SOURCE();
#endif /* !(STM32L051xx) && !(STM32L061xx) */
}
/**
* @brief Enables the LSE Clock Security System.
* @param None
* @retval None
*/
void HAL_RCCEx_EnableLSECSS(void)
{
SET_BIT(RCC->CSR, RCC_CSR_LSECSSON) ;
}
/**
* @brief Disables the LSE Clock Security System.
* @param None
* @retval None
*/
void HAL_RCCEx_DisableLSECSS(void)
{
CLEAR_BIT(RCC->CSR, RCC_CSR_LSECSSON) ;
}
#if !defined(STM32L051xx) && !defined(STM32L061xx)
/**
* @brief Start automatic synchronization using polling mode
* @param pInit Pointer on RCC_CRSInitTypeDef structure
* @retval None
*/
void HAL_RCCEx_CRSConfig(RCC_CRSInitTypeDef *pInit)
{
/* Check the parameters */
assert_param(IS_RCC_CRS_SYNC_DIV(pInit->Prescaler));
assert_param(IS_RCC_CRS_SYNC_SOURCE(pInit->Source));
assert_param(IS_RCC_CRS_SYNC_POLARITY(pInit->Polarity));
assert_param(IS_RCC_CRS_RELOADVALUE(pInit->ReloadValue));
assert_param(IS_RCC_CRS_ERRORLIMIT(pInit->ErrorLimitValue));
assert_param(IS_RCC_CRS_HSI48CALIBRATION(pInit->HSI48CalibrationValue));
/* CONFIGURATION */
/* Before configuration, reset CRS registers to their default values*/
__CRS_FORCE_RESET();
__CRS_RELEASE_RESET();
/* Configure Synchronization input */
/* Clear SYNCDIV[2:0], SYNCSRC[1:0] & SYNCSPOL bits */
CRS->CFGR &= ~(CRS_CFGR_SYNCDIV | CRS_CFGR_SYNCSRC | CRS_CFGR_SYNCPOL);
/* Set the CRS_CFGR_SYNCDIV[2:0] bits according to Prescaler value */
CRS->CFGR |= pInit->Prescaler;
/* Set the SYNCSRC[1:0] bits according to Source value */
CRS->CFGR |= pInit->Source;
/* Set the SYNCSPOL bits according to Polarity value */
CRS->CFGR |= pInit->Polarity;
/* Configure Frequency Error Measurement */
/* Clear RELOAD[15:0] & FELIM[7:0] bits*/
CRS->CFGR &= ~(CRS_CFGR_RELOAD | CRS_CFGR_FELIM);
/* Set the RELOAD[15:0] bits according to ReloadValue value */
CRS->CFGR |= pInit->ReloadValue;
/* Set the FELIM[7:0] bits according to ErrorLimitValue value */
CRS->CFGR |= (pInit->ErrorLimitValue << CRS_CFGR_FELIM_BITNUMBER);
/* Adjust HSI48 oscillator smooth trimming */
/* Clear TRIM[5:0] bits */
CRS->CR &= ~CRS_CR_TRIM;
/* Set the TRIM[5:0] bits according to RCC_CRS_HSI48CalibrationValue value */
CRS->CR |= (pInit->HSI48CalibrationValue << CRS_CR_TRIM_BITNUMBER);
/* START AUTOMATIC SYNCHRONIZATION*/
/* Enable Automatic trimming */
__HAL_RCC_CRS_ENABLE_AUTOMATIC_CALIB();
/* Enable Frequency error counter */
__HAL_RCC_CRS_ENABLE_FREQ_ERROR_COUNTER();
}
/**
* @brief Generate the software synchronization event
* @param None
* @retval None
*/
void HAL_RCCEx_CRSSoftwareSynchronizationGenerate(void)
{
CRS->CR |= CRS_CR_SWSYNC;
}
/**
* @brief Function to return synchronization info
* @param pSynchroInfo Pointer on RCC_CRSSynchroInfoTypeDef structure
* @retval None
*/
void HAL_RCCEx_CRSGetSynchronizationInfo(RCC_CRSSynchroInfoTypeDef *pSynchroInfo)
{
/* Check the parameter */
assert_param(pSynchroInfo != NULL);
/* Get the reload value */
pSynchroInfo->ReloadValue = (uint32_t)(CRS->CFGR & CRS_CFGR_RELOAD);
/* Get HSI48 oscillator smooth trimming */
pSynchroInfo->HSI48CalibrationValue = (uint32_t)((CRS->CR & CRS_CR_TRIM) >> CRS_CR_TRIM_BITNUMBER);
/* Get Frequency error capture */
pSynchroInfo->FreqErrorCapture = (uint32_t)((CRS->ISR & CRS_ISR_FECAP) >> CRS_ISR_FECAP_BITNUMBER);
/* Get Frequency error direction */
pSynchroInfo->FreqErrorDirection = (uint32_t)(CRS->ISR & CRS_ISR_FEDIR);
}
/**
* @brief This function handles CRS Synchronization Timeout.
* @param Timeout: Duration of the timeout
* @note Timeout is based on the maximum time to receive a SYNC event based on synchronization
* frequency.
* @note If Timeout set to HAL_MAX_DELAY, HAL_TIMEOUT will be never returned.
* @retval Combination of Synchronization status
* This parameter can be a combination of the following values:
* @arg RCC_CRS_TIMEOUT
* @arg RCC_CRS_SYNCOK
* @arg RCC_CRS_SYNCWARM
* @arg RCC_CRS_SYNCERR
* @arg RCC_CRS_SYNCMISS
* @arg RCC_CRS_TRIMOV
*/
RCC_CRSStatusTypeDef HAL_RCCEx_CRSWaitSynchronization(uint32_t Timeout)
{
RCC_CRSStatusTypeDef crsstatus = RCC_CRS_NONE;
uint32_t tickstart = 0;
/* Get timeout */
tickstart = HAL_GetTick();
/* Check that if one of CRS flags have been set */
while(RCC_CRS_NONE == crsstatus)
{
if(Timeout != HAL_MAX_DELAY)
{
if((Timeout == 0)||((HAL_GetTick() - tickstart ) > Timeout))
{
crsstatus = RCC_CRS_TIMEOUT;
}
}
/* Check CRS SYNCOK flag */
if(__HAL_RCC_CRS_GET_FLAG(RCC_CRS_FLAG_SYNCOK))
{
/* CRS SYNC event OK */
crsstatus |= RCC_CRS_SYNCOK;
/* Clear CRS SYNC event OK bit */
__HAL_RCC_CRS_CLEAR_FLAG(RCC_CRS_FLAG_SYNCOK);
}
/* Check CRS SYNCWARN flag */
if(__HAL_RCC_CRS_GET_FLAG(RCC_CRS_FLAG_SYNCWARN))
{
/* CRS SYNC warning */
crsstatus |= RCC_CRS_SYNCWARM;
/* Clear CRS SYNCWARN bit */
__HAL_RCC_CRS_CLEAR_FLAG(RCC_CRS_FLAG_SYNCWARN);
}
/* Check CRS TRIM overflow flag */
if(__HAL_RCC_CRS_GET_FLAG(RCC_CRS_FLAG_TRIMOVF))
{
/* CRS SYNC Error */
crsstatus |= RCC_CRS_TRIMOV;
/* Clear CRS Error bit */
__HAL_RCC_CRS_CLEAR_FLAG(RCC_CRS_FLAG_TRIMOVF);
}
/* Check CRS Error flag */
if(__HAL_RCC_CRS_GET_FLAG(RCC_CRS_FLAG_SYNCERR))
{
/* CRS SYNC Error */
crsstatus |= RCC_CRS_SYNCERR;
/* Clear CRS Error bit */
__HAL_RCC_CRS_CLEAR_FLAG(RCC_CRS_FLAG_SYNCERR);
}
/* Check CRS SYNC Missed flag */
if(__HAL_RCC_CRS_GET_FLAG(RCC_CRS_FLAG_SYNCMISS))
{
/* CRS SYNC Missed */
crsstatus |= RCC_CRS_SYNCMISS;
/* Clear CRS SYNC Missed bit */
__HAL_RCC_CRS_CLEAR_FLAG(RCC_CRS_FLAG_SYNCMISS);
}
/* Check CRS Expected SYNC flag */
if(__HAL_RCC_CRS_GET_FLAG(RCC_CRS_FLAG_ESYNC))
{
/* frequency error counter reached a zero value */
__HAL_RCC_CRS_CLEAR_FLAG(RCC_CRS_FLAG_ESYNC);
}
}
return crsstatus;
}
#endif /* !(STM32L051xx) && !(STM32L061xx) */
/**
* @}
*/
/**
* @}
*/
#endif /* HAL_RCC_MODULE_ENABLED */
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,429 @@
/**
******************************************************************************
* @file stm32l0xx_hal_rng.c
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief RNG HAL module driver.
* This file provides firmware functions to manage the following
* functionalities of the Random Number Generator (RNG) peripheral:
* + Initialization/de-initialization functions
* + Peripheral Control functions
* + Peripheral State functions
*
@verbatim
==============================================================================
##### How to use this driver #####
==============================================================================
[..]
The RNG HAL driver can be used as follows:
(#) Enable the RNG controller clock using __RNG_CLK_ENABLE() macro.
(#) Activate the RNG peripheral using __HAL_RNG_ENABLE() macro.
(#) Wait until the 32 bit Random Number Generator contains a valid
random data using (polling/interrupt) mode.
(#) Get the 32 bit random number using HAL_RNG_GetRandomNumber() function.
@endverbatim
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @defgroup RNG
* @brief RNG HAL module driver.
* @{
*/
#ifdef HAL_RNG_MODULE_ENABLED
#if !defined (STM32L051xx) && !defined (STM32L061xx)
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
#define RNG_TIMEOUT_VALUE 1000
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/** @defgroup RNG_Private_Functions
* @{
*/
/** @defgroup RNG_Group1 Initialization and de-initialization functions
* @brief Initialization and Configuration functions.
*
@verbatim
===============================================================================
##### Initialization and de-initialization functions #####
===============================================================================
[..] This section provides functions allowing to:
(+) Initialize the RNG according to the specified parameters
in the RNG_InitTypeDef and create the associated handle
(+) DeInitialize the RNG peripheral
(+) Initialize the RNG MSP
(+) DeInitialize RNG MSP
@endverbatim
* @{
*/
/**
* @brief Initializes the RNG according to the specified
* parameters in the RNG_InitTypeDef and creates the associated handle.
* @param hrng: pointer to a RNG_HandleTypeDef structure that contains
* the configuration information for RNG.
* @retval HAL status
*/
HAL_StatusTypeDef HAL_RNG_Init(RNG_HandleTypeDef *hrng)
{
/* Check the RNG handle allocation */
if(hrng == NULL)
{
return HAL_ERROR;
}
if(hrng->State == HAL_RNG_STATE_RESET)
{
/* Init the low level hardware */
HAL_RNG_MspInit(hrng);
}
/* Change RNG peripheral state */
hrng->State = HAL_RNG_STATE_BUSY;
/* Enable the RNG Peripheral */
__HAL_RNG_ENABLE(hrng);
/* Initialize the RNG state */
hrng->State = HAL_RNG_STATE_READY;
/* Return function status */
return HAL_OK;
}
/**
* @brief DeInitializes the RNG peripheral.
* @param hrng: pointer to a RNG_HandleTypeDef structure that contains
* the configuration information for RNG.
* @retval HAL status
*/
HAL_StatusTypeDef HAL_RNG_DeInit(RNG_HandleTypeDef *hrng)
{
/* Check the RNG peripheral state */
if(hrng->State == HAL_RNG_STATE_BUSY)
{
return HAL_BUSY;
}
/* Update the RNG state */
hrng->State = HAL_RNG_STATE_BUSY;
/* Disable the RNG Peripheral */
__HAL_RNG_DISABLE(hrng);
/* Set the RNG registers to their reset values */
hrng->Instance->CR &= 0xFFFFFFF3;
hrng->Instance->SR &= 0xFFFFFF98;
hrng->Instance->DR &= 0x0;
/* DeInit the low level hardware */
HAL_RNG_MspDeInit(hrng);
/* Update the RNG state */
hrng->State = HAL_RNG_STATE_RESET;
/* Release Lock */
__HAL_UNLOCK(hrng);
/* Return the function status */
return HAL_OK;
}
/**
* @brief Initializes the RNG MSP.
* @param hrng: pointer to a RNG_HandleTypeDef structure that contains
* the configuration information for RNG.
* @retval None
*/
__weak void HAL_RNG_MspInit(RNG_HandleTypeDef *hrng)
{
/* NOTE : This function Should not be modified, when the callback is needed,
the HAL_RNG_MspInit could be implemented in the user file
*/
}
/**
* @brief DeInitializes the RNG MSP.
* @param hrng: pointer to a RNG_HandleTypeDef structure that contains
* the configuration information for RNG.
* @retval None
*/
__weak void HAL_RNG_MspDeInit(RNG_HandleTypeDef *hrng)
{
/* NOTE : This function Should not be modified, when the callback is needed,
the HAL_RNG_MspDeInit could be implemented in the user file
*/
}
/**
* @}
*/
/** @defgroup RNG_Group2 Peripheral Control functions
* @brief management functions.
*
@verbatim
===============================================================================
##### Peripheral Control functions #####
===============================================================================
[..] This section provides functions allowing to:
(+) Get the 32 bit Random number
(+) Get the 32 bit Random number with interrupt enabled
(+) Handle RNG interrupt request
@endverbatim
* @{
*/
/**
* @brief Returns a 32-bit random number.
* @note Each time the random number data is read the RNG_FLAG_DRDY flag
* is automatically cleared.
* @param hrng: pointer to a RNG_HandleTypeDef structure that contains
* the configuration information for RNG.
* @retval 32-bit random number
*/
uint32_t HAL_RNG_GetRandomNumber(RNG_HandleTypeDef *hrng)
{
uint32_t random32bit = 0;
uint32_t tickstart = 0;
/* Process Locked */
__HAL_LOCK(hrng);
/* Get timeout */
tickstart = HAL_GetTick();
/* Check if data register contains valid random data */
while(__HAL_RNG_GET_FLAG(hrng, RNG_FLAG_DRDY) == RESET)
{
if((HAL_GetTick() - tickstart ) > RNG_TIMEOUT_VALUE)
{
return HAL_TIMEOUT;
}
}
/* Get a 32bit Random number */
random32bit = hrng->Instance->DR;
/* Process Unlocked */
__HAL_UNLOCK(hrng);
/* Return the 32 bit random number */
return random32bit;
}
/**
* @brief Returns a 32-bit random number with interrupt enabled.
* @param hrng: pointer to a RNG_HandleTypeDef structure that contains
* the configuration information for RNG.
* @retval 32-bit random number
*/
uint32_t HAL_RNG_GetRandomNumber_IT(RNG_HandleTypeDef *hrng)
{
uint32_t random32bit = 0;
/* Process Locked */
__HAL_LOCK(hrng);
/* Change RNG peripheral state */
hrng->State = HAL_RNG_STATE_BUSY;
/* Get a 32bit Random number */
random32bit = hrng->Instance->DR;
/* Enable the RNG Interrupts: Data Ready, Clock error, Seed error */
__HAL_RNG_ENABLE_IT(hrng);
/* Return the 32 bit random number */
return random32bit;
}
/**
* @brief Handles RNG interrupt request.
* @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 has
* to check that the clock controller is correctly configured to provide
* the RNG clock and clear the CEIS bit using __HAL_RNG_CLEAR_FLAG().
* The clock error has no impact on the previously generated
* random numbers, and the RNG_DR register contents can be used.
* @note In the case of a seed error, the generation of random numbers is
* interrupted 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 __HAL_RNG_CLEAR_FLAG(), then disable and enable
* the RNG peripheral to reinitialize and restart the RNG.
* @param hrng: pointer to a RNG_HandleTypeDef structure that contains
* the configuration information for RNG.
* @retval None
*/
void HAL_RNG_IRQHandler(RNG_HandleTypeDef *hrng)
{
/* RNG clock error interrupt occurred */
if(__HAL_RNG_GET_FLAG(hrng, RNG_IT_CEI) != RESET)
{
HAL_RNG_ErrorCallback(hrng);
/* Clear the clock error flag */
__HAL_RNG_CLEAR_FLAG(hrng, RNG_IT_CEI);
/* Change RNG peripheral state */
hrng->State = HAL_RNG_STATE_ERROR;
/* Process Unlocked */
__HAL_UNLOCK(hrng);
}
/* RNG seed error interrupt occurred */
if(__HAL_RNG_GET_FLAG(hrng, RNG_IT_SEI) != RESET)
{
HAL_RNG_ErrorCallback(hrng);
/* Clear the seed error flag */
__HAL_RNG_CLEAR_FLAG(hrng, RNG_IT_SEI);
/* Change RNG peripheral state */
hrng->State = HAL_RNG_STATE_ERROR;
/* Process Unlocked */
__HAL_UNLOCK(hrng);
}
/* Check RNG data ready flag */
if(__HAL_RNG_GET_FLAG(hrng, RNG_FLAG_DRDY) != RESET)
{
/* Data Ready callback */
HAL_RNG_ReadyCallback(hrng);
/* Change RNG peripheral state */
hrng->State = HAL_RNG_STATE_READY;
/* Clear the RNG Data Ready flag */
__HAL_RNG_CLEAR_FLAG(hrng, RNG_FLAG_DRDY);
/* Process Unlocked */
__HAL_UNLOCK(hrng);
}
}
/**
* @brief Data Ready callback in non-blocking mode.
* @param hrng: pointer to a RNG_HandleTypeDef structure that contains
* the configuration information for RNG.
* @retval None
*/
__weak void HAL_RNG_ReadyCallback(RNG_HandleTypeDef* hrng)
{
/* NOTE : This function Should not be modified, when the callback is needed,
the HAL_RNG_ReadyCallback could be implemented in the user file
*/
}
/**
* @brief RNG error callbacks.
* @param hrng: pointer to a RNG_HandleTypeDef structure that contains
* the configuration information for RNG.
* @retval None
*/
__weak void HAL_RNG_ErrorCallback(RNG_HandleTypeDef *hrng)
{
/* NOTE : This function Should not be modified, when the callback is needed,
the HAL_RNG_ErrorCallback could be implemented in the user file
*/
}
/**
* @}
*/
/** @defgroup RNG_Group3 Peripheral State functions
* @brief Peripheral State functions.
*
@verbatim
===============================================================================
##### Peripheral State functions #####
===============================================================================
[..]
This subsection permits to get in run-time the status of the peripheral
and the data flow.
@endverbatim
* @{
*/
/**
* @brief Returns the RNG state.
* @param hrng: pointer to a RNG_HandleTypeDef structure that contains
* the configuration information for RNG.
* @retval HAL state
*/
HAL_RNG_StateTypeDef HAL_RNG_GetState(RNG_HandleTypeDef *hrng)
{
return hrng->State;
}
/**
* @}
*/
/**
* @}
*/
#endif /* STM32L051xx && STM32L061xx*/
#endif /* HAL_RNG_MODULE_ENABLED */
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,224 @@
/**
******************************************************************************
* @file stm32l0xx_hal_rng.h
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief Header file of RNG HAL module.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32L0xx_HAL_RNG_H
#define __STM32L0xx_HAL_RNG_H
#ifdef __cplusplus
extern "C" {
#endif
#if !defined (STM32L051xx) && !defined (STM32L061xx)
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal_def.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @addtogroup RNG
* @{
*/
/* Exported types ------------------------------------------------------------*/
/**
* @brief RNG HAL State Structure definition
*/
typedef enum
{
HAL_RNG_STATE_RESET = 0x00, /*!< RNG not yet initialized or disabled */
HAL_RNG_STATE_READY = 0x01, /*!< RNG initialized and ready for use */
HAL_RNG_STATE_BUSY = 0x02, /*!< RNG internal process is ongoing */
HAL_RNG_STATE_TIMEOUT = 0x03, /*!< RNG timeout state */
HAL_RNG_STATE_ERROR = 0x04 /*!< RNG error state */
}HAL_RNG_StateTypeDef;
/**
* @brief RNG Handle Structure definition
*/
typedef struct
{
RNG_TypeDef *Instance; /*!< Register base address */
HAL_LockTypeDef Lock; /*!< RNG locking object */
__IO HAL_RNG_StateTypeDef State; /*!< RNG communication state */
}RNG_HandleTypeDef;
/* Exported constants --------------------------------------------------------*/
/** @defgroup RNG_Exported_Constants
* @{
*/
/** @defgroup RNG_Interrupt_definition
* @{
*/
#define RNG_IT_CEI ((uint32_t)0x20) /*!< Clock error interrupt */
#define RNG_IT_SEI ((uint32_t)0x40) /*!< Seed error interrupt */
#define IS_RNG_IT(IT) (((IT) == RNG_IT_CEI) || \
((IT) == RNG_IT_SEI))
/**
* @}
*/
/** @defgroup RNG_Flag_definition
* @{
*/
#define RNG_FLAG_DRDY ((uint32_t)0x0001) /*!< Data ready */
#define RNG_FLAG_CECS ((uint32_t)0x0002) /*!< Clock error current status */
#define RNG_FLAG_SECS ((uint32_t)0x0004) /*!< Seed error current status */
#define IS_RNG_FLAG(FLAG) (((FLAG) == RNG_FLAG_DRDY) || \
((FLAG) == RNG_FLAG_CECS) || \
((FLAG) == RNG_FLAG_SECS))
/**
* @}
*/
/**
* @}
*/
/* Exported macro ------------------------------------------------------------*/
/** @brief Reset RNG handle state
* @param __HANDLE__: RNG Handle
* @retval None
*/
#define __HAL_RNG_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_RNG_STATE_RESET)
/**
* @brief Enables the RNG peripheral.
* @param __HANDLE__: RNG Handle
* @retval None
*/
#define __HAL_RNG_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR |= RNG_CR_RNGEN)
/**
* @brief Disables the RNG peripheral.
* @param __HANDLE__: RNG Handle
* @retval None
*/
#define __HAL_RNG_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR &= ~RNG_CR_RNGEN)
/**
* @brief Gets the selected RNG's flag status.
* @param __HANDLE__: RNG Handle
* @param __FLAG__: RNG flag
* @retval The new state of RNG_FLAG (SET or RESET).
*/
#define __HAL_RNG_GET_FLAG(__HANDLE__, __FLAG__) (((__HANDLE__)->Instance->SR & (__FLAG__)) == (__FLAG__))
/**
* @brief Clears the RNG's pending flags.
* @param __HANDLE__: RNG Handle
* @param __FLAG__: RNG flag
* @retval None
*/
#define __HAL_RNG_CLEAR_FLAG(__HANDLE__, __FLAG__) (((__HANDLE__)->Instance->SR) = ~(__FLAG__))
/**
* @brief Enables the RNG interrupts.
* @param __HANDLE__: RNG Handle
* @retval None
*/
#define __HAL_RNG_ENABLE_IT(__HANDLE__) ((__HANDLE__)->Instance->CR |= RNG_CR_IE)
/**
* @brief Disables the RNG interrupts.
* @param __HANDLE__: RNG Handle
* This parameter can be one of the following values:
* @arg RNG_FLAG_DRDY: Data ready interrupt
* @arg RNG_FLAG_CECS: Clock error interrupt
* @arg RNG_FLAG_SECS: Seed error interrupt
* @retval None
*/
#define __HAL_RNG_DISABLE_IT(__HANDLE__) ((__HANDLE__)->Instance->CR &= ~RNG_CR_IE)
/**
* @brief Checks whether the specified RNG interrupt has occurred or not.
* @param __HANDLE__: RNG Handle
* @param __INTERRUPT__: specifies the RNG interrupt source to check.
* This parameter can be one of the following values:
* @arg RNG_FLAG_DRDY: Data ready interrupt
* @arg RNG_FLAG_CECS: Clock error interrupt
* @arg RNG_FLAG_SECS: Seed error interrupt
* @retval The new state of RNG_FLAG (SET or RESET).
*/
#define __HAL_RNG_GET_IT(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->SR & (__INTERRUPT__)) == (__INTERRUPT__))
/* Exported functions --------------------------------------------------------*/
/* Initialization/de-initialization functions **********************************/
HAL_StatusTypeDef HAL_RNG_Init(RNG_HandleTypeDef *hrng);
HAL_StatusTypeDef HAL_RNG_DeInit (RNG_HandleTypeDef *hrng);
void HAL_RNG_MspInit(RNG_HandleTypeDef *hrng);
void HAL_RNG_MspDeInit(RNG_HandleTypeDef *hrng);
/* Peripheral Control functions ************************************************/
uint32_t HAL_RNG_GetRandomNumber(RNG_HandleTypeDef *hrng);
uint32_t HAL_RNG_GetRandomNumber_IT(RNG_HandleTypeDef *hrng);
void HAL_RNG_IRQHandler(RNG_HandleTypeDef *hrng);
void HAL_RNG_ReadyCallback(RNG_HandleTypeDef* hrng);
void HAL_RNG_ErrorCallback(RNG_HandleTypeDef *hrng);
/* Peripheral State functions **************************************************/
HAL_RNG_StateTypeDef HAL_RNG_GetState(RNG_HandleTypeDef *hrng);
#endif /* STM32L051xx && STM32L061xx*/
/**
* @}
*/
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif /* __STM32L0xx_HAL_RNG_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,765 @@
/**
******************************************************************************
* @file stm32l0xx_hal_rtc.h
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief Header file of RTC HAL module.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32L0xx_HAL_RTC_H
#define __STM32L0xx_HAL_RTC_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal_def.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @addtogroup RTC
* @{
*/
/* Exported types ------------------------------------------------------------*/
/**
* @brief HAL State structures definition
*/
typedef enum
{
HAL_RTC_STATE_RESET = 0x00, /*!< RTC not yet initialized or disabled */
HAL_RTC_STATE_READY = 0x01, /*!< RTC initialized and ready for use */
HAL_RTC_STATE_BUSY = 0x02, /*!< RTC process is ongoing */
HAL_RTC_STATE_TIMEOUT = 0x03, /*!< RTC timeout state */
HAL_RTC_STATE_ERROR = 0x04 /*!< RTC error state */
}HAL_RTCStateTypeDef;
/**
* @brief RTC Configuration Structure definition
*/
typedef struct
{
uint32_t HourFormat; /*!< Specifies the RTC Hour Format.
This parameter can be a value of @ref RTC_Hour_Formats */
uint32_t AsynchPrediv; /*!< Specifies the RTC Asynchronous Predivider value.
This parameter must be a number between Min_Data = 0x00 and Max_Data = 0x7F */
uint32_t SynchPrediv; /*!< Specifies the RTC Synchronous Predivider value.
This parameter must be a number between Min_Data = 0x00 and Max_Data = 0x7FFF */
uint32_t OutPut; /*!< Specifies which signal will be routed to the RTC output.
This parameter can be a value of @ref RTC_Output_selection_Definitions */
uint32_t OutPutRemap; /*!< Specifies the remap for RTC output.
This parameter can be a value of @ref RTC_Output_ALARM_OUT_Remap */
uint32_t OutPutPolarity; /*!< Specifies the polarity of the output signal.
This parameter can be a value of @ref RTC_Output_Polarity_Definitions */
uint32_t OutPutType; /*!< Specifies the RTC Output Pin mode.
This parameter can be a value of @ref RTC_Output_Type_ALARM_OUT */
}RTC_InitTypeDef;
/**
* @brief RTC Time structure definition
*/
typedef struct
{
uint8_t Hours; /*!< Specifies the RTC Time Hour.
This parameter must be a number between Min_Data = 0 and Max_Data = 12 if the RTC_HourFormat_12 is selected.
This parameter must be a number between Min_Data = 0 and Max_Data = 23 if the RTC_HourFormat_24 is selected */
uint8_t Minutes; /*!< Specifies the RTC Time Minutes.
This parameter must be a number between Min_Data = 0 and Max_Data = 59 */
uint8_t Seconds; /*!< Specifies the RTC Time Seconds.
This parameter must be a number between Min_Data = 0 and Max_Data = 59 */
uint32_t SubSeconds; /*!< Specifies the RTC Time SubSeconds.
This parameter must be a number between Min_Data = 0 and Max_Data = 59 */
uint8_t TimeFormat; /*!< Specifies the RTC AM/PM Time.
This parameter can be a value of @ref RTC_AM_PM_Definitions */
uint32_t DayLightSaving; /*!< Specifies DayLight Save Operation.
This parameter can be a value of @ref RTC_DayLightSaving_Definitions */
uint32_t StoreOperation; /*!< Specifies RTC_StoreOperation value to be written in the BCK bit
in CR register to store the operation.
This parameter can be a value of @ref RTC_StoreOperation_Definitions */
}RTC_TimeTypeDef;
/**
* @brief RTC Date structure definition
*/
typedef struct
{
uint8_t WeekDay; /*!< Specifies the RTC Date WeekDay.
This parameter can be a value of @ref RTC_WeekDay_Definitions */
uint8_t Month; /*!< Specifies the RTC Date Month (in BCD format).
This parameter can be a value of @ref RTC_Month_Date_Definitions */
uint8_t Date; /*!< Specifies the RTC Date.
This parameter must be a number between Min_Data = 1 and Max_Data = 31 */
uint8_t Year; /*!< Specifies the RTC Date Year.
This parameter must be a number between Min_Data = 0 and Max_Data = 99 */
}RTC_DateTypeDef;
/**
* @brief RTC Alarm structure definition
*/
typedef struct
{
RTC_TimeTypeDef AlarmTime; /*!< Specifies the RTC Alarm Time members */
uint32_t AlarmMask; /*!< Specifies the RTC Alarm Masks.
This parameter can be a value of @ref RTC_AlarmMask_Definitions */
uint32_t AlarmSubSecondMask; /*!< Specifies the RTC Alarm SubSeconds Masks.
This parameter can be a value of @ref RTC_Alarm_Sub_Seconds_Masks_Definitions */
uint32_t AlarmDateWeekDaySel; /*!< Specifies the RTC Alarm is on Date or WeekDay.
This parameter can be a value of @ref RTC_AlarmDateWeekDay_Definitions */
uint8_t AlarmDateWeekDay; /*!< Specifies the RTC Alarm Date/WeekDay.
If the Alarm Date is selected, this parameter must be set to a value in the 1-31 range.
If the Alarm WeekDay is selected, this parameter can be a value of @ref RTC_WeekDay_Definitions */
uint32_t Alarm; /*!< Specifies the alarm .
This parameter can be a value of @ref RTC_Alarms_Definitions */
}RTC_AlarmTypeDef;
/**
* @brief Time Handle Structure definition
*/
typedef struct
{
RTC_TypeDef *Instance; /*!< Register base address */
RTC_InitTypeDef Init; /*!< RTC required parameters */
HAL_LockTypeDef Lock; /*!< RTC locking object */
__IO HAL_RTCStateTypeDef State; /*!< Time communication state */
}RTC_HandleTypeDef;
/* Exported constants --------------------------------------------------------*/
/** @defgroup RTC_Exported_Constants
* @{
*/
/** @defgroup RTC_Hour_Formats
* @{
*/
#define RTC_HOURFORMAT_24 ((uint32_t)0x00000000)
#define RTC_HOURFORMAT_12 ((uint32_t)0x00000040)
#define IS_RTC_HOUR_FORMAT(FORMAT) (((FORMAT) == RTC_HOURFORMAT_12) || \
((FORMAT) == RTC_HOURFORMAT_24))
/**
* @}
*/
/** @defgroup RTC_Output_selection_Definitions
* @{
*/
#define RTC_OUTPUT_DISABLE ((uint32_t)0x00000000)
#define RTC_OUTPUT_ALARMA ((uint32_t)RTC_CR_OSEL_0)
#define RTC_OUTPUT_ALARMB ((uint32_t)RTC_CR_OSEL_1)
#define RTC_OUTPUT_WAKEUP ((uint32_t)RTC_CR_OSEL)
#define IS_RTC_OUTPUT(OUTPUT) (((OUTPUT) == RTC_OUTPUT_DISABLE) || \
((OUTPUT) == RTC_OUTPUT_ALARMA) || \
((OUTPUT) == RTC_OUTPUT_ALARMB) || \
((OUTPUT) == RTC_OUTPUT_WAKEUP))
/**
* @}
*/
/** @defgroup RTC_Output_Polarity_Definitions
* @{
*/
#define RTC_OUTPUT_POLARITY_HIGH ((uint32_t)0x00000000)
#define RTC_OUTPUT_POLARITY_LOW ((uint32_t)0x00100000)
#define IS_RTC_OUTPUT_POL(POL) (((POL) == RTC_OUTPUT_POLARITY_HIGH) || \
((POL) == RTC_OUTPUT_POLARITY_LOW))
/**
* @}
*/
/** @defgroup RTC_Output_Type_ALARM_OUT
* @{
*/
#define RTC_OUTPUT_TYPE_OPENDRAIN ((uint32_t)0x00000000)
#define RTC_OUTPUT_TYPE_PUSHPULL ((uint32_t)RTC_OR_ALARMOUTTYPE)
#define IS_RTC_OUTPUT_TYPE(TYPE) (((TYPE) == RTC_OUTPUT_TYPE_OPENDRAIN) || \
((TYPE) == RTC_OUTPUT_TYPE_PUSHPULL))
/**
* @}
*/
/** @defgroup RTC_Output_ALARM_OUT_Remap
* @{
*/
#define RTC_OUTPUT_REMAP_PC13 ((uint32_t)0x00000000)
#define RTC_OUTPUT_REMAP_PB14 ((uint32_t)RTC_OR_RTC_OUT_RMP)
#define IS_RTC_OUTPUT_REMAP(REMAP) (((REMAP) == RTC_OUTPUT_REMAP_PC13) || \
((REMAP) == RTC_OUTPUT_REMAP_PB14))
/**
* @}
*/
/** @defgroup RTC_Asynchronous_Predivider
* @{
*/
#define IS_RTC_ASYNCH_PREDIV(PREDIV) ((PREDIV) <= (uint32_t)0x7F)
/**
* @}
*/
/** @defgroup RTC_Synchronous_Predivider
* @{
*/
#define IS_RTC_SYNCH_PREDIV(PREDIV) ((PREDIV) <= (uint32_t)0x7FFF)
/**
* @}
*/
/** @defgroup RTC_Time_Definitions
* @{
*/
#define IS_RTC_HOUR12(HOUR) (((HOUR) > (uint32_t)0) && ((HOUR) <= (uint32_t)12))
#define IS_RTC_HOUR24(HOUR) ((HOUR) <= (uint32_t)23)
#define IS_RTC_MINUTES(MINUTES) ((MINUTES) <= (uint32_t)59)
#define IS_RTC_SECONDS(SECONDS) ((SECONDS) <= (uint32_t)59)
/**
* @}
*/
/** @defgroup RTC_AM_PM_Definitions
* @{
*/
#define RTC_HOURFORMAT12_AM ((uint8_t)0x00)
#define RTC_HOURFORMAT12_PM ((uint8_t)0x40)
#define IS_RTC_HOURFORMAT12(PM) (((PM) == RTC_HOURFORMAT12_AM) || ((PM) == RTC_HOURFORMAT12_PM))
/**
* @}
*/
/** @defgroup RTC_DayLightSaving_Definitions
* @{
*/
#define RTC_DAYLIGHTSAVING_SUB1H ((uint32_t)0x00020000)
#define RTC_DAYLIGHTSAVING_ADD1H ((uint32_t)0x00010000)
#define RTC_DAYLIGHTSAVING_NONE ((uint32_t)0x00000000)
#define IS_RTC_DAYLIGHT_SAVING(SAVE) (((SAVE) == RTC_DAYLIGHTSAVING_SUB1H) || \
((SAVE) == RTC_DAYLIGHTSAVING_ADD1H) || \
((SAVE) == RTC_DAYLIGHTSAVING_NONE))
/**
* @}
*/
/** @defgroup RTC_StoreOperation_Definitions
* @{
*/
#define RTC_STOREOPERATION_RESET ((uint32_t)0x00000000)
#define RTC_STOREOPERATION_SET ((uint32_t)0x00040000)
#define IS_RTC_STORE_OPERATION(OPERATION) (((OPERATION) == RTC_STOREOPERATION_RESET) || \
((OPERATION) == RTC_STOREOPERATION_SET))
/**
* @}
*/
/** @defgroup RTC_Input_parameter_format_definitions
* @{
*/
#define FORMAT_BIN ((uint32_t)0x000000000)
#define FORMAT_BCD ((uint32_t)0x000000001)
#define IS_RTC_FORMAT(FORMAT) (((FORMAT) == FORMAT_BIN) || ((FORMAT) == FORMAT_BCD))
/**
* @}
*/
/** @defgroup RTC_Year_Date_Definitions
* @{
*/
#define IS_RTC_YEAR(YEAR) ((YEAR) <= (uint32_t)99)
/**
* @}
*/
/** @defgroup RTC_Month_Date_Definitions
* @{
*/
/* Coded in BCD format */
#define RTC_MONTH_JANUARY ((uint8_t)0x01)
#define RTC_MONTH_FEBRUARY ((uint8_t)0x02)
#define RTC_MONTH_MARCH ((uint8_t)0x03)
#define RTC_MONTH_APRIL ((uint8_t)0x04)
#define RTC_MONTH_MAY ((uint8_t)0x05)
#define RTC_MONTH_JUNE ((uint8_t)0x06)
#define RTC_MONTH_JULY ((uint8_t)0x07)
#define RTC_MONTH_AUGUST ((uint8_t)0x08)
#define RTC_MONTH_SEPTEMBER ((uint8_t)0x09)
#define RTC_MONTH_OCTOBER ((uint8_t)0x10)
#define RTC_MONTH_NOVEMBER ((uint8_t)0x11)
#define RTC_MONTH_DECEMBER ((uint8_t)0x12)
#define IS_RTC_MONTH(MONTH) (((MONTH) >= (uint32_t)1) && ((MONTH) <= (uint32_t)12))
#define IS_RTC_DATE(DATE) (((DATE) >= (uint32_t)1) && ((DATE) <= (uint32_t)31))
/**
* @}
*/
/** @defgroup RTC_WeekDay_Definitions
* @{
*/
#define RTC_WEEKDAY_MONDAY ((uint8_t)0x01)
#define RTC_WEEKDAY_TUESDAY ((uint8_t)0x02)
#define RTC_WEEKDAY_WEDNESDAY ((uint8_t)0x03)
#define RTC_WEEKDAY_THURSDAY ((uint8_t)0x04)
#define RTC_WEEKDAY_FRIDAY ((uint8_t)0x05)
#define RTC_WEEKDAY_SATURDAY ((uint8_t)0x06)
#define RTC_WEEKDAY_SUNDAY ((uint8_t)0x07)
#define IS_RTC_WEEKDAY(WEEKDAY) (((WEEKDAY) == RTC_WEEKDAY_MONDAY) || \
((WEEKDAY) == RTC_WEEKDAY_TUESDAY) || \
((WEEKDAY) == RTC_WEEKDAY_WEDNESDAY) || \
((WEEKDAY) == RTC_WEEKDAY_THURSDAY) || \
((WEEKDAY) == RTC_WEEKDAY_FRIDAY) || \
((WEEKDAY) == RTC_WEEKDAY_SATURDAY) || \
((WEEKDAY) == RTC_WEEKDAY_SUNDAY))
/**
* @}
*/
/** @defgroup RTC_Alarm_Definitions
* @{
*/
#define IS_RTC_ALARM_DATE_WEEKDAY_DATE(DATE) (((DATE) >(uint32_t) 0) && ((DATE) <= (uint32_t)31))
#define IS_RTC_ALARM_DATE_WEEKDAY_WEEKDAY(WEEKDAY) (((WEEKDAY) == RTC_WEEKDAY_MONDAY) || \
((WEEKDAY) == RTC_WEEKDAY_TUESDAY) || \
((WEEKDAY) == RTC_WEEKDAY_WEDNESDAY) || \
((WEEKDAY) == RTC_WEEKDAY_THURSDAY) || \
((WEEKDAY) == RTC_WEEKDAY_FRIDAY) || \
((WEEKDAY) == RTC_WEEKDAY_SATURDAY) || \
((WEEKDAY) == RTC_WEEKDAY_SUNDAY))
/**
* @}
*/
/** @defgroup RTC_AlarmDateWeekDay_Definitions
* @{
*/
#define RTC_ALARMDATEWEEKDAYSEL_DATE ((uint32_t)0x00000000)
#define RTC_ALARMDATEWEEKDAYSEL_WEEKDAY ((uint32_t)0x40000000)
#define IS_RTC_ALARM_DATE_WEEKDAY_SEL(SEL) (((SEL) == RTC_ALARMDATEWEEKDAYSEL_DATE) || \
((SEL) == RTC_ALARMDATEWEEKDAYSEL_WEEKDAY))
/**
* @}
*/
/** @defgroup RTC_AlarmMask_Definitions
* @{
*/
#define RTC_ALARMMASK_NONE ((uint32_t)0x00000000)
#define RTC_ALARMMASK_DATEWEEKDAY RTC_ALRMAR_MSK4
#define RTC_ALARMMASK_HOURS RTC_ALRMAR_MSK3
#define RTC_ALARMMASK_MINUTES RTC_ALRMAR_MSK2
#define RTC_ALARMMASK_SECONDS RTC_ALRMAR_MSK1
#define RTC_ALARMMASK_ALL ((uint32_t)0x80808080)
#define IS_ALARM_MASK(MASK) (((MASK) & 0x7F7F7F7F) == (uint32_t)RESET)
/**
* @}
*/
/** @defgroup RTC_Alarms_Definitions
* @{
*/
#define RTC_ALARM_A RTC_CR_ALRAE
#define RTC_ALARM_B RTC_CR_ALRBE
#define IS_ALARM(ALARM) (((ALARM) == RTC_ALARM_A) || ((ALARM) == RTC_ALARM_B))
/**
* @}
*/
/** @defgroup RTC_Alarm_Sub_Seconds_Value
* @{
*/
#define IS_RTC_ALARM_SUB_SECOND_VALUE(VALUE) ((VALUE) <= (uint32_t)0x00007FFF)
/**
* @}
*/
/** @defgroup RTC_Alarm_Sub_Seconds_Masks_Definitions
* @{
*/
#define RTC_ALARMSUBSECONDMASK_ALL ((uint32_t)0x00000000) /*!< All Alarm SS fields are masked.
There is no comparison on sub seconds
for Alarm */
#define RTC_ALARMSUBSECONDMASK_SS14_1 ((uint32_t)0x01000000) /*!< SS[14:1] are don't care in Alarm
comparison. Only SS[0] is compared. */
#define RTC_ALARMSUBSECONDMASK_SS14_2 ((uint32_t)0x02000000) /*!< SS[14:2] are don't care in Alarm
comparison. Only SS[1:0] are compared */
#define RTC_ALARMSUBSECONDMASK_SS14_3 ((uint32_t)0x03000000) /*!< SS[14:3] are don't care in Alarm
comparison. Only SS[2:0] are compared */
#define RTC_ALARMSUBSECONDMASK_SS14_4 ((uint32_t)0x04000000) /*!< SS[14:4] are don't care in Alarm
comparison. Only SS[3:0] are compared */
#define RTC_ALARMSUBSECONDMASK_SS14_5 ((uint32_t)0x05000000) /*!< SS[14:5] are don't care in Alarm
comparison. Only SS[4:0] are compared */
#define RTC_ALARMSUBSECONDMASK_SS14_6 ((uint32_t)0x06000000) /*!< SS[14:6] are don't care in Alarm
comparison. Only SS[5:0] are compared */
#define RTC_ALARMSUBSECONDMASK_SS14_7 ((uint32_t)0x07000000) /*!< SS[14:7] are don't care in Alarm
comparison. Only SS[6:0] are compared */
#define RTC_ALARMSUBSECONDMASK_SS14_8 ((uint32_t)0x08000000) /*!< SS[14:8] are don't care in Alarm
comparison. Only SS[7:0] are compared */
#define RTC_ALARMSUBSECONDMASK_SS14_9 ((uint32_t)0x09000000) /*!< SS[14:9] are don't care in Alarm
comparison. Only SS[8:0] are compared */
#define RTC_ALARMSUBSECONDMASK_SS14_10 ((uint32_t)0x0A000000) /*!< SS[14:10] are don't care in Alarm
comparison. Only SS[9:0] are compared */
#define RTC_ALARMSUBSECONDMASK_SS14_11 ((uint32_t)0x0B000000) /*!< SS[14:11] are don't care in Alarm
comparison. Only SS[10:0] are compared */
#define RTC_ALARMSUBSECONDMASK_SS14_12 ((uint32_t)0x0C000000) /*!< SS[14:12] are don't care in Alarm
comparison.Only SS[11:0] are compared */
#define RTC_ALARMSUBSECONDMASK_SS14_13 ((uint32_t)0x0D000000) /*!< SS[14:13] are don't care in Alarm
comparison. Only SS[12:0] are compared */
#define RTC_ALARMSUBSECONDMASK_SS14 ((uint32_t)0x0E000000) /*!< SS[14] is don't care in Alarm
comparison.Only SS[13:0] are compared */
#define RTC_ALARMSUBSECONDMASK_None ((uint32_t)0x0F000000) /*!< SS[14:0] are compared and must match
to activate alarm. */
#define IS_RTC_ALARM_SUB_SECOND_MASK(MASK) (((MASK) == RTC_ALARMSUBSECONDMASK_ALL) || \
((MASK) == RTC_ALARMSUBSECONDMASK_SS14_1) || \
((MASK) == RTC_ALARMSUBSECONDMASK_SS14_2) || \
((MASK) == RTC_ALARMSUBSECONDMASK_SS14_3) || \
((MASK) == RTC_ALARMSUBSECONDMASK_SS14_4) || \
((MASK) == RTC_ALARMSUBSECONDMASK_SS14_5) || \
((MASK) == RTC_ALARMSUBSECONDMASK_SS14_6) || \
((MASK) == RTC_ALARMSUBSECONDMASK_SS14_7) || \
((MASK) == RTC_ALARMSUBSECONDMASK_SS14_8) || \
((MASK) == RTC_ALARMSUBSECONDMASK_SS14_9) || \
((MASK) == RTC_ALARMSUBSECONDMASK_SS14_10) || \
((MASK) == RTC_ALARMSUBSECONDMASK_SS14_11) || \
((MASK) == RTC_ALARMSUBSECONDMASK_SS14_12) || \
((MASK) == RTC_ALARMSUBSECONDMASK_SS14_13) || \
((MASK) == RTC_ALARMSUBSECONDMASK_SS14) || \
((MASK) == RTC_ALARMSUBSECONDMASK_None))
/**
* @}
*/
/** @defgroup RTC_Interrupts_Definitions
* @{
*/
#define RTC_IT_TS ((uint32_t)RTC_CR_TSIE)
#define RTC_IT_WUT ((uint32_t)RTC_CR_WUTIE)
#define RTC_IT_ALRA ((uint32_t)RTC_CR_ALRAIE)
#define RTC_IT_ALRB ((uint32_t)RTC_CR_ALRBIE)
#define RTC_IT_TAMP ((uint32_t)RTC_TAMPCR_TAMPIE) /* Used only to Enable the Tamper Interrupt */
#define RTC_IT_TAMP1 ((uint32_t)RTC_TAMPCR_TAMP1IE)
#define RTC_IT_TAMP2 ((uint32_t)RTC_TAMPCR_TAMP2IE)
/**
* @}
*/
/** @defgroup RTC_Flags_Definitions
* @{
*/
#define RTC_FLAG_RECALPF ((uint32_t)RTC_ISR_RECALPF)
#define RTC_FLAG_TAMP2F ((uint32_t)RTC_ISR_TAMP2F)
#define RTC_FLAG_TAMP1F ((uint32_t)RTC_ISR_TAMP1F)
#define RTC_FLAG_TSOVF ((uint32_t)RTC_ISR_TSOVF)
#define RTC_FLAG_TSF ((uint32_t)RTC_ISR_TSF)
#define RTC_FLAG_WUTF ((uint32_t)RTC_ISR_WUTF)
#define RTC_FLAG_ALRBF ((uint32_t)RTC_ISR_ALRBF)
#define RTC_FLAG_ALRAF ((uint32_t)RTC_ISR_ALRAF)
#define RTC_FLAG_INITF ((uint32_t)RTC_ISR_INITF)
#define RTC_FLAG_RSF ((uint32_t)RTC_ISR_RSF)
#define RTC_FLAG_INITS ((uint32_t)RTC_ISR_INITS)
#define RTC_FLAG_SHPF ((uint32_t)RTC_ISR_SHPF)
#define RTC_FLAG_WUTWF ((uint32_t)RTC_ISR_WUTWF)
#define RTC_FLAG_ALRBWF ((uint32_t)RTC_ISR_ALRBWF)
#define RTC_FLAG_ALRAWF ((uint32_t)RTC_ISR_ALRAWF)
/**
* @}
*/
/**
* @}
*/
/* Exported macro ------------------------------------------------------------*/
/** @brief Reset RTC handle state
* @param __HANDLE__: specifies the RTC handle.
* @retval None
*/
#define __HAL_RTC_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_RTC_STATE_RESET)
/**
* @brief Disable the write protection for RTC registers.
* @param __HANDLE__: specifies the RTC handle.
* @retval None
*/
#define __HAL_RTC_WRITEPROTECTION_DISABLE(__HANDLE__) \
do{ \
(__HANDLE__)->Instance->WPR = 0xCA; \
(__HANDLE__)->Instance->WPR = 0x53; \
} while(0)
/**
* @brief Enable the write protection for RTC registers.
* @param __HANDLE__: specifies the RTC handle.
* @retval None
*/
#define __HAL_RTC_WRITEPROTECTION_ENABLE(__HANDLE__) \
do{ \
(__HANDLE__)->Instance->WPR = 0xFF; \
} while(0)
/**
* @brief Enable the RTC ALARMA peripheral.
* @param __HANDLE__: specifies the RTC handle.
* @retval None
*/
#define __HAL_RTC_ALARMA_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR |= (RTC_CR_ALRAE))
/**
* @brief Disable the RTC ALARMA peripheral.
* @param __HANDLE__: specifies the RTC handle.
* @retval None
*/
#define __HAL_RTC_ALARMA_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR &= ~(RTC_CR_ALRAE))
/**
* @brief Enable the RTC ALARMB peripheral.
* @param __HANDLE__: specifies the RTC handle.
* @retval None
*/
#define __HAL_RTC_ALARMB_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR |= (RTC_CR_ALRBE))
/**
* @brief Disable the RTC ALARMB peripheral.
* @param __HANDLE__: specifies the RTC handle.
* @retval None
*/
#define __HAL_RTC_ALARMB_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR &= ~(RTC_CR_ALRBE))
/**
* @brief Enable the RTC Alarm interrupt.
* @param __HANDLE__: specifies the RTC handle.
* @param __INTERRUPT__: specifies the RTC Alarm interrupt sources to be enabled or disabled.
* This parameter can be any combination of the following values:
* @arg RTC_IT_ALRA: Alarm A interrupt
* @arg RTC_IT_ALRB: Alarm B interrupt
* @retval None
*/
#define __HAL_RTC_ALARM_ENABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->CR |= (__INTERRUPT__))
/**
* @brief Disable the RTC Alarm interrupt.
* @param __HANDLE__: specifies the RTC handle.
* @param __INTERRUPT__: specifies the RTC Alarm interrupt sources to be enabled or disabled.
* This parameter can be any combination of the following values:
* @arg RTC_IT_ALRA: Alarm A interrupt
* @arg RTC_IT_ALRB: Alarm B interrupt
* @retval None
*/
#define __HAL_RTC_ALARM_DISABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->CR &= ~(__INTERRUPT__))
/**
* @brief Check whether the specified RTC Alarm interrupt has occurred or not.
* @param __HANDLE__: specifies the RTC handle.
* @param __FLAG__: specifies the RTC Alarm interrupt sources to be enabled or disabled.
* This parameter can be:
* @arg RTC_IT_ALRA: Alarm A interrupt
* @arg RTC_IT_ALRB: Alarm B interrupt
* @retval None
*/
#define __HAL_RTC_ALARM_GET_IT(__HANDLE__, __FLAG__) ((((((__HANDLE__)->Instance->ISR)& ((__FLAG__)>> 4)) & 0x0000FFFF) != RESET)? SET : RESET)
/**
* @brief Get the selected RTC Alarm's flag status.
* @param __HANDLE__: specifies the RTC handle.
* @param __FLAG__: specifies the RTC Alarm Flag sources to be enabled or disabled.
* This parameter can be:
* @arg RTC_FLAG_ALRAF
* @arg RTC_FLAG_ALRBF
* @arg RTC_FLAG_ALRAWF
* @arg RTC_FLAG_ALRBWF
* @retval None
*/
#define __HAL_RTC_ALARM_GET_FLAG(__HANDLE__, __FLAG__) (((((__HANDLE__)->Instance->ISR) & (__FLAG__)) != RESET)? SET : RESET)
/**
* @brief Clear the RTC Alarm's pending flags.
* @param __HANDLE__: specifies the RTC handle.
* @param __FLAG__: specifies the RTC Alarm Flag sources to be enabled or disabled.
* This parameter can be:
* @arg RTC_FLAG_ALRAF
* @arg RTC_FLAG_ALRBF
* @retval None
*/
#define __HAL_RTC_ALARM_CLEAR_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->ISR) = (~(((__FLAG__) | RTC_ISR_INIT)& 0x0000FFFF)|((__HANDLE__)->Instance->ISR & RTC_ISR_INIT))
#define RTC_EXTI_LINE_ALARM_EVENT ((uint32_t)0x00020000) /*!< External interrupt line 17 Connected to the RTC Alarm event */
#define RTC_EXTI_LINE_TAMPER_TIMESTAMP_EVENT ((uint32_t)0x00080000) /*!< External interrupt line 19 Connected to the RTC Tamper and Time Stamp events */
#define RTC_EXTI_LINE_WAKEUPTIMER_EVENT ((uint32_t)0x00100000) /*!< External interrupt line 20 Connected to the RTC Wakeup event */
/**
* @brief Enable the RTC Exti line.
* @param __EXTILINE__: specifies the RTC Exti sources to be enabled or disabled.
* This parameter can be:
* @arg RTC_EXTI_LINE_ALARM_EVENT
* @arg RTC_EXTI_LINE_TAMPER_TIMESTAMP_EVENT
* @arg RTC_EXTI_LINE_WAKEUPTIMER_EVENT
* @retval None
*/
#define __HAL_RTC_EXTI_ENABLE_IT(__EXTILINE__) (EXTI->IMR |= (__EXTILINE__))
/* alias define maintained for legacy */
#define __HAL_RTC_ENABLE_IT __HAL_RTC_EXTI_ENABLE_IT
/**
* @brief Disable the RTC Exti line.
* @param __EXTILINE__: specifies the RTC Exti sources to be enabled or disabled.
* This parameter can be:
* @arg RTC_EXTI_LINE_ALARM_EVENT
* @arg RTC_EXTI_LINE_TAMPER_TIMESTAMP_EVENT
* @arg RTC_EXTI_LINE_WAKEUPTIMER_EVENT
* @retval None
*/
#define __HAL_RTC_EXTI_DISABLE_IT(__EXTILINE__) (EXTI->IMR &= ~(__EXTILINE__))
/* alias define maintained for legacy */
#define __HAL_RTC_DISABLE_IT __HAL_RTC_EXTI_DISABLE_IT
/**
* @brief Generates a Software interrupt on selected EXTI line.
* @param __EXTILINE__: specifies the RTC Exti sources to be enabled or disabled.
* This parameter can be:
* @arg RTC_EXTI_LINE_ALARM_EVENT
* @arg RTC_EXTI_LINE_TAMPER_TIMESTAMP_EVENT
* @arg RTC_EXTI_LINE_WAKEUPTIMER_EVENT
* @retval None
*/
#define __HAL_RTC_EXTI_GENERATE_SWIT(__EXTI_LINE__) (EXTI->SWIER |= (__EXTI_LINE__))
/**
* @brief Clear the RTC Exti flags.
* @param __FLAG__: specifies the RTC Exti sources to be enabled or disabled.
* This parameter can be:
* @arg RTC_EXTI_LINE_ALARM_EVENT
* @arg RTC_EXTI_LINE_TAMPER_TIMESTAMP_EVENT
* @arg RTC_EXTI_LINE_WAKEUPTIMER_EVENT
* @retval None
*/
#define __HAL_RTC_EXTI_CLEAR_FLAG(__FLAG__) (EXTI->PR = (__FLAG__))
/* alias define maintained for legacy */
#define __HAL_RTC_CLEAR_FLAG __HAL_RTC_EXTI_CLEAR_FLAG
/* Include RTC HAL Extension module */
#include "stm32l0xx_hal_rtc_ex.h"
/* Exported functions --------------------------------------------------------*/
/* Initialization and de-initialization functions ****************************/
HAL_StatusTypeDef HAL_RTC_Init(RTC_HandleTypeDef *hrtc);
HAL_StatusTypeDef HAL_RTC_DeInit(RTC_HandleTypeDef *hrtc);
void HAL_RTC_MspInit(RTC_HandleTypeDef *hrtc);
void HAL_RTC_MspDeInit(RTC_HandleTypeDef *hrtc);
/* RTC Time and Date functions ************************************************/
HAL_StatusTypeDef HAL_RTC_SetTime(RTC_HandleTypeDef *hrtc, RTC_TimeTypeDef *sTime, uint32_t Format);
HAL_StatusTypeDef HAL_RTC_GetTime(RTC_HandleTypeDef *hrtc, RTC_TimeTypeDef *sTime, uint32_t Format);
HAL_StatusTypeDef HAL_RTC_SetDate(RTC_HandleTypeDef *hrtc, RTC_DateTypeDef *sDate, uint32_t Format);
HAL_StatusTypeDef HAL_RTC_GetDate(RTC_HandleTypeDef *hrtc, RTC_DateTypeDef *sDate, uint32_t Format);
HAL_StatusTypeDef HAL_RTC_SetAlarm(RTC_HandleTypeDef *hrtc, RTC_AlarmTypeDef *sAlarm, uint32_t Format);
HAL_StatusTypeDef HAL_RTC_SetAlarm_IT(RTC_HandleTypeDef *hrtc, RTC_AlarmTypeDef *sAlarm, uint32_t Format);
HAL_StatusTypeDef HAL_RTC_DeactivateAlarm(RTC_HandleTypeDef *hrtc, uint32_t Alarm);
HAL_StatusTypeDef HAL_RTC_GetAlarm(RTC_HandleTypeDef *hrtc, RTC_AlarmTypeDef *sAlarm, uint32_t Alarm, uint32_t Format);
/* Peripheral State functions ***************************************************/
HAL_StatusTypeDef HAL_RTC_WaitForSynchro(RTC_HandleTypeDef* hrtc);
HAL_RTCStateTypeDef HAL_RTC_GetState(RTC_HandleTypeDef *hrtc);
void HAL_RTC_AlarmIRQHandler(RTC_HandleTypeDef *hrtc);
HAL_StatusTypeDef HAL_RTC_PollForAlarmAEvent(RTC_HandleTypeDef *hrtc, uint32_t Timeout);
void HAL_RTC_AlarmAEventCallback(RTC_HandleTypeDef *hrtc);
/* Peripheral State functions *************************************************/
HAL_StatusTypeDef RTC_EnterInitMode(RTC_HandleTypeDef* hrtc);
uint8_t RTC_ByteToBcd2(uint8_t Value);
uint8_t RTC_Bcd2ToByte(uint8_t Value);
/**
* @}
*/
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif /* __STM32L0xx_HAL_RTC_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,681 @@
/**
******************************************************************************
* @file stm32l0xx_hal_rtc_ex.h
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief Header file of PWR HAL Extension module.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32L0xx_HAL_RTC_EX_H
#define __STM32L0xx_HAL_RTC_EX_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal_def.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @addtogroup RTCEx
* @{
*/
/* Exported types ------------------------------------------------------------*/
/**
* @brief RTC Tamper structure definition
*/
typedef struct
{
uint32_t Tamper; /*!< Specifies the Tamper Pin.
This parameter can be a value of @ref RTCEx_Tamper_Pins_Definitions */
uint32_t Interrupt; /*!< Specifies the Tamper Interrupt.
This parameter can be a value of @ref RTCEx_Tamper_Interrupt_Definitions */
uint32_t Trigger; /*!< Specifies the Tamper Trigger.
This parameter can be a value of @ref RTCEx_Tamper_Trigger_Definitions */
uint32_t NoErase; /*!< Specifies the Tamper no erase mode.
This parameter can be a value of @ref RTCEx_Tamper_EraseBackUp_Definitions */
uint32_t MaskFlag; /*!< Specifies the Tamper Flag masking.
This parameter can be a value of @ref RTCEx_Tamper_MaskFlag_Definitions */
uint32_t Filter; /*!< Specifies the RTC Filter Tamper.
This parameter can be a value of @ref RTCEx_Tamper_Filter_Definitions */
uint32_t SamplingFrequency; /*!< Specifies the sampling frequency.
This parameter can be a value of @ref RTCEx_Tamper_Sampling_Frequencies_Definitions */
uint32_t PrechargeDuration; /*!< Specifies the Precharge Duration .
This parameter can be a value of @ref RTCEx_Tamper_Pin_Precharge_Duration_Definitions */
uint32_t TamperPullUp; /*!< Specifies the Tamper PullUp .
This parameter can be a value of @ref RTCEx_Tamper_PullUP_Definitions */
uint32_t TimeStampOnTamperDetection; /*!< Specifies the TimeStampOnTamperDetection.
This parameter can be a value of @ref RTCEx_Tamper_TimeStampOnTamperDetection_Definitions */
}RTC_TamperTypeDef;
/* Exported constants --------------------------------------------------------*/
/** @defgroup RTCEx_Exported_Constants
* @{
*/
/** @defgroup RTCEx_Backup_Registers_Definitions
* @{
*/
#define RTC_BKP_DR0 ((uint32_t)0x00000000)
#define RTC_BKP_DR1 ((uint32_t)0x00000001)
#define RTC_BKP_DR2 ((uint32_t)0x00000002)
#define RTC_BKP_DR3 ((uint32_t)0x00000003)
#define RTC_BKP_DR4 ((uint32_t)0x00000004)
#define IS_RTC_BKP(BKP) (((BKP) == RTC_BKP_DR0) || \
((BKP) == RTC_BKP_DR1) || \
((BKP) == RTC_BKP_DR2) || \
((BKP) == RTC_BKP_DR3) || \
((BKP) == RTC_BKP_DR4))
/**
* @}
*/
/** @defgroup RTCEx_Time_Stamp_Edges_definitions
* @{
*/
#define RTC_TIMESTAMPEDGE_RISING ((uint32_t)0x00000000)
#define RTC_TIMESTAMPEDGE_FALLING ((uint32_t)0x00000008)
#define IS_TIMESTAMP_EDGE(EDGE) (((EDGE) == RTC_TIMESTAMPEDGE_RISING) || \
((EDGE) == RTC_TIMESTAMPEDGE_FALLING))
/**
* @}
*/
/** @defgroup RTCEx_Tamper_Pins_Definitions
* @{
*/
#define RTC_TAMPER_1 RTC_TAMPCR_TAMP1E
#define RTC_TAMPER_2 RTC_TAMPCR_TAMP2E
#define IS_TAMPER(TAMPER) ((((TAMPER) & (uint32_t)0xFFFFFFF6) == 0x00) && ((TAMPER) != (uint32_t)RESET))
/**
* @}
*/
/** @defgroup RTCEx_Tamper_Interrupt_Definitions
* @{
*/
#define RTC_TAMPER1_INTERRUPT RTC_TAMPCR_TAMP1IE
#define RTC_TAMPER2_INTERRUPT RTC_TAMPCR_TAMP2IE
#define RTC_TAMPER1_2_INTERRUPT RTC_TAMPCR_TAMPIE
#define IS_TAMPER_INTERRUPT(INTERRUPT) (((INTERRUPT) == RTC_TAMPER1_INTERRUPT) || \
((INTERRUPT) == RTC_TAMPER2_INTERRUPT) || \
((INTERRUPT) == RTC_TAMPER1_2_INTERRUPT))
/**
* @}
*/
/** @defgroup RTCEx_TimeStamp_Pin_Selection
* @{
*/
#define RTC_TIMESTAMPPIN_PC13 ((uint32_t)0x00000000)
#define IS_RTC_TIMESTAMP_PIN(PIN) ((PIN) == RTC_TIMESTAMPPIN_PC13)
/**
* @}
*/
/** @defgroup RTCEx_Tamper_Trigger_Definitions
* @{
*/
#define RTC_TAMPERTRIGGER_RISINGEDGE ((uint32_t)0x00000000)
#define RTC_TAMPERTRIGGER_FALLINGEDGE ((uint32_t)0x00000002)
#define RTC_TAMPERTRIGGER_LOWLEVEL RTC_TAMPERTRIGGER_RISINGEDGE
#define RTC_TAMPERTRIGGER_HIGHLEVEL RTC_TAMPERTRIGGER_FALLINGEDGE
#define IS_TAMPER_TRIGGER(TRIGGER) (((TRIGGER) == RTC_TAMPERTRIGGER_RISINGEDGE) || \
((TRIGGER) == RTC_TAMPERTRIGGER_FALLINGEDGE) || \
((TRIGGER) == RTC_TAMPERTRIGGER_LOWLEVEL) || \
((TRIGGER) == RTC_TAMPERTRIGGER_HIGHLEVEL))
/**
* @}
*/
/** @defgroup RTCEx_Tamper_EraseBackUp_Definitions
* @{
*/
#define RTC_TAMPERERASEBACKUP_ENABLED ((uint32_t)0x00000000)
#define RTC_TAMPERERASEBACKUP_DISABLED ((uint32_t)0x00020000)
#define IS_TAMPER_ERASE_MODE(MODE) (((MODE) == RTC_TAMPERERASEBACKUP_ENABLED) || \
((MODE) == RTC_TAMPERERASEBACKUP_DISABLED))
/**
* @}
*/
/** @defgroup RTCEx_Tamper_MaskFlag_Definitions
* @{
*/
#define RTC_MASKTAMPERFLAG_DISABLED ((uint32_t)0x00000000)
#define RTC_MASKTAMPERFLAG_ENABLED ((uint32_t)0x00040000)
#define IS_TAMPER_MASKFLAG_STATE(STATE) (((STATE) == RTC_MASKTAMPERFLAG_ENABLED) || \
((STATE) == RTC_MASKTAMPERFLAG_DISABLED))
/**
* @}
*/
/** @defgroup RTCEx_Tamper_Filter_Definitions
* @{
*/
#define RTC_TAMPERFILTER_DISABLE ((uint32_t)0x00000000) /*!< Tamper filter is disabled */
#define RTC_TAMPERFILTER_2SAMPLE ((uint32_t)0x00000800) /*!< Tamper is activated after 2
consecutive samples at the active level */
#define RTC_TAMPERFILTER_4SAMPLE ((uint32_t)0x00001000) /*!< Tamper is activated after 4
consecutive samples at the active level */
#define RTC_TAMPERFILTER_8SAMPLE ((uint32_t)0x00001800) /*!< Tamper is activated after 8
consecutive samples at the active leve. */
#define IS_TAMPER_FILTER(FILTER) (((FILTER) == RTC_TAMPERFILTER_DISABLE) || \
((FILTER) == RTC_TAMPERFILTER_2SAMPLE) || \
((FILTER) == RTC_TAMPERFILTER_4SAMPLE) || \
((FILTER) == RTC_TAMPERFILTER_8SAMPLE))
/**
* @}
*/
/** @defgroup RTCEx_Tamper_Sampling_Frequencies_Definitions
* @{
*/
#define RTC_TAMPERSAMPLINGFREQ_RTCCLK_DIV32768 ((uint32_t)0x00000000) /*!< Each of the tamper inputs are sampled
with a frequency = RTCCLK / 32768 */
#define RTC_TAMPERSAMPLINGFREQ_RTCCLK_DIV16384 ((uint32_t)0x00000100) /*!< Each of the tamper inputs are sampled
with a frequency = RTCCLK / 16384 */
#define RTC_TAMPERSAMPLINGFREQ_RTCCLK_DIV8192 ((uint32_t)0x00000200) /*!< Each of the tamper inputs are sampled
with a frequency = RTCCLK / 8192 */
#define RTC_TAMPERSAMPLINGFREQ_RTCCLK_DIV4096 ((uint32_t)0x00000300) /*!< Each of the tamper inputs are sampled
with a frequency = RTCCLK / 4096 */
#define RTC_TAMPERSAMPLINGFREQ_RTCCLK_DIV2048 ((uint32_t)0x00000400) /*!< Each of the tamper inputs are sampled
with a frequency = RTCCLK / 2048 */
#define RTC_TAMPERSAMPLINGFREQ_RTCCLK_DIV1024 ((uint32_t)0x00000500) /*!< Each of the tamper inputs are sampled
with a frequency = RTCCLK / 1024 */
#define RTC_TAMPERSAMPLINGFREQ_RTCCLK_DIV512 ((uint32_t)0x00000600) /*!< Each of the tamper inputs are sampled
with a frequency = RTCCLK / 512 */
#define RTC_TAMPERSAMPLINGFREQ_RTCCLK_DIV256 ((uint32_t)0x00000700) /*!< Each of the tamper inputs are sampled
with a frequency = RTCCLK / 256 */
#define IS_TAMPER_SAMPLING_FREQ(FREQ) (((FREQ) == RTC_TAMPERSAMPLINGFREQ_RTCCLK_DIV32768)|| \
((FREQ) == RTC_TAMPERSAMPLINGFREQ_RTCCLK_DIV16384)|| \
((FREQ) == RTC_TAMPERSAMPLINGFREQ_RTCCLK_DIV8192) || \
((FREQ) == RTC_TAMPERSAMPLINGFREQ_RTCCLK_DIV4096) || \
((FREQ) == RTC_TAMPERSAMPLINGFREQ_RTCCLK_DIV2048) || \
((FREQ) == RTC_TAMPERSAMPLINGFREQ_RTCCLK_DIV1024) || \
((FREQ) == RTC_TAMPERSAMPLINGFREQ_RTCCLK_DIV512) || \
((FREQ) == RTC_TAMPERSAMPLINGFREQ_RTCCLK_DIV256))
/**
* @}
*/
/** @defgroup RTCEx_Tamper_Pin_Precharge_Duration_Definitions
* @{
*/
#define RTC_TAMPERPRECHARGEDURATION_1RTCCLK ((uint32_t)0x00000000) /*!< Tamper pins are pre-charged before
sampling during 1 RTCCLK cycle */
#define RTC_TAMPERPRECHARGEDURATION_2RTCCLK ((uint32_t)0x00002000) /*!< Tamper pins are pre-charged before
sampling during 2 RTCCLK cycles */
#define RTC_TAMPERPRECHARGEDURATION_4RTCCLK ((uint32_t)0x00004000) /*!< Tamper pins are pre-charged before
sampling during 4 RTCCLK cycles */
#define RTC_TAMPERPRECHARGEDURATION_8RTCCLK ((uint32_t)0x00006000) /*!< Tamper pins are pre-charged before
sampling during 8 RTCCLK cycles */
#define IS_TAMPER_PRECHARGE_DURATION(DURATION) (((DURATION) == RTC_TAMPERPRECHARGEDURATION_1RTCCLK) || \
((DURATION) == RTC_TAMPERPRECHARGEDURATION_2RTCCLK) || \
((DURATION) == RTC_TAMPERPRECHARGEDURATION_4RTCCLK) || \
((DURATION) == RTC_TAMPERPRECHARGEDURATION_8RTCCLK))
/**
* @}
*/
/** @defgroup RTCEx_Tamper_TimeStampOnTamperDetection_Definitions
* @{
*/
#define RTC_TIMESTAMPONTAMPERDETECTION_ENABLE ((uint32_t)RTC_TAMPCR_TAMPTS) /*!< TimeStamp on Tamper Detection event saved */
#define RTC_TIMESTAMPONTAMPERDETECTION_DISABLE ((uint32_t)0x00000000) /*!< TimeStamp on Tamper Detection event is not saved */
#define IS_TAMPER_TIMESTAMPONTAMPER_DETECTION(DETECTION) (((DETECTION) == RTC_TIMESTAMPONTAMPERDETECTION_ENABLE) || \
((DETECTION) == RTC_TIMESTAMPONTAMPERDETECTION_DISABLE))
/**
* @}
*/
/** @defgroup RTCEx_Tamper_PullUP_Definitions
* @{
*/
#define RTC_TAMPER_PULLUP_ENABLE ((uint32_t)0x00000000) /*!< TimeStamp on Tamper Detection event saved */
#define RTC_TAMPER_PULLUP_DISABLE ((uint32_t)RTC_TAMPCR_TAMPPUDIS) /*!< TimeStamp on Tamper Detection event is not saved */
#define IS_TAMPER_PULLUP_STATE(STATE) (((STATE) == RTC_TAMPER_PULLUP_ENABLE) || \
((STATE) == RTC_TAMPER_PULLUP_DISABLE))
/**
* @}
*/
/** @defgroup RTCEx_Wakeup_Timer_Definitions
* @{
*/
#define RTC_WAKEUPCLOCK_RTCCLK_DIV16 ((uint32_t)0x00000000)
#define RTC_WAKEUPCLOCK_RTCCLK_DIV8 ((uint32_t)0x00000001)
#define RTC_WAKEUPCLOCK_RTCCLK_DIV4 ((uint32_t)0x00000002)
#define RTC_WAKEUPCLOCK_RTCCLK_DIV2 ((uint32_t)0x00000003)
#define RTC_WAKEUPCLOCK_CK_SPRE_16BITS ((uint32_t)0x00000004)
#define RTC_WAKEUPCLOCK_CK_SPRE_17BITS ((uint32_t)0x00000006)
#define IS_WAKEUP_CLOCK(CLOCK) (((CLOCK) == RTC_WAKEUPCLOCK_RTCCLK_DIV16) || \
((CLOCK) == RTC_WAKEUPCLOCK_RTCCLK_DIV8) || \
((CLOCK) == RTC_WAKEUPCLOCK_RTCCLK_DIV4) || \
((CLOCK) == RTC_WAKEUPCLOCK_RTCCLK_DIV2) || \
((CLOCK) == RTC_WAKEUPCLOCK_CK_SPRE_16BITS) || \
((CLOCK) == RTC_WAKEUPCLOCK_CK_SPRE_17BITS))
#define IS_WAKEUP_COUNTER(COUNTER) ((COUNTER) <= 0xFFFF)
/**
* @}
*/
/** @defgroup RTCEx_Digital_Calibration_Definitions
* @{
*/
#define RTC_CALIBSIGN_POSITIVE ((uint32_t)0x00000000)
#define RTC_CALIBSIGN_NEGATIVE ((uint32_t)0x00000080)
#define IS_RTC_CALIB_SIGN(SIGN) (((SIGN) == RTC_CALIBSIGN_POSITIVE) || \
((SIGN) == RTC_CALIBSIGN_NEGATIVE))
#define IS_RTC_CALIB_VALUE(VALUE) ((VALUE) < 0x20)
/**
* @}
*/
/** @defgroup RTCEx_Smooth_calib_period_Definitions
* @{
*/
#define RTC_SMOOTHCALIB_PERIOD_32SEC ((uint32_t)0x00000000) /*!< If RTCCLK = 32768 Hz, Smooth calibation
period is 32s, else 2exp20 RTCCLK seconds */
#define RTC_SMOOTHCALIB_PERIOD_16SEC ((uint32_t)0x00002000) /*!< If RTCCLK = 32768 Hz, Smooth calibation
period is 16s, else 2exp19 RTCCLK seconds */
#define RTC_SMOOTHCALIB_PERIOD_8SEC ((uint32_t)0x00004000) /*!< If RTCCLK = 32768 Hz, Smooth calibation
period is 8s, else 2exp18 RTCCLK seconds */
#define IS_RTC_SMOOTH_CALIB_PERIOD(PERIOD) (((PERIOD) == RTC_SMOOTHCALIB_PERIOD_32SEC) || \
((PERIOD) == RTC_SMOOTHCALIB_PERIOD_16SEC) || \
((PERIOD) == RTC_SMOOTHCALIB_PERIOD_8SEC))
/**
* @}
*/
/** @defgroup RTCEx_Smooth_calib_Plus_pulses_Definitions
* @{
*/
#define RTC_SMOOTHCALIB_PLUSPULSES_SET ((uint32_t)0x00008000) /*!< The number of RTCCLK pulses added
during a X -second window = Y - CALM[8:0]
with Y = 512, 256, 128 when X = 32, 16, 8 */
#define RTC_SMOOTHCALIB_PLUSPULSES_RESET ((uint32_t)0x00000000) /*!< The number of RTCCLK pulses subbstited
during a 32-second window = CALM[8:0] */
#define IS_RTC_SMOOTH_CALIB_PLUS(PLUS) (((PLUS) == RTC_SMOOTHCALIB_PLUSPULSES_SET) || \
((PLUS) == RTC_SMOOTHCALIB_PLUSPULSES_RESET))
/**
* @}
*/
/** @defgroup RTCEx_Smooth_calib_Minus_pulses_Definitions
* @{
*/
#define IS_RTC_SMOOTH_CALIB_MINUS(VALUE) ((VALUE) <= 0x000001FF)
/**
* @}
*/
/** @defgroup RTCEx_Add_1_Second_Parameter_Definitions
* @{
*/
#define RTC_SHIFTADD1S_RESET ((uint32_t)0x00000000)
#define RTC_SHIFTADD1S_SET ((uint32_t)0x80000000)
#define IS_RTC_SHIFT_ADD1S(SEL) (((SEL) == RTC_SHIFTADD1S_RESET) || \
((SEL) == RTC_SHIFTADD1S_SET))
/**
* @}
*/
/** @defgroup RTCEx_Substract_Fraction_Of_Second_Value
* @{
*/
#define IS_RTC_SHIFT_SUBFS(FS) ((FS) <= 0x00007FFF)
/**
* @}
*/
/** @defgroup RTCEx_Calib_Output_selection_Definitions
* @{
*/
#define RTC_CALIBOUTPUT_512HZ ((uint32_t)0x00000000)
#define RTC_CALIBOUTPUT_1HZ ((uint32_t)0x00080000)
#define IS_RTC_CALIB_OUTPUT(OUTPUT) (((OUTPUT) == RTC_CALIBOUTPUT_512HZ) || \
((OUTPUT) == RTC_CALIBOUTPUT_1HZ))
/**
* @}
*/
/**
* @}
*/
/* Exported macro ------------------------------------------------------------*/
/** @defgroup RTCEx_Exported macro
* @{
*/
/**
* @brief Enable the RTC WakeUp Timer peripheral.
* @param __HANDLE__: specifies the RTC handle.
* @retval None
*/
#define __HAL_RTC_WAKEUPTIMER_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR |= (RTC_CR_WUTE))
/**
* @brief Disable the RTC WakeUp Timer peripheral.
* @param __HANDLE__: specifies the RTC handle.
* @retval None
*/
#define __HAL_RTC_WAKEUPTIMER_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR &= ~(RTC_CR_WUTE))
/**
* @brief Enable the RTC TimeStamp peripheral.
* @param __HANDLE__: specifies the RTC handle.
* @retval None
*/
#define __HAL_RTC_TIMESTAMP_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR |= (RTC_CR_TSE))
/**
* @brief Disable the RTC TimeStamp peripheral.
* @param __HANDLE__: specifies the RTC handle.
* @retval None
*/
#define __HAL_RTC_TIMESTAMP_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR &= ~(RTC_CR_TSE))
/**
* @brief Enable the RTC calibration output.
* @param __HANDLE__: specifies the RTC handle.
* @retval None
*/
#define __HAL_RTC_CALIBRATION_OUTPUT_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR |= (RTC_CR_COE))
/**
* @brief Disable the calibration output.
* @param __HANDLE__: specifies the RTC handle.
* @retval None
*/
#define __HAL_RTC_CALIBRATION_OUTPUT_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR &= ~(RTC_CR_COE))
/**
* @brief Enable the clock reference detection.
* @param __HANDLE__: specifies the RTC handle.
* @retval None
*/
#define __HAL_RTC_CLOCKREF_DETECTION_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR |= (RTC_CR_REFCKON))
/**
* @brief Disable the clock reference detection.
* @param __HANDLE__: specifies the RTC handle.
* @retval None
*/
#define __HAL_RTC_CLOCKREF_DETECTION_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR &= ~(RTC_CR_REFCKON))
/**
* @brief Enable the RTC TimeStamp interrupt.
* @param __HANDLE__: specifies the RTC handle.
* @param __INTERRUPT__: specifies the RTC TimeStamp interrupt sources to be enabled or disabled.
* This parameter can be:
* @arg RTC_IT_TS: TimeStamp interrupt
* @retval None
*/
#define __HAL_RTC_TIMESTAMP_ENABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->CR |= (__INTERRUPT__))
/**
* @brief Disable the RTC TimeStamp interrupt.
* @param __HANDLE__: specifies the RTC handle.
* @param __INTERRUPT__: specifies the RTC TimeStamp interrupt sources to be enabled or disabled.
* This parameter can be:
* @arg RTC_IT_TS: TimeStamp interrupt
* @retval None
*/
#define __HAL_RTC_TIMESTAMP_DISABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->CR &= ~(__INTERRUPT__))
/**
* @brief Enable the RTC WakeUpTimer interrupt.
* @param __HANDLE__: specifies the RTC handle.
* @param __INTERRUPT__: specifies the RTC WakeUpTimer interrupt sources to be enabled or disabled.
* This parameter can be:
* @arg RTC_IT_WUT: WakeUpTimer A interrupt
* @retval None
*/
#define __HAL_RTC_WAKEUPTIMER_ENABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->CR |= (__INTERRUPT__))
/**
* @brief Disable the RTC WakeUpTimer interrupt.
* @param __HANDLE__: specifies the RTC handle.
* @param __INTERRUPT__: specifies the RTC WakeUpTimer interrupt sources to be enabled or disabled.
* This parameter can be:
* @arg RTC_IT_WUT: WakeUpTimer A interrupt
* @retval None
*/
#define __HAL_RTC_WAKEUPTIMER_DISABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->CR &= ~(__INTERRUPT__))
/**
* @brief Check whether the specified RTC Tamper interrupt has occurred or not.
* @param __HANDLE__: specifies the RTC handle.
* @param __FLAG__: specifies the RTC Tamper interrupt sources to be enabled or disabled.
* This parameter can be:
* @arg RTC_IT_TAMP1
* @retval None
*/
#define __HAL_RTC_TAMPER_GET_IT(__HANDLE__, __FLAG__) (((((__HANDLE__)->Instance->ISR) & ((__FLAG__)>> 4)) != RESET)? SET : RESET)
/**
* @brief Check whether the specified RTC WakeUpTimer interrupt has occurred or not.
* @param __HANDLE__: specifies the RTC handle.
* @param __FLAG__: specifies the RTC WakeUpTimer interrupt sources to be enabled or disabled.
* This parameter can be:
* @arg RTC_IT_WUT: WakeUpTimer A interrupt
* @retval None
*/
#define __HAL_RTC_WAKEUPTIMER_GET_IT(__HANDLE__, __FLAG__) (((((__HANDLE__)->Instance->ISR) & ((__FLAG__)>> 4)) != RESET)? SET : RESET)
/**
* @brief Check whether the specified RTC TimeStamp interrupt has occurred or not.
* @param __HANDLE__: specifies the RTC handle.
* @param __FLAG__: specifies the RTC TimeStamp interrupt sources to be enabled or disabled.
* This parameter can be:
* @arg RTC_IT_TS: TimeStamp interrupt
* @retval None
*/
#define __HAL_RTC_TIMESTAMP_GET_IT(__HANDLE__, __FLAG__) (((((__HANDLE__)->Instance->ISR) & ((__FLAG__)>> 4)) != RESET)? SET : RESET)
/**
* @brief Get the selected RTC TimeStamp's flag status.
* @param __HANDLE__: specifies the RTC handle.
* @param __FLAG__: specifies the RTC TimeStamp Flag sources to be enabled or disabled.
* This parameter can be:
* @arg RTC_FLAG_TSF
* @arg RTC_FLAG_TSOVF
* @retval None
*/
#define __HAL_RTC_TIMESTAMP_GET_FLAG(__HANDLE__, __FLAG__) (((((__HANDLE__)->Instance->ISR) & (__FLAG__)) != RESET)? SET : RESET)
/**
* @brief Get the selected RTC WakeUpTimer's flag status.
* @param __HANDLE__: specifies the RTC handle.
* @param __FLAG__: specifies the RTC WakeUpTimer Flag sources to be enabled or disabled.
* This parameter can be:
* @arg RTC_FLAG_WUTF
* @arg RTC_FLAG_WUTWF
* @retval None
*/
#define __HAL_RTC_WAKEUPTIMER_GET_FLAG(__HANDLE__, __FLAG__) (((((__HANDLE__)->Instance->ISR) & (__FLAG__)) != RESET)? SET : RESET)
/**
* @brief Get the selected RTC Tamper's flag status.
* @param __HANDLE__: specifies the RTC handle.
* @param __FLAG__: specifies the RTC Tamper Flag sources to be enabled or disabled.
* This parameter can be:
* @arg RTC_FLAG_TAMP1F
* @retval None
*/
#define __HAL_RTC_TAMPER_GET_FLAG(__HANDLE__, __FLAG__) (((((__HANDLE__)->Instance->ISR) & (__FLAG__)) != RESET)? SET : RESET)
/**
* @brief Get the selected RTC shift operation's flag status.
* @param __HANDLE__: specifies the RTC handle.
* @param __FLAG__: specifies the RTC shift operation Flag is pending or not.
* This parameter can be:
* @arg RTC_FLAG_SHPF
* @retval None
*/
#define __HAL_RTC_SHIFT_GET_FLAG(__HANDLE__, __FLAG__) (((((__HANDLE__)->Instance->ISR) & (__FLAG__)) != RESET)? SET : RESET)
/**
* @brief Clear the RTC Time Stamp's pending flags.
* @param __HANDLE__: specifies the RTC handle.
* @param __FLAG__: specifies the RTC Alarm Flag sources to be enabled or disabled.
* This parameter can be:
* @arg RTC_FLAG_TSF
* @retval None
*/
#define __HAL_RTC_TIMESTAMP_CLEAR_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->ISR) = (~(((__FLAG__) | RTC_ISR_INIT)& 0x0000FFFF)|((__HANDLE__)->Instance->ISR & RTC_ISR_INIT))
/**
* @brief Clear the RTC Tamper's pending flags.
* @param __HANDLE__: specifies the RTC handle.
* @param __FLAG__: specifies the RTC Tamper Flag sources to be enabled or disabled.
* This parameter can be:
* @arg RTC_FLAG_TAMP1F
* @retval None
*/
#define __HAL_RTC_TAMPER_CLEAR_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->ISR) = (~(((__FLAG__) | RTC_ISR_INIT)& 0x0000FFFF)|((__HANDLE__)->Instance->ISR & RTC_ISR_INIT))
/**
* @brief Clear the RTC Wake Up timer's pending flags.
* @param __HANDLE__: specifies the RTC handle.
* @param __FLAG__: specifies the RTC Tamper Flag sources to be enabled or disabled.
* This parameter can be:
* @arg RTC_FLAG_WUTF
* @retval None
*/
#define __HAL_RTC_WAKEUPTIMER_CLEAR_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->ISR) = (~(((__FLAG__) | RTC_ISR_INIT)& 0x0000FFFF)|((__HANDLE__)->Instance->ISR & RTC_ISR_INIT))
/**
* @}
*/
/* Exported functions --------------------------------------------------------*/
/* RTC TimeStamp and Tamper functions *****************************************/
HAL_StatusTypeDef HAL_RTCEx_SetTimeStamp(RTC_HandleTypeDef *hrtc, uint32_t TimeStampEdge, uint32_t RTC_TimeStampPin);
HAL_StatusTypeDef HAL_RTCEx_SetTimeStamp_IT(RTC_HandleTypeDef *hrtc, uint32_t TimeStampEdge, uint32_t RTC_TimeStampPin);
HAL_StatusTypeDef HAL_RTCEx_DeactivateTimeStamp(RTC_HandleTypeDef *hrtc);
HAL_StatusTypeDef HAL_RTCEx_GetTimeStamp(RTC_HandleTypeDef *hrtc, RTC_TimeTypeDef *sTimeStamp, RTC_DateTypeDef *sTimeStampDate, uint32_t Format);
HAL_StatusTypeDef HAL_RTCEx_SetTamper(RTC_HandleTypeDef *hrtc, RTC_TamperTypeDef* sTamper);
HAL_StatusTypeDef HAL_RTCEx_SetTamper_IT(RTC_HandleTypeDef *hrtc, RTC_TamperTypeDef* sTamper);
HAL_StatusTypeDef HAL_RTCEx_DeactivateTamper(RTC_HandleTypeDef *hrtc, uint32_t Tamper);
HAL_StatusTypeDef HAL_RTCEx_SetWakeUpTimer(RTC_HandleTypeDef *hrtc, uint32_t WakeUpCounter, uint32_t WakeUpClock);
HAL_StatusTypeDef HAL_RTCEx_SetWakeUpTimer_IT(RTC_HandleTypeDef *hrtc, uint32_t WakeUpCounter, uint32_t WakeUpClock);
uint32_t HAL_RTCEx_DeactivateWakeUpTimer(RTC_HandleTypeDef *hrtc);
uint32_t HAL_RTCEx_GetWakeUpTimer(RTC_HandleTypeDef *hrtc);
void HAL_RTCEx_BKUPWrite(RTC_HandleTypeDef *hrtc, uint32_t BackupRegister, uint32_t Data);
uint32_t HAL_RTCEx_BKUPRead(RTC_HandleTypeDef *hrtc, uint32_t BackupRegister);
HAL_StatusTypeDef HAL_RTCEx_SetSmoothCalib(RTC_HandleTypeDef *hrtc, uint32_t SmoothCalibPeriod, uint32_t SmoothCalibPlusPulses, uint32_t SmouthCalibMinusPulsesValue);
HAL_StatusTypeDef HAL_RTCEx_SetSynchroShift(RTC_HandleTypeDef *hrtc, uint32_t ShiftAdd1S, uint32_t ShiftSubFS);
HAL_StatusTypeDef HAL_RTCEx_SetCalibrationOutPut(RTC_HandleTypeDef *hrtc, uint32_t CalibOutput);
HAL_StatusTypeDef HAL_RTCEx_DeactivateCalibrationOutPut(RTC_HandleTypeDef *hrtc);
HAL_StatusTypeDef HAL_RTCEx_SetRefClock(RTC_HandleTypeDef *hrtc);
HAL_StatusTypeDef HAL_RTCEx_DeactivateRefClock(RTC_HandleTypeDef *hrtc);
HAL_StatusTypeDef HAL_RTCEx_EnableBypassShadow(RTC_HandleTypeDef *hrtc);
HAL_StatusTypeDef HAL_RTCEx_DisableBypassShadow(RTC_HandleTypeDef *hrtc);
/* Peripheral State functions ***************************************************/
void HAL_RTCEx_TamperTimeStampIRQHandler(RTC_HandleTypeDef *hrtc);
void HAL_RTCEx_WakeUpTimerIRQHandler(RTC_HandleTypeDef *hrtc);
void HAL_RTCEx_AlarmBEventCallback(RTC_HandleTypeDef *hrtc);
void HAL_RTCEx_TimeStampEventCallback(RTC_HandleTypeDef *hrtc);
void HAL_RTCEx_WakeUpTimerEventCallback(RTC_HandleTypeDef *hrtc);
void HAL_RTCEx_Tamper1EventCallback(RTC_HandleTypeDef *hrtc);
void HAL_RTCEx_Tamper2EventCallback(RTC_HandleTypeDef *hrtc);
HAL_StatusTypeDef HAL_RTCEx_PollForAlarmBEvent(RTC_HandleTypeDef *hrtc, uint32_t Timeout);
HAL_StatusTypeDef HAL_RTCEx_PollForTimeStampEvent(RTC_HandleTypeDef *hrtc, uint32_t Timeout);
HAL_StatusTypeDef HAL_RTCEx_PollForTamper1Event(RTC_HandleTypeDef *hrtc, uint32_t Timeout);
HAL_StatusTypeDef HAL_RTCEx_PollForTamper2Event(RTC_HandleTypeDef *hrtc, uint32_t Timeout);
HAL_StatusTypeDef HAL_RTCEx_PollForWakeUpTimerEvent(RTC_HandleTypeDef *hrtc, uint32_t Timeout);
/**
* @}
*/
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif /* __STM32L0xx_HAL_PWR_EX_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,799 @@
/**
******************************************************************************
* @file stm32l0xx_hal_smartcard.h
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief Header file of SMARTCARD HAL module.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32L0xx_HAL_SMARTCARD_H
#define __STM32L0xx_HAL_SMARTCARD_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal_def.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @addtogroup SMARTCARD
* @{
*/
/* Exported types ------------------------------------------------------------*/
/**
* @brief SMARTCARD Init Structure definition
*/
typedef struct
{
uint32_t BaudRate; /*!< Configures the SmartCard communication baud rate.
The baud rate register is computed using the following formula:
Baud Rate Register = ((PCLKx) / ((hsc->Init.BaudRate))) */
uint32_t WordLength; /*!< Specifies the number of data bits transmitted or received in a frame.
This parameter @ref SMARTCARD_Word_Length can only be set to 9 (8 data + 1 parity bits). */
uint32_t StopBits; /*!< Specifies the number of stop bits @ref SMARTCARD_Stop_Bits.
Only 1.5 stop bits are authorized in SmartCard mode. */
uint32_t Parity; /*!< Specifies the parity mode.
This parameter can be a value of @ref SMARTCARD_Parity
@note The parity is enabled by default (PCE is forced to 1).
Since the WordLength is forced to 8 bits + parity, M is
forced to 1 and the parity bit is the 9th bit. */
uint32_t Mode; /*!< Specifies whether the Receive or Transmit mode is enabled or disabled.
This parameter can be a value of @ref SMARTCARD_Mode */
uint32_t CLKPolarity; /*!< Specifies the steady state of the serial clock.
This parameter can be a value of @ref SMARTCARD_Clock_Polarity */
uint32_t CLKPhase; /*!< Specifies the clock transition on which the bit capture is made.
This parameter can be a value of @ref SMARTCARD_Clock_Phase */
uint32_t CLKLastBit; /*!< Specifies whether the clock pulse corresponding to the last transmitted
data bit (MSB) has to be output on the SCLK pin in synchronous mode.
This parameter can be a value of @ref SMARTCARD_Last_Bit */
uint32_t OneBitSampling; /*!< Specifies wether a single sample or three samples' majority vote is selected.
Selecting the single sample method increases the receiver tolerance to clock
deviations. This parameter can be a value of @ref SMARTCARD_OneBit_Sampling */
uint32_t Prescaler; /*!< Specifies the SmartCard Prescaler */
uint32_t GuardTime; /*!< Specifies the SmartCard Guard Time */
uint32_t NACKState; /*!< Specifies whether the SmartCard NACK transmission is enabled
in case of parity error.
This parameter can be a value of @ref SMARTCARD_NACK_Enable */
uint32_t TimeOutEnable; /*!< Specifies whether the receiver timeout is enabled.
This parameter can be a value of @ref SMARTCARD_Timeout_Enable*/
uint32_t TimeOutValue; /*!< Specifies the receiver time out value in number of baud blocks:
it is used to implement the Character Wait Time (CWT) and
Block Wait Time (BWT). It is coded over 24 bits. */
uint32_t BlockLength; /*!< Specifies the SmartCard Block Length in T=1 Reception mode.
This parameter can be any value from 0x0 to 0xFF */
uint32_t AutoRetryCount; /*!< Specifies the SmartCard auto-retry count (number of retries in
receive and transmit mode). When set to 0, retransmission is
disabled. Otherwise, its maximum value is 7 (before signalling
an error) */
}SMARTCARD_InitTypeDef;
/**
* @brief SMARTCARD advanced features initalization structure definition
*/
typedef struct
{
uint32_t AdvFeatureInit; /*!< Specifies which advanced SMARTCARD features is initialized. Several
advanced features may be initialized at the same time. This parameter
can be a value of @ref SMARTCARD_Advanced_Features_Initialization_Type */
uint32_t TxPinLevelInvert; /*!< Specifies whether the TX pin active level is inverted.
This parameter can be a value of @ref SMARTCARD_Tx_Inv */
uint32_t RxPinLevelInvert; /*!< Specifies whether the RX pin active level is inverted.
This parameter can be a value of @ref SMARTCARD_Rx_Inv */
uint32_t DataInvert; /*!< Specifies whether data are inverted (positive/direct logic
vs negative/inverted logic).
This parameter can be a value of @ref SMARTCARD_Data_Inv */
uint32_t Swap; /*!< Specifies whether TX and RX pins are swapped.
This parameter can be a value of @ref SMARTCARD_Rx_Tx_Swap */
uint32_t OverrunDisable; /*!< Specifies whether the reception overrun detection is disabled.
This parameter can be a value of @ref SMARTCARD_Overrun_Disable */
uint32_t DMADisableonRxError; /*!< Specifies whether the DMA is disabled in case of reception error.
This parameter can be a value of @ref SMARTCARD_DMA_Disable_on_Rx_Error */
uint32_t MSBFirst; /*!< Specifies whether MSB is sent first on UART line.
This parameter can be a value of @ref SMARTCARD_MSB_First */
}SMARTCARD_AdvFeatureInitTypeDef;
/**
* @brief HAL State structures definition
*/
typedef enum
{
HAL_SMARTCARD_STATE_RESET = 0x00, /*!< Peripheral is not yet Initialized */
HAL_SMARTCARD_STATE_READY = 0x01, /*!< Peripheral Initialized and ready for use */
HAL_SMARTCARD_STATE_BUSY = 0x02, /*!< an internal process is ongoing */
HAL_SMARTCARD_STATE_BUSY_TX = 0x12, /*!< Data Transmission process is ongoing */
HAL_SMARTCARD_STATE_BUSY_RX = 0x22, /*!< Data Reception process is ongoing */
HAL_SMARTCARD_STATE_BUSY_TX_RX = 0x32, /*!< Data Transmission and Reception process is ongoing */
HAL_SMARTCARD_STATE_TIMEOUT = 0x03, /*!< Timeout state */
HAL_SMARTCARD_STATE_ERROR = 0x04 /*!< Error */
}HAL_SMARTCARD_StateTypeDef;
/**
* @brief HAL SMARTCARD Error Code structure definition
*/
typedef enum
{
HAL_SMARTCARD_ERROR_NONE = 0x00, /*!< No error */
HAL_SMARTCARD_ERROR_PE = 0x01, /*!< Parity error */
HAL_SMARTCARD_ERROR_NE = 0x02, /*!< Noise error */
HAL_SMARTCARD_ERROR_FE = 0x04, /*!< frame error */
HAL_SMARTCARD_ERROR_ORE = 0x08, /*!< Overrun error */
HAL_SMARTCARD_ERROR_DMA = 0x10, /*!< DMA transfer error */
HAL_SMARTCARD_ERROR_RTO = 0x20 /*!< Receiver TimeOut error */
}HAL_SMARTCARD_ErrorTypeDef;
/**
* @brief SMARTCARD clock sources definition
*/
typedef enum
{
SMARTCARD_CLOCKSOURCE_PCLK1 = 0x00, /*!< PCLK1 clock source */
SMARTCARD_CLOCKSOURCE_PCLK2 = 0x01, /*!< PCLK2 clock source */
SMARTCARD_CLOCKSOURCE_HSI = 0x02, /*!< HSI clock source */
SMARTCARD_CLOCKSOURCE_SYSCLK = 0x04, /*!< SYSCLK clock source */
SMARTCARD_CLOCKSOURCE_LSE = 0x08 /*!< LSE clock source */
}SMARTCARD_ClockSourceTypeDef;
/**
* @brief SMARTCARD handle Structure definition
*/
typedef struct
{
USART_TypeDef *Instance; /* USART registers base address */
SMARTCARD_InitTypeDef Init; /* SmartCard communication parameters */
SMARTCARD_AdvFeatureInitTypeDef AdvancedInit; /* SmartCard advanced features initialization parameters */
uint8_t *pTxBuffPtr; /* Pointer to SmartCard Tx transfer Buffer */
uint16_t TxXferSize; /* SmartCard Tx Transfer size */
uint16_t TxXferCount; /* SmartCard Tx Transfer Counter */
uint8_t *pRxBuffPtr; /* Pointer to SmartCard Rx transfer Buffer */
uint16_t RxXferSize; /* SmartCard Rx Transfer size */
uint16_t RxXferCount; /* SmartCard Rx Transfer Counter */
DMA_HandleTypeDef *hdmatx; /* SmartCard Tx DMA Handle parameters */
DMA_HandleTypeDef *hdmarx; /* SmartCard Rx DMA Handle parameters */
HAL_LockTypeDef Lock; /* Locking object */
__IO HAL_SMARTCARD_StateTypeDef State; /* SmartCard communication state */
__IO HAL_SMARTCARD_ErrorTypeDef ErrorCode; /* SmartCard Error code */
}SMARTCARD_HandleTypeDef;
/* Exported constants --------------------------------------------------------*/
/** @defgroup SMARTCARD_Exported_Constants
* @{
*/
/** @defgroup SMARTCARD_Word_Length
* @{
*/
#define SMARTCARD_WORDLENGTH_9B ((uint32_t)USART_CR1_M_0)
#define IS_SMARTCARD_WORD_LENGTH(LENGTH) ((LENGTH) == SMARTCARD_WORDLENGTH_9B)
/**
* @}
*/
/** @defgroup SMARTCARD_Stop_Bits
* @{
*/
#define SMARTCARD_STOPBITS_1_5 ((uint32_t)(USART_CR2_STOP))
#define IS_SMARTCARD_STOPBITS(STOPBITS) ((STOPBITS) == SMARTCARD_STOPBITS_1_5)
/**
* @}
*/
/** @defgroup SMARTCARD_Parity
* @{
*/
#define SMARTCARD_PARITY_EVEN ((uint32_t)USART_CR1_PCE)
#define SMARTCARD_PARITY_ODD ((uint32_t)(USART_CR1_PCE | USART_CR1_PS))
#define IS_SMARTCARD_PARITY(PARITY) (((PARITY) == SMARTCARD_PARITY_EVEN) || \
((PARITY) == SMARTCARD_PARITY_ODD))
/**
* @}
*/
/** @defgroup SMARTCARD_Mode
* @{
*/
#define SMARTCARD_MODE_RX ((uint32_t)USART_CR1_RE)
#define SMARTCARD_MODE_TX ((uint32_t)USART_CR1_TE)
#define SMARTCARD_MODE_TX_RX ((uint32_t)(USART_CR1_TE |USART_CR1_RE))
#define IS_SMARTCARD_MODE(MODE) ((((MODE) & (uint32_t)0xFFF3) == 0x00) && ((MODE) != (uint32_t)0x00))
/**
* @}
*/
/** @defgroup SMARTCARD_Clock_Polarity
* @{
*/
#define SMARTCARD_POLARITY_LOW ((uint32_t)0x0000)
#define SMARTCARD_POLARITY_HIGH ((uint32_t)USART_CR2_CPOL)
#define IS_SMARTCARD_POLARITY(CPOL) (((CPOL) == SMARTCARD_POLARITY_LOW) || ((CPOL) == SMARTCARD_POLARITY_HIGH))
/**
* @}
*/
/** @defgroup SMARTCARD_Clock_Phase
* @{
*/
#define SMARTCARD_PHASE_1EDGE ((uint32_t)0x0000)
#define SMARTCARD_PHASE_2EDGE ((uint32_t)USART_CR2_CPHA)
#define IS_SMARTCARD_PHASE(CPHA) (((CPHA) == SMARTCARD_PHASE_1EDGE) || ((CPHA) == SMARTCARD_PHASE_2EDGE))
/**
* @}
*/
/** @defgroup SMARTCARD_Last_Bit
* @{
*/
#define SMARTCARD_LASTBIT_DISABLE ((uint32_t)0x0000)
#define SMARTCARD_LASTBIT_ENABLE ((uint32_t)USART_CR2_LBCL)
#define IS_SMARTCARD_LASTBIT(LASTBIT) (((LASTBIT) == SMARTCARD_LASTBIT_DISABLE) || \
((LASTBIT) == SMARTCARD_LASTBIT_ENABLE))
/**
* @}
*/
/** @defgroup SMARTCARD_OneBit_Sampling
* @{
*/
#define SMARTCARD_ONEBIT_SAMPLING_DISABLED ((uint32_t)0x0000)
#define SMARTCARD_ONEBIT_SAMPLING_ENABLED ((uint32_t)USART_CR3_ONEBIT)
#define IS_SMARTCARD_ONEBIT_SAMPLING(ONEBIT) (((ONEBIT) == SMARTCARD_ONEBIT_SAMPLING_DISABLED) || \
((ONEBIT) == SMARTCARD_ONEBIT_SAMPLING_ENABLED))
/**
* @}
*/
/** @defgroup SMARTCARD_NACK_Enable
* @{
*/
#define SMARTCARD_NACK_ENABLED ((uint32_t)USART_CR3_NACK)
#define SMARTCARD_NACK_DISABLED ((uint32_t)0x0000)
#define IS_SMARTCARD_NACK(NACK) (((NACK) == SMARTCARD_NACK_ENABLED) || \
((NACK) == SMARTCARD_NACK_DISABLED))
/**
* @}
*/
/** @defgroup SMARTCARD_Timeout_Enable
* @{
*/
#define SMARTCARD_TIMEOUT_DISABLED ((uint32_t)0x00000000)
#define SMARTCARD_TIMEOUT_ENABLED ((uint32_t)USART_CR2_RTOEN)
#define IS_SMARTCARD_TIMEOUT(TIMEOUT) (((TIMEOUT) == SMARTCARD_TIMEOUT_DISABLED) || \
((TIMEOUT) == SMARTCARD_TIMEOUT_ENABLED))
/**
* @}
*/
/** @defgroup SmartCard_DMA_Requests
* @{
*/
#define SMARTCARD_DMAREQ_TX ((uint32_t)USART_CR3_DMAT)
#define SMARTCARD_DMAREQ_RX ((uint32_t)USART_CR3_DMAR)
/**
* @}
*/
/** @defgroup SMARTCARD_Advanced_Features_Initialization_Type
* @{
*/
#define SMARTCARD_ADVFEATURE_NO_INIT ((uint32_t)0x00000000)
#define SMARTCARD_ADVFEATURE_TXINVERT_INIT ((uint32_t)0x00000001)
#define SMARTCARD_ADVFEATURE_RXINVERT_INIT ((uint32_t)0x00000002)
#define SMARTCARD_ADVFEATURE_DATAINVERT_INIT ((uint32_t)0x00000004)
#define SMARTCARD_ADVFEATURE_SWAP_INIT ((uint32_t)0x00000008)
#define SMARTCARD_ADVFEATURE_RXOVERRUNDISABLE_INIT ((uint32_t)0x00000010)
#define SMARTCARD_ADVFEATURE_DMADISABLEONERROR_INIT ((uint32_t)0x00000020)
#define SMARTCARD_ADVFEATURE_MSBFIRST_INIT ((uint32_t)0x00000080)
#define IS_SMARTCARD_ADVFEATURE_INIT(INIT) ((INIT) <= (SMARTCARD_ADVFEATURE_NO_INIT | \
SMARTCARD_ADVFEATURE_TXINVERT_INIT | \
SMARTCARD_ADVFEATURE_RXINVERT_INIT | \
SMARTCARD_ADVFEATURE_DATAINVERT_INIT | \
SMARTCARD_ADVFEATURE_SWAP_INIT | \
SMARTCARD_ADVFEATURE_RXOVERRUNDISABLE_INIT | \
SMARTCARD_ADVFEATURE_DMADISABLEONERROR_INIT | \
SMARTCARD_ADVFEATURE_MSBFIRST_INIT))
/**
* @}
*/
/** @defgroup SMARTCARD_Tx_Inv
* @{
*/
#define SMARTCARD_ADVFEATURE_TXINV_DISABLE ((uint32_t)0x00000000)
#define SMARTCARD_ADVFEATURE_TXINV_ENABLE ((uint32_t)USART_CR2_TXINV)
#define IS_SMARTCARD_ADVFEATURE_TXINV(TXINV) (((TXINV) == SMARTCARD_ADVFEATURE_TXINV_DISABLE) || \
((TXINV) == SMARTCARD_ADVFEATURE_TXINV_ENABLE))
/**
* @}
*/
/** @defgroup SMARTCARD_Rx_Inv
* @{
*/
#define SMARTCARD_ADVFEATURE_RXINV_DISABLE ((uint32_t)0x00000000)
#define SMARTCARD_ADVFEATURE_RXINV_ENABLE ((uint32_t)USART_CR2_RXINV)
#define IS_SMARTCARD_ADVFEATURE_RXINV(RXINV) (((RXINV) == SMARTCARD_ADVFEATURE_RXINV_DISABLE) || \
((RXINV) == SMARTCARD_ADVFEATURE_RXINV_ENABLE))
/**
* @}
*/
/** @defgroup SMARTCARD_Data_Inv
* @{
*/
#define SMARTCARD_ADVFEATURE_DATAINV_DISABLE ((uint32_t)0x00000000)
#define SMARTCARD_ADVFEATURE_DATAINV_ENABLE ((uint32_t)USART_CR2_DATAINV)
#define IS_SMARTCARD_ADVFEATURE_DATAINV(DATAINV) (((DATAINV) == SMARTCARD_ADVFEATURE_DATAINV_DISABLE) || \
((DATAINV) == SMARTCARD_ADVFEATURE_DATAINV_ENABLE))
/**
* @}
*/
/** @defgroup SMARTCARD_Rx_Tx_Swap
* @{
*/
#define SMARTCARD_ADVFEATURE_SWAP_DISABLE ((uint32_t)0x00000000)
#define SMARTCARD_ADVFEATURE_SWAP_ENABLE ((uint32_t)USART_CR2_SWAP)
#define IS_SMARTCARD_ADVFEATURE_SWAP(SWAP) (((SWAP) == SMARTCARD_ADVFEATURE_SWAP_DISABLE) || \
((SWAP) == SMARTCARD_ADVFEATURE_SWAP_ENABLE))
/**
* @}
*/
/** @defgroup SMARTCARD_Overrun_Disable
* @{
*/
#define SMARTCARD_ADVFEATURE_OVERRUN_ENABLE ((uint32_t)0x00000000)
#define SMARTCARD_ADVFEATURE_OVERRUN_DISABLE ((uint32_t)USART_CR3_OVRDIS)
#define IS_SMARTCARD_OVERRUN(OVERRUN) (((OVERRUN) == SMARTCARD_ADVFEATURE_OVERRUN_ENABLE) || \
((OVERRUN) == SMARTCARD_ADVFEATURE_OVERRUN_DISABLE))
/**
* @}
*/
/** @defgroup SMARTCARD_DMA_Disable_on_Rx_Error
* @{
*/
#define SMARTCARD_ADVFEATURE_DMA_ENABLEONRXERROR ((uint32_t)0x00000000)
#define SMARTCARD_ADVFEATURE_DMA_DISABLEONRXERROR ((uint32_t)USART_CR3_DDRE)
#define IS_SMARTCARD_ADVFEATURE_DMAONRXERROR(DMA) (((DMA) == SMARTCARD_ADVFEATURE_DMA_ENABLEONRXERROR) || \
((DMA) == SMARTCARD_ADVFEATURE_DMA_DISABLEONRXERROR))
/**
* @}
*/
/** @defgroup SMARTCARD_MSB_First
* @{
*/
#define SMARTCARD_ADVFEATURE_MSBFIRST_DISABLE ((uint32_t)0x00000000)
#define SMARTCARD_ADVFEATURE_MSBFIRST_ENABLE ((uint32_t)USART_CR2_MSBFIRST)
#define IS_SMARTCARD_ADVFEATURE_MSBFIRST(MSBFIRST) (((MSBFIRST) == SMARTCARD_ADVFEATURE_MSBFIRST_DISABLE) || \
((MSBFIRST) == SMARTCARD_ADVFEATURE_MSBFIRST_ENABLE))
/**
* @}
*/
/** @defgroup SmartCard_Flags
* Elements values convention: 0xXXXX
* - 0xXXXX : Flag mask in the ISR register
* @{
*/
#define SMARTCARD_FLAG_REACK ((uint32_t)0x00400000)
#define SMARTCARD_FLAG_TEACK ((uint32_t)0x00200000)
#define SMARTCARD_FLAG_BUSY ((uint32_t)0x00010000)
#define SMARTCARD_FLAG_EOBF ((uint32_t)0x00001000)
#define SMARTCARD_FLAG_RTOF ((uint32_t)0x00000800)
#define SMARTCARD_FLAG_TXE ((uint32_t)0x00000080)
#define SMARTCARD_FLAG_TC ((uint32_t)0x00000040)
#define SMARTCARD_FLAG_RXNE ((uint32_t)0x00000020)
#define SMARTCARD_FLAG_ORE ((uint32_t)0x00000008)
#define SMARTCARD_FLAG_NE ((uint32_t)0x00000004)
#define SMARTCARD_FLAG_FE ((uint32_t)0x00000002)
#define SMARTCARD_FLAG_PE ((uint32_t)0x00000001)
/**
* @}
*/
/** @defgroup SMARTCARD_Interrupt_definition
* Elements values convention: 0000ZZZZ0XXYYYYYb
* - YYYYY : Interrupt source position in the XX register (5bits)
* - XX : Interrupt source register (2bits)
* - 01: CR1 register
* - 10: CR2 register
* - 11: CR3 register
* - ZZZZ : Flag position in the ISR register(4bits)
* @{
*/
#define SMARTCARD_IT_PE ((uint16_t)0x0028)
#define SMARTCARD_IT_TXE ((uint16_t)0x0727)
#define SMARTCARD_IT_TC ((uint16_t)0x0626)
#define SMARTCARD_IT_RXNE ((uint16_t)0x0525)
#define SMARTCARD_IT_ERR ((uint16_t)0x0060)
#define SMARTCARD_IT_ORE ((uint16_t)0x0300)
#define SMARTCARD_IT_NE ((uint16_t)0x0200)
#define SMARTCARD_IT_FE ((uint16_t)0x0100)
#define SMARTCARD_IT_EOB ((uint16_t)0x0C3B)
#define SMARTCARD_IT_RTO ((uint16_t)0x0B3A)
/**
* @}
*/
/** @defgroup SMARTCARD_IT_CLEAR_Flags
* @{
*/
#define SMARTCARD_CLEAR_PEF USART_ICR_PECF /*!< Parity Error Clear Flag */
#define SMARTCARD_CLEAR_FEF USART_ICR_FECF /*!< Framing Error Clear Flag */
#define SMARTCARD_CLEAR_NEF USART_ICR_NCF /*!< Noise detected Clear Flag */
#define SMARTCARD_CLEAR_OREF USART_ICR_ORECF /*!< OverRun Error Clear Flag */
#define SMARTCARD_CLEAR_TCF USART_ICR_TCCF /*!< Transmission Complete Clear Flag */
#define SMARTCARD_CLEAR_RTOF USART_ICR_RTOCF /*!< Receiver Time Out Clear Flag */
#define SMARTCARD_CLEAR_EOBF USART_ICR_EOBCF /*!< End Of Block Clear Flag */
/**
* @}
*/
/** @defgroup SMARTCARD_Request_Parameters
* @{
*/
#define SMARTCARD_RXDATA_FLUSH_REQUEST ((uint32_t)USART_RQR_RXFRQ) /*!< Receive Data flush Request */
#define SMARTCARD_TXDATA_FLUSH_REQUEST ((uint32_t)USART_RQR_TXFRQ) /*!< Transmit data flush Request */
#define IS_SMARTCARD_REQUEST_PARAMETER(PARAM) (((PARAM) == SMARTCARD_RXDATA_FLUSH_REQUEST) || \
((PARAM) == SMARTCARD_TXDATA_FLUSH_REQUEST))
/**
* @}
*/
/** @defgroup SMARTCARD_CR3_SCAR_CNT_LSB_POS
* @{
*/
#define SMARTCARD_CR3_SCARCNT_LSB_POS ((uint32_t) 17)
/**
* @}
*/
/** @defgroup SMARTCARD_GTPR_GT_LSBPOS
* @{
*/
#define SMARTCARD_GTPR_GT_LSB_POS ((uint32_t) 8)
/**
* @}
*/
/** @defgroup SMARTCARD_RTOR_BLEN_LSBPOS
* @{
*/
#define SMARTCARD_RTOR_BLEN_LSB_POS ((uint32_t) 24)
/**
* @}
*/
/** @defgroup SMARTCARD_Interruption_Mask
* @{
*/
#define SMARTCARD_IT_MASK ((uint16_t)0x001F)
/**
* @}
*/
/**
* @}
*/
/* Exported macro ------------------------------------------------------------*/
/** @defgroup SMARTCARD_Exported_Macros
* @{
*/
/** @brief Reset SMARTCARD handle state
* @param __HANDLE__: specifies the SMARTCARD Handle.
* The Handle Instance which can be USART1 or USART2
* @retval None
*/
#define __HAL_SMARTCARD_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_SMARTCARD_STATE_RESET)
/** @brief Flushs the Smartcard DR register
* @param __HANDLE__: specifies the SMARTCARD Handle.
* The Handle Instance which can be USART1 or USART2.
* @retval None
*/
#define __HAL_SMARTCARD_FLUSH_DRREGISTER(__HANDLE__) (__HAL_SMARTCARD_SEND_REQ((__HANDLE__), SMARTCARD_RXDATA_FLUSH_REQUEST))
/** @brief Checks whether the specified Smartcard flag is set or not.
* @param __HANDLE__: specifies the SMARTCARD Handle.
* The Handle Instance which can be USART1 or USART2.
* @param __FLAG__: specifies the flag to check.
* This parameter can be one of the following values:
* @arg SMARTCARD_FLAG_REACK: Receive enable ackowledge flag
* @arg SMARTCARD_FLAG_TEACK: Transmit enable ackowledge flag
* @arg SMARTCARD_FLAG_BUSY: Busy flag
* @arg SMARTCARD_FLAG_EOBF: End of block flag
* @arg SMARTCARD_FLAG_RTOF: Receiver timeout flag
* @arg SMARTCARD_FLAG_TXE: Transmit data register empty flag
* @arg SMARTCARD_FLAG_TC: Transmission Complete flag
* @arg SMARTCARD_FLAG_RXNE: Receive data register not empty flag
* @arg SMARTCARD_FLAG_ORE: OverRun Error flag
* @arg SMARTCARD_FLAG_NE: Noise Error flag
* @arg SMARTCARD_FLAG_FE: Framing Error flag
* @arg SMARTCARD_FLAG_PE: Parity Error flag
* @retval The new state of __FLAG__ (TRUE or FALSE).
*/
#define __HAL_SMARTCARD_GET_FLAG(__HANDLE__, __FLAG__) (((__HANDLE__)->Instance->ISR & (__FLAG__)) == (__FLAG__))
/** @brief Enables the specified SmartCard interrupt.
* @param __HANDLE__: specifies the SMARTCARD Handle.
* The Handle Instance which can be USART1 or USART2.
* @param __INTERRUPT__: specifies the SMARTCARD interrupt to enable.
* This parameter can be one of the following values:
* @arg SMARTCARD_IT_EOBF: End Of Block interrupt
* @arg SMARTCARD_IT_RTOF: Receive TimeOut interrupt
* @arg SMARTCARD_IT_TXE: Transmit Data Register empty interrupt
* @arg SMARTCARD_IT_TC: Transmission complete interrupt
* @arg SMARTCARD_IT_RXNE: Receive Data register not empty interrupt
* @arg SMARTCARD_IT_PE: Parity Error interrupt
* @arg SMARTCARD_IT_ERR: Error interrupt(Frame error, noise error, overrun error)
* @retval None
*/
#define __HAL_SMARTCARD_ENABLE_IT(__HANDLE__, __INTERRUPT__) (((((uint8_t)(__INTERRUPT__)) >> 5) == 1)? ((__HANDLE__)->Instance->CR1 |= (1 << ((__INTERRUPT__) & SMARTCARD_IT_MASK))): \
((((uint8_t)(__INTERRUPT__)) >> 5) == 2)? ((__HANDLE__)->Instance->CR2 |= (1 << ((__INTERRUPT__) & SMARTCARD_IT_MASK))): \
((__HANDLE__)->Instance->CR3 |= (1 << ((__INTERRUPT__) & SMARTCARD_IT_MASK))))
/** @brief Disables the specified SmartCard interrupt.
* @param __HANDLE__: specifies the SMARTCARD Handle.
* The Handle Instance which can be USART1 or USART2.
* @param __INTERRUPT__: specifies the SMARTCARD interrupt to enable.
* This parameter can be one of the following values:
* @arg SMARTCARD_IT_EOBF: End Of Block interrupt
* @arg SMARTCARD_IT_RTOF: Receive TimeOut interrupt
* @arg SMARTCARD_IT_TXE: Transmit Data Register empty interrupt
* @arg SMARTCARD_IT_TC: Transmission complete interrupt
* @arg SMARTCARD_IT_RXNE: Receive Data register not empty interrupt
* @arg SMARTCARD_IT_PE: Parity Error interrupt
* @arg SMARTCARD_IT_ERR: Error interrupt(Frame error, noise error, overrun error)
* @retval None
*/
#define __HAL_SMARTCARD_DISABLE_IT(__HANDLE__, __INTERRUPT__) (((((uint8_t)(__INTERRUPT__)) >> 5) == 1)? ((__HANDLE__)->Instance->CR1 &= ~ ((uint32_t)1 << ((__INTERRUPT__) & SMARTCARD_IT_MASK))): \
((((uint8_t)(__INTERRUPT__)) >> 5) == 2)? ((__HANDLE__)->Instance->CR2 &= ~ ((uint32_t)1 << ((__INTERRUPT__) & SMARTCARD_IT_MASK))): \
((__HANDLE__)->Instance->CR3 &= ~ ((uint32_t)1 << ((__INTERRUPT__) & SMARTCARD_IT_MASK))))
/** @brief Checks whether the specified SmartCard interrupt has occurred or not.
* @param __HANDLE__: specifies the SMARTCARD Handle.
* The Handle Instance which can be USART1 or USART2.
* @param __IT__: specifies the SMARTCARD interrupt to check.
* This parameter can be one of the following values:
* @arg SMARTCARD_IT_EOBF: End Of Block interrupt
* @arg SMARTCARD_IT_RTOF: Receive TimeOut interrupt
* @arg SMARTCARD_IT_TXE: Transmit Data Register empty interrupt
* @arg SMARTCARD_IT_TC: Transmission complete interrupt
* @arg SMARTCARD_IT_RXNE: Receive Data register not empty interrupt
* @arg SMARTCARD_IT_ORE: OverRun Error interrupt
* @arg SMARTCARD_IT_NE: Noise Error interrupt
* @arg SMARTCARD_IT_FE: Framing Error interrupt
* @arg SMARTCARD_IT_PE: Parity Error interrupt
* @retval The new state of __IT__ (TRUE or FALSE).
*/
#define __HAL_SMARTCARD_GET_IT(__HANDLE__, __IT__) ((__HANDLE__)->Instance->ISR & ((uint32_t)1 << ((__IT__)>> 0x08)))
/** @brief Checks whether the specified SmartCard interrupt interrupt source is enabled.
* @param __HANDLE__: specifies the SMARTCARD Handle.
* The Handle Instance which can be USART1 or USART2.
* @param __IT__: specifies the SMARTCARD interrupt source to check.
* This parameter can be one of the following values:
* @arg SMARTCARD_IT_EOBF: End Of Block interrupt
* @arg SMARTCARD_IT_RTOF: Receive TimeOut interrupt
* @arg SMARTCARD_IT_TXE: Transmit Data Register empty interrupt
* @arg SMARTCARD_IT_TC: Transmission complete interrupt
* @arg SMARTCARD_IT_RXNE: Receive Data register not empty interrupt
* @arg SMARTCARD_IT_ORE: OverRun Error interrupt
* @arg SMARTCARD_IT_NE: Noise Error interrupt
* @arg SMARTCARD_IT_FE: Framing Error interrupt
* @arg SMARTCARD_IT_PE: Parity Error interrupt
* @retval The new state of __IT__ (TRUE or FALSE).
*/
#define __HAL_SMARTCARD_GET_IT_SOURCE(__HANDLE__, __IT__) ((((((uint8_t)(__IT__)) >> 5) == 1)? (__HANDLE__)->Instance->CR1:(((((uint8_t)(__IT__)) >> 5) == 2)? \
(__HANDLE__)->Instance->CR2 : (__HANDLE__)->Instance->CR3)) & ((uint32_t)1 << \
(((uint16_t)(__IT__)) & SMARTCARD_IT_MASK)))
/** @brief Clears the specified SMARTCARD ISR flag, in setting the proper ICR register flag.
* @param __HANDLE__: specifies the SMARTCARD Handle.
* The Handle Instance which can be USART1 or USART2.
* @param __IT_CLEAR__: specifies the interrupt clear register flag that needs to be set
* to clear the corresponding interrupt
* This parameter can be one of the following values:
* @arg USART_CLEAR_PEF: Parity Error Clear Flag
* @arg USART_CLEAR_FEF: Framing Error Clear Flag
* @arg USART_CLEAR_NEF: Noise detected Clear Flag
* @arg USART_CLEAR_OREF: OverRun Error Clear Flag
* @arg USART_CLEAR_TCF: Transmission Complete Clear Flag
* @arg USART_CLEAR_RTOF: Receiver Time Out Clear Flag
* @arg USART_CLEAR_EOBF: End Of Block Clear Flag
* @retval None
*/
#define __HAL_SMARTCARD_CLEAR_IT(__HANDLE__, __IT_CLEAR__) ((__HANDLE__)->Instance->ICR = (uint32_t)(__IT_CLEAR__))
/** @brief Set a specific SMARTCARD request flag.
* @param __HANDLE__: specifies the SMARTCARD Handle.
* The Handle Instance which can be USART1 or USART2.
* @param __REQ__: specifies the request flag to set
* This parameter can be one of the following values:
* @arg SMARTCARD_RXDATA_FLUSH_REQUEST: Receive Data flush Request
* @arg SMARTCARD_TXDATA_FLUSH_REQUEST: Transmit data flush Request
*
* @retval None
*/
#define __HAL_SMARTCARD_SEND_REQ(__HANDLE__, __REQ__) ((__HANDLE__)->Instance->RQR |= (uint32_t)(__REQ__))
/** @brief Enable the USART associated to the SMARTCARD Handle
* @param __HANDLE__: specifies the SMARTCARD Handle.
* The Handle Instance which can be USART1 or USART2.
* @retval None
*/
#define __HAL_SMARTCARD_ENABLE(__HANDLE__) ( (__HANDLE__)->Instance->CR1 |= USART_CR1_UE)
/** @brief Disable the USART associated to the SMARTCARD Handle
* @param __HANDLE__: specifies the SMARTCARD Handle.
* The Handle Instance which can be USART1 or USART2.
* @retval None
*/
#define __HAL_SMARTCARD_DISABLE(__HANDLE__) ( (__HANDLE__)->Instance->CR1 &= ~USART_CR1_UE)
/** @brief Macros to enable or disable the SmartCard DMA request.
* @param __HANDLE__: specifies the SMARTCARD Handle.
* The Handle Instance which can be USART1 or USART2.
* @param __REQUEST__: specifies the SmartCard DMA request.
* This parameter can be one of the following values:
* @arg SMARTCARD_DMAREQ_TX: SmartCard DMA transmit request
* @arg SMARTCARD_DMAREQ_RX: SmartCard DMA receive request
*/
#define __HAL_SMARTCARD_DMA_REQUEST_ENABLE(__HANDLE__, __REQUEST__) ((__HANDLE__)->Instance->CR3 |= (__REQUEST__))
#define __HAL_SMARTCARD_DMA_REQUEST_DISABLE(__HANDLE__, __REQUEST__) ((__HANDLE__)->Instance->CR3 &= ~(__REQUEST__))
/** @brief Check the Baud rate range. The maximum Baud Rate is derived from the
* maximum clock on F3 (i.e. 72 MHz) divided by the oversampling used
* on the SMARTCARD (i.e. 16)
* @param __BAUDRATE__: Baud rate set by the configuration function.
* @retval Test result (TRUE or FALSE)
*/
#define IS_SMARTCARD_BAUDRATE(__BAUDRATE__) ((__BAUDRATE__) < 4500001)
/** @brief Check the block length range. The maximum SMARTCARD block length is 0xFF.
* @param __LENGTH__: block length.
* @retval Test result (TRUE or FALSE)
*/
#define IS_SMARTCARD_BLOCKLENGTH(__LENGTH__) ((__LENGTH__) <= 0xFF)
/** @brief Check the receiver timeout value. The maximum SMARTCARD receiver timeout
* value is 0xFFFFFF.
* @param __TIMEOUTVALUE__: receiver timeout value.
* @retval Test result (TRUE or FALSE)
*/
#define IS_SMARTCARD_TIMEOUT_VALUE(__TIMEOUTVALUE__) ((__TIMEOUTVALUE__) <= 0xFFFFFF)
/** @brief Check the SMARTCARD autoretry counter value. The maximum number of
* retransmissions is 0x7.
* @param __COUNT__: number of retransmissions
* @retval Test result (TRUE or FALSE)
*/
#define IS_SMARTCARD_AUTORETRY_COUNT(__COUNT__) ((__COUNT__) <= 0x7)
/**
* @}
*/
/* Include SMARTCARD HAL Extension module */
#include "stm32l0xx_hal_smartcard_ex.h"
/* Exported functions --------------------------------------------------------*/
/* Initialization/de-initialization functions **********************************/
HAL_StatusTypeDef HAL_SMARTCARD_Init(SMARTCARD_HandleTypeDef *hsc);
HAL_StatusTypeDef HAL_SMARTCARD_DeInit(SMARTCARD_HandleTypeDef *hsc);
void HAL_SMARTCARD_MspInit(SMARTCARD_HandleTypeDef *hsc);
void HAL_SMARTCARD_MspDeInit(SMARTCARD_HandleTypeDef *hsc);
/* IO operation functions *******************************************************/
HAL_StatusTypeDef HAL_SMARTCARD_Transmit(SMARTCARD_HandleTypeDef *hsc, uint8_t *pData, uint16_t Size, uint32_t Timeout);
HAL_StatusTypeDef HAL_SMARTCARD_Receive(SMARTCARD_HandleTypeDef *hsc, uint8_t *pData, uint16_t Size, uint32_t Timeout);
HAL_StatusTypeDef HAL_SMARTCARD_Transmit_IT(SMARTCARD_HandleTypeDef *hsc, uint8_t *pData, uint16_t Size);
HAL_StatusTypeDef HAL_SMARTCARD_Receive_IT(SMARTCARD_HandleTypeDef *hsc, uint8_t *pData, uint16_t Size);
HAL_StatusTypeDef HAL_SMARTCARD_Transmit_DMA(SMARTCARD_HandleTypeDef *hsc, uint8_t *pData, uint16_t Size);
HAL_StatusTypeDef HAL_SMARTCARD_Receive_DMA(SMARTCARD_HandleTypeDef *hsc, uint8_t *pData, uint16_t Size);
void HAL_SMARTCARD_IRQHandler(SMARTCARD_HandleTypeDef *hsc);
void HAL_SMARTCARD_TxCpltCallback(SMARTCARD_HandleTypeDef *hsc);
void HAL_SMARTCARD_RxCpltCallback(SMARTCARD_HandleTypeDef *hsc);
void HAL_SMARTCARD_ErrorCallback(SMARTCARD_HandleTypeDef *hsc);
/* Peripheral State functions **************************************************/
HAL_SMARTCARD_StateTypeDef HAL_SMARTCARD_GetState(SMARTCARD_HandleTypeDef *hsc);
uint32_t HAL_SMARTCARD_GetError(SMARTCARD_HandleTypeDef *hsc);
/**
* @}
*/
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif /* __STM32L0xx_HAL_SMARTCARD_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,184 @@
/**
******************************************************************************
* @file stm32l0xx_hal_smartcard_ex.c
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief SMARTCARD HAL module driver.
*
* This file provides extended firmware functions to manage the following
* functionalities of the SmartCard.
* + Initialization and de-initialization functions
* + Peripheral Control functions
@verbatim
===============================================================================
##### How to use this driver #####
===============================================================================
[..]
The Extended SMARTCARD HAL driver can be used as follow:
(#) After having configured the SMARTCARD basic features with HAL_SMARTCARD_Init(),
then if required, program SMARTCARD advanced features (TX/RX pins swap, TimeOut,
auto-retry counter,...) in the hsc AdvancedInit structure.
@endverbatim
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @defgroup SMARTCARDEx
* @brief SMARTCARD Extended HAL module driver
* @{
*/
#ifdef HAL_SMARTCARD_MODULE_ENABLED
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/** @defgroup SMARTCARDEx_Private_Functions
* @{
*/
/** @defgroup SMARTCARDEx_Group1 Extended Peripheral Control functions
* @brief Extended control functions
*
@verbatim
===============================================================================
##### Peripheral Control functions #####
===============================================================================
[..]
This subsection provides a set of functions allowing to initialize the SMARTCARD.
(+) HAL_SMARTCARDEx_BlockLength_Config() API allows to configure the Block Length on the fly
(+) HAL_SMARTCARDEx_TimeOut_Config() API allows to configure the receiver timeout value on the fly
(+) HAL_SMARTCARDEx_EnableReceiverTimeOut() API enables the receiver timeout feature
(+) HAL_SMARTCARDEx_DisableReceiverTimeOut() API disables the receiver timeout feature
@endverbatim
* @{
*/
/**
* @brief Update on the fly the SMARTCARD block length in RTOR register
* @param hsc: SMARTCARD handle
* @param BlockLength: SMARTCARD block length (8-bit long at most)
* @retval None
*/
void HAL_SMARTCARDEx_BlockLength_Config(SMARTCARD_HandleTypeDef *hsc, uint8_t BlockLength)
{
MODIFY_REG(hsc->Instance->RTOR, USART_RTOR_BLEN, ((uint32_t)BlockLength << SMARTCARD_RTOR_BLEN_LSB_POS));
}
/**
* @brief Update on the fly the receiver timeout value in RTOR register
* @param hsc: SMARTCARD handle
* @param TimeOutValue: receiver timeout value in number of baud blocks. The timeout
* value must be less or equal to 0x0FFFFFFFF.
* @retval None
*/
void HAL_SMARTCARDEx_TimeOut_Config(SMARTCARD_HandleTypeDef *hsc, uint32_t TimeOutValue)
{
assert_param(IS_SMARTCARD_TIMEOUT_VALUE(hsc->Init.TimeOutValue));
MODIFY_REG(hsc->Instance->RTOR, USART_RTOR_RTO, TimeOutValue);
}
/**
* @brief Enable the SMARTCARD receiver timeout feature
* @param hsc: SMARTCARD handle
* @retval HAL status
*/
HAL_StatusTypeDef HAL_SMARTCARDEx_EnableReceiverTimeOut(SMARTCARD_HandleTypeDef *hsc)
{
/* Process Locked */
__HAL_LOCK(hsc);
hsc->State = HAL_SMARTCARD_STATE_BUSY;
/* Set the USART RTOEN bit */
hsc->Instance->CR2 |= USART_CR2_RTOEN;
hsc->State = HAL_SMARTCARD_STATE_READY;
/* Process Unlocked */
__HAL_UNLOCK(hsc);
return HAL_OK;
}
/**
* @brief Disable the SMARTCARD receiver timeout feature
* @param hsc: SMARTCARD handle
* @retval HAL status
*/
HAL_StatusTypeDef HAL_SMARTCARDEx_DisableReceiverTimeOut(SMARTCARD_HandleTypeDef *hsc)
{
/* Process Locked */
__HAL_LOCK(hsc);
hsc->State = HAL_SMARTCARD_STATE_BUSY;
/* Clear the USART RTOEN bit */
hsc->Instance->CR2 &= ~(USART_CR2_RTOEN);
hsc->State = HAL_SMARTCARD_STATE_READY;
/* Process Unlocked */
__HAL_UNLOCK(hsc);
return HAL_OK;
}
/**
* @}
*/
/**
* @}
*/
#endif /* HAL_SMARTCARD_MODULE_ENABLED */
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,135 @@
/**
******************************************************************************
* @file stm32l0xx_hal_smartcard_ex.h
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief Header file of SMARTCARD HAL module.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32L0xx_HAL_SMARTCARD_EX_H
#define __STM32L0xx_HAL_SMARTCARD_EX_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal_def.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @addtogroup SMARTCARDEx
* @{
*/
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
/* Exported macro ------------------------------------------------------------*/
/** @brief Reports the SMARTCARD clock source.
* @param __HANDLE__: specifies the USART Handle
* @param __CLOCKSOURCE__ : output variable
* @retval the USART clocking source, written in __CLOCKSOURCE__.
*/
#define __HAL_SMARTCARD_GETCLOCKSOURCE(__HANDLE__,__CLOCKSOURCE__) \
do { \
if((__HANDLE__)->Instance == USART1) \
{ \
switch(__HAL_RCC_GET_USART1_SOURCE()) \
{ \
case RCC_USART1CLKSOURCE_PCLK2: \
(__CLOCKSOURCE__) = SMARTCARD_CLOCKSOURCE_PCLK2; \
break; \
case RCC_USART1CLKSOURCE_HSI: \
(__CLOCKSOURCE__) = SMARTCARD_CLOCKSOURCE_HSI; \
break; \
case RCC_USART1CLKSOURCE_SYSCLK: \
(__CLOCKSOURCE__) = SMARTCARD_CLOCKSOURCE_SYSCLK; \
break; \
case RCC_USART1CLKSOURCE_LSE: \
(__CLOCKSOURCE__) = SMARTCARD_CLOCKSOURCE_LSE; \
break; \
default: \
break; \
} \
} \
else if((__HANDLE__)->Instance == USART2) \
{ \
switch(__HAL_RCC_GET_USART2_SOURCE()) \
{ \
case RCC_USART2CLKSOURCE_PCLK1: \
(__CLOCKSOURCE__) = SMARTCARD_CLOCKSOURCE_PCLK1; \
break; \
case RCC_USART2CLKSOURCE_HSI: \
(__CLOCKSOURCE__) = SMARTCARD_CLOCKSOURCE_HSI; \
break; \
case RCC_USART2CLKSOURCE_SYSCLK: \
(__CLOCKSOURCE__) = SMARTCARD_CLOCKSOURCE_SYSCLK; \
break; \
case RCC_USART2CLKSOURCE_LSE: \
(__CLOCKSOURCE__) = SMARTCARD_CLOCKSOURCE_LSE; \
break; \
default: \
break; \
} \
} \
} while(0)
/* Exported functions --------------------------------------------------------*/
/* Initialization and de-initialization functions ****************************/
/* IO operation functions *****************************************************/
/* Peripheral Control functions ***********************************************/
void HAL_SMARTCARDEx_BlockLength_Config(SMARTCARD_HandleTypeDef *hsc, uint8_t BlockLength);
void HAL_SMARTCARDEx_TimeOut_Config(SMARTCARD_HandleTypeDef *hsc, uint32_t TimeOutValue);
HAL_StatusTypeDef HAL_SMARTCARDEx_EnableReceiverTimeOut(SMARTCARD_HandleTypeDef *hsc);
HAL_StatusTypeDef HAL_SMARTCARDEx_DisableReceiverTimeOut(SMARTCARD_HandleTypeDef *hsc);
/* Peripheral State and Error functions ***************************************/
/**
* @}
*/
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif /* __STM32L0xx_HAL_SMARTCARD_EX_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,565 @@
/**
******************************************************************************
* @file stm32l0xx_hal_smbus.h
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief Header file of SMBUS HAL module.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32L0xx_HAL_SMBUS_H
#define __STM32L0xx_HAL_SMBUS_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal_def.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @addtogroup SMBUS
* @{
*/
/* Exported types ------------------------------------------------------------*/
/**
* @brief SMBUS Configuration Structure definition
*/
typedef struct
{
uint32_t Timing; /*!< Specifies the SMBUS_TIMINGR_register value.
This parameter calculated by referring to SMBUS initialization
section in Reference manual */
uint32_t AnalogFilter; /*!< Specifies if Analog Filter is enable or not.
This parameter can be a a value of @ref SMBUS_Analog_Filter */
uint32_t OwnAddress1; /*!< Specifies the first device own address.
This parameter can be a 7-bit or 10-bit address. */
uint32_t AddressingMode; /*!< Specifies if 7-bit or 10-bit addressing mode for master is selected.
This parameter can be a value of @ref SMBUS_addressing_mode */
uint32_t DualAddressMode; /*!< Specifies if dual addressing mode is selected.
This parameter can be a value of @ref SMBUS_dual_addressing_mode */
uint32_t OwnAddress2; /*!< Specifies the second device own address if dual addressing mode is selected
This parameter can be a 7-bit address. */
uint32_t OwnAddress2Masks; /*!< Specifies the acknoledge mask address second device own address if dual addressing mode is selected
This parameter can be a value of @ref SMBUS_own_address2_masks */
uint32_t GeneralCallMode; /*!< Specifies if general call mode is selected.
This parameter can be a value of @ref SMBUS_general_call_addressing_mode */
uint32_t NoStretchMode; /*!< Specifies if nostretch mode is selected.
This parameter can be a value of @ref SMBUS_nostretch_mode */
uint32_t PacketErrorCheckMode; /*!< Specifies if Packet Error Check mode is selected.
This parameter can be a value of @ref SMBUS_packet_error_check_mode */
uint32_t PeripheralMode; /*!< Specifies which mode of Periphal is selected.
This parameter can be a value of @ref SMBUS_peripheral_mode */
uint32_t SMBusTimeout; /*!< Specifies the content of the 32 Bits SMBUS_TIMEOUT_register value.
(Enable bits and different timeout values)
This parameter calculated by referring to SMBUS initialization
section in Reference manual */
} SMBUS_InitTypeDef;
/**
* @brief HAL State structures definition
*/
typedef enum
{
HAL_SMBUS_STATE_RESET = 0x00, /*!< SMBUS not yet initialized or disabled */
HAL_SMBUS_STATE_READY = 0x01, /*!< SMBUS initialized and ready for use */
HAL_SMBUS_STATE_BUSY = 0x02, /*!< SMBUS internal process is ongoing */
HAL_SMBUS_STATE_MASTER_BUSY_TX = 0x12, /*!< Master Data Transmission process is ongoing */
HAL_SMBUS_STATE_MASTER_BUSY_RX = 0x22, /*!< Master Data Reception process is ongoing */
HAL_SMBUS_STATE_SLAVE_BUSY_TX = 0x32, /*!< Slave Data Transmission process is ongoing */
HAL_SMBUS_STATE_SLAVE_BUSY_RX = 0x42, /*!< Slave Data Reception process is ongoing */
HAL_SMBUS_STATE_TIMEOUT = 0x03, /*!< Timeout state */
HAL_SMBUS_STATE_ERROR = 0x04, /*!< Reception process is ongoing */
HAL_SMBUS_STATE_LISTEN = 0x08, /*!< Address Listen Mode is ongoing */
/* Aliases for inter STM32 series compatibility */
HAL_SMBUS_STATE_SLAVE_LISTEN = HAL_SMBUS_STATE_LISTEN
}HAL_SMBUS_StateTypeDef;
/**
* @brief HAL SMBUS Error Code structure definition
*/
typedef enum
{
HAL_SMBUS_ERROR_NONE = 0x00, /*!< No error */
HAL_SMBUS_ERROR_BERR = 0x01, /*!< BERR error */
HAL_SMBUS_ERROR_ARLO = 0x02, /*!< ARLO error */
HAL_SMBUS_ERROR_ACKF = 0x04, /*!< ACKF error */
HAL_SMBUS_ERROR_OVR = 0x08, /*!< OVR error */
HAL_SMBUS_ERROR_HALTIMEOUT = 0x10, /*!< Timeout error */
HAL_SMBUS_ERROR_BUSTIMEOUT = 0x20, /*!< Bus Timeout error */
HAL_SMBUS_ERROR_ALERT = 0x40, /*!< Alert error */
HAL_SMBUS_ERROR_PECERR = 0x80 /*!< PEC error */
}HAL_SMBUS_ErrorTypeDef;
/**
* @brief SMBUS handle Structure definition
*/
typedef struct
{
I2C_TypeDef *Instance; /*!< SMBUS registers base address */
SMBUS_InitTypeDef Init; /*!< SMBUS communication parameters */
uint8_t *pBuffPtr; /*!< Pointer to SMBUS transfer buffer */
uint16_t XferSize; /*!< SMBUS transfer size */
__IO uint16_t XferCount; /*!< SMBUS transfer counter */
__IO uint32_t XferOptions; /*!< SMBUS transfer options */
__IO HAL_SMBUS_StateTypeDef PreviousState; /*!< SMBUS communication Previous tate */
HAL_LockTypeDef Lock; /*!< SMBUS locking object */
__IO HAL_SMBUS_StateTypeDef State; /*!< SMBUS communication state */
__IO HAL_SMBUS_ErrorTypeDef ErrorCode; /*!< SMBUS Error code */
}SMBUS_HandleTypeDef;
/* Exported constants --------------------------------------------------------*/
/** @defgroup SMBUS_Exported_Constants
* @{
*/
/** @defgroup SMBUS_Analog_Filter
* @{
*/
#define SMBUS_ANALOGFILTER_ENABLED ((uint32_t)0x00000000)
#define SMBUS_ANALOGFILTER_DISABLED I2C_CR1_ANFOFF
#define IS_SMBUS_ANALOG_FILTER(FILTER) (((FILTER) == SMBUS_ANALOGFILTER_ENABLED) || \
((FILTER) == SMBUS_ANALOGFILTER_DISABLED))
/**
* @}
*/
/** @defgroup SMBUS_addressing_mode
* @{
*/
#define SMBUS_ADDRESSINGMODE_7BIT ((uint32_t)0x00000001)
#define SMBUS_ADDRESSINGMODE_10BIT ((uint32_t)0x00000002)
#define IS_SMBUS_ADDRESSING_MODE(MODE) (((MODE) == SMBUS_ADDRESSINGMODE_7BIT) || \
((MODE) == SMBUS_ADDRESSINGMODE_10BIT))
/**
* @}
*/
/** @defgroup SMBUS_dual_addressing_mode
* @{
*/
#define SMBUS_DUALADDRESS_DISABLED ((uint32_t)0x00000000)
#define SMBUS_DUALADDRESS_ENABLED I2C_OAR2_OA2EN
#define IS_SMBUS_DUAL_ADDRESS(ADDRESS) (((ADDRESS) == SMBUS_DUALADDRESS_DISABLED) || \
((ADDRESS) == SMBUS_DUALADDRESS_ENABLED))
/**
* @}
*/
/** @defgroup SMBUS_own_address2_masks
* @{
*/
#define SMBUS_OA2_NOMASK ((uint8_t)0x00)
#define SMBUS_OA2_MASK01 ((uint8_t)0x01)
#define SMBUS_OA2_MASK02 ((uint8_t)0x02)
#define SMBUS_OA2_MASK03 ((uint8_t)0x03)
#define SMBUS_OA2_MASK04 ((uint8_t)0x04)
#define SMBUS_OA2_MASK05 ((uint8_t)0x05)
#define SMBUS_OA2_MASK06 ((uint8_t)0x06)
#define SMBUS_OA2_MASK07 ((uint8_t)0x07)
#define IS_SMBUS_OWN_ADDRESS2_MASK(MASK) (((MASK) == SMBUS_OA2_NOMASK) || \
((MASK) == SMBUS_OA2_MASK01) || \
((MASK) == SMBUS_OA2_MASK02) || \
((MASK) == SMBUS_OA2_MASK03) || \
((MASK) == SMBUS_OA2_MASK04) || \
((MASK) == SMBUS_OA2_MASK05) || \
((MASK) == SMBUS_OA2_MASK06) || \
((MASK) == SMBUS_OA2_MASK07))
/**
* @}
*/
/** @defgroup SMBUS_general_call_addressing_mode
* @{
*/
#define SMBUS_GENERALCALL_DISABLED ((uint32_t)0x00000000)
#define SMBUS_GENERALCALL_ENABLED I2C_CR1_GCEN
#define IS_SMBUS_GENERAL_CALL(CALL) (((CALL) == SMBUS_GENERALCALL_DISABLED) || \
((CALL) == SMBUS_GENERALCALL_ENABLED))
/**
* @}
*/
/** @defgroup SMBUS_nostretch_mode
* @{
*/
#define SMBUS_NOSTRETCH_DISABLED ((uint32_t)0x00000000)
#define SMBUS_NOSTRETCH_ENABLED I2C_CR1_NOSTRETCH
#define IS_SMBUS_NO_STRETCH(STRETCH) (((STRETCH) == SMBUS_NOSTRETCH_DISABLED) || \
((STRETCH) == SMBUS_NOSTRETCH_ENABLED))
/**
* @}
*/
/** @defgroup SMBUS_packet_error_check_mode
* @{
*/
#define SMBUS_PEC_DISABLED ((uint32_t)0x00000000)
#define SMBUS_PEC_ENABLED I2C_CR1_PECEN
#define IS_SMBUS_PEC(PEC) (((PEC) == SMBUS_PEC_DISABLED) || \
((PEC) == SMBUS_PEC_ENABLED))
/**
* @}
*/
/** @defgroup SMBUS_peripheral_mode
* @{
*/
#define SMBUS_PERIPHERAL_MODE_SMBUS_HOST (uint32_t)(I2C_CR1_SMBHEN)
#define SMBUS_PERIPHERAL_MODE_SMBUS_SLAVE (uint32_t)(0x00000000)
#define SMBUS_PERIPHERAL_MODE_SMBUS_SLAVE_ARP (uint32_t)(I2C_CR1_SMBDEN)
#define IS_SMBUS_PERIPHERAL_MODE(MODE) (((MODE) == SMBUS_PERIPHERAL_MODE_SMBUS_HOST) || \
((MODE) == SMBUS_PERIPHERAL_MODE_SMBUS_SLAVE) || \
((MODE) == SMBUS_PERIPHERAL_MODE_SMBUS_SLAVE_ARP))
/**
* @}
*/
/** @defgroup SMBUS_ReloadEndMode_definition
* @{
*/
#define SMBUS_SOFTEND_MODE ((uint32_t)0x00000000)
#define SMBUS_RELOAD_MODE I2C_CR2_RELOAD
#define SMBUS_AUTOEND_MODE I2C_CR2_AUTOEND
#define SMBUS_SENDPEC_MODE I2C_CR2_PECBYTE
#define IS_SMBUS_TRANSFER_MODE(MODE) (((MODE) == SMBUS_RELOAD_MODE) || \
((MODE) == SMBUS_AUTOEND_MODE) || \
((MODE) == SMBUS_SOFTEND_MODE) || \
((MODE) == (SMBUS_AUTOEND_MODE | SMBUS_SENDPEC_MODE)) || \
((MODE) == (SMBUS_AUTOEND_MODE | SMBUS_RELOAD_MODE)) || \
((MODE) == (SMBUS_AUTOEND_MODE | SMBUS_SENDPEC_MODE | SMBUS_RELOAD_MODE )))
/**
* @}
*/
/** @defgroup SMBUS_StartStopMode_definition
* @{
*/
#define SMBUS_NO_STARTSTOP ((uint32_t)0x00000000)
#define SMBUS_GENERATE_STOP I2C_CR2_STOP
#define SMBUS_GENERATE_START_READ (uint32_t)(I2C_CR2_START | I2C_CR2_RD_WRN)
#define SMBUS_GENERATE_START_WRITE I2C_CR2_START
#define IS_SMBUS_TRANSFER_REQUEST(REQUEST) (((REQUEST) == SMBUS_GENERATE_STOP) || \
((REQUEST) == SMBUS_GENERATE_START_READ) || \
((REQUEST) == SMBUS_GENERATE_START_WRITE) || \
((REQUEST) == SMBUS_NO_STARTSTOP))
/**
* @}
*/
/** @defgroup SMBUS_XferOptions_definition
* @{
*/
#define SMBUS_FIRST_FRAME ((uint32_t)(SMBUS_SOFTEND_MODE))
#define SMBUS_NEXT_FRAME ((uint32_t)(SMBUS_RELOAD_MODE | SMBUS_SOFTEND_MODE))
#define SMBUS_FIRST_AND_LAST_FRAME_NO_PEC SMBUS_AUTOEND_MODE
#define SMBUS_LAST_FRAME_NO_PEC SMBUS_AUTOEND_MODE
#define SMBUS_FIRST_AND_LAST_FRAME_WITH_PEC ((uint32_t)(SMBUS_AUTOEND_MODE | SMBUS_SENDPEC_MODE))
#define SMBUS_LAST_FRAME_WITH_PEC ((uint32_t)(SMBUS_AUTOEND_MODE | SMBUS_SENDPEC_MODE))
#define IS_SMBUS_TRANSFER_OPTIONS_REQUEST(REQUEST) (((REQUEST) == SMBUS_FIRST_FRAME) || \
((REQUEST) == SMBUS_NEXT_FRAME) || \
((REQUEST) == SMBUS_FIRST_AND_LAST_FRAME_NO_PEC) || \
((REQUEST) == SMBUS_LAST_FRAME_NO_PEC) || \
((REQUEST) == SMBUS_FIRST_AND_LAST_FRAME_WITH_PEC) || \
((REQUEST) == SMBUS_LAST_FRAME_WITH_PEC))
/**
* @}
*/
/** @defgroup SMBUS_Interrupt_configuration_definition
* @brief SMBUS Interrupt definition
* Elements values convention: 0xXXXXXXXX
* - XXXXXXXX : Interrupt control mask
* @{
*/
#define SMBUS_IT_ERRI I2C_CR1_ERRIE
#define SMBUS_IT_TCI I2C_CR1_TCIE
#define SMBUS_IT_STOPI I2C_CR1_STOPIE
#define SMBUS_IT_NACKI I2C_CR1_NACKIE
#define SMBUS_IT_ADDRI I2C_CR1_ADDRIE
#define SMBUS_IT_RXI I2C_CR1_RXIE
#define SMBUS_IT_TXI I2C_CR1_TXIE
#define SMBUS_IT_TX (SMBUS_IT_ERRI | SMBUS_IT_TCI | SMBUS_IT_STOPI | SMBUS_IT_NACKI | SMBUS_IT_TXI)
#define SMBUS_IT_RX (SMBUS_IT_ERRI | SMBUS_IT_TCI | SMBUS_IT_NACKI | SMBUS_IT_RXI)
#define SMBUS_IT_ALERT (SMBUS_IT_ERRI)
#define SMBUS_IT_ADDR (SMBUS_IT_ADDRI | SMBUS_IT_STOPI | SMBUS_IT_NACKI)
/**
* @}
*/
/** @defgroup SMBUS_Flag_definition
* @brief Flag definition
* Elements values convention: 0xXXXXYYYY
* - XXXXXXXX : Flag mask
* @{
*/
#define SMBUS_FLAG_TXE I2C_ISR_TXE
#define SMBUS_FLAG_TXIS I2C_ISR_TXIS
#define SMBUS_FLAG_RXNE I2C_ISR_RXNE
#define SMBUS_FLAG_ADDR I2C_ISR_ADDR
#define SMBUS_FLAG_AF I2C_ISR_NACKF
#define SMBUS_FLAG_STOPF I2C_ISR_STOPF
#define SMBUS_FLAG_TC I2C_ISR_TC
#define SMBUS_FLAG_TCR I2C_ISR_TCR
#define SMBUS_FLAG_BERR I2C_ISR_BERR
#define SMBUS_FLAG_ARLO I2C_ISR_ARLO
#define SMBUS_FLAG_OVR I2C_ISR_OVR
#define SMBUS_FLAG_PECERR I2C_ISR_PECERR
#define SMBUS_FLAG_TIMEOUT I2C_ISR_TIMEOUT
#define SMBUS_FLAG_ALERT I2C_ISR_ALERT
#define SMBUS_FLAG_BUSY I2C_ISR_BUSY
#define SMBUS_FLAG_DIR I2C_ISR_DIR
/**
* @}
*/
/**
* @}
*/
/* Exported macro ------------------------------------------------------------*/
/** @brief Reset SMBUS handle state
* @param __HANDLE__: specifies the SMBUS Handle.
* This parameter can be SMBUSx where x: 1 or 2 to select the SMBUS peripheral.
* @retval None
*/
#define __HAL_SMBUS_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_SMBUS_STATE_RESET)
/** @brief Enable or disable the specified SMBUS interrupts.
* @param __HANDLE__: specifies the SMBUS Handle.
* This parameter can be SMBUSx where x: 1 or 2 to select the SMBUS peripheral.
* @param __INTERRUPT__: specifies the interrupt source to enable or disable.
* This parameter can be one of the following values:
* @arg SMBUS_IT_ERRI: Errors interrupt enable
* @arg SMBUS_IT_TCI: Transfer complete interrupt enable
* @arg SMBUS_IT_STOPI: STOP detection interrupt enable
* @arg SMBUS_IT_NACKI: NACK received interrupt enable
* @arg SMBUS_IT_ADDRI: Address match interrupt enable
* @arg SMBUS_IT_RXI: RX interrupt enable
* @arg SMBUS_IT_TXI: TX interrupt enable
*
* @retval None
*/
#define __HAL_SMBUS_ENABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->CR1 |= (__INTERRUPT__))
#define __HAL_SMBUS_DISABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->CR1 &= (~(__INTERRUPT__)))
/** @brief Checks if the specified SMBUS interrupt source is enabled or disabled.
* @param __HANDLE__: specifies the SMBUS Handle.
* This parameter can be SMBUSx where x: 1 or 2 to select the SMBUS peripheral.
* @param __INTERRUPT__: specifies the SMBUS interrupt source to check.
* This parameter can be one of the following values:
* @arg SMBUS_IT_ERRI: Errors interrupt enable
* @arg SMBUS_IT_TCI: Transfer complete interrupt enable
* @arg SMBUS_IT_STOPI: STOP detection interrupt enable
* @arg SMBUS_IT_NACKI: NACK received interrupt enable
* @arg SMBUS_IT_ADDRI: Address match interrupt enable
* @arg SMBUS_IT_RXI: RX interrupt enable
* @arg SMBUS_IT_TXI: TX interrupt enable
*
* @retval The new state of __IT__ (TRUE or FALSE).
*/
#define __HAL_SMBUS_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) ((((__HANDLE__)->Instance->CR1 & (__INTERRUPT__)) == (__INTERRUPT__)) ? SET : RESET)
/** @brief Checks whether the specified SMBUS flag is set or not.
* @param __HANDLE__: specifies the SMBUS Handle.
* This parameter can be SMBUSx where x: 1 or 2 to select the SMBUS peripheral.
* @param __FLAG__: specifies the flag to check.
* This parameter can be one of the following values:
* @arg SMBUS_FLAG_TXE: Transmit data register empty
* @arg SMBUS_FLAG_TXIS: Transmit interrupt status
* @arg SMBUS_FLAG_RXNE: Receive data register not empty
* @arg SMBUS_FLAG_ADDR: Address matched (slave mode)
* @arg SMBUS_FLAG_AF NACK received flag
* @arg SMBUS_FLAG_STOPF: STOP detection flag
* @arg SMBUS_FLAG_TC: Transfer complete (master mode)
* @arg SMBUS_FLAG_TCR: Transfer complete reload
* @arg SMBUS_FLAG_BERR: Bus error
* @arg SMBUS_FLAG_ARLO: Arbitration lost
* @arg SMBUS_FLAG_OVR: Overrun/Underrun
* @arg SMBUS_FLAG_PECERR: PEC error in reception
* @arg SMBUS_FLAG_TIMEOUT: Timeout or Tlow detection flag
* @arg SMBUS_FLAG_ALERT: SMBus alert
* @arg SMBUS_FLAG_BUSY: Bus busy
* @arg SMBUS_FLAG_DIR: Transfer direction (slave mode)
* @retval The new state of __FLAG__ (TRUE or FALSE).
*/
#define SMBUS_FLAG_MASK ((uint32_t)0x0001FFFF)
#define __HAL_SMBUS_GET_FLAG(__HANDLE__, __FLAG__) (((((__HANDLE__)->Instance->ISR) & ((__FLAG__) & SMBUS_FLAG_MASK)) == ((__FLAG__) & SMBUS_FLAG_MASK)))
/** @brief Clears the SMBUS pending flags which are cleared by writing 1 in a specific bit.
* @param __HANDLE__: specifies the SMBUS Handle.
* This parameter can be SMBUSx where x: 1 or 2 to select the SMBUS peripheral.
* @param __FLAG__: specifies the flag to clear.
* This parameter can be any combination of the following values:
* @arg SMBUS_FLAG_ADDR: Address matched (slave mode)
* @arg SMBUS_FLAG_AF: NACK received flag
* @arg SMBUS_FLAG_STOPF: STOP detection flag
* @arg SMBUS_FLAG_BERR: Bus error
* @arg SMBUS_FLAG_ARLO: Arbitration lost
* @arg SMBUS_FLAG_OVR: Overrun/Underrun
* @arg SMBUS_FLAG_PECERR: PEC error in reception
* @arg SMBUS_FLAG_TIMEOUT: Timeout or Tlow detection flag
* @arg SMBUS_FLAG_ALERT: SMBus alert
* @retval None
*/
#define __HAL_SMBUS_CLEAR_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->ICR = ((__FLAG__) & SMBUS_FLAG_MASK))
#define __HAL_SMBUS_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR1 |= I2C_CR1_PE)
#define __HAL_SMBUS_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR1 &= ~I2C_CR1_PE)
#define __HAL_SMBUS_RESET_CR1(__HANDLE__) ((__HANDLE__)->Instance->CR1 &= (uint32_t)~((uint32_t)(I2C_CR1_SMBHEN | I2C_CR1_SMBDEN | I2C_CR1_PECEN)))
#define __HAL_SMBUS_RESET_CR2(__HANDLE__) ((__HANDLE__)->Instance->CR2 &= (uint32_t)~((uint32_t)(I2C_CR2_SADD | I2C_CR2_HEAD10R | I2C_CR2_NBYTES | I2C_CR2_RELOAD | I2C_CR2_RD_WRN)))
#define __HAL_SMBUS_GENERATE_START(__ADDMODE__,__ADDRESS__) (((__ADDMODE__) == SMBUS_ADDRESSINGMODE_7BIT) ? (uint32_t)((((uint32_t)(__ADDRESS__) & (I2C_CR2_SADD)) | (I2C_CR2_START) | (I2C_CR2_AUTOEND)) & (~I2C_CR2_RD_WRN)) : \
(uint32_t)((((uint32_t)(__ADDRESS__) & (I2C_CR2_SADD)) | (I2C_CR2_ADD10) | (I2C_CR2_START)) & (~I2C_CR2_RD_WRN)))
#define __HAL_SMBUS_GET_ADDR_MATCH(__HANDLE__) (((__HANDLE__)->Instance->ISR & I2C_ISR_ADDCODE) >> 17)
#define __HAL_SMBUS_GET_DIR(__HANDLE__) (((__HANDLE__)->Instance->ISR & I2C_ISR_DIR) >> 16)
#define __HAL_SMBUS_GET_STOP_MODE(__HANDLE__) ((__HANDLE__)->Instance->CR2 & I2C_CR2_AUTOEND)
#define __HAL_SMBUS_GET_PEC_MODE(__HANDLE__) ((__HANDLE__)->Instance->CR2 & I2C_CR2_PECBYTE)
#define __HAL_SMBUS_GET_ALERT_ENABLED(__HANDLE__) ((__HANDLE__)->Instance->CR1 & I2C_CR1_ALERTEN)
#define __HAL_SMBUS_GENERATE_NACK(__HANDLE__) ((__HANDLE__)->Instance->CR2 |= I2C_CR2_NACK)
#define IS_SMBUS_OWN_ADDRESS1(ADDRESS1) ((ADDRESS1) <= (uint32_t)0x000003FF)
#define IS_SMBUS_OWN_ADDRESS2(ADDRESS2) ((ADDRESS2) <= (uint16_t)0x00FF)
/* Exported functions --------------------------------------------------------*/
/* Initialization and de-initialization functions ****************************/
HAL_StatusTypeDef HAL_SMBUS_Init(SMBUS_HandleTypeDef *hsmbus);
HAL_StatusTypeDef HAL_SMBUS_DeInit (SMBUS_HandleTypeDef *hsmbus);
void HAL_SMBUS_MspInit(SMBUS_HandleTypeDef *hsmbus);
void HAL_SMBUS_MspDeInit(SMBUS_HandleTypeDef *hsmbus);
/* IO operation functions ****************************************************/
HAL_StatusTypeDef HAL_SMBUS_EnableAlert_IT(SMBUS_HandleTypeDef *hsmbus);
HAL_StatusTypeDef HAL_SMBUS_DisableAlert_IT(SMBUS_HandleTypeDef *hsmbus);
HAL_StatusTypeDef HAL_SMBUS_EnableListen_IT(SMBUS_HandleTypeDef *hsmbus);
HAL_StatusTypeDef HAL_SMBUS_DisableListen_IT(SMBUS_HandleTypeDef *hsmbus);
/* Aliases for inter STM32 series compatibility */
#define HAL_SMBUS_Slave_Listen_IT HAL_SMBUS_EnableListen_IT
/******* Blocking mode: Polling */
HAL_StatusTypeDef HAL_SMBUS_IsDeviceReady(SMBUS_HandleTypeDef *hsmbus, uint16_t DevAddress, uint32_t Trials, uint32_t Timeout);
/******* Non-Blocking mode: Interrupt */
HAL_StatusTypeDef HAL_SMBUS_Master_Transmit_IT(SMBUS_HandleTypeDef *hsmbus, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t XferOptions);
HAL_StatusTypeDef HAL_SMBUS_Master_Receive_IT(SMBUS_HandleTypeDef *hsmbus, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t XferOptions);
HAL_StatusTypeDef HAL_SMBUS_Master_Abort_IT(SMBUS_HandleTypeDef *hsmbus, uint16_t DevAddress);
HAL_StatusTypeDef HAL_SMBUS_Slave_Transmit_IT(SMBUS_HandleTypeDef *hsmbus, uint8_t *pData, uint16_t Size, uint32_t XferOptions);
HAL_StatusTypeDef HAL_SMBUS_Slave_Receive_IT(SMBUS_HandleTypeDef *hsmbus, uint8_t *pData, uint16_t Size, uint32_t XferOptions);
/******* SMBUS IRQHandler and Callbacks used in non blocking modes (Interrupt) */
void HAL_SMBUS_EV_IRQHandler(SMBUS_HandleTypeDef *hsmbus);
void HAL_SMBUS_ER_IRQHandler(SMBUS_HandleTypeDef *hsmbus);
void HAL_SMBUS_MasterTxCpltCallback(SMBUS_HandleTypeDef *hsmbus);
void HAL_SMBUS_MasterRxCpltCallback(SMBUS_HandleTypeDef *hsmbus);
void HAL_SMBUS_SlaveTxCpltCallback(SMBUS_HandleTypeDef *hsmbus);
void HAL_SMBUS_SlaveRxCpltCallback(SMBUS_HandleTypeDef *hsmbus);
void HAL_SMBUS_AddrCallback(SMBUS_HandleTypeDef *hsmbus, uint8_t TransferDirection, uint16_t AddrMatchCode);
void HAL_SMBUS_ListenCpltCallback(SMBUS_HandleTypeDef *hsmbus);
/* Aliases for inter STM32 series compatibility */
#define HAL_SMBUS_SlaveAddrCallback HAL_SMBUS_AddrCallback
#define HAL_SMBUS_SlaveListenCpltCallback HAL_SMBUS_ListenCpltCallback
void HAL_SMBUS_ErrorCallback(SMBUS_HandleTypeDef *hsmbus);
/* Peripheral State and Errors functions *************************************/
HAL_SMBUS_StateTypeDef HAL_SMBUS_GetState(SMBUS_HandleTypeDef *hsmbus);
uint32_t HAL_SMBUS_GetError(SMBUS_HandleTypeDef *hsmbus);
/**
* @}
*/
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif /* __STM32L0xx_HAL_SMBUS_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,488 @@
/**
******************************************************************************
* @file stm32l0xx_hal_spi.h
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief Header file of SPI HAL module.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32L0xx_HAL_SPI_H
#define __STM32L0xx_HAL_SPI_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal_def.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @addtogroup SPI
* @{
*/
/* Exported types ------------------------------------------------------------*/
/**
* @brief SPI Configuration Structure definition
*/
typedef struct
{
uint32_t Mode; /*!< Specifies the SPI operating mode.
This parameter can be a value of @ref SPI_mode */
uint32_t Direction; /*!< Specifies the SPI Directional mode state.
This parameter can be a value of @ref SPI_Direction_mode */
uint32_t DataSize; /*!< Specifies the SPI data size.
This parameter can be a value of @ref SPI_data_size */
uint32_t CLKPolarity; /*!< Specifies the serial clock steady state.
This parameter can be a value of @ref SPI_Clock_Polarity */
uint32_t CLKPhase; /*!< Specifies the clock active edge for the bit capture.
This parameter can be a value of @ref SPI_Clock_Phase */
uint32_t NSS; /*!< Specifies whether the NSS signal is managed by
hardware (NSS pin) or by software using the SSI bit.
This parameter can be a value of @ref SPI_Slave_Select_management */
uint32_t BaudRatePrescaler; /*!< Specifies the Baud Rate prescaler value which will be
used to configure the transmit and receive SCK clock.
This parameter can be a value of @ref SPI_BaudRate_Prescaler
@note The communication clock is derived from the master
clock. The slave clock does not need to be set */
uint32_t FirstBit; /*!< Specifies whether data transfers start from MSB or LSB bit.
This parameter can be a value of @ref SPI_MSB_LSB_transmission */
uint32_t TIMode; /*!< Specifies if the TI mode is enabled or not.
This parameter can be a value of @ref SPI_TI_mode */
uint32_t CRCCalculation; /*!< Specifies if the CRC calculation is enabled or not.
This parameter can be a value of @ref SPI_CRC_Calculation */
uint32_t CRCPolynomial; /*!< Specifies the polynomial used for the CRC calculation.
This parameter must be a number between Min_Data = 0 and Max_Data = 65535 */
}SPI_InitTypeDef;
/**
* @brief HAL SPI State structure definition
*/
typedef enum
{
HAL_SPI_STATE_RESET = 0x00, /*!< SPI not yet initialized or disabled */
HAL_SPI_STATE_READY = 0x01, /*!< SPI initialized and ready for use */
HAL_SPI_STATE_BUSY = 0x02, /*!< SPI process is ongoing */
HAL_SPI_STATE_BUSY_TX = 0x12, /*!< Data Transmission process is ongoing */
HAL_SPI_STATE_BUSY_RX = 0x22, /*!< Data Reception process is ongoing */
HAL_SPI_STATE_BUSY_TX_RX = 0x32, /*!< Data Transmission and Reception process is ongoing */
HAL_SPI_STATE_ERROR = 0x03 /*!< SPI error state */
}HAL_SPI_StateTypeDef;
/**
* @brief HAL SPI Error Code structure definition
*/
typedef enum
{
HAL_SPI_ERROR_NONE = 0x00, /*!< No error */
HAL_SPI_ERROR_MODF = 0x01, /*!< MODF error */
HAL_SPI_ERROR_CRC = 0x02, /*!< CRC error */
HAL_SPI_ERROR_OVR = 0x04, /*!< OVR error */
HAL_SPI_ERROR_FRE = 0x08, /*!< FRE error */
HAL_SPI_ERROR_DMA = 0x10, /*!< DMA transfer error */
HAL_SPI_ERROR_FLAG = 0x20 /*!< Flag: RXNE,TXE, BSY */
}HAL_SPI_ErrorTypeDef;
/**
* @brief SPI handle Structure definition
*/
typedef struct __SPI_HandleTypeDef
{
SPI_TypeDef *Instance; /* SPI registers base address */
SPI_InitTypeDef Init; /* SPI communication parameters */
uint8_t *pTxBuffPtr; /* Pointer to SPI Tx transfer Buffer */
uint16_t TxXferSize; /* SPI Tx transfer size */
uint16_t TxXferCount; /* SPI Tx Transfer Counter */
uint8_t *pRxBuffPtr; /* Pointer to SPI Rx transfer Buffer */
uint16_t RxXferSize; /* SPI Rx transfer size */
uint16_t RxXferCount; /* SPI Rx Transfer Counter */
DMA_HandleTypeDef *hdmatx; /* SPI Tx DMA handle parameters */
DMA_HandleTypeDef *hdmarx; /* SPI Rx DMA handle parameters */
void (*RxISR)(struct __SPI_HandleTypeDef * hspi); /* function pointer on Rx ISR */
void (*TxISR)(struct __SPI_HandleTypeDef * hspi); /* function pointer on Tx ISR */
HAL_LockTypeDef Lock; /* SPI locking object */
__IO HAL_SPI_StateTypeDef State; /* SPI communication state */
__IO HAL_SPI_ErrorTypeDef ErrorCode; /* SPI Error code */
}SPI_HandleTypeDef;
/* Exported constants --------------------------------------------------------*/
/** @defgroup SPI_Exported_Constants
* @{
*/
/** @defgroup SPI_mode
* @{
*/
#define SPI_MODE_SLAVE ((uint32_t)0x00000000)
#define SPI_MODE_MASTER (SPI_CR1_MSTR | SPI_CR1_SSI)
#define IS_SPI_MODE(MODE) (((MODE) == SPI_MODE_SLAVE) || \
((MODE) == SPI_MODE_MASTER))
/**
* @}
*/
/** @defgroup SPI_Direction_mode
* @{
*/
#define SPI_DIRECTION_2LINES ((uint32_t)0x00000000)
#define SPI_DIRECTION_2LINES_RXONLY SPI_CR1_RXONLY
#define SPI_DIRECTION_1LINE SPI_CR1_BIDIMODE
#define IS_SPI_DIRECTION_MODE(MODE) (((MODE) == SPI_DIRECTION_2LINES) || \
((MODE) == SPI_DIRECTION_2LINES_RXONLY) || \
((MODE) == SPI_DIRECTION_1LINE))
#define IS_SPI_DIRECTION_2LINES_OR_1LINE(MODE) (((MODE) == SPI_DIRECTION_2LINES) || \
((MODE) == SPI_DIRECTION_1LINE))
#define IS_SPI_DIRECTION_2LINES(MODE) ((MODE) == SPI_DIRECTION_2LINES)
/**
* @}
*/
/** @defgroup SPI_data_size
* @{
*/
#define SPI_DATASIZE_8BIT ((uint32_t)0x00000000)
#define SPI_DATASIZE_16BIT SPI_CR1_DFF
#define IS_SPI_DATASIZE(DATASIZE) (((DATASIZE) == SPI_DATASIZE_16BIT) || \
((DATASIZE) == SPI_DATASIZE_8BIT))
/**
* @}
*/
/** @defgroup SPI_Clock_Polarity
* @{
*/
#define SPI_POLARITY_LOW ((uint32_t)0x00000000)
#define SPI_POLARITY_HIGH SPI_CR1_CPOL
#define IS_SPI_CPOL(CPOL) (((CPOL) == SPI_POLARITY_LOW) || \
((CPOL) == SPI_POLARITY_HIGH))
/**
* @}
*/
/** @defgroup SPI_Clock_Phase
* @{
*/
#define SPI_PHASE_1EDGE ((uint32_t)0x00000000)
#define SPI_PHASE_2EDGE SPI_CR1_CPHA
#define IS_SPI_CPHA(CPHA) (((CPHA) == SPI_PHASE_1EDGE) || \
((CPHA) == SPI_PHASE_2EDGE))
/**
* @}
*/
/** @defgroup SPI_Slave_Select_management
* @{
*/
#define SPI_NSS_SOFT SPI_CR1_SSM
#define SPI_NSS_HARD_INPUT ((uint32_t)0x00000000)
#define SPI_NSS_HARD_OUTPUT ((uint32_t)0x00040000)
#define IS_SPI_NSS(NSS) (((NSS) == SPI_NSS_SOFT) || \
((NSS) == SPI_NSS_HARD_INPUT) || \
((NSS) == SPI_NSS_HARD_OUTPUT))
/**
* @}
*/
/** @defgroup SPI_BaudRate_Prescaler
* @{
*/
#define SPI_BAUDRATEPRESCALER_2 ((uint32_t)0x00000000)
#define SPI_BAUDRATEPRESCALER_4 ((uint32_t)0x00000008)
#define SPI_BAUDRATEPRESCALER_8 ((uint32_t)0x00000010)
#define SPI_BAUDRATEPRESCALER_16 ((uint32_t)0x00000018)
#define SPI_BAUDRATEPRESCALER_32 ((uint32_t)0x00000020)
#define SPI_BAUDRATEPRESCALER_64 ((uint32_t)0x00000028)
#define SPI_BAUDRATEPRESCALER_128 ((uint32_t)0x00000030)
#define SPI_BAUDRATEPRESCALER_256 ((uint32_t)0x00000038)
#define IS_SPI_BAUDRATE_PRESCALER(PRESCALER) (((PRESCALER) == SPI_BAUDRATEPRESCALER_2) || \
((PRESCALER) == SPI_BAUDRATEPRESCALER_4) || \
((PRESCALER) == SPI_BAUDRATEPRESCALER_8) || \
((PRESCALER) == SPI_BAUDRATEPRESCALER_16) || \
((PRESCALER) == SPI_BAUDRATEPRESCALER_32) || \
((PRESCALER) == SPI_BAUDRATEPRESCALER_64) || \
((PRESCALER) == SPI_BAUDRATEPRESCALER_128) || \
((PRESCALER) == SPI_BAUDRATEPRESCALER_256))
/**
* @}
*/
/** @defgroup SPI_MSB_LSB_transmission
* @{
*/
#define SPI_FIRSTBIT_MSB ((uint32_t)0x00000000)
#define SPI_FIRSTBIT_LSB SPI_CR1_LSBFIRST
#define IS_SPI_FIRST_BIT(BIT) (((BIT) == SPI_FIRSTBIT_MSB) || \
((BIT) == SPI_FIRSTBIT_LSB))
/**
* @}
*/
/** @defgroup SPI_TI_mode
* @{
*/
#define SPI_TIMODE_DISABLED ((uint32_t)0x00000000)
#define SPI_TIMODE_ENABLED SPI_CR2_FRF
#define IS_SPI_TIMODE(MODE) (((MODE) == SPI_TIMODE_DISABLED) || \
((MODE) == SPI_TIMODE_ENABLED))
/**
* @}
*/
/** @defgroup SPI_CRC_Calculation
* @{
*/
#define SPI_CRCCALCULATION_DISABLED ((uint32_t)0x00000000)
#define SPI_CRCCALCULATION_ENABLED SPI_CR1_CRCEN
#define IS_SPI_CRC_CALCULATION(CALCULATION) (((CALCULATION) == SPI_CRCCALCULATION_DISABLED) || \
((CALCULATION) == SPI_CRCCALCULATION_ENABLED))
/**
* @}
*/
/** @defgroup SPI_Interrupt_configuration_definition
* @{
*/
#define SPI_IT_TXE SPI_CR2_TXEIE
#define SPI_IT_RXNE SPI_CR2_RXNEIE
#define SPI_IT_ERR SPI_CR2_ERRIE
/**
* @}
*/
/** @defgroup SPI_Flag_definition
* @{
*/
#define SPI_FLAG_RXNE SPI_SR_RXNE
#define SPI_FLAG_TXE SPI_SR_TXE
#define SPI_FLAG_CRCERR SPI_SR_CRCERR
#define SPI_FLAG_MODF SPI_SR_MODF
#define SPI_FLAG_OVR SPI_SR_OVR
#define SPI_FLAG_BSY SPI_SR_BSY
#define SPI_FLAG_FRE SPI_SR_FRE
/**
* @}
*/
/**
* @}
*/
/* Exported macro ------------------------------------------------------------*/
/** @brief Reset SPI handle state
* @param __HANDLE__: specifies the SPI handle.
* This parameter can be SPIx where x: 1, 2, or 3 to select the SPI peripheral.
* @retval None
*/
#define __HAL_SPI_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_SPI_STATE_RESET)
/** @brief Enable or disable the specified SPI interrupts.
* @param __HANDLE__: specifies the SPI handle.
* This parameter can be SPIx where x: 1, 2, or 3 to select the SPI peripheral.
* @param __INTERRUPT__: specifies the interrupt source to enable or disable.
* This parameter can be one of the following values:
* @arg SPI_IT_TXE: Tx buffer empty interrupt enable
* @arg SPI_IT_RXNE: RX buffer not empty interrupt enable
* @arg SPI_IT_ERR: Error interrupt enable
* @retval None
*/
#define __HAL_SPI_ENABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->CR2 |= (__INTERRUPT__))
#define __HAL_SPI_DISABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->CR2 &= (~(__INTERRUPT__)))
/** @brief Check if the specified SPI interrupt source is enabled or disabled.
* @param __HANDLE__: specifies the SPI handle.
* This parameter can be SPIx where x: 1, 2, or 3 to select the SPI peripheral.
* @param __INTERRUPT__: specifies the SPI interrupt source to check.
* This parameter can be one of the following values:
* @arg SPI_IT_TXE: Tx buffer empty interrupt enable
* @arg SPI_IT_RXNE: RX buffer not empty interrupt enable
* @arg SPI_IT_ERR: Error interrupt enable
* @retval The new state of __IT__ (TRUE or FALSE).
*/
#define __HAL_SPI_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) ((((__HANDLE__)->Instance->CR2 & (__INTERRUPT__)) == (__INTERRUPT__)) ? SET : RESET)
/** @brief Check whether the specified SPI flag is set or not.
* @param __HANDLE__: specifies the SPI handle.
* This parameter can be SPIx where x: 1, 2, or 3 to select the SPI peripheral.
* @param __FLAG__: specifies the flag to check.
* This parameter can be one of the following values:
* @arg SPI_FLAG_RXNE: Receive buffer not empty flag
* @arg SPI_FLAG_TXE: Transmit buffer empty flag
* @arg SPI_FLAG_CRCERR: CRC error flag
* @arg SPI_FLAG_MODF: Mode fault flag
* @arg SPI_FLAG_OVR: Overrun flag
* @arg SPI_FLAG_BSY: Busy flag
* @arg SPI_FLAG_FRE: Frame format error flag
* @retval The new state of __FLAG__ (TRUE or FALSE).
*/
#define __HAL_SPI_GET_FLAG(__HANDLE__, __FLAG__) ((((__HANDLE__)->Instance->SR) & (__FLAG__)) == (__FLAG__))
/** @brief Clear the SPI CRCERR pending flag.
* @param __HANDLE__: specifies the SPI handle.
* This parameter can be SPIx where x: 1, 2, or 3 to select the SPI peripheral.
* @retval None
*/
#define __HAL_SPI_CLEAR_CRCERRFLAG(__HANDLE__) ((__HANDLE__)->Instance->SR &= (uint32_t)~((uint32_t)SPI_FLAG_CRCERR))
/** @brief Clear the SPI MODF pending flag.
* @param __HANDLE__: specifies the SPI handle.
* This parameter can be SPIx where x: 1, 2, or 3 to select the SPI peripheral.
* @retval None
*/
#define __HAL_SPI_CLEAR_MODFFLAG(__HANDLE__) do{(__HANDLE__)->Instance->SR;\
(__HANDLE__)->Instance->CR1 &= (uint32_t)~((uint32_t)SPI_CR1_SPE);}while(0)
/** @brief Clear the SPI OVR pending flag.
* @param __HANDLE__: specifies the SPI handle.
* This parameter can be SPIx where x: 1, 2, or 3 to select the SPI peripheral.
* @retval None
*/
#define __HAL_SPI_CLEAR_OVRFLAG(__HANDLE__) do{(__HANDLE__)->Instance->DR;\
(__HANDLE__)->Instance->SR;}while(0)
/** @brief Clear the SPI FRE pending flag.
* @param __HANDLE__: specifies the SPI handle.
* This parameter can be SPIx where x: 1, 2, or 3 to select the SPI peripheral.
* @retval None
*/
#define __HAL_SPI_CLEAR_FREFLAG(__HANDLE__) ((__HANDLE__)->Instance->SR)
#define __HAL_SPI_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR1 |= SPI_CR1_SPE)
#define __HAL_SPI_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR1 &= (uint32_t)~((uint32_t)SPI_CR1_SPE))
#define IS_SPI_CRC_POLYNOMIAL(POLYNOMIAL) (((POLYNOMIAL) >= 0x1) && ((POLYNOMIAL) <= 0xFFFF))
#define __HAL_SPI_1LINE_TX(__HANDLE__) ((__HANDLE__)->Instance->CR1 |= SPI_CR1_BIDIOE)
#define __HAL_SPI_1LINE_RX(__HANDLE__) ((__HANDLE__)->Instance->CR1 &= (uint32_t)~((uint32_t)SPI_CR1_BIDIOE))
#define __HAL_SPI_RESET_CRC(__HANDLE__) do{(__HANDLE__)->Instance->CR1 &= (uint32_t)~((uint32_t)SPI_CR1_CRCEN);\
(__HANDLE__)->Instance->CR1 |= SPI_CR1_CRCEN;}while(0)
/* Exported functions --------------------------------------------------------*/
/* Initialization/de-initialization functions **********************************/
HAL_StatusTypeDef HAL_SPI_Init(SPI_HandleTypeDef *hspi);
HAL_StatusTypeDef HAL_SPI_DeInit (SPI_HandleTypeDef *hspi);
void HAL_SPI_MspInit(SPI_HandleTypeDef *hspi);
void HAL_SPI_MspDeInit(SPI_HandleTypeDef *hspi);
/* I/O operation functions *****************************************************/
HAL_StatusTypeDef HAL_SPI_Transmit(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size, uint32_t Timeout);
HAL_StatusTypeDef HAL_SPI_Receive(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size, uint32_t Timeout);
HAL_StatusTypeDef HAL_SPI_TransmitReceive(SPI_HandleTypeDef *hspi, uint8_t *pTxData, uint8_t *pRxData, uint16_t Size, uint32_t Timeout);
HAL_StatusTypeDef HAL_SPI_Transmit_IT(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size);
HAL_StatusTypeDef HAL_SPI_Receive_IT(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size);
HAL_StatusTypeDef HAL_SPI_TransmitReceive_IT(SPI_HandleTypeDef *hspi, uint8_t *pTxData, uint8_t *pRxData, uint16_t Size);
HAL_StatusTypeDef HAL_SPI_Transmit_DMA(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size);
HAL_StatusTypeDef HAL_SPI_Receive_DMA(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size);
HAL_StatusTypeDef HAL_SPI_TransmitReceive_DMA(SPI_HandleTypeDef *hspi, uint8_t *pTxData, uint8_t *pRxData, uint16_t Size);
HAL_StatusTypeDef HAL_SPI_DMAPause(SPI_HandleTypeDef *hspi);
HAL_StatusTypeDef HAL_SPI_DMAResume(SPI_HandleTypeDef *hspi);
HAL_StatusTypeDef HAL_SPI_DMAStop(SPI_HandleTypeDef *hspi);
void HAL_SPI_IRQHandler(SPI_HandleTypeDef *hspi);
void HAL_SPI_TxCpltCallback(SPI_HandleTypeDef *hspi);
void HAL_SPI_RxCpltCallback(SPI_HandleTypeDef *hspi);
void HAL_SPI_TxRxCpltCallback(SPI_HandleTypeDef *hspi);
void HAL_SPI_ErrorCallback(SPI_HandleTypeDef *hspi);
void HAL_SPI_TxHalfCpltCallback(SPI_HandleTypeDef *hspi);
void HAL_SPI_RxHalfCpltCallback(SPI_HandleTypeDef *hspi);
void HAL_SPI_TxRxHalfCpltCallback(SPI_HandleTypeDef *hspi);
/* Peripheral State and Control functions **************************************/
HAL_SPI_StateTypeDef HAL_SPI_GetState(SPI_HandleTypeDef *hspi);
HAL_SPI_ErrorTypeDef HAL_SPI_GetError(SPI_HandleTypeDef *hspi);
/**
* @}
*/
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif /* __STM32L0xx_HAL_SPI_H */
/************************ (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,240 @@
/**
******************************************************************************
* @file stm32l0xx_hal_tim_ex.c
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief TIM HAL module driver.
* @brief This file provides firmware functions to manage the following
* functionalities of the Timer (TIM) peripheral:
* + Time Hall Sensor Interface Initialization
* + Time Hall Sensor Interface Start
* + Time Master and Slave synchronization configuration
@verbatim
================================================================================
##### TIM specific features integration #####
================================================================================
[..] The Timer features include:
(#) 16-bit up, down, up/down auto-reload counter.
(#) 16-bit programmable prescaler allowing dividing (also on the fly) the counter clock
frequency either by any factor between 1 and 65536.
(#) Up to 4 independent channels for:
Input Capture
Output Compare
PWM generation (Edge and Center-aligned Mode)
One-pulse mode output
(#) Synchronization circuit to control the timer with external signals and to interconnect
several timers together.
(#) Supports incremental (quadrature) encoder and hall-sensor circuitry for positioning
purposes
##### How to use this driver #####
================================================================================
[..]
(#) Enable the TIM interface clock using
__TIMx_CLK_ENABLE();
(#) TIM pins configuration
(++) Enable the clock for the TIM GPIOs using the following function:
__GPIOx_CLK_ENABLE();
(++) Configure these TIM pins in Alternate function mode using HAL_GPIO_Init();
(#) The external Clock can be configured, if needed (the default clock is the internal clock from the APBx),
using the following function:
HAL_TIM_ConfigClockSource, the clock configuration should be done before any start function.
(#) Configure the TIM in the desired operating mode using one of the
configuration function of this driver:
(++) HAL_TIMEx_MasterConfigSynchronization() to configure the peripheral in master mode.
(#) Remap the Timer I/O using HAL_TIMEx_RemapConfig() API.
@endverbatim
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @defgroup TIMEx
* @brief TIMEx HAL module driver
* @{
*/
#ifdef HAL_TIM_MODULE_ENABLED
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/** @defgroup TIMEx_Private_Functions
* @{
*/
/** @defgroup TIMEx_Group1 Peripheral Control functions
* @brief Peripheral Control functions
*
@verbatim
===============================================================================
##### Peripheral Control functions #####
===============================================================================
[..] This section provides functions allowing to:
(+) Configure Master and the Slave synchronization.
@endverbatim
* @{
*/
/**
* @brief Configures the TIM in master mode.
* @param htim: TIM handle.
* @param sMasterConfig: pointer to a TIM_MasterConfigTypeDef structure that
* contains the selected trigger output (TRGO) and the Master/Slave
* mode.
* @retval HAL status
*/
HAL_StatusTypeDef HAL_TIMEx_MasterConfigSynchronization(TIM_HandleTypeDef *htim, TIM_MasterConfigTypeDef * sMasterConfig)
{
/* Check the parameters */
assert_param(IS_TIM_MASTER_INSTANCE(htim->Instance));
assert_param(IS_TIM_TRGO_SOURCE(sMasterConfig->MasterOutputTrigger));
assert_param(IS_TIM_MSM_STATE(sMasterConfig->MasterSlaveMode));
__HAL_LOCK(htim);
/* Change the handler state */
htim->State = HAL_TIM_STATE_BUSY;
/* Reset the MMS Bits */
htim->Instance->CR2 &= ~TIM_CR2_MMS;
/* Select the TRGO source */
htim->Instance->CR2 |= sMasterConfig->MasterOutputTrigger;
/* Reset the MSM Bit */
htim->Instance->SMCR &= ~TIM_SMCR_MSM;
/* Set or Reset the MSM Bit */
htim->Instance->SMCR |= sMasterConfig->MasterSlaveMode;
htim->State = HAL_TIM_STATE_READY;
__HAL_UNLOCK(htim);
return HAL_OK;
}
/**
* @brief Configures the TIM2, TIM21 and TIM22 Remapping input capabilities.
* @param htim: pointer to a TIM_HandleTypeDef structure that contains
* the configuration information for TIM module.
* @param TIM_Remap: specifies the TIM input remapping source.
* This parameter can be one of the following values:
* @arg TIM2_ETR_GPIO: TIM2 ETR is connected to GPIO (default)
* @arg TIM2_ETR_HSI48: TIM2 ETR is connected to HSI48
* @arg TIM2_ETR_LSE: TIM2 ETR is connected to LSE
* @arg TIM2_ETR_COMP2_OUT: TIM2 ETR is connected to COMP2 output
* @arg TIM2_ETR_COMP1_OUT: TIM2 ETR is connected to COMP1 output
* @arg TIM2_TI4_GPIO1: TIM2 TI4 is connected to GPIO1(default)
* @arg TIM2_TI4_COMP1: TIM2 TI4 is connected to COMP1
* @arg TIM2_TI4_COMP2: TIM2 TI4 is connected to COMP2
* @arg TIM2_TI4_GPIO2: TIM2 TI4 is connected to GPIO2
* @arg TIM21_ETR_GPIO: TIM21 ETR is connected to GPIO(default)
* @arg TIM21_ETR_COMP2_OUT: TIM21 ETR is connected to COMP2 output
* @arg TIM21_ETR_COMP1_OUT: TIM21 ETR is connected to COMP1 output
* @arg TIM21_ETR_LSE: TIM21 ETR is connected to LSE
* @arg TIM21_TI1_MCO: TIM21 TI1 is connected to MCO
* @arg TIM21_TI1_RTC_WKUT_IT: TIM21 TI1 is connected to RTC WAKEUP interrupt
* @arg TIM21_TI1_HSE_RTC: TIM21 TI1 is connected to HSE_RTC
* @arg TIM21_TI1_MSI: TIM21 TI1 is connected to MSI clock
* @arg TIM21_TI1_LSE: TIM21 TI1 is connected to LSE
* @arg TIM21_TI1_LSI: TIM21 TI1 is connected to LSI
* @arg TIM21_TI1_COMP1_OUT: TIM21 TI1 is connected to COMP1_OUT
* @arg TIM21_TI1_GPIO: TIM21 TI1 is connected to GPIO(default)
* @arg TIM21_TI2_GPIO: TIM21 TI2 is connected to GPIO(default)
* @arg TIM21_TI2_COMP2_OUT: TIM21 TI2 is connected to COMP2 output
* @arg TIM22_ETR_LSE: TIM22 ETR is connected to LSE
* @arg TIM22_ETR_COMP2_OUT: TIM22 ETR is connected to COMP2 output
* @arg TIM22_ETR_COMP1_OUT: TIM22 ETR is connected to COMP1 output
* @arg TIM22_ETR_GPIO: TIM22 ETR is connected to GPIO(default)
* @arg TIM22_TI1_GPIO1: TIM22 TI1 is connected to GPIO(default)
* @arg TIM22_TI1_COMP2_OUT: TIM22 TI1 is connected to COMP2 output
* @arg TIM22_TI1_COMP1_OUT: TIM22 TI1 is connected to COMP1 output
* @arg TIM22_TI1_GPIO2: TIM22 TI1 is connected to GPIO
* @retval HAL status
*/
HAL_StatusTypeDef HAL_TIMEx_RemapConfig(TIM_HandleTypeDef *htim, uint32_t Remap)
{
__HAL_LOCK(htim);
/* Check parameters */
assert_param(IS_TIM_REMAP_INSTANCE(htim->Instance));
assert_param(IS_TIM_REMAP(Remap));
/* Change the handler state */
htim->State = HAL_TIM_STATE_BUSY;
/* Set the Timer remapping configuration */
htim->Instance->OR &= (uint32_t)(Remap >> 16);
htim->Instance->OR |= Remap;
/* Change the handler state */
htim->State = HAL_TIM_STATE_READY;
__HAL_UNLOCK(htim);
return HAL_OK;
}
/**
* @}
*/
/**
* @}
*/
#endif /* HAL_TIM_MODULE_ENABLED */
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,197 @@
/**
******************************************************************************
* @file stm32l0xx_hal_tim_ex.h
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief Header file of TIM HAL module.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32L0xx_HAL_TIM_EX_H
#define __STM32L0xx_HAL_TIM_EX_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal_def.h"
/** @addtogroup STM32L0xx_HAL
* @{
*/
/** @addtogroup TIMEx
* @{
*/
/* Exported types ------------------------------------------------------------*/
/**
* @brief TIM Master configuration Structure definition
*/
typedef struct {
uint32_t MasterOutputTrigger; /*!< Trigger output (TRGO) selection
This parameter can be a value of @ref TIMEx_Master_Mode_Selection */
uint32_t MasterSlaveMode; /*!< Master/slave mode selection
This parameter can be a value of @ref TIM_Master_Slave_Mode */
}TIM_MasterConfigTypeDef;
/* Exported constants --------------------------------------------------------*/
/** @defgroup TIMEx_Exported_Constants
* @{
*/
/** @defgroup TIMEx_Master_Mode_Selection
* @{
*/
#define TIM_TRGO_RESET ((uint32_t)0x0000)
#define TIM_TRGO_ENABLE (TIM_CR2_MMS_0)
#define TIM_TRGO_UPDATE (TIM_CR2_MMS_1)
#define TIM_TRGO_OC1 ((TIM_CR2_MMS_1 | TIM_CR2_MMS_0))
#define TIM_TRGO_OC1REF (TIM_CR2_MMS_2)
#define TIM_TRGO_OC2REF ((TIM_CR2_MMS_2 | TIM_CR2_MMS_0))
#define TIM_TRGO_OC3REF ((TIM_CR2_MMS_2 | TIM_CR2_MMS_1))
#define TIM_TRGO_OC4REF ((TIM_CR2_MMS_2 | TIM_CR2_MMS_1 | TIM_CR2_MMS_0))
#define IS_TIM_TRGO_SOURCE(SOURCE) (((SOURCE) == TIM_TRGO_RESET) || \
((SOURCE) == TIM_TRGO_ENABLE) || \
((SOURCE) == TIM_TRGO_UPDATE) || \
((SOURCE) == TIM_TRGO_OC1) || \
((SOURCE) == TIM_TRGO_OC1REF) || \
((SOURCE) == TIM_TRGO_OC2REF) || \
((SOURCE) == TIM_TRGO_OC3REF) || \
((SOURCE) == TIM_TRGO_OC4REF))
/**
* @}
*/
/** @defgroup TIMEx_Remap
* @{
*/
#define TIM2_ETR_GPIO ((uint32_t)0xFFF80000)
#define TIM2_ETR_HSI48 ((uint32_t)0xFFF80004)
#define TIM2_ETR_LSE ((uint32_t)0xFFF80005)
#define TIM2_ETR_COMP2_OUT ((uint32_t)0xFFF80006)
#define TIM2_ETR_COMP1_OUT ((uint32_t)0xFFF80007)
#define TIM2_TI4_GPIO1 ((uint32_t)0xFFE70000)
#define TIM2_TI4_COMP2 ((uint32_t)0xFFE70008)
#define TIM2_TI4_COMP1 ((uint32_t)0xFFE70010)
#define TIM2_TI4_GPIO2 ((uint32_t)0xFFE70018)
#define TIM21_ETR_GPIO ((uint32_t)0xFFF40000)
#define TIM21_ETR_COMP2_OUT ((uint32_t)0xFFF40001)
#define TIM21_ETR_COMP1_OUT ((uint32_t)0xFFF40002)
#define TIM21_ETR_LSE ((uint32_t)0xFFF40003)
#define TIM21_TI1_MCO ((uint32_t)0xFFE3001C)
#define TIM21_TI1_RTC_WKUT_IT ((uint32_t)0xFFE30004)
#define TIM21_TI1_HSE_RTC ((uint32_t)0xFFE30008)
#define TIM21_TI1_MSI ((uint32_t)0xFFE3000C)
#define TIM21_TI1_LSE ((uint32_t)0xFFE30010)
#define TIM21_TI1_LSI ((uint32_t)0xFFE30014)
#define TIM21_TI1_COMP1_OUT ((uint32_t)0xFFE30018)
#define TIM21_TI1_GPIO ((uint32_t)0xFFE30000)
#define TIM21_TI2_GPIO ((uint32_t)0xFFDF0000)
#define TIM21_TI2_COMP2_OUT ((uint32_t)0xFFDF0020)
#define TIM22_ETR_LSE ((uint32_t)0xFFFC0000)
#define TIM22_ETR_COMP2_OUT ((uint32_t)0xFFFC0001)
#define TIM22_ETR_COMP1_OUT ((uint32_t)0xFFFC0002)
#define TIM22_ETR_GPIO ((uint32_t)0xFFFC0003)
#define TIM22_TI1_GPIO1 ((uint32_t)0xFFF70000)
#define TIM22_TI1_COMP2_OUT ((uint32_t)0xFFF70004)
#define TIM22_TI1_COMP1_OUT ((uint32_t)0xFFF70008)
#define TIM22_TI1_GPIO2 ((uint32_t)0xFFF7000C)
#define IS_TIM_REMAP(TIM_REMAP) (((TIM_REMAP) == TIM2_ETR_GPIO )|| \
((TIM_REMAP) == TIM2_ETR_HSI48 )|| \
((TIM_REMAP) == TIM2_ETR_LSE )|| \
((TIM_REMAP) == TIM2_ETR_COMP2_OUT )|| \
((TIM_REMAP) == TIM2_ETR_COMP1_OUT )|| \
((TIM_REMAP) == TIM2_TI4_GPIO1 )|| \
((TIM_REMAP) == TIM2_TI4_COMP1 )|| \
((TIM_REMAP) == TIM2_TI4_COMP2 )|| \
((TIM_REMAP) == TIM2_TI4_GPIO2 )|| \
((TIM_REMAP) == TIM21_ETR_GPIO )|| \
((TIM_REMAP) == TIM21_ETR_COMP2_OUT )|| \
((TIM_REMAP) == TIM21_ETR_COMP1_OUT )|| \
((TIM_REMAP) == TIM21_ETR_LSE )|| \
((TIM_REMAP) == TIM21_TI1_MCO )|| \
((TIM_REMAP) == TIM21_TI1_RTC_WKUT_IT )|| \
((TIM_REMAP) == TIM21_TI1_HSE_RTC )|| \
((TIM_REMAP) == TIM21_TI1_MSI )|| \
((TIM_REMAP) == TIM21_TI1_LSE )|| \
((TIM_REMAP) == TIM21_TI1_LSI )|| \
((TIM_REMAP) == TIM21_TI1_COMP1_OUT )|| \
((TIM_REMAP) == TIM21_TI1_GPIO )|| \
((TIM_REMAP) == TIM21_TI2_GPIO )|| \
((TIM_REMAP) == TIM21_TI2_COMP2_OUT )|| \
((TIM_REMAP) == TIM22_ETR_LSE )|| \
((TIM_REMAP) == TIM22_ETR_COMP2_OUT )|| \
((TIM_REMAP) == TIM22_ETR_COMP1_OUT )|| \
((TIM_REMAP) == TIM22_ETR_GPIO )|| \
((TIM_REMAP) == TIM22_TI1_GPIO1 )|| \
((TIM_REMAP) == TIM22_TI1_COMP2_OUT )|| \
((TIM_REMAP) == TIM22_TI1_COMP1_OUT )|| \
((TIM_REMAP) == TIM22_TI1_GPIO2 ))
/**
* @}
*/
/**
* @}
*/
/* Exported macro ------------------------------------------------------------*/
/* Exported functions --------------------------------------------------------*/
/* Control functions ***********************************************************/
HAL_StatusTypeDef HAL_TIMEx_RemapConfig(TIM_HandleTypeDef *htim, uint32_t Remap);
HAL_StatusTypeDef HAL_TIMEx_MasterConfigSynchronization(TIM_HandleTypeDef *htim, TIM_MasterConfigTypeDef * sMasterConfig);
/**
* @}
*/
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif /* __STM32L0xx_HAL_TIM_EX_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,766 @@
/**
******************************************************************************
* @file stm32l0xx_hal_tsc.c
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief This file provides firmware functions to manage the following
* functionalities of the Touch Sensing Controller (TSC) peripheral:
* + Initialization and DeInitialization
* + Channel IOs, Shield IOs and Sampling IOs configuration
* + Start and Stop an acquisition
* + Read acquisition result
* + Interrupts and flags management
*
@verbatim
================================================================================
##### TSC specific features #####
================================================================================
[..]
(#) Proven and robust surface charge transfer acquisition principle
(#) Supports up to 3 capacitive sensing channels per group
(#) Capacitive sensing channels can be acquired in parallel offering a very good
response time
(#) Spread spectrum feature to improve system robustness in noisy environments
(#) Full hardware management of the charge transfer acquisition sequence
(#) Programmable charge transfer frequency
(#) Programmable sampling capacitor I/O pin
(#) Programmable channel I/O pin
(#) Programmable max count value to avoid long acquisition when a channel is faulty
(#) Dedicated end of acquisition and max count error flags with interrupt capability
(#) One sampling capacitor for up to 3 capacitive sensing channels to reduce the system
components
(#) Compatible with proximity, touchkey, linear and rotary touch sensor implementation
##### How to use this driver #####
================================================================================
[..]
(#) Enable the TSC interface clock using __TSC_CLK_ENABLE() macro.
(#) GPIO pins configuration
(++) Enable the clock for the TSC GPIOs using __GPIOx_CLK_ENABLE() macro.
(++) Configure the TSC pins used as sampling IOs in alternate function output Open-Drain mode,
and TSC pins used as channel/shield IOs in alternate function output Push-Pull mode
using HAL_GPIO_Init() function.
(++) Configure the alternate function on all the TSC pins using HAL_xxxx() function.
(#) Interrupts configuration
(++) Configure the NVIC (if the interrupt model is used) using HAL_xxx() function.
(#) TSC configuration
(++) Configure all TSC parameters and used TSC IOs using HAL_TSC_Init() function.
*** Acquisition sequence ***
===================================
[..]
(+) Discharge all IOs using HAL_TSC_IODischarge() function.
(+) Wait a certain time allowing a good discharge of all capacitors. This delay depends
of the sampling capacitor and electrodes design.
(+) Select the channel IOs to be acquired using HAL_TSC_IOConfig() function.
(+) Launch the acquisition using either HAL_TSC_Start() or HAL_TSC_Start_IT() function.
If the synchronized mode is selected, the acquisition will start as soon as the signal
is received on the synchro pin.
(+) Wait the end of acquisition using either HAL_TSC_PollForAcquisition() or
HAL_TSC_GetState() function or using WFI instruction for example.
(+) Check the group acquisition status using HAL_TSC_GroupGetStatus() function.
(+) Read the acquisition value using HAL_TSC_GroupGetValue() function.
@endverbatim
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @defgroup TSC
* @brief HAL TSC module driver
* @{
*/
#ifdef HAL_TSC_MODULE_ENABLED
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
static uint32_t TSC_extract_groups(uint32_t iomask);
/* Private functions ---------------------------------------------------------*/
/** @defgroup TSC_Private_Functions
* @{
*/
/** @defgroup TSC_Group1 Initialization/de-initialization functions
* @brief Initialization and Configuration functions
*
@verbatim
===============================================================================
##### Initialization and de-initialization functions #####
===============================================================================
[..] This section provides functions allowing to:
(+) Initialize and configure the TSC.
(+) De-initialize the TSC.
@endverbatim
* @{
*/
/**
* @brief Initializes the TSC peripheral according to the specified parameters
* in the TSC_InitTypeDef structure.
* @param htsc: TSC handle
* @retval HAL status
*/
HAL_StatusTypeDef HAL_TSC_Init(TSC_HandleTypeDef* htsc)
{
/* Check TSC handle allocation */
if (htsc == NULL)
{
return HAL_ERROR;
}
/* Check the parameters */
assert_param(IS_TSC_ALL_INSTANCE(htsc->Instance));
assert_param(IS_TSC_CTPH(htsc->Init.CTPulseHighLength));
assert_param(IS_TSC_CTPL(htsc->Init.CTPulseLowLength));
assert_param(IS_TSC_SS(htsc->Init.SpreadSpectrum));
assert_param(IS_TSC_SSD(htsc->Init.SpreadSpectrumDeviation));
assert_param(IS_TSC_SS_PRESC(htsc->Init.SpreadSpectrumPrescaler));
assert_param(IS_TSC_PG_PRESC(htsc->Init.PulseGeneratorPrescaler));
assert_param(IS_TSC_MCV(htsc->Init.MaxCountValue));
assert_param(IS_TSC_IODEF(htsc->Init.IODefaultMode));
assert_param(IS_TSC_SYNC_POL(htsc->Init.SynchroPinPolarity));
assert_param(IS_TSC_ACQ_MODE(htsc->Init.AcquisitionMode));
assert_param(IS_TSC_MCE_IT(htsc->Init.MaxCountInterrupt));
/* Initialize the TSC state */
htsc->State = HAL_TSC_STATE_BUSY;
/* Init the low level hardware : GPIO, CLOCK, CORTEX */
HAL_TSC_MspInit(htsc);
/*--------------------------------------------------------------------------*/
/* Set TSC parameters */
/* Enable TSC */
htsc->Instance->CR = TSC_CR_TSCE;
/* Set all functions */
htsc->Instance->CR |= (htsc->Init.CTPulseHighLength |
htsc->Init.CTPulseLowLength |
(uint32_t)(htsc->Init.SpreadSpectrumDeviation << 17) |
htsc->Init.SpreadSpectrumPrescaler |
htsc->Init.PulseGeneratorPrescaler |
htsc->Init.MaxCountValue |
htsc->Init.IODefaultMode |
htsc->Init.SynchroPinPolarity |
htsc->Init.AcquisitionMode);
/* Spread spectrum */
if (htsc->Init.SpreadSpectrum == ENABLE)
{
htsc->Instance->CR |= TSC_CR_SSE;
}
/* Disable Schmitt trigger hysteresis on all used TSC IOs */
htsc->Instance->IOHCR = (uint32_t)(~(htsc->Init.ChannelIOs | htsc->Init.ShieldIOs | htsc->Init.SamplingIOs));
/* Set channel and shield IOs */
htsc->Instance->IOCCR = (htsc->Init.ChannelIOs | htsc->Init.ShieldIOs);
/* Set sampling IOs */
htsc->Instance->IOSCR = htsc->Init.SamplingIOs;
/* Set the groups to be acquired */
htsc->Instance->IOGCSR = TSC_extract_groups(htsc->Init.ChannelIOs);
/* Clear interrupts */
htsc->Instance->IER &= (uint32_t)(~(TSC_IT_EOA | TSC_IT_MCE));
/* Clear flags */
htsc->Instance->ICR |= (TSC_FLAG_EOA | TSC_FLAG_MCE);
/*--------------------------------------------------------------------------*/
/* Initialize the TSC state */
htsc->State = HAL_TSC_STATE_READY;
/* Return function status */
return HAL_OK;
}
/**
* @brief Deinitializes the TSC peripheral registers to their default reset values.
* @param htsc: TSC handle
* @retval HAL status
*/
HAL_StatusTypeDef HAL_TSC_DeInit(TSC_HandleTypeDef* htsc)
{
/* Check TSC handle allocation */
if (htsc == NULL)
{
return HAL_ERROR;
}
/* Check the parameters */
assert_param(IS_TSC_ALL_INSTANCE(htsc->Instance));
/* Change TSC state */
htsc->State = HAL_TSC_STATE_BUSY;
/* DeInit the low level hardware */
HAL_TSC_MspDeInit(htsc);
/* Change TSC state */
htsc->State = HAL_TSC_STATE_RESET;
/* Process unlocked */
__HAL_UNLOCK(htsc);
/* Return function status */
return HAL_OK;
}
/**
* @brief Initializes the TSC MSP.
* @param htsc: pointer to a TSC_HandleTypeDef structure that contains
* the configuration information for the specified TSC.
* @retval None
*/
__weak void HAL_TSC_MspInit(TSC_HandleTypeDef* htsc)
{
/* NOTE : This function should not be modified, when the callback is needed,
the HAL_TSC_MspInit could be implemented in the user file.
*/
}
/**
* @brief DeInitializes the TSC MSP.
* @param htsc: pointer to a TSC_HandleTypeDef structure that contains
* the configuration information for the specified TSC.
* @retval None
*/
__weak void HAL_TSC_MspDeInit(TSC_HandleTypeDef* htsc)
{
/* NOTE : This function should not be modified, when the callback is needed,
the HAL_TSC_MspDeInit could be implemented in the user file.
*/
}
/**
* @}
*/
/** @defgroup HAL_TSC_Group2 IO operation functions
* @brief IO operation functions
*
@verbatim
===============================================================================
##### I/O Operation functions #####
===============================================================================
[..] This section provides functions allowing to:
(+) Start acquisition in polling mode.
(+) Start acquisition in interrupt mode.
(+) Stop conversion in polling mode.
(+) Stop conversion in interrupt mode.
(+) Get group acquisition status.
(+) Get group acquisition value.
@endverbatim
* @{
*/
/**
* @brief Starts the acquisition.
* @param htsc: pointer to a TSC_HandleTypeDef structure that contains
* the configuration information for the specified TSC.
* @retval HAL status
*/
HAL_StatusTypeDef HAL_TSC_Start(TSC_HandleTypeDef* htsc)
{
/* Check the parameters */
assert_param(IS_TSC_ALL_INSTANCE(htsc->Instance));
/* Process locked */
__HAL_LOCK(htsc);
/* Change TSC state */
htsc->State = HAL_TSC_STATE_BUSY;
/* Clear interrupts */
__HAL_TSC_DISABLE_IT(htsc, (TSC_IT_EOA | TSC_IT_MCE));
/* Clear flags */
__HAL_TSC_CLEAR_FLAG(htsc, (TSC_FLAG_EOA | TSC_FLAG_MCE));
/* Stop discharging the IOs */
__HAL_TSC_SET_IODEF_INFLOAT(htsc);
/* Launch the acquisition */
__HAL_TSC_START_ACQ(htsc);
/* Process unlocked */
__HAL_UNLOCK(htsc);
/* Return function status */
return HAL_OK;
}
/**
* @brief Enables the interrupt and starts the acquisition
* @param htsc: pointer to a TSC_HandleTypeDef structure that contains
* the configuration information for the specified TSC.
* @retval HAL status.
*/
HAL_StatusTypeDef HAL_TSC_Start_IT(TSC_HandleTypeDef* htsc)
{
/* Check the parameters */
assert_param(IS_TSC_ALL_INSTANCE(htsc->Instance));
assert_param(IS_TSC_MCE_IT(htsc->Init.MaxCountInterrupt));
/* Process locked */
__HAL_LOCK(htsc);
/* Change TSC state */
htsc->State = HAL_TSC_STATE_BUSY;
/* Enable end of acquisition interrupt */
__HAL_TSC_ENABLE_IT(htsc, TSC_IT_EOA);
/* Enable max count error interrupt (optional) */
if (htsc->Init.MaxCountInterrupt == ENABLE)
{
__HAL_TSC_ENABLE_IT(htsc, TSC_IT_MCE);
}
else
{
__HAL_TSC_DISABLE_IT(htsc, TSC_IT_MCE);
}
/* Clear flags */
__HAL_TSC_CLEAR_FLAG(htsc, (TSC_FLAG_EOA | TSC_FLAG_MCE));
/* Stop discharging the IOs */
__HAL_TSC_SET_IODEF_INFLOAT(htsc);
/* Launch the acquisition */
__HAL_TSC_START_ACQ(htsc);
/* Process unlocked */
__HAL_UNLOCK(htsc);
/* Return function status */
return HAL_OK;
}
/**
* @brief Stops the acquisition previously launched in polling mode
* @param htsc: pointer to a TSC_HandleTypeDef structure that contains
* the configuration information for the specified TSC.
* @retval HAL status
*/
HAL_StatusTypeDef HAL_TSC_Stop(TSC_HandleTypeDef* htsc)
{
/* Check the parameters */
assert_param(IS_TSC_ALL_INSTANCE(htsc->Instance));
/* Process locked */
__HAL_LOCK(htsc);
/* Stop the acquisition */
__HAL_TSC_STOP_ACQ(htsc);
/* Clear flags */
__HAL_TSC_CLEAR_FLAG(htsc, (TSC_FLAG_EOA | TSC_FLAG_MCE));
/* Change TSC state */
htsc->State = HAL_TSC_STATE_READY;
/* Process unlocked */
__HAL_UNLOCK(htsc);
/* Return function status */
return HAL_OK;
}
/**
* @brief Stops the acquisition previously launched in interrupt mode
* @param htsc: pointer to a TSC_HandleTypeDef structure that contains
* the configuration information for the specified TSC.
* @retval HAL status
*/
HAL_StatusTypeDef HAL_TSC_Stop_IT(TSC_HandleTypeDef* htsc)
{
/* Check the parameters */
assert_param(IS_TSC_ALL_INSTANCE(htsc->Instance));
/* Process locked */
__HAL_LOCK(htsc);
/* Stop the acquisition */
__HAL_TSC_STOP_ACQ(htsc);
/* Disable interrupts */
__HAL_TSC_DISABLE_IT(htsc, (TSC_IT_EOA | TSC_IT_MCE));
/* Clear flags */
__HAL_TSC_CLEAR_FLAG(htsc, (TSC_FLAG_EOA | TSC_FLAG_MCE));
/* Change TSC state */
htsc->State = HAL_TSC_STATE_READY;
/* Process unlocked */
__HAL_UNLOCK(htsc);
/* Return function status */
return HAL_OK;
}
/**
* @brief Gets the acquisition status for a group
* @param htsc: pointer to a TSC_HandleTypeDef structure that contains
* the configuration information for the specified TSC.
* @param gx_index: Index of the group
* @retval Group status
*/
TSC_GroupStatusTypeDef HAL_TSC_GroupGetStatus(TSC_HandleTypeDef* htsc, uint32_t gx_index)
{
/* Check the parameters */
assert_param(IS_TSC_ALL_INSTANCE(htsc->Instance));
assert_param(IS_GROUP_INDEX(gx_index));
/* Return the group status */
return(__HAL_TSC_GET_GROUP_STATUS(htsc, gx_index));
}
/**
* @brief Gets the acquisition measure for a group
* @param htsc: pointer to a TSC_HandleTypeDef structure that contains
* the configuration information for the specified TSC.
* @param gx_index: Index of the group
* @retval Acquisition measure
*/
uint32_t HAL_TSC_GroupGetValue(TSC_HandleTypeDef* htsc, uint32_t gx_index)
{
/* Check the parameters */
assert_param(IS_TSC_ALL_INSTANCE(htsc->Instance));
assert_param(IS_GROUP_INDEX(gx_index));
/* Return the group acquisition counter */
return htsc->Instance->IOGXCR[gx_index];
}
/**
* @}
*/
/** @defgroup HAL_TSC_Group3 Peripheral Control functions
* @brief Peripheral Control functions
*
@verbatim
===============================================================================
##### Peripheral Control functions #####
===============================================================================
[..] This section provides functions allowing to:
(+) Configure TSC IOs
(+) Discharge TSC IOs
@endverbatim
* @{
*/
/**
* @brief Configures TSC IOs
* @param htsc: pointer to a TSC_HandleTypeDef structure that contains
* the configuration information for the specified TSC.
* @param config: pointer to the configuration structure.
* @retval HAL status
*/
HAL_StatusTypeDef HAL_TSC_IOConfig(TSC_HandleTypeDef* htsc, TSC_IOConfigTypeDef* config)
{
/* Check the parameters */
assert_param(IS_TSC_ALL_INSTANCE(htsc->Instance));
/* Process locked */
__HAL_LOCK(htsc);
/* Stop acquisition */
__HAL_TSC_STOP_ACQ(htsc);
/* Disable Schmitt trigger hysteresis on all used TSC IOs */
htsc->Instance->IOHCR = (uint32_t)(~(config->ChannelIOs | config->ShieldIOs | config->SamplingIOs));
/* Set channel and shield IOs */
htsc->Instance->IOCCR = (config->ChannelIOs | config->ShieldIOs);
/* Set sampling IOs */
htsc->Instance->IOSCR = config->SamplingIOs;
/* Set groups to be acquired */
htsc->Instance->IOGCSR = TSC_extract_groups(config->ChannelIOs);
/* Process unlocked */
__HAL_UNLOCK(htsc);
/* Return function status */
return HAL_OK;
}
/**
* @brief Discharge TSC IOs
* @param htsc: pointer to a TSC_HandleTypeDef structure that contains
* the configuration information for the specified TSC.
* @param choice: enable or disable
* @retval HAL status
*/
HAL_StatusTypeDef HAL_TSC_IODischarge(TSC_HandleTypeDef* htsc, uint32_t choice)
{
/* Check the parameters */
assert_param(IS_TSC_ALL_INSTANCE(htsc->Instance));
/* Process locked */
__HAL_LOCK(htsc);
if (choice == ENABLE)
{
__HAL_TSC_SET_IODEF_OUTPPLOW(htsc);
}
else
{
__HAL_TSC_SET_IODEF_INFLOAT(htsc);
}
/* Process unlocked */
__HAL_UNLOCK(htsc);
/* Return the group acquisition counter */
return HAL_OK;
}
/**
* @}
*/
/** @defgroup HAL_TSC_Group4 State functions
* @brief State functions
*
@verbatim
===============================================================================
##### State functions #####
===============================================================================
[..]
This subsection provides functions allowing to
(+) Get TSC state.
(+) Poll for acquisition completed.
(+) Handles TSC interrupt request.
@endverbatim
* @{
*/
/**
* @brief Return the TSC state
* @param htsc: pointer to a TSC_HandleTypeDef structure that contains
* the configuration information for the specified TSC.
* @retval HAL state
*/
HAL_TSC_StateTypeDef HAL_TSC_GetState(TSC_HandleTypeDef* htsc)
{
/* Check the parameters */
assert_param(IS_TSC_ALL_INSTANCE(htsc->Instance));
if (htsc->State == HAL_TSC_STATE_BUSY)
{
/* Check end of acquisition flag */
if (__HAL_TSC_GET_FLAG(htsc, TSC_FLAG_EOA) != RESET)
{
/* Check max count error flag */
if (__HAL_TSC_GET_FLAG(htsc, TSC_FLAG_MCE) != RESET)
{
/* Change TSC state */
htsc->State = HAL_TSC_STATE_ERROR;
}
else
{
/* Change TSC state */
htsc->State = HAL_TSC_STATE_READY;
}
}
}
/* Return TSC state */
return htsc->State;
}
/**
* @brief Start acquisition and wait until completion
* @note There is no need of a timeout parameter as the max count error is already
* managed by the TSC peripheral.
* @param htsc: pointer to a TSC_HandleTypeDef structure that contains
* the configuration information for the specified TSC.
* @retval HAL state
*/
HAL_StatusTypeDef HAL_TSC_PollForAcquisition(TSC_HandleTypeDef* htsc)
{
/* Check the parameters */
assert_param(IS_TSC_ALL_INSTANCE(htsc->Instance));
/* Process locked */
__HAL_LOCK(htsc);
/* Check end of acquisition */
while (HAL_TSC_GetState(htsc) == HAL_TSC_STATE_BUSY)
{
/* The timeout (max count error) is managed by the TSC peripheral itself. */
}
/* Process unlocked */
__HAL_UNLOCK(htsc);
return HAL_OK;
}
/**
* @brief Handles TSC interrupt request
* @param htsc: pointer to a TSC_HandleTypeDef structure that contains
* the configuration information for the specified TSC.
* @retval None
*/
void HAL_TSC_IRQHandler(TSC_HandleTypeDef* htsc)
{
/* Check the parameters */
assert_param(IS_TSC_ALL_INSTANCE(htsc->Instance));
/* Check if the end of acquisition occured */
if (__HAL_TSC_GET_FLAG(htsc, TSC_FLAG_EOA) != RESET)
{
/* Clear EOA flag */
__HAL_TSC_CLEAR_FLAG(htsc, TSC_FLAG_EOA);
}
/* Check if max count error occured */
if (__HAL_TSC_GET_FLAG(htsc, TSC_FLAG_MCE) != RESET)
{
/* Clear MCE flag */
__HAL_TSC_CLEAR_FLAG(htsc, TSC_FLAG_MCE);
/* Change TSC state */
htsc->State = HAL_TSC_STATE_ERROR;
/* Conversion completed callback */
HAL_TSC_ErrorCallback(htsc);
}
else
{
/* Change TSC state */
htsc->State = HAL_TSC_STATE_READY;
/* Conversion completed callback */
HAL_TSC_ConvCpltCallback(htsc);
}
}
/**
* @}
*/
/**
* @brief Acquisition completed callback in non blocking mode
* @param htsc: pointer to a TSC_HandleTypeDef structure that contains
* the configuration information for the specified TSC.
* @retval None
*/
__weak void HAL_TSC_ConvCpltCallback(TSC_HandleTypeDef* htsc)
{
/* NOTE : This function should not be modified, when the callback is needed,
the HAL_TSC_ConvCpltCallback could be implemented in the user file.
*/
}
/**
* @brief Error callback in non blocking mode
* @param htsc: pointer to a TSC_HandleTypeDef structure that contains
* the configuration information for the specified TSC.
* @retval None
*/
__weak void HAL_TSC_ErrorCallback(TSC_HandleTypeDef* htsc)
{
/* NOTE : This function should not be modified, when the callback is needed,
the HAL_TSC_ErrorCallback could be implemented in the user file.
*/
}
/**
* @brief Utility function used to set the acquired groups mask
* @param iomask: Channels IOs mask
* @retval Acquired groups mask
*/
static uint32_t TSC_extract_groups(uint32_t iomask)
{
uint32_t groups = 0;
uint32_t idx;
for (idx = 0; idx < TSC_NB_OF_GROUPS; idx++)
{
if ((iomask & ((uint32_t)0x0F << (idx * 4))) != RESET)
{
groups |= ((uint32_t)1 << idx);
}
}
return groups;
}
/**
* @}
*/
#endif /* HAL_TSC_MODULE_ENABLED */
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,586 @@
/**
******************************************************************************
* @file stm32l0xx_hal_tsc.h
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief This file contains all the functions prototypes for the TSC firmware
* library.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32L0xx_TSC_H
#define __STM32L0xx_TSC_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal_def.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @addtogroup TSC
* @{
*/
/* Exported types ------------------------------------------------------------*/
/**
* @brief TSC state structure definition
*/
typedef enum
{
HAL_TSC_STATE_RESET = 0x00, /*!< TSC registers have their reset value */
HAL_TSC_STATE_READY = 0x01, /*!< TSC registers are initialized or acquisition is completed with success */
HAL_TSC_STATE_BUSY = 0x02, /*!< TSC initialization or acquisition is on-going */
HAL_TSC_STATE_ERROR = 0x03 /*!< Acquisition is completed with max count error */
} HAL_TSC_StateTypeDef;
/**
* @brief TSC group status structure definition
*/
typedef enum
{
TSC_GROUP_ONGOING = 0x00, /*!< Acquisition on group is on-going or not started */
TSC_GROUP_COMPLETED = 0x01 /*!< Acquisition on group is completed with success (no max count error) */
} TSC_GroupStatusTypeDef;
/**
* @brief TSC init structure definition
*/
typedef struct
{
uint32_t CTPulseHighLength; /*!< Charge-transfer high pulse length */
uint32_t CTPulseLowLength; /*!< Charge-transfer low pulse length */
uint32_t SpreadSpectrum; /*!< Spread spectrum activation */
uint32_t SpreadSpectrumDeviation; /*!< Spread spectrum deviation */
uint32_t SpreadSpectrumPrescaler; /*!< Spread spectrum prescaler */
uint32_t PulseGeneratorPrescaler; /*!< Pulse generator prescaler */
uint32_t MaxCountValue; /*!< Max count value */
uint32_t IODefaultMode; /*!< IO default mode */
uint32_t SynchroPinPolarity; /*!< Synchro pin polarity */
uint32_t AcquisitionMode; /*!< Acquisition mode */
uint32_t MaxCountInterrupt; /*!< Max count interrupt activation */
uint32_t ChannelIOs; /*!< Channel IOs mask */
uint32_t ShieldIOs; /*!< Shield IOs mask */
uint32_t SamplingIOs; /*!< Sampling IOs mask */
} TSC_InitTypeDef;
/**
* @brief TSC IOs configuration structure definition
*/
typedef struct
{
uint32_t ChannelIOs; /*!< Channel IOs mask */
uint32_t ShieldIOs; /*!< Shield IOs mask */
uint32_t SamplingIOs; /*!< Sampling IOs mask */
} TSC_IOConfigTypeDef;
/**
* @brief TSC handle Structure definition
*/
typedef struct
{
TSC_TypeDef *Instance; /*!< Register base address */
TSC_InitTypeDef Init; /*!< Initialization parameters */
__IO HAL_TSC_StateTypeDef State; /*!< Peripheral state */
HAL_LockTypeDef Lock; /*!< Lock feature */
} TSC_HandleTypeDef;
/* Exported constants --------------------------------------------------------*/
/** @defgroup TSC_Exported_Constants
* @{
*/
#define IS_TSC_ALL_INSTANCE(PERIPH) ((PERIPH) == TSC)
#define TSC_CTPH_1CYCLE ((uint32_t)((uint32_t) 0 << 28))
#define TSC_CTPH_2CYCLES ((uint32_t)((uint32_t) 1 << 28))
#define TSC_CTPH_3CYCLES ((uint32_t)((uint32_t) 2 << 28))
#define TSC_CTPH_4CYCLES ((uint32_t)((uint32_t) 3 << 28))
#define TSC_CTPH_5CYCLES ((uint32_t)((uint32_t) 4 << 28))
#define TSC_CTPH_6CYCLES ((uint32_t)((uint32_t) 5 << 28))
#define TSC_CTPH_7CYCLES ((uint32_t)((uint32_t) 6 << 28))
#define TSC_CTPH_8CYCLES ((uint32_t)((uint32_t) 7 << 28))
#define TSC_CTPH_9CYCLES ((uint32_t)((uint32_t) 8 << 28))
#define TSC_CTPH_10CYCLES ((uint32_t)((uint32_t) 9 << 28))
#define TSC_CTPH_11CYCLES ((uint32_t)((uint32_t)10 << 28))
#define TSC_CTPH_12CYCLES ((uint32_t)((uint32_t)11 << 28))
#define TSC_CTPH_13CYCLES ((uint32_t)((uint32_t)12 << 28))
#define TSC_CTPH_14CYCLES ((uint32_t)((uint32_t)13 << 28))
#define TSC_CTPH_15CYCLES ((uint32_t)((uint32_t)14 << 28))
#define TSC_CTPH_16CYCLES ((uint32_t)((uint32_t)15 << 28))
#define IS_TSC_CTPH(VAL) (((VAL) == TSC_CTPH_1CYCLE) || \
((VAL) == TSC_CTPH_2CYCLES) || \
((VAL) == TSC_CTPH_3CYCLES) || \
((VAL) == TSC_CTPH_4CYCLES) || \
((VAL) == TSC_CTPH_5CYCLES) || \
((VAL) == TSC_CTPH_6CYCLES) || \
((VAL) == TSC_CTPH_7CYCLES) || \
((VAL) == TSC_CTPH_8CYCLES) || \
((VAL) == TSC_CTPH_9CYCLES) || \
((VAL) == TSC_CTPH_10CYCLES) || \
((VAL) == TSC_CTPH_11CYCLES) || \
((VAL) == TSC_CTPH_12CYCLES) || \
((VAL) == TSC_CTPH_13CYCLES) || \
((VAL) == TSC_CTPH_14CYCLES) || \
((VAL) == TSC_CTPH_15CYCLES) || \
((VAL) == TSC_CTPH_16CYCLES))
#define TSC_CTPL_1CYCLE ((uint32_t)((uint32_t) 0 << 24))
#define TSC_CTPL_2CYCLES ((uint32_t)((uint32_t) 1 << 24))
#define TSC_CTPL_3CYCLES ((uint32_t)((uint32_t) 2 << 24))
#define TSC_CTPL_4CYCLES ((uint32_t)((uint32_t) 3 << 24))
#define TSC_CTPL_5CYCLES ((uint32_t)((uint32_t) 4 << 24))
#define TSC_CTPL_6CYCLES ((uint32_t)((uint32_t) 5 << 24))
#define TSC_CTPL_7CYCLES ((uint32_t)((uint32_t) 6 << 24))
#define TSC_CTPL_8CYCLES ((uint32_t)((uint32_t) 7 << 24))
#define TSC_CTPL_9CYCLES ((uint32_t)((uint32_t) 8 << 24))
#define TSC_CTPL_10CYCLES ((uint32_t)((uint32_t) 9 << 24))
#define TSC_CTPL_11CYCLES ((uint32_t)((uint32_t)10 << 24))
#define TSC_CTPL_12CYCLES ((uint32_t)((uint32_t)11 << 24))
#define TSC_CTPL_13CYCLES ((uint32_t)((uint32_t)12 << 24))
#define TSC_CTPL_14CYCLES ((uint32_t)((uint32_t)13 << 24))
#define TSC_CTPL_15CYCLES ((uint32_t)((uint32_t)14 << 24))
#define TSC_CTPL_16CYCLES ((uint32_t)((uint32_t)15 << 24))
#define IS_TSC_CTPL(VAL) (((VAL) == TSC_CTPL_1CYCLE) || \
((VAL) == TSC_CTPL_2CYCLES) || \
((VAL) == TSC_CTPL_3CYCLES) || \
((VAL) == TSC_CTPL_4CYCLES) || \
((VAL) == TSC_CTPL_5CYCLES) || \
((VAL) == TSC_CTPL_6CYCLES) || \
((VAL) == TSC_CTPL_7CYCLES) || \
((VAL) == TSC_CTPL_8CYCLES) || \
((VAL) == TSC_CTPL_9CYCLES) || \
((VAL) == TSC_CTPL_10CYCLES) || \
((VAL) == TSC_CTPL_11CYCLES) || \
((VAL) == TSC_CTPL_12CYCLES) || \
((VAL) == TSC_CTPL_13CYCLES) || \
((VAL) == TSC_CTPL_14CYCLES) || \
((VAL) == TSC_CTPL_15CYCLES) || \
((VAL) == TSC_CTPL_16CYCLES))
#define IS_TSC_SS(VAL) (((VAL) == DISABLE) || ((VAL) == ENABLE))
#define IS_TSC_SSD(VAL) (((VAL) == 0) || (((VAL) > 0) && ((VAL) < 128)))
#define TSC_SS_PRESC_DIV1 ((uint32_t)0)
#define TSC_SS_PRESC_DIV2 (TSC_CR_SSPSC)
#define IS_TSC_SS_PRESC(VAL) (((VAL) == TSC_SS_PRESC_DIV1) || ((VAL) == TSC_SS_PRESC_DIV2))
#define TSC_PG_PRESC_DIV1 ((uint32_t)(0 << 12))
#define TSC_PG_PRESC_DIV2 ((uint32_t)(1 << 12))
#define TSC_PG_PRESC_DIV4 ((uint32_t)(2 << 12))
#define TSC_PG_PRESC_DIV8 ((uint32_t)(3 << 12))
#define TSC_PG_PRESC_DIV16 ((uint32_t)(4 << 12))
#define TSC_PG_PRESC_DIV32 ((uint32_t)(5 << 12))
#define TSC_PG_PRESC_DIV64 ((uint32_t)(6 << 12))
#define TSC_PG_PRESC_DIV128 ((uint32_t)(7 << 12))
#define IS_TSC_PG_PRESC(VAL) (((VAL) == TSC_PG_PRESC_DIV1) || \
((VAL) == TSC_PG_PRESC_DIV2) || \
((VAL) == TSC_PG_PRESC_DIV4) || \
((VAL) == TSC_PG_PRESC_DIV8) || \
((VAL) == TSC_PG_PRESC_DIV16) || \
((VAL) == TSC_PG_PRESC_DIV32) || \
((VAL) == TSC_PG_PRESC_DIV64) || \
((VAL) == TSC_PG_PRESC_DIV128))
#define TSC_MCV_255 ((uint32_t)(0 << 5))
#define TSC_MCV_511 ((uint32_t)(1 << 5))
#define TSC_MCV_1023 ((uint32_t)(2 << 5))
#define TSC_MCV_2047 ((uint32_t)(3 << 5))
#define TSC_MCV_4095 ((uint32_t)(4 << 5))
#define TSC_MCV_8191 ((uint32_t)(5 << 5))
#define TSC_MCV_16383 ((uint32_t)(6 << 5))
#define IS_TSC_MCV(VAL) (((VAL) == TSC_MCV_255) || \
((VAL) == TSC_MCV_511) || \
((VAL) == TSC_MCV_1023) || \
((VAL) == TSC_MCV_2047) || \
((VAL) == TSC_MCV_4095) || \
((VAL) == TSC_MCV_8191) || \
((VAL) == TSC_MCV_16383))
#define TSC_IODEF_OUT_PP_LOW ((uint32_t)0)
#define TSC_IODEF_IN_FLOAT (TSC_CR_IODEF)
#define IS_TSC_IODEF(VAL) (((VAL) == TSC_IODEF_OUT_PP_LOW) || ((VAL) == TSC_IODEF_IN_FLOAT))
#define TSC_SYNC_POL_FALL ((uint32_t)0)
#define TSC_SYNC_POL_RISE_HIGH (TSC_CR_SYNCPOL)
#define IS_TSC_SYNC_POL(VAL) (((VAL) == TSC_SYNC_POL_FALL) || ((VAL) == TSC_SYNC_POL_RISE_HIGH))
#define TSC_ACQ_MODE_NORMAL ((uint32_t)0)
#define TSC_ACQ_MODE_SYNCHRO (TSC_CR_AM)
#define IS_TSC_ACQ_MODE(VAL) (((VAL) == TSC_ACQ_MODE_NORMAL) || ((VAL) == TSC_ACQ_MODE_SYNCHRO))
#define TSC_IOMODE_UNUSED ((uint32_t)0)
#define TSC_IOMODE_CHANNEL ((uint32_t)1)
#define TSC_IOMODE_SHIELD ((uint32_t)2)
#define TSC_IOMODE_SAMPLING ((uint32_t)3)
#define IS_TSC_IOMODE(VAL) (((VAL) == TSC_IOMODE_UNUSED) || \
((VAL) == TSC_IOMODE_CHANNEL) || \
((VAL) == TSC_IOMODE_SHIELD) || \
((VAL) == TSC_IOMODE_SAMPLING))
/** @defgroup TSC_interrupts_definition
* @{
*/
#define TSC_IT_EOA ((uint32_t)TSC_IER_EOAIE)
#define TSC_IT_MCE ((uint32_t)TSC_IER_MCEIE)
#define IS_TSC_MCE_IT(VAL) (((VAL) == DISABLE) || ((VAL) == ENABLE))
/**
* @}
*/
/** @defgroup TSC_flags_definition
* @{
*/
#define TSC_FLAG_EOA ((uint32_t)TSC_ISR_EOAF)
#define TSC_FLAG_MCE ((uint32_t)TSC_ISR_MCEF)
/**
* @}
*/
#define TSC_NB_OF_GROUPS (8)
#define TSC_GROUP1 ((uint32_t)0x00000001)
#define TSC_GROUP2 ((uint32_t)0x00000002)
#define TSC_GROUP3 ((uint32_t)0x00000004)
#define TSC_GROUP4 ((uint32_t)0x00000008)
#define TSC_GROUP5 ((uint32_t)0x00000010)
#define TSC_GROUP6 ((uint32_t)0x00000020)
#define TSC_GROUP7 ((uint32_t)0x00000040)
#define TSC_GROUP8 ((uint32_t)0x00000080)
#define TSC_ALL_GROUPS ((uint32_t)0x000000FF)
#define TSC_GROUP1_IDX ((uint32_t)0)
#define TSC_GROUP2_IDX ((uint32_t)1)
#define TSC_GROUP3_IDX ((uint32_t)2)
#define TSC_GROUP4_IDX ((uint32_t)3)
#define TSC_GROUP5_IDX ((uint32_t)4)
#define TSC_GROUP6_IDX ((uint32_t)5)
#define TSC_GROUP7_IDX ((uint32_t)6)
#define TSC_GROUP8_IDX ((uint32_t)7)
#define IS_GROUP_INDEX(VAL) (((VAL) == 0) || (((VAL) > 0) && ((VAL) < TSC_NB_OF_GROUPS)))
#define TSC_GROUP1_IO1 ((uint32_t)0x00000001)
#define TSC_GROUP1_IO2 ((uint32_t)0x00000002)
#define TSC_GROUP1_IO3 ((uint32_t)0x00000004)
#define TSC_GROUP1_IO4 ((uint32_t)0x00000008)
#define TSC_GROUP1_ALL_IOS ((uint32_t)0x0000000F)
#define TSC_GROUP2_IO1 ((uint32_t)0x00000010)
#define TSC_GROUP2_IO2 ((uint32_t)0x00000020)
#define TSC_GROUP2_IO3 ((uint32_t)0x00000040)
#define TSC_GROUP2_IO4 ((uint32_t)0x00000080)
#define TSC_GROUP2_ALL_IOS ((uint32_t)0x000000F0)
#define TSC_GROUP3_IO1 ((uint32_t)0x00000100)
#define TSC_GROUP3_IO2 ((uint32_t)0x00000200)
#define TSC_GROUP3_IO3 ((uint32_t)0x00000400)
#define TSC_GROUP3_IO4 ((uint32_t)0x00000800)
#define TSC_GROUP3_ALL_IOS ((uint32_t)0x00000F00)
#define TSC_GROUP4_IO1 ((uint32_t)0x00001000)
#define TSC_GROUP4_IO2 ((uint32_t)0x00002000)
#define TSC_GROUP4_IO3 ((uint32_t)0x00004000)
#define TSC_GROUP4_IO4 ((uint32_t)0x00008000)
#define TSC_GROUP4_ALL_IOS ((uint32_t)0x0000F000)
#define TSC_GROUP5_IO1 ((uint32_t)0x00010000)
#define TSC_GROUP5_IO2 ((uint32_t)0x00020000)
#define TSC_GROUP5_IO3 ((uint32_t)0x00040000)
#define TSC_GROUP5_IO4 ((uint32_t)0x00080000)
#define TSC_GROUP5_ALL_IOS ((uint32_t)0x000F0000)
#define TSC_GROUP6_IO1 ((uint32_t)0x00100000)
#define TSC_GROUP6_IO2 ((uint32_t)0x00200000)
#define TSC_GROUP6_IO3 ((uint32_t)0x00400000)
#define TSC_GROUP6_IO4 ((uint32_t)0x00800000)
#define TSC_GROUP6_ALL_IOS ((uint32_t)0x00F00000)
#define TSC_GROUP7_IO1 ((uint32_t)0x01000000)
#define TSC_GROUP7_IO2 ((uint32_t)0x02000000)
#define TSC_GROUP7_IO3 ((uint32_t)0x04000000)
#define TSC_GROUP7_IO4 ((uint32_t)0x08000000)
#define TSC_GROUP7_ALL_IOS ((uint32_t)0x0F000000)
#define TSC_GROUP8_IO1 ((uint32_t)0x10000000)
#define TSC_GROUP8_IO2 ((uint32_t)0x20000000)
#define TSC_GROUP8_IO3 ((uint32_t)0x40000000)
#define TSC_GROUP8_IO4 ((uint32_t)0x80000000)
#define TSC_GROUP8_ALL_IOS ((uint32_t)0xF0000000)
#define TSC_ALL_GROUPS_ALL_IOS ((uint32_t)0xFFFFFFFF)
/**
* @}
*/
/* Exported macro ------------------------------------------------------------*/
/** @brief Reset TSC handle state
* @param __HANDLE__: TSC handle
* @retval None
*/
#define __HAL_TSC_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_TSC_STATE_RESET)
/**
* @brief Enable the TSC peripheral.
* @param __HANDLE__: TSC handle
* @retval None
*/
#define __HAL_TSC_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR |= TSC_CR_TSCE)
/**
* @brief Disable the TSC peripheral.
* @param __HANDLE__: TSC handle
* @retval None
*/
#define __HAL_TSC_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR &= (uint32_t)(~TSC_CR_TSCE))
/**
* @brief Start acquisition
* @param __HANDLE__: TSC handle
* @retval None
*/
#define __HAL_TSC_START_ACQ(__HANDLE__) ((__HANDLE__)->Instance->CR |= TSC_CR_START)
/**
* @brief Stop acquisition
* @param __HANDLE__: TSC handle
* @retval None
*/
#define __HAL_TSC_STOP_ACQ(__HANDLE__) ((__HANDLE__)->Instance->CR &= (uint32_t)(~TSC_CR_START))
/**
* @brief Set IO default mode to output push-pull low
* @param __HANDLE__: TSC handle
* @retval None
*/
#define __HAL_TSC_SET_IODEF_OUTPPLOW(__HANDLE__) ((__HANDLE__)->Instance->CR &= (uint32_t)(~TSC_CR_IODEF))
/**
* @brief Set IO default mode to input floating
* @param __HANDLE__: TSC handle
* @retval None
*/
#define __HAL_TSC_SET_IODEF_INFLOAT(__HANDLE__) ((__HANDLE__)->Instance->CR |= TSC_CR_IODEF)
/**
* @brief Set synchronization polarity to falling edge
* @param __HANDLE__: TSC handle
* @retval None
*/
#define __HAL_TSC_SET_SYNC_POL_FALL(__HANDLE__) ((__HANDLE__)->Instance->CR &= (uint32_t)(~TSC_CR_SYNCPOL))
/**
* @brief Set synchronization polarity to rising edge and high level
* @param __HANDLE__: TSC handle
* @retval None
*/
#define __HAL_TSC_SET_SYNC_POL_RISE_HIGH(__HANDLE__) ((__HANDLE__)->Instance->CR |= TSC_CR_SYNCPOL)
/**
* @brief Enable TSC interrupt.
* @param __HANDLE__: TSC handle
* @param __INTERRUPT__: TSC interrupt
* @retval None
*/
#define __HAL_TSC_ENABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->IER |= (__INTERRUPT__))
/**
* @brief Disable TSC interrupt.
* @param __HANDLE__: TSC handle
* @param __INTERRUPT__: TSC interrupt
* @retval None
*/
#define __HAL_TSC_DISABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->IER &= (uint32_t)(~(__INTERRUPT__)))
/** @brief Check if the specified TSC interrupt source is enabled or disabled.
* @param __HANDLE__: TSC Handle
* @param __INTERRUPT__: TSC interrupt
* @retval SET or RESET
*/
#define __HAL_TSC_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) ((((__HANDLE__)->Instance->IER & (__INTERRUPT__)) == (__INTERRUPT__)) ? SET : RESET)
/**
* @brief Get the selected TSC's flag status.
* @param __HANDLE__: TSC handle
* @param __FLAG__: TSC flag
* @retval SET or RESET
*/
#define __HAL_TSC_GET_FLAG(__HANDLE__, __FLAG__) ((((__HANDLE__)->Instance->ISR & (__FLAG__)) == (__FLAG__)) ? SET : RESET)
/**
* @brief Clear the TSC's pending flag.
* @param __HANDLE__: TSC handle
* @param __FLAG__: TSC flag
* @retval None
*/
#define __HAL_TSC_CLEAR_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->ICR = (__FLAG__))
/**
* @brief Enable schmitt trigger hysteresis on a group of IOs
* @param __HANDLE__: TSC handle
* @param __GX_IOY_MASK__: IOs mask
* @retval None
*/
#define __HAL_TSC_ENABLE_HYSTERESIS(__HANDLE__, __GX_IOY_MASK__) ((__HANDLE__)->Instance->IOHCR |= (__GX_IOY_MASK__))
/**
* @brief Disable schmitt trigger hysteresis on a group of IOs
* @param __HANDLE__: TSC handle
* @param __GX_IOY_MASK__: IOs mask
* @retval None
*/
#define __HAL_TSC_DISABLE_HYSTERESIS(__HANDLE__, __GX_IOY_MASK__) ((__HANDLE__)->Instance->IOHCR &= (uint32_t)(~(__GX_IOY_MASK__)))
/**
* @brief Open analog switch on a group of IOs
* @param __HANDLE__: TSC handle
* @param __GX_IOY_MASK__: IOs mask
* @retval None
*/
#define __HAL_TSC_OPEN_ANALOG_SWITCH(__HANDLE__, __GX_IOY_MASK__) ((__HANDLE__)->Instance->IOASCR &= (uint32_t)(~(__GX_IOY_MASK__)))
/**
* @brief Close analog switch on a group of IOs
* @param __HANDLE__: TSC handle
* @param __GX_IOY_MASK__: IOs mask
* @retval None
*/
#define __HAL_TSC_CLOSE_ANALOG_SWITCH(__HANDLE__, __GX_IOY_MASK__) ((__HANDLE__)->Instance->IOASCR |= (__GX_IOY_MASK__))
/**
* @brief Enable a group of IOs in channel mode
* @param __HANDLE__: TSC handle
* @param __GX_IOY_MASK__: IOs mask
* @retval None
*/
#define __HAL_TSC_ENABLE_CHANNEL(__HANDLE__, __GX_IOY_MASK__) ((__HANDLE__)->Instance->IOCCR |= (__GX_IOY_MASK__))
/**
* @brief Disable a group of channel IOs
* @param __HANDLE__: TSC handle
* @param __GX_IOY_MASK__: IOs mask
* @retval None
*/
#define __HAL_TSC_DISABLE_CHANNEL(__HANDLE__, __GX_IOY_MASK__) ((__HANDLE__)->Instance->IOCCR &= (uint32_t)(~(__GX_IOY_MASK__)))
/**
* @brief Enable a group of IOs in sampling mode
* @param __HANDLE__: TSC handle
* @param __GX_IOY_MASK__: IOs mask
* @retval None
*/
#define __HAL_TSC_ENABLE_SAMPLING(__HANDLE__, __GX_IOY_MASK__) ((__HANDLE__)->Instance->IOSCR |= (__GX_IOY_MASK__))
/**
* @brief Disable a group of sampling IOs
* @param __HANDLE__: TSC handle
* @param __GX_IOY_MASK__: IOs mask
* @retval None
*/
#define __HAL_TSC_DISABLE_SAMPLING(__HANDLE__, __GX_IOY_MASK__) ((__HANDLE__)->Instance->IOSCR &= (uint32_t)(~(__GX_IOY_MASK__)))
/**
* @brief Enable acquisition groups
* @param __HANDLE__: TSC handle
* @param __GX_MASK__: Groups mask
* @retval None
*/
#define __HAL_TSC_ENABLE_GROUP(__HANDLE__, __GX_MASK__) ((__HANDLE__)->Instance->IOGCSR |= (__GX_MASK__))
/**
* @brief Disable acquisition groups
* @param __HANDLE__: TSC handle
* @param __GX_MASK__: Groups mask
* @retval None
*/
#define __HAL_TSC_DISABLE_GROUP(__HANDLE__, __GX_MASK__) ((__HANDLE__)->Instance->IOGCSR &= (uint32_t)(~(__GX_MASK__)))
/** @brief Gets acquisition group status
* @param __HANDLE__: TSC Handle
* @param __GX_INDEX__: Group index
* @retval SET or RESET
*/
#define __HAL_TSC_GET_GROUP_STATUS(__HANDLE__, __GX_INDEX__) \
((((__HANDLE__)->Instance->IOGCSR & (uint32_t)((uint32_t)1 << ((__GX_INDEX__) + (uint32_t)16))) == (uint32_t)((uint32_t)1 << ((__GX_INDEX__) + (uint32_t)16))) ? TSC_GROUP_COMPLETED : TSC_GROUP_ONGOING)
/* Exported functions --------------------------------------------------------*/
/* Initialization and de-initialization functions *****************************/
HAL_StatusTypeDef HAL_TSC_Init(TSC_HandleTypeDef* htsc);
HAL_StatusTypeDef HAL_TSC_DeInit(TSC_HandleTypeDef *htsc);
void HAL_TSC_MspInit(TSC_HandleTypeDef* htsc);
void HAL_TSC_MspDeInit(TSC_HandleTypeDef* htsc);
/* IO operation functions *****************************************************/
HAL_StatusTypeDef HAL_TSC_Start(TSC_HandleTypeDef* htsc);
HAL_StatusTypeDef HAL_TSC_Start_IT(TSC_HandleTypeDef* htsc);
HAL_StatusTypeDef HAL_TSC_Stop(TSC_HandleTypeDef* htsc);
HAL_StatusTypeDef HAL_TSC_Stop_IT(TSC_HandleTypeDef* htsc);
TSC_GroupStatusTypeDef HAL_TSC_GroupGetStatus(TSC_HandleTypeDef* htsc, uint32_t gx_index);
uint32_t HAL_TSC_GroupGetValue(TSC_HandleTypeDef* htsc, uint32_t gx_index);
/* Peripheral Control functions ***********************************************/
HAL_StatusTypeDef HAL_TSC_IOConfig(TSC_HandleTypeDef* htsc, TSC_IOConfigTypeDef* config);
HAL_StatusTypeDef HAL_TSC_IODischarge(TSC_HandleTypeDef* htsc, uint32_t choice);
/* Peripheral State and Error functions ***************************************/
HAL_TSC_StateTypeDef HAL_TSC_GetState(TSC_HandleTypeDef* htsc);
HAL_StatusTypeDef HAL_TSC_PollForAcquisition(TSC_HandleTypeDef* htsc);
void HAL_TSC_IRQHandler(TSC_HandleTypeDef* htsc);
/* Callback functions *********************************************************/
void HAL_TSC_ConvCpltCallback(TSC_HandleTypeDef* htsc);
void HAL_TSC_ErrorCallback(TSC_HandleTypeDef* htsc);
/**
* @}
*/
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif /*__STM32L0xx_TSC_H */
/************************ (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,440 @@
/**
******************************************************************************
* @file stm32l0xx_hal_uart_ex.c
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief Extended UART HAL module driver.
*
* This file provides firmware functions to manage the following
* functionalities of the Inter Integrated Circuit (UART) peripheral:
* + Extended Control methods
*
@verbatim
==============================================================================
##### UART peripheral extended features #####
==============================================================================
[..] Comparing to other previous devices, the UART interface for STM32L0XX
devices contains the following additional features
(+) Possibility to disable or enable Analog Noise Filter
(+) Use of a configured Digital Noise Filter
(+) Disable or enable wakeup from Stop mode
##### How to use this driver #####
==============================================================================
[..] This driver provides functions to configure Noise Filter
@endverbatim
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @defgroup UARTEx
* @brief UARTEx module driver
* @{
*/
#ifdef HAL_UART_MODULE_ENABLED
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
#define UART_REACK_TIMEOUT ((uint32_t) 1000)
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
static void UART_Wakeup_AddressConfig(UART_HandleTypeDef *huart, UART_WakeUpTypeDef WakeUpSelection);
/* Private functions ---------------------------------------------------------*/
/** @defgroup UARTEX_Private_Functions
* @{
*/
/** @defgroup UARTEx_Group1 Extended Initialization/de-initialization functions
* @brief Extended Initialization and Configuration Functions
*
@verbatim
===============================================================================
##### Initialization and Configuration functions #####
===============================================================================
[..]
The HAL_RS485Ex_Init() API follows respectively the UART RS485 mode
configuration procedures (details for the procedures are available in reference manual).
@endverbatim
* @{
*/
/**
* @brief Initializes the RS485 Driver enable feature according to the specified
* parameters in the UART_InitTypeDef and creates the associated handle .
* @param huart: uart handle
* @param Polarity: select the driver enable polarity
* This parameter can be one of the following values:
* @arg UART_DE_POLARITY_HIGH: DE signal is active high
* @arg UART_DE_POLARITY_LOW: DE signal is active low
* @param AssertionTime: Driver Enable assertion time
* 5-bit value defining the time between the activation of the DE (Driver Enable)
* signal and the beginning of the start bit. It is expressed in sample time
* units (1/8 or 1/16 bit time, depending on the oversampling rate)
* @param DeassertionTime: Driver Enable deassertion time
* 5-bit value defining the time between the end of the last stop bit, in a
* transmitted message, and the de-activation of the DE (Driver Enable) signal.
* It is expressed in sample time units (1/8 or 1/16 bit time, depending on the
* oversampling rate).
* @retval HAL status
*/
HAL_StatusTypeDef HAL_RS485Ex_Init(UART_HandleTypeDef *huart, uint32_t Polarity, uint32_t AssertionTime, uint32_t DeassertionTime)
{
uint32_t temp = 0x0;
/* Check the UART handle allocation */
if(huart == NULL)
{
return HAL_ERROR;
}
/* Check the Driver Enable polarity */
assert_param(IS_UART_DE_POLARITY(Polarity));
/* Check the Driver Enable assertion time */
assert_param(IS_UART_ASSERTIONTIME(AssertionTime));
/* Check the Driver Enable deassertion time */
assert_param(IS_UART_DEASSERTIONTIME(DeassertionTime));
if(huart->State == HAL_UART_STATE_RESET)
{
/* Init the low level hardware : GPIO, CLOCK, CORTEX */
HAL_UART_MspInit(huart);
}
huart->State = HAL_UART_STATE_BUSY;
/* Disable the Peripheral */
__HAL_UART_DISABLE(huart);
/* Set the UART Communication parameters */
UART_SetConfig(huart);
if(huart->AdvancedInit.AdvFeatureInit != UART_ADVFEATURE_NO_INIT)
{
UART_AdvFeatureConfig(huart);
}
/* Enable the Driver Enable mode by setting the DEM bit in the CR3 register */
huart->Instance->CR3 |= USART_CR3_DEM;
/* Set the Driver Enable polarity */
MODIFY_REG(huart->Instance->CR3, USART_CR3_DEP, Polarity);
/* Set the Driver Enable assertion and deassertion times */
temp = (AssertionTime << UART_CR1_DEAT_ADDRESS_LSB_POS);
temp |= (DeassertionTime << UART_CR1_DEDT_ADDRESS_LSB_POS);
MODIFY_REG(huart->Instance->CR1, (USART_CR1_DEDT|USART_CR1_DEAT), temp);
/* Enable the Peripheral */
__HAL_UART_ENABLE(huart);
/* TEACK and/or REACK to check before moving huart->State to Ready */
return (UART_CheckIdleState(huart));
}
/**
* @brief UART wakeup from Stop mode callback
* @param huart: uart handle
* @retval None
*/
__weak void HAL_UARTEx_WakeupCallback(UART_HandleTypeDef *huart)
{
/* NOTE : This function should not be modified, when the callback is needed,
the HAL_UART_WakeupCallback can be implemented in the user file
*/
}
/**
* @}
*/
/** @defgroup UARTEX_Group2 Peripheral Control functions
* @brief management functions
*
@verbatim
===============================================================================
##### Peripheral Control funtions #####
===============================================================================
[..] This section provides functions allowing to:
(+) UART_AdvFeatureConfig() API optionally configures the UART advanced features
(+) HAL_MultiProcessorEx_AddressLength_Set() API optionally sets the UART node address
detection length to more than 4 bits for multiprocessor address mark wake up.
(+) HAL_UARTEx_EnableStopMode() API enables the UART to wake up the MCU from stop mode
(+) HAL_UARTEx_DisableStopMode() API disables the above functionality
(+) HAL_UARTEx_EnableClockStopMode() API enables the UART HSI clock during stop mode
(+) HAL_UARTEx_DisableClockStopMode() API disables the above functionality
(+) UART_Wakeup_AddressConfig() API configures the wake-up from stop mode parameters
@endverbatim
* @{
*/
/**
* @brief Enable UART Stop Mode
* The UART is able to wake up the MCU from Stop mode as long as UART clock is HSI or LSE
* @param huart: uart handle
* @retval HAL status
*/
HAL_StatusTypeDef HAL_UARTEx_EnableStopMode(UART_HandleTypeDef *huart)
{
/* Process Locked */
__HAL_LOCK(huart);
huart->State = HAL_UART_STATE_BUSY;
/* Set the USART UESM bit */
huart->Instance->CR1 |= USART_CR1_UESM;
huart->State = HAL_UART_STATE_READY;
/* Process Unlocked */
__HAL_UNLOCK(huart);
return HAL_OK;
}
/**
* @brief Enable UART Clock in Stop Mode
* The UART keeps the Clock ON during Stop mode
* @param huart: uart handle
* @retval HAL status
*/
HAL_StatusTypeDef HAL_UARTEx_EnableClockStopMode(UART_HandleTypeDef *huart)
{
/* Process Locked */
__HAL_LOCK(huart);
huart->State = HAL_UART_STATE_BUSY;
/* Set the USART UESM bit */
huart->Instance->CR3 |= USART_CR3_UCESM;
huart->State = HAL_UART_STATE_READY;
/* Process Unlocked */
__HAL_UNLOCK(huart);
return HAL_OK;
}
/**
* @brief Disable UART Stop Mode
* @param huart: uart handle
* @retval HAL status
*/
HAL_StatusTypeDef HAL_UARTEx_DisableStopMode(UART_HandleTypeDef *huart)
{
/* Process Locked */
__HAL_LOCK(huart);
huart->State = HAL_UART_STATE_BUSY;
/* Clear USART UESM bit */
huart->Instance->CR1 &= ~(USART_CR1_UESM);
huart->State = HAL_UART_STATE_READY;
/* Process Unlocked */
__HAL_UNLOCK(huart);
return HAL_OK;
}
/**
* @brief Disable UART Clock in Stop Mode
* @param huart: uart handle
* @retval HAL status
*/
HAL_StatusTypeDef HAL_UARTEx_DisableClockStopMode(UART_HandleTypeDef *huart)
{
/* Process Locked */
__HAL_LOCK(huart);
huart->State = HAL_UART_STATE_BUSY;
/* Clear USART UESM bit */
huart->Instance->CR3 &= ~(USART_CR3_UCESM);
huart->State = HAL_UART_STATE_READY;
/* Process Unlocked */
__HAL_UNLOCK(huart);
return HAL_OK;
}
/**
* @brief Set Wakeup from Stop mode interrupt flag selection
* @param huart: uart handle,
* @param WakeUpSelection: address match, Start Bit detection or RXNE bit status.
* This parameter can be one of the following values:
* @arg UART_WAKEUP_ON_ADDRESS
* @arg UART_WAKEUP_ON_STARTBIT
* @arg UART_WAKEUP_ON_READDATA_NONEMPTY
* @retval HAL status
*/
HAL_StatusTypeDef HAL_UARTEx_StopModeWakeUpSourceConfig(UART_HandleTypeDef *huart, UART_WakeUpTypeDef WakeUpSelection)
{
/* Check the wake-up selection parameter */
assert_param(IS_UART_WAKEUP_SELECTION(WakeUpSelection.WakeUpEvent));
/* Process Locked */
__HAL_LOCK(huart);
huart->State = HAL_UART_STATE_BUSY;
/* Disable the Peripheral */
__HAL_UART_DISABLE(huart);
/* Set the wake-up selection scheme */
MODIFY_REG(huart->Instance->CR3, USART_CR3_WUS, WakeUpSelection.WakeUpEvent);
if(WakeUpSelection.WakeUpEvent == UART_WAKEUP_ON_ADDRESS)
{
UART_Wakeup_AddressConfig(huart, WakeUpSelection);
}
/* Enable the Peripheral */
__HAL_UART_ENABLE(huart);
/* Wait until REACK flag is set before moving huart->State to Ready */
if(UART_WaitOnFlagUntilTimeout(huart, USART_ISR_REACK, RESET, UART_REACK_TIMEOUT) != HAL_OK)
{
return HAL_TIMEOUT;
}
/* Process Unlocked */
__HAL_UNLOCK(huart);
/* Initialize the UART state*/
huart->ErrorCode = HAL_UART_ERROR_NONE;
huart->State= HAL_UART_STATE_READY;
return HAL_OK;
}
/**
* @brief By default in multiprocessor mode, when the wake up method is set
* to address mark, the UART handles only 4-bit long addresses detection.
* This API allows to enable longer addresses detection (6-, 7- or 8-bit
* long):
* - 6-bit address detection in 7-bit data mode
* - 7-bit address detection in 8-bit data mode
* - 8-bit address detection in 9-bit data mode
* @param huart: UART handle
* @param AddressLength: this parameter can be one of the following values:
* @arg UART_ADDRESS_DETECT_4B: 4-bit long address
* @arg UART_ADDRESS_DETECT_7B: 6-, 7- or 8-bit long address
* @retval HAL status
*/
HAL_StatusTypeDef HAL_MultiProcessorEx_AddressLength_Set(UART_HandleTypeDef *huart, uint32_t AddressLength)
{
/* Check the UART handle allocation */
if(huart == NULL)
{
return HAL_ERROR;
}
/* Check the address length parameter */
assert_param(IS_UART_ADDRESSLENGTH_DETECT(AddressLength));
huart->State = HAL_UART_STATE_BUSY;
/* Disable the Peripheral */
__HAL_UART_DISABLE(huart);
/* Set the address length */
MODIFY_REG(huart->Instance->CR2, USART_CR2_ADDM7, AddressLength);
/* Enable the Peripheral */
__HAL_UART_ENABLE(huart);
/* TEACK and/or REACK to check before moving huart->State to Ready */
return (UART_CheckIdleState(huart));
}
/**
* @}
*/
/**
* @brief Initializes the UART wake-up from stop mode parameters when triggered by address detection.
* @param huart: uart handle
* @param WakeUpSelection: UART wake up from stop mode parameters
* @retval HAL status
*/
static void UART_Wakeup_AddressConfig(UART_HandleTypeDef *huart, UART_WakeUpTypeDef WakeUpSelection)
{
assert_param(IS_UART_ADDRESSLENGTH_DETECT(WakeUpSelection.AddressLength));
if(WakeUpSelection.AddressLength == UART_ADDRESS_DETECT_4B)
{
assert_param(IS_UART_4B_ADDRESS(WakeUpSelection.Address));
}
else
{
assert_param(IS_UART_7B_ADDRESS(WakeUpSelection.Address));
}
/* Set the USART address length */
MODIFY_REG(huart->Instance->CR2, USART_CR2_ADDM7, WakeUpSelection.AddressLength);
/* Set the USART address node */
MODIFY_REG(huart->Instance->CR2, USART_CR2_ADD, ((uint32_t)WakeUpSelection.Address << UART_CR2_ADDRESS_LSB_POS));
}
/**
* @}
*/
#endif /* HAL_UART_MODULE_ENABLED */
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,292 @@
/**
******************************************************************************
* @file stm32l0xx_hal_uart_ex.h
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief Header file of UART HAL Extension module.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32L0xx_HAL_UART_EX_H
#define __STM32L0xx_HAL_UART_EX_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal_def.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @addtogroup UARTEx
* @{
*/
/* Exported types ------------------------------------------------------------*/
/**
* @brief UART wake up from stop mode parameters
*/
typedef struct
{
uint32_t WakeUpEvent; /*!< Specifies which event will activat the Wakeup from Stop mode flag (WUF).
This parameter can be a value of @ref UART_WakeUp_from_Stop_Selection.
If set to UART_WAKEUP_ON_ADDRESS, the two other fields below must
be filled up. */
uint16_t AddressLength; /*!< Specifies whether the address is 4 or 7-bit long.
This parameter can be a value of @ref UARTEx_WakeUp_Address_Length */
uint8_t Address; /*!< UART/USART node address (7-bit long max) */
} UART_WakeUpTypeDef;
/* Exported constants --------------------------------------------------------*/
/** @defgroup UARTEx_Extended_Exported_Constants
* @{
*/
/** @defgroup UARTEx_Word_Length
* @{
*/
#define UART_WORDLENGTH_7B ((uint32_t)USART_CR1_M_1)
#define UART_WORDLENGTH_8B ((uint32_t)0x0000)
#define UART_WORDLENGTH_9B ((uint32_t)USART_CR1_M_0)
#define IS_UART_WORD_LENGTH(LENGTH) (((LENGTH) == UART_WORDLENGTH_7B) || \
((LENGTH) == UART_WORDLENGTH_8B) || \
((LENGTH) == UART_WORDLENGTH_9B))
/**
* @}
*/
/** @defgroup UARTEx_AutoBaud_Rate_Mode
* @{
*/
#define UART_ADVFEATURE_AUTOBAUDRATE_ONSTARTBIT ((uint32_t)0x0000)
#define UART_ADVFEATURE_AUTOBAUDRATE_ONFALLINGEDGE ((uint32_t)USART_CR2_ABRMODE_0)
#define UART_ADVFEATURE_AUTOBAUDRATE_ON0X7FFRAME ((uint32_t)USART_CR2_ABRMODE_1)
#define UART_ADVFEATURE_AUTOBAUDRATE_ON0X55FRAME ((uint32_t)USART_CR2_ABRMODE)
#define IS_UART_ADVFEATURE_AUTOBAUDRATEMODE(MODE) (((MODE) == UART_ADVFEATURE_AUTOBAUDRATE_ONSTARTBIT) || \
((MODE) == UART_ADVFEATURE_AUTOBAUDRATE_ONFALLINGEDGE) || \
((MODE) == UART_ADVFEATURE_AUTOBAUDRATE_ON0X7FFRAME) || \
((MODE) == UART_ADVFEATURE_AUTOBAUDRATE_ON0X55FRAME))
/**
* @}
*/
/** @defgroup UARTEx_WakeUp_Address_Length
* @{
*/
#define UART_ADDRESS_DETECT_4B ((uint32_t)0x00000000)
#define UART_ADDRESS_DETECT_7B ((uint32_t)USART_CR2_ADDM7)
#define IS_UART_ADDRESSLENGTH_DETECT(ADDRESS) (((ADDRESS) == UART_ADDRESS_DETECT_4B) || \
((ADDRESS) == UART_ADDRESS_DETECT_7B))
/**
* @}
*/
/** @defgroup UARTEx_WakeUp_Methods
* @{
*/
#define UART_WAKEUPMETHOD_IDLELINE ((uint32_t)0x00000000)
#define UART_WAKEUPMETHOD_ADDRESSMARK ((uint32_t)USART_CR1_WAKE)
#define IS_UART_WAKEUPMETHOD(WAKEUP) (((WAKEUP) == UART_WAKEUPMETHOD_IDLELINE) || \
((WAKEUP) == UART_WAKEUPMETHOD_ADDRESSMARK))
/**
* @}
*/
/**
* @}
*/
/* Exported macro ------------------------------------------------------------*/
/** @defgroup UARTEx_Extended_Exported_Macros
* @{
*/
/** @brief Reports the UART clock source.
* @param __HANDLE__: specifies the UART Handle
* @param __CLOCKSOURCE__ : output variable
* @retval UART clocking source, written in __CLOCKSOURCE__.
*/
#define __HAL_UART_GETCLOCKSOURCE(__HANDLE__,__CLOCKSOURCE__) \
do { \
if((__HANDLE__)->Instance == USART1) \
{ \
switch(__HAL_RCC_GET_USART1_SOURCE()) \
{ \
case RCC_USART1CLKSOURCE_PCLK2: \
(__CLOCKSOURCE__) = UART_CLOCKSOURCE_PCLK2; \
break; \
case RCC_USART1CLKSOURCE_HSI: \
(__CLOCKSOURCE__) = UART_CLOCKSOURCE_HSI; \
break; \
case RCC_USART1CLKSOURCE_SYSCLK: \
(__CLOCKSOURCE__) = UART_CLOCKSOURCE_SYSCLK; \
break; \
case RCC_USART1CLKSOURCE_LSE: \
(__CLOCKSOURCE__) = UART_CLOCKSOURCE_LSE; \
break; \
default: \
break; \
} \
} \
else if((__HANDLE__)->Instance == USART2) \
{ \
switch(__HAL_RCC_GET_USART2_SOURCE()) \
{ \
case RCC_USART2CLKSOURCE_PCLK1: \
(__CLOCKSOURCE__) = UART_CLOCKSOURCE_PCLK1; \
break; \
case RCC_USART2CLKSOURCE_HSI: \
(__CLOCKSOURCE__) = UART_CLOCKSOURCE_HSI; \
break; \
case RCC_USART2CLKSOURCE_SYSCLK: \
(__CLOCKSOURCE__) = UART_CLOCKSOURCE_SYSCLK; \
break; \
case RCC_USART2CLKSOURCE_LSE: \
(__CLOCKSOURCE__) = UART_CLOCKSOURCE_LSE; \
break; \
default: \
break; \
} \
} \
else if((__HANDLE__)->Instance == LPUART1) \
{ \
switch(__HAL_RCC_GET_LPUART1_SOURCE()) \
{ \
case RCC_LPUART1CLKSOURCE_PCLK1: \
(__CLOCKSOURCE__) = UART_CLOCKSOURCE_PCLK1; \
break; \
case RCC_LPUART1CLKSOURCE_HSI: \
(__CLOCKSOURCE__) = UART_CLOCKSOURCE_HSI; \
break; \
case RCC_LPUART1CLKSOURCE_SYSCLK: \
(__CLOCKSOURCE__) = UART_CLOCKSOURCE_SYSCLK; \
break; \
case RCC_LPUART1CLKSOURCE_LSE: \
(__CLOCKSOURCE__) = UART_CLOCKSOURCE_LSE; \
break; \
default: \
break; \
} \
} \
} while(0)
/** @brief Reports the UART mask to apply to retrieve the received data
* according to the word length and to the parity bits activation.
* If PCE = 1, the parity bit is not included in the data extracted
* by the reception API().
* This masking operation is not carried out in the case of
* DMA transfers.
* @param __HANDLE__: specifies the UART Handle
* @param __MASK__ : output variable
* @retval mask to apply to UART RDR register value.
*/
#define __HAL_UART_MASK_COMPUTATION(__HANDLE__) \
do { \
if ((__HANDLE__)->Init.WordLength == UART_WORDLENGTH_9B) \
{ \
if ((__HANDLE__)->Init.Parity == UART_PARITY_NONE) \
{ \
(__HANDLE__)->Mask = 0x01FF ; \
} \
else \
{ \
(__HANDLE__)->Mask = 0x00FF ; \
} \
} \
else if ((__HANDLE__)->Init.WordLength == UART_WORDLENGTH_8B) \
{ \
if ((__HANDLE__)->Init.Parity == UART_PARITY_NONE) \
{ \
(__HANDLE__)->Mask = 0x00FF ; \
} \
else \
{ \
(__HANDLE__)->Mask = 0x007F ; \
} \
} \
else if ((__HANDLE__)->Init.WordLength == UART_WORDLENGTH_7B) \
{ \
if ((__HANDLE__)->Init.Parity == UART_PARITY_NONE) \
{ \
(__HANDLE__)->Mask = 0x007F ; \
} \
else \
{ \
(__HANDLE__)->Mask = 0x003F ; \
} \
} \
} while(0)
/**
* @}
*/
/* Exported functions --------------------------------------------------------*/
/* Initialization/de-initialization functions ********************************/
HAL_StatusTypeDef HAL_RS485Ex_Init(UART_HandleTypeDef *huart, uint32_t Polarity, uint32_t AssertionTime, uint32_t DeassertionTime);
/* IO operation functions *****************************************************/
/* Peripheral Control functions **********************************************/
HAL_StatusTypeDef HAL_UARTEx_StopModeWakeUpSourceConfig(UART_HandleTypeDef *huart, UART_WakeUpTypeDef WakeUpSelection);
HAL_StatusTypeDef HAL_UARTEx_EnableStopMode(UART_HandleTypeDef *huart);
HAL_StatusTypeDef HAL_UARTEx_EnableClockStopMode(UART_HandleTypeDef *huart);
HAL_StatusTypeDef HAL_UARTEx_DisableStopMode(UART_HandleTypeDef *huart);
HAL_StatusTypeDef HAL_UARTEx_DisableClockStopMode(UART_HandleTypeDef *huart);
void HAL_UARTEx_WakeupCallback(UART_HandleTypeDef *huart);
/* Aliases for inter STM32 series compatibility */
#define HAL_UART_WakeupCallback HAL_UARTEx_WakeupCallback
/* Peripheral State functions ************************************************/
HAL_StatusTypeDef HAL_MultiProcessorEx_AddressLength_Set(UART_HandleTypeDef *huart, uint32_t AddressLength);
/**
* @}
*/
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif /* __STM32L0xx_HAL_UART_EX_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,557 @@
/**
******************************************************************************
* @file stm32l0xx_hal_usart.h
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief Header file of USART HAL module.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32L0xx_HAL_USART_H
#define __STM32L0xx_HAL_USART_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal_def.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @addtogroup USART
* @{
*/
/* Exported types ------------------------------------------------------------*/
/**
* @brief USART Init Structure definition
*/
typedef struct
{
uint32_t BaudRate; /*!< This member configures the Usart communication baud rate.
The baud rate is computed using the following formula:
Baud Rate Register = ((PCLKx) / ((huart->Init.BaudRate))) */
uint32_t WordLength; /*!< Specifies the number of data bits transmitted or received in a frame.
This parameter can be a value of @ref USARTEx_Word_Length */
uint32_t StopBits; /*!< Specifies the number of stop bits transmitted.
This parameter can be a value of @ref USART_Stop_Bits */
uint32_t Parity; /*!< Specifies the parity mode.
This parameter can be a value of @ref USART_Parity
@note When parity is enabled, the computed parity is inserted
at the MSB position of the transmitted data (9th bit when
the word length is set to 9 data bits; 8th bit when the
word length is set to 8 data bits). */
uint32_t Mode; /*!< Specifies wether the Receive or Transmit mode is enabled or disabled.
This parameter can be a value of @ref USART_Mode */
uint32_t CLKPolarity; /*!< Specifies the steady state of the serial clock.
This parameter can be a value of @ref USART_Clock_Polarity */
uint32_t CLKPhase; /*!< Specifies the clock transition on which the bit capture is made.
This parameter can be a value of @ref USART_Clock_Phase */
uint32_t CLKLastBit; /*!< Specifies whether the clock pulse corresponding to the last transmitted
data bit (MSB) has to be output on the SCLK pin in synchronous mode.
This parameter can be a value of @ref USART_Last_Bit */
}USART_InitTypeDef;
/**
* @brief HAL State structures definition
*/
typedef enum
{
HAL_USART_STATE_RESET = 0x00, /*!< Peripheral Reset state */
HAL_USART_STATE_READY = 0x01, /*!< Peripheral Initialized and ready for use */
HAL_USART_STATE_BUSY = 0x02, /*!< an internal process is ongoing */
HAL_USART_STATE_BUSY_TX = 0x12, /*!< Data Transmission process is ongoing */
HAL_USART_STATE_BUSY_RX = 0x22, /*!< Data Reception process is ongoing */
HAL_USART_STATE_BUSY_TX_RX = 0x32, /*!< Data Transmission Reception process is ongoing */
HAL_USART_STATE_TIMEOUT = 0x03, /*!< Timeout state */
HAL_USART_STATE_ERROR = 0x04 /*!< Error */
}HAL_USART_StateTypeDef;
/**
* @brief HAL USART Error Code structure definition
*/
typedef enum
{
HAL_USART_ERROR_NONE = 0x00, /*!< No error */
HAL_USART_ERROR_PE = 0x01, /*!< Parity error */
HAL_USART_ERROR_NE = 0x02, /*!< Noise error */
HAL_USART_ERROR_FE = 0x04, /*!< frame error */
HAL_USART_ERROR_ORE = 0x08, /*!< Overrun error */
HAL_USART_ERROR_DMA = 0x10 /*!< DMA transfer error */
}HAL_USART_ErrorTypeDef;
/**
* @brief USART clock sources definitions
*/
typedef enum
{
USART_CLOCKSOURCE_PCLK1 = 0x00, /*!< PCLK1 clock source */
USART_CLOCKSOURCE_PCLK2 = 0x01, /*!< PCLK2 clock source */
USART_CLOCKSOURCE_HSI = 0x02, /*!< HSI clock source */
USART_CLOCKSOURCE_SYSCLK = 0x04, /*!< SYSCLK clock source */
USART_CLOCKSOURCE_LSE = 0x08 /*!< LSE clock source */
}USART_ClockSourceTypeDef;
/**
* @brief HAL USART Error Code structure definition
*/
/**
* @brief USART handle Structure definition
*/
typedef struct
{
USART_TypeDef *Instance; /*!< USART registers base address */
USART_InitTypeDef Init; /*!< Usart communication parameters */
uint8_t *pTxBuffPtr; /*!< Pointer to Usart Tx transfer Buffer */
uint16_t TxXferSize; /*!< Usart Tx Transfer size */
__IO uint16_t TxXferCount; /*!< Usart Tx Transfer Counter */
uint8_t *pRxBuffPtr; /*!< Pointer to Usart Rx transfer Buffer */
uint16_t RxXferSize; /*!< Usart Rx Transfer size */
__IO uint16_t RxXferCount; /*!< Usart Rx Transfer Counter */
uint16_t Mask; /* USART Rx RDR register mask */
DMA_HandleTypeDef *hdmatx; /*!< Usart Tx DMA Handle parameters */
DMA_HandleTypeDef *hdmarx; /*!< Usart Rx DMA Handle parameters */
HAL_LockTypeDef Lock; /*!< Locking object */
__IO HAL_USART_StateTypeDef State; /*!< Usart communication state */
__IO HAL_USART_ErrorTypeDef ErrorCode; /*!< USART Error code */
}USART_HandleTypeDef;
/* Exported constants --------------------------------------------------------*/
/** @defgroup USART_Exported_Constants
* @{
*/
/** @defgroup USART_Stop_Bits
* @{
*/
#define USART_STOPBITS_1 ((uint32_t)0x0000)
#define USART_STOPBITS_0_5 ((uint32_t)USART_CR2_STOP_0)
#define USART_STOPBITS_2 ((uint32_t)USART_CR2_STOP_1)
#define USART_STOPBITS_1_5 ((uint32_t)(USART_CR2_STOP_0 | USART_CR2_STOP_1))
#define IS_USART_STOPBITS(STOPBITS) (((STOPBITS) == USART_STOPBITS_1) || \
((STOPBITS) == USART_STOPBITS_0_5) || \
((STOPBITS) == USART_STOPBITS_1_5) || \
((STOPBITS) == USART_STOPBITS_2))
/**
* @}
*/
/** @defgroup USART_Parity
* @{
*/
#define USART_PARITY_NONE ((uint32_t)0x0000)
#define USART_PARITY_EVEN ((uint32_t)USART_CR1_PCE)
#define USART_PARITY_ODD ((uint32_t)(USART_CR1_PCE | USART_CR1_PS))
#define IS_USART_PARITY(PARITY) (((PARITY) == USART_PARITY_NONE) || \
((PARITY) == USART_PARITY_EVEN) || \
((PARITY) == USART_PARITY_ODD))
/**
* @}
*/
/** @defgroup USART_Mode
* @{
*/
#define USART_MODE_RX ((uint32_t)USART_CR1_RE)
#define USART_MODE_TX ((uint32_t)USART_CR1_TE)
#define USART_MODE_TX_RX ((uint32_t)(USART_CR1_TE |USART_CR1_RE))
#define IS_USART_MODE(MODE) ((((MODE) & (uint32_t)0xFFFFFFF3) == 0x00) && ((MODE) != (uint32_t)0x00))
/**
* @}
*/
/** @defgroup USART_Clock
* @{
*/
#define USART_CLOCK_DISABLED ((uint32_t)0x0000)
#define USART_CLOCK_ENABLED ((uint32_t)USART_CR2_CLKEN)
#define IS_USART_CLOCK(CLOCK) (((CLOCK) == USART_CLOCK_DISABLED) || \
((CLOCK) == USART_CLOCK_ENABLED))
/**
* @}
*/
/** @defgroup USART_Clock_Polarity
* @{
*/
#define USART_POLARITY_LOW ((uint32_t)0x0000)
#define USART_POLARITY_HIGH ((uint32_t)USART_CR2_CPOL)
#define IS_USART_POLARITY(CPOL) (((CPOL) == USART_POLARITY_LOW) || ((CPOL) == USART_POLARITY_HIGH))
/**
* @}
*/
/** @defgroup USART_Clock_Phase
* @{
*/
#define USART_PHASE_1EDGE ((uint32_t)0x0000)
#define USART_PHASE_2EDGE ((uint32_t)USART_CR2_CPHA)
#define IS_USART_PHASE(CPHA) (((CPHA) == USART_PHASE_1EDGE) || ((CPHA) == USART_PHASE_2EDGE))
/**
* @}
*/
/** @defgroup USART_Last_Bit
* @{
*/
#define USART_LASTBIT_DISABLE ((uint32_t)0x0000)
#define USART_LASTBIT_ENABLE ((uint32_t)USART_CR2_LBCL)
#define IS_USART_LASTBIT(LASTBIT) (((LASTBIT) == USART_LASTBIT_DISABLE) || \
((LASTBIT) == USART_LASTBIT_ENABLE))
/**
* @}
*/
/** @defgroup USART_Flags
* Elements values convention: 0xXXXX
* - 0xXXXX : Flag mask in the ISR register
* @{
*/
#define USART_FLAG_REACK ((uint32_t)0x00400000)
#define USART_FLAG_TEACK ((uint32_t)0x00200000)
#define USART_FLAG_BUSY ((uint32_t)0x00010000)
#define USART_FLAG_CTS ((uint32_t)0x00000400)
#define USART_FLAG_CTSIF ((uint32_t)0x00000200)
#define USART_FLAG_LBDF ((uint32_t)0x00000100)
#define USART_FLAG_TXE ((uint32_t)0x00000080)
#define USART_FLAG_TC ((uint32_t)0x00000040)
#define USART_FLAG_RXNE ((uint32_t)0x00000020)
#define USART_FLAG_IDLE ((uint32_t)0x00000010)
#define USART_FLAG_ORE ((uint32_t)0x00000008)
#define USART_FLAG_NE ((uint32_t)0x00000004)
#define USART_FLAG_FE ((uint32_t)0x00000002)
#define USART_FLAG_PE ((uint32_t)0x00000001)
/**
* @}
*/
/** @defgroup USART_Interrupt_definition
* Elements values convention: 0000ZZZZ0XXYYYYYb
* - YYYYY : Interrupt source position in the XX register (5bits)
* - XX : Interrupt source register (2bits)
* - 01: CR1 register
* - 10: CR2 register
* - 11: CR3 register
* - ZZZZ : Flag position in the ISR register(4bits)
* @{
*/
#define USART_IT_PE ((uint16_t)0x0028)
#define USART_IT_TXE ((uint16_t)0x0727)
#define USART_IT_TC ((uint16_t)0x0626)
#define USART_IT_RXNE ((uint16_t)0x0525)
#define USART_IT_IDLE ((uint16_t)0x0424)
#define USART_IT_ERR ((uint16_t)0x0060)
#define USART_IT_ORE ((uint16_t)0x0300)
#define USART_IT_NE ((uint16_t)0x0200)
#define USART_IT_FE ((uint16_t)0x0100)
/**
* @}
*/
/** @defgroup USART_IT_CLEAR_Flags
* @{
*/
#define USART_CLEAR_PEF USART_ICR_PECF /*!< Parity Error Clear Flag */
#define USART_CLEAR_FEF USART_ICR_FECF /*!< Framing Error Clear Flag */
#define USART_CLEAR_NEF USART_ICR_NCF /*!< Noise detected Clear Flag */
#define USART_CLEAR_OREF USART_ICR_ORECF /*!< OverRun Error Clear Flag */
#define USART_CLEAR_IDLEF USART_ICR_IDLECF /*!< IDLE line detected Clear Flag */
#define USART_CLEAR_TCF USART_ICR_TCCF /*!< Transmission Complete Clear Flag */
#define USART_CLEAR_CTSF USART_ICR_CTSCF /*!< CTS Interrupt Clear Flag */
/**
* @}
*/
/** @defgroup USART_Request_Parameters
* @{
*/
#define USART_RXDATA_FLUSH_REQUEST ((uint32_t)USART_RQR_RXFRQ) /*!< Receive Data flush Request */
#define USART_TXDATA_FLUSH_REQUEST ((uint32_t)USART_RQR_TXFRQ) /*!< Transmit data flush Request */
#define IS_USART_REQUEST_PARAMETER(PARAM) (((PARAM) == USART_RXDATA_FLUSH_REQUEST) || \
((PARAM) == USART_TXDATA_FLUSH_REQUEST))
/**
* @}
*/
/** @defgroup USART_Interruption_Mask
* @{
*/
#define USART_IT_MASK ((uint16_t)0x001F)
/**
* @}
*/
/**
* @}
*/
/* Exported macro ------------------------------------------------------------*/
/** @defgroup USART_Exported_Macros
* @{
*/
/** @brief Reset USART handle state
* @param __HANDLE__: specifies the UART Handle.
* The Handle Instance which can be USART1 or USART2.
* @retval None
*/
#define __HAL_USART_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_USART_STATE_RESET)
/** @brief Checks whether the specified USART flag is set or not.
* @param __HANDLE__: specifies the USART Handle which can be USART1 or USART2.
* @param __FLAG__: specifies the flag to check.
* This parameter can be one of the following values:
* @arg USART_FLAG_REACK: Receive enable ackowledge flag
* @arg USART_FLAG_TEACK: Transmit enable ackowledge flag
* @arg USART_FLAG_BUSY: Busy flag
* @arg USART_FLAG_CTS: CTS Change flag
* @arg USART_FLAG_TXE: Transmit data register empty flag
* @arg USART_FLAG_TC: Transmission Complete flag
* @arg USART_FLAG_RXNE: Receive data register not empty flag
* @arg USART_FLAG_IDLE: Idle Line detection flag
* @arg USART_FLAG_ORE: OverRun Error flag
* @arg USART_FLAG_NE: Noise Error flag
* @arg USART_FLAG_FE: Framing Error flag
* @arg USART_FLAG_PE: Parity Error flag
* @retval The new state of __FLAG__ (TRUE or FALSE).
*/
#define __HAL_USART_GET_FLAG(__HANDLE__, __FLAG__) (((__HANDLE__)->Instance->ISR & (__FLAG__)) == (__FLAG__))
/** @brief Enables the specified USART interrupt.
* @param __HANDLE__: specifies the USART Handle which can be USART1 or USART2.
* @param __INTERRUPT__: specifies the USART interrupt source to enable.
* This parameter can be one of the following values:
* @arg USART_IT_TXE: Transmit Data Register empty interrupt
* @arg USART_IT_TC: Transmission complete interrupt
* @arg USART_IT_RXNE: Receive Data register not empty interrupt
* @arg USART_IT_IDLE: Idle line detection interrupt
* @arg USART_IT_PE: Parity Error interrupt
* @arg USART_IT_ERR: Error interrupt(Frame error, noise error, overrun error)
* @retval None
*/
#define __HAL_USART_ENABLE_IT(__HANDLE__, __INTERRUPT__)(((((uint8_t)(__INTERRUPT__)) >> 5) == 1)? ((__HANDLE__)->Instance->CR1 |= (1 << ((__INTERRUPT__) & USART_IT_MASK))): \
((((uint8_t)(__INTERRUPT__)) >> 5) == 2)? ((__HANDLE__)->Instance->CR2 |= (1 << ((__INTERRUPT__) & USART_IT_MASK))): \
((__HANDLE__)->Instance->CR3 |= (1 << ((__INTERRUPT__) & USART_IT_MASK))))
/** @brief Disables the specified USART interrupt.
* @param __HANDLE__: specifies the USART Handle which can be USART1 or USART2.
* @param __INTERRUPT__: specifies the USART interrupt source to disable.
* This parameter can be one of the following values:
* @arg USART_IT_TXE: Transmit Data Register empty interrupt
* @arg USART_IT_TC: Transmission complete interrupt
* @arg USART_IT_RXNE: Receive Data register not empty interrupt
* @arg USART_IT_IDLE: Idle line detection interrupt
* @arg USART_IT_PE: Parity Error interrupt
* @arg USART_IT_ERR: Error interrupt(Frame error, noise error, overrun error)
* @retval None
*/
#define __HAL_USART_DISABLE_IT(__HANDLE__, __INTERRUPT__) (((((uint8_t)(__INTERRUPT__)) >> 5) == 1)? ((__HANDLE__)->Instance->CR1 &= ~ ((uint32_t)1 << ((__INTERRUPT__) & USART_IT_MASK))): \
((((uint8_t)(__INTERRUPT__)) >> 5) == 2)? ((__HANDLE__)->Instance->CR2 &= ~ ((uint32_t)1 << ((__INTERRUPT__) & USART_IT_MASK))): \
((__HANDLE__)->Instance->CR3 &= ~ ((uint32_t)1 << ((__INTERRUPT__) & USART_IT_MASK))))
/** @brief Checks whether the specified USART interrupt has occurred or not.
* @param __HANDLE__: specifies the USART Handle which can be USART1 or USART2.
* @param __IT__: specifies the USART interrupt source to check.
* This parameter can be one of the following values:
* @arg USART_IT_TXE: Transmit Data Register empty interrupt
* @arg USART_IT_TC: Transmission complete interrupt
* @arg USART_IT_RXNE: Receive Data register not empty interrupt
* @arg USART_IT_IDLE: Idle line detection interrupt
* @arg USART_IT_ORE: OverRun Error interrupt
* @arg USART_IT_NE: Noise Error interrupt
* @arg USART_IT_FE: Framing Error interrupt
* @arg USART_IT_PE: Parity Error interrupt
* @retval The new state of __IT__ (TRUE or FALSE).
*/
#define __HAL_USART_GET_IT(__HANDLE__, __IT__) ((__HANDLE__)->Instance->ISR & ((uint32_t)1 << ((__IT__)>> 0x08)))
/** @brief Checks whether the specified USART interrupt source is enabled.
* @param __HANDLE__: specifies the USART Handle which can be USART1 or USART2.
* @param __IT__: specifies the USART interrupt source to check.
* This parameter can be one of the following values:
* @arg USART_IT_TXE: Transmit Data Register empty interrupt
* @arg USART_IT_TC: Transmission complete interrupt
* @arg USART_IT_RXNE: Receive Data register not empty interrupt
* @arg USART_IT_IDLE: Idle line detection interrupt
* @arg USART_IT_ORE: OverRun Error interrupt
* @arg USART_IT_NE: Noise Error interrupt
* @arg USART_IT_FE: Framing Error interrupt
* @arg USART_IT_PE: Parity Error interrupt
* @retval The new state of __IT__ (TRUE or FALSE).
*/
#define __HAL_USART_GET_IT_SOURCE(__HANDLE__, __IT__) ((((((uint8_t)(__IT__)) >> 5) == 1)? (__HANDLE__)->Instance->CR1:(((((uint8_t)(__IT__)) >> 5) == 2)? \
(__HANDLE__)->Instance->CR2 : (__HANDLE__)->Instance->CR3)) & ((uint32_t)1 << \
(((uint16_t)(__IT__)) & USART_IT_MASK)))
/** @brief Clears the specified USART ISR flag, in setting the proper ICR register flag.
* @param __HANDLE__: specifies the USART Handle which can be USART1 or USART2.
* @param __IT_CLEAR__: specifies the interrupt clear register flag that needs to be set
* to clear the corresponding interrupt
* This parameter can be one of the following values:
* @arg USART_CLEAR_PEF: Parity Error Clear Flag
* @arg USART_CLEAR_FEF: Framing Error Clear Flag
* @arg USART_CLEAR_NEF: Noise detected Clear Flag
* @arg USART_CLEAR_OREF: OverRun Error Clear Flag
* @arg USART_CLEAR_IDLEF: IDLE line detected Clear Flag
* @arg USART_CLEAR_TCF: Transmission Complete Clear Flag
* @arg USART_CLEAR_CTSF: CTS Interrupt Clear Flag
* @retval None
*/
#define __HAL_USART_CLEAR_IT(__HANDLE__, __IT_CLEAR__) ((__HANDLE__)->Instance->ICR = (uint32_t)(__IT_CLEAR__))
/** @brief Set a specific USART request flag.
* @param __HANDLE__: specifies the USART Handle which can be USART1 or USART2.
* @param __REQ__: specifies the request flag to set
* This parameter can be one of the following values:
* @arg USART_RXDATA_FLUSH_REQUEST: Receive Data flush Request
* @arg USART_TXDATA_FLUSH_REQUEST: Transmit data flush Request
*
* @retval None
*/
#define __HAL_USART_SEND_REQ(__HANDLE__, __REQ__) ((__HANDLE__)->Instance->RQR |= (uint16_t)(__REQ__))
/** @brief Enable USART
* @param __HANDLE__: specifies the USART Handle.
* The Handle Instance which can be USART1 or USART2.
* @retval None
*/
#define __HAL_USART_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR1 |= USART_CR1_UE)
/** @brief Disable USART
* @param __HANDLE__: specifies the USART Handle.
* The Handle Instance which can be USART1 or USART2.
* @retval None
*/
#define __HAL_USART_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR1 &= ~USART_CR1_UE)
/** @brief Check USART Baud rate
* @param BAUDRATE: Baudrate specified by the user
* The maximum Baud Rate is derived from the maximum clock on L0 (i.e. 32 MHz)
* divided by the smallest oversampling used on the USART (i.e. 8)
* @retval Test result (TRUE or FALSE).
*/
#define IS_USART_BAUDRATE(BAUDRATE) ((BAUDRATE) < 4000001)
/**
* @}
*/
/* Include UART HAL Extension module */
#include "stm32l0xx_hal_usart_ex.h"
/* Exported functions --------------------------------------------------------*/
/* Initialization/de-initialization functions ********************************/
HAL_StatusTypeDef HAL_USART_Init(USART_HandleTypeDef *husart);
HAL_StatusTypeDef HAL_USART_DeInit(USART_HandleTypeDef *husart);
void HAL_USART_MspInit(USART_HandleTypeDef *husart);
void HAL_USART_MspDeInit(USART_HandleTypeDef *husart);
void HAL_USART_SetConfig(USART_HandleTypeDef *husart);
/* IO operation functions *****************************************************/
HAL_StatusTypeDef HAL_USART_Transmit(USART_HandleTypeDef *husart, uint8_t *pTxData, uint16_t Size, uint32_t Timeout);
HAL_StatusTypeDef HAL_USART_Receive(USART_HandleTypeDef *husart, uint8_t *pRxData, uint16_t Size, uint32_t Timeout);
HAL_StatusTypeDef HAL_USART_TransmitReceive(USART_HandleTypeDef *husart, uint8_t *pTxData, uint8_t *pRxData, uint16_t Size, uint32_t Timeout);
HAL_StatusTypeDef HAL_USART_Transmit_IT(USART_HandleTypeDef *husart, uint8_t *pTxData, uint16_t Size);
HAL_StatusTypeDef HAL_USART_Receive_IT(USART_HandleTypeDef *husart, uint8_t *pRxData, uint16_t Size);
HAL_StatusTypeDef HAL_USART_TransmitReceive_IT(USART_HandleTypeDef *husart, uint8_t *pTxData, uint8_t *pRxData, uint16_t Size);
HAL_StatusTypeDef HAL_USART_Transmit_DMA(USART_HandleTypeDef *husart, uint8_t *pTxData, uint16_t Size);
HAL_StatusTypeDef HAL_USART_Receive_DMA(USART_HandleTypeDef *husart, uint8_t *pRxData, uint16_t Size);
HAL_StatusTypeDef HAL_USART_TransmitReceive_DMA(USART_HandleTypeDef *husart, uint8_t *pTxData, uint8_t *pRxData, uint16_t Size);
HAL_StatusTypeDef HAL_USART_DMAPause(USART_HandleTypeDef *husart);
HAL_StatusTypeDef HAL_USART_DMAResume(USART_HandleTypeDef *husart);
HAL_StatusTypeDef HAL_USART_DMAStop(USART_HandleTypeDef *husart);
void HAL_USART_IRQHandler(USART_HandleTypeDef *husart);
void HAL_USART_TxCpltCallback(USART_HandleTypeDef *husart);
void HAL_USART_TxHalfCpltCallback(USART_HandleTypeDef *husart);
void HAL_USART_RxCpltCallback(USART_HandleTypeDef *husart);
void HAL_USART_RxHalfCpltCallback(USART_HandleTypeDef *husart);
void HAL_USART_TxRxCpltCallback(USART_HandleTypeDef *husart);
void HAL_USART_ErrorCallback(USART_HandleTypeDef *husart);
/* Peripheral State functions ************************************************/
HAL_USART_StateTypeDef HAL_USART_GetState(USART_HandleTypeDef *husart);
uint32_t HAL_USART_GetError(USART_HandleTypeDef *husart);
/**
* @}
*/
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif /* __STM32L0xx_HAL_USART_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,206 @@
/**
******************************************************************************
* @file stm32l0xx_hal_usart_ex.h
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief Header file of USART HAL Extension module.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32L0xx_HAL_USART_EX_H
#define __STM32L0xx_HAL_USART_EX_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal_def.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @addtogroup USARTEx
* @{
*/
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
/** @defgroup USARTEx_Exported_Constants
* @{
*/
/** @defgroup USARTEx_Word_Length
* @{
*/
#define USART_WORDLENGTH_7B ((uint32_t)USART_CR1_M_1)
#define USART_WORDLENGTH_8B ((uint32_t)0x00000000)
#define USART_WORDLENGTH_9B ((uint32_t)USART_CR1_M_0)
#define IS_USART_WORD_LENGTH(LENGTH) (((LENGTH) == USART_WORDLENGTH_7B) || \
((LENGTH) == USART_WORDLENGTH_8B) || \
((LENGTH) == USART_WORDLENGTH_9B))
/**
* @}
*/
/**
* @}
*/
/* Exported macro ------------------------------------------------------------*/
/** @defgroup USARTEx_Extended_Exported_Macros
* @{
*/
/** @brief Reports the USART clock source.
* @param __HANDLE__: specifies the USART Handle
* @param __CLOCKSOURCE__ : output variable
* @retval the USART clocking source, written in __CLOCKSOURCE__.
*/
#define __HAL_USART_GETCLOCKSOURCE(__HANDLE__,__CLOCKSOURCE__) \
do { \
if((__HANDLE__)->Instance == USART1) \
{ \
switch(__HAL_RCC_GET_USART1_SOURCE()) \
{ \
case RCC_USART1CLKSOURCE_PCLK2: \
(__CLOCKSOURCE__) = USART_CLOCKSOURCE_PCLK2; \
break; \
case RCC_USART1CLKSOURCE_HSI: \
(__CLOCKSOURCE__) = USART_CLOCKSOURCE_HSI; \
break; \
case RCC_USART1CLKSOURCE_SYSCLK: \
(__CLOCKSOURCE__) = USART_CLOCKSOURCE_SYSCLK; \
break; \
case RCC_USART1CLKSOURCE_LSE: \
(__CLOCKSOURCE__) = USART_CLOCKSOURCE_LSE; \
break; \
default: \
break; \
} \
} \
else if((__HANDLE__)->Instance == USART2) \
{ \
switch(__HAL_RCC_GET_USART2_SOURCE()) \
{ \
case RCC_USART2CLKSOURCE_PCLK1: \
(__CLOCKSOURCE__) = USART_CLOCKSOURCE_PCLK1; \
break; \
case RCC_USART2CLKSOURCE_HSI: \
(__CLOCKSOURCE__) = USART_CLOCKSOURCE_HSI; \
break; \
case RCC_USART2CLKSOURCE_SYSCLK: \
(__CLOCKSOURCE__) = USART_CLOCKSOURCE_SYSCLK; \
break; \
case RCC_USART2CLKSOURCE_LSE: \
(__CLOCKSOURCE__) = USART_CLOCKSOURCE_LSE; \
break; \
default: \
break; \
} \
} \
} while(0)
/** @brief Reports the USART mask to apply to retrieve the received data
* according to the word length and to the parity bits activation.
* If PCE = 1, the parity bit is not included in the data extracted
* by the reception API().
* This masking operation is not carried out in the case of
* DMA transfers.
* @param __HANDLE__: specifies the USART Handle
* @param __MASK__ : output variable
* @retval mask to apply to USART RDR register value.
*/
#define __HAL_USART_MASK_COMPUTATION(__HANDLE__) \
do { \
if ((__HANDLE__)->Init.WordLength == USART_WORDLENGTH_9B) \
{ \
if ((__HANDLE__)->Init.Parity == USART_PARITY_NONE) \
{ \
(__HANDLE__)->Mask = 0x01FF ; \
} \
else \
{ \
(__HANDLE__)->Mask = 0x00FF ; \
} \
} \
else if ((__HANDLE__)->Init.WordLength == USART_WORDLENGTH_8B) \
{ \
if ((__HANDLE__)->Init.Parity == USART_PARITY_NONE) \
{ \
(__HANDLE__)->Mask = 0x00FF ; \
} \
else \
{ \
(__HANDLE__)->Mask = 0x007F ; \
} \
} \
else if ((__HANDLE__)->Init.WordLength == USART_WORDLENGTH_7B) \
{ \
if ((__HANDLE__)->Init.Parity == USART_PARITY_NONE) \
{ \
(__HANDLE__)->Mask = 0x007F ; \
} \
else \
{ \
(__HANDLE__)->Mask = 0x003F ; \
} \
} \
} while(0)
/**
* @}
*/
/* Exported functions --------------------------------------------------------*/
/* Initialization/de-initialization methods **********************************/
/* IO operation methods *******************************************************/
/* Peripheral Control methods ************************************************/
/* Peripheral State methods **************************************************/
/**
* @}
*/
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif /* __STM32L0xx_HAL_USART_EX_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,461 @@
/**
******************************************************************************
* @file stm32l0xx_hal_wwdg.c
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief WWDG HAL module driver.
* This file provides firmware functions to manage the following
* functionalities of the Window Watchdog (WWDG) peripheral:
* + Initialization and de-initialization functions
* + IO operation functions
* + Peripheral State functions
@verbatim
==============================================================================
##### WWDG specific features #####
==============================================================================
[..]
Once enabled the WWDG generates a system reset on expiry of a programmed
time period, unless the program refreshes the counter (downcounter)
before reaching 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 @32 MHz(PCLK1): ~128.0 us / ~65.54 ms
##### How to use this driver #####
==============================================================================
[..]
(+) Enable WWDG APB1 clock using __WWDG_CLK_ENABLE().
(+) Set the WWDG prescaler, refresh window and counter value
using HAL_WWDG_Init() function.
(+) Start the WWDG using HAL_WWDG_Start() 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 (EWI) which is
generated when the counter reaches 0x40, and then start the WWDG using
HAL_WWDG_Start_IT().
Once enabled, EWI 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
HAL_WWDG_Refresh() function. This operation must occur only when
the counter is lower than the refresh window value already programmed.
*** WWDG HAL driver macros list ***
==================================
[..]
Below the list of most used macros in WWDG HAL driver.
(+) __HAL_WWDG_ENABLE: Enable the WWDG peripheral
(+) __HAL_WWDG_GET_FLAG: Get the selected WWDG's flag status
(+) __HAL_WWDG_CLEAR_FLAG: Clear the WWDG's pending flags
(+) __HAL_WWDG_ENABLE_IT: Enables the WWDG early wakeup interrupt
@endverbatim
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @defgroup WWDG
* @brief WWDG HAL module driver.
* @{
*/
#ifdef HAL_WWDG_MODULE_ENABLED
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/** @defgroup WWDG_Private_Functions
* @{
*/
/** @defgroup WWDG_Group1 Initialization and de-initialization functions
* @brief Initialization and Configuration functions.
*
@verbatim
==============================================================================
##### Initialization and de-initialization functions #####
==============================================================================
[..]
This section provides functions allowing to:
(+) Initialize the WWDG according to the specified parameters
in the WWDG_InitTypeDef and create the associated handle
(+) DeInitialize the WWDG peripheral
(+) Initialize the WWDG MSP
(+) DeInitialize the WWDG MSP
@endverbatim
* @{
*/
/**
* @brief Initializes the WWDG according to the specified
* parameters in the WWDG_InitTypeDef and creates the associated handle.
* @param hwwdg: pointer to a WWDG_HandleTypeDef structure that contains
* the configuration information for the specified WWDG module.
* @retval HAL status
*/
HAL_StatusTypeDef HAL_WWDG_Init(WWDG_HandleTypeDef *hwwdg)
{
uint32_t tmp = 0;
/* Check the WWDG handle allocation */
if(hwwdg == NULL)
{
return HAL_ERROR;
}
/* Check the parameters */
assert_param(IS_WWDG_ALL_INSTANCE(hwwdg->Instance));
assert_param(IS_WWDG_PRESCALER(hwwdg->Init.Prescaler));
assert_param(IS_WWDG_WINDOW(hwwdg->Init.Window));
assert_param(IS_WWDG_COUNTER(hwwdg->Init.Counter));
if(hwwdg->State == HAL_WWDG_STATE_RESET)
{
/* Init the low level hardware */
HAL_WWDG_MspInit(hwwdg);
}
/* Change WWDG peripheral state */
hwwdg->State = HAL_WWDG_STATE_BUSY;
/* Set WWDG Prescaler and Window */
/* Get the CFR register value */
tmp = hwwdg->Instance->CFR;
/* Clear WDGTB[1:0] and W[6:0] bits */
tmp &= ((uint32_t)~(WWDG_CFR_WDGTB | WWDG_CFR_W));
/* Prepare the WWDG Prescaler and Window parameters */
tmp |= hwwdg->Init.Prescaler | hwwdg->Init.Window;
/* Write to WWDG CFR */
hwwdg->Instance->CFR = tmp;
/* Set WWDG Counter */
/* Get the CR register value */
tmp = hwwdg->Instance->CR;
/* Clear T[6:0] bits */
tmp &= (uint32_t)~((uint32_t)WWDG_CR_T);
/* Prepare the WWDG Counter parameter */
tmp |= (hwwdg->Init.Counter);
/* Write to WWDG CR */
hwwdg->Instance->CR = tmp;
/* Change WWDG peripheral state */
hwwdg->State = HAL_WWDG_STATE_READY;
/* Return function status */
return HAL_OK;
}
/**
* @brief DeInitializes the WWDG peripheral.
* @param hwwdg: pointer to a WWDG_HandleTypeDef structure that contains
* the configuration information for the specified WWDG module.
* @retval HAL status
*/
HAL_StatusTypeDef HAL_WWDG_DeInit(WWDG_HandleTypeDef *hwwdg)
{
/* Check the parameters */
assert_param(IS_WWDG_ALL_INSTANCE(hwwdg->Instance));
/* Change WWDG peripheral state */
hwwdg->State = HAL_WWDG_STATE_BUSY;
/* DeInit the low level hardware */
HAL_WWDG_MspDeInit(hwwdg);
/* Reset WWDG Control register */
hwwdg->Instance->CR = (uint32_t)0x0000007F;
/* Reset WWDG Configuration register */
hwwdg->Instance->CFR = (uint32_t)0x0000007F;
/* Reset WWDG Status register */
hwwdg->Instance->SR = 0;
/* Change WWDG peripheral state */
hwwdg->State = HAL_WWDG_STATE_RESET;
/* Release Lock */
__HAL_UNLOCK(hwwdg);
/* Return function status */
return HAL_OK;
}
/**
* @brief Initializes the WWDG MSP.
* @param hwwdg: pointer to a WWDG_HandleTypeDef structure that contains
* the configuration information for the specified WWDG module.
* @retval None
*/
__weak void HAL_WWDG_MspInit(WWDG_HandleTypeDef *hwwdg)
{
/* NOTE: This function Should not be modified, when the callback is needed,
the HAL_WWDG_MspInit could be implemented in the user file
*/
}
/**
* @brief DeInitializes the WWDG MSP.
* @param hwwdg: pointer to a WWDG_HandleTypeDef structure that contains
* the configuration information for the specified WWDG module.
* @retval None
*/
__weak void HAL_WWDG_MspDeInit(WWDG_HandleTypeDef *hwwdg)
{
/* NOTE: This function Should not be modified, when the callback is needed,
the HAL_WWDG_MspDeInit could be implemented in the user file
*/
}
/**
* @}
*/
/** @defgroup WWDG_Group2 IO operation functions
* @brief IO operation functions
*
@verbatim
==============================================================================
##### IO operation functions #####
==============================================================================
[..]
This section provides functions allowing to:
(+) Start the WWDG.
(+) Refresh the WWDG.
(+) Handle WWDG interrupt request.
@endverbatim
* @{
*/
/**
* @brief Starts the WWDG.
* @param hwwdg: pointer to a WWDG_HandleTypeDef structure that contains
* the configuration information for the specified WWDG module.
* @retval HAL status
*/
HAL_StatusTypeDef HAL_WWDG_Start(WWDG_HandleTypeDef *hwwdg)
{
/* Process Locked */
__HAL_LOCK(hwwdg);
/* Change WWDG peripheral state */
hwwdg->State = HAL_WWDG_STATE_BUSY;
/* Enable the peripheral */
__HAL_WWDG_ENABLE(hwwdg);
/* Change WWDG peripheral state */
hwwdg->State = HAL_WWDG_STATE_READY;
/* Process Unlocked */
__HAL_UNLOCK(hwwdg);
/* Return function status */
return HAL_OK;
}
/**
* @brief Starts the WWDG with interrupt enabled.
* @param hwwdg: pointer to a WWDG_HandleTypeDef structure that contains
* the configuration information for the specified WWDG module.
* @retval HAL status
*/
HAL_StatusTypeDef HAL_WWDG_Start_IT(WWDG_HandleTypeDef *hwwdg)
{
/* Process Locked */
__HAL_LOCK(hwwdg);
/* Change WWDG peripheral state */
hwwdg->State = HAL_WWDG_STATE_BUSY;
/* Enable the Early Wakeup Interrupt */
__HAL_WWDG_ENABLE_IT(WWDG_IT_EWI);
/* Enable the peripheral */
__HAL_WWDG_ENABLE(hwwdg);
/* Return function status */
return HAL_OK;
}
/**
* @brief Refreshes the WWDG.
* @param hwwdg: pointer to a WWDG_HandleTypeDef structure that contains
* the configuration information for the specified WWDG module.
* @param Counter: value of counter to put in WWDG counter
* @retval HAL status
*/
HAL_StatusTypeDef HAL_WWDG_Refresh(WWDG_HandleTypeDef *hwwdg, uint32_t Counter)
{
/* Process Locked */
__HAL_LOCK(hwwdg);
/* Change WWDG peripheral state */
hwwdg->State = HAL_WWDG_STATE_BUSY;
/* Check the parameters */
assert_param(IS_WWDG_COUNTER(Counter));
/* Write to WWDG CR the WWDG Counter value to refresh with */
MODIFY_REG(hwwdg->Instance->CR, (uint32_t)WWDG_CR_T, Counter);
/* Change WWDG peripheral state */
hwwdg->State = HAL_WWDG_STATE_READY;
/* Process Unlocked */
__HAL_UNLOCK(hwwdg);
/* Return function status */
return HAL_OK;
}
/**
* @brief Handles WWDG interrupt request.
* @note The Early Wakeup Interrupt (EWI) can be used if specific safety operations
* or data logging must be performed before the actual reset is generated.
* The EWI interrupt is enabled using __HAL_WWDG_ENABLE_IT() macro.
* When the downcounter reaches the value 0x40, and EWI interrupt is
* generated and the corresponding Interrupt Service Routine (ISR) can
* be used to trigger specific actions (such as communications or data
* logging), before resetting the device.
* @param hwwdg: pointer to a WWDG_HandleTypeDef structure that contains
* the configuration information for the specified WWDG module.
* @retval None
*/
void HAL_WWDG_IRQHandler(WWDG_HandleTypeDef *hwwdg)
{
/* WWDG Early Wakeup Interrupt occurred */
if(__HAL_WWDG_GET_FLAG(hwwdg, WWDG_FLAG_EWIF) != RESET)
{
/* Early Wakeup callback */
HAL_WWDG_WakeupCallback(hwwdg);
/* Change WWDG peripheral state */
hwwdg->State = HAL_WWDG_STATE_READY;
/* Clear the WWDG Data Ready flag */
__HAL_WWDG_CLEAR_IT(hwwdg, WWDG_FLAG_EWIF);
/* Process Unlocked */
__HAL_UNLOCK(hwwdg);
}
}
/**
* @brief Early Wakeup WWDG callback.
* @param hwwdg: pointer to a WWDG_HandleTypeDef structure that contains
* the configuration information for the specified WWDG module.
* @retval None
*/
__weak void HAL_WWDG_WakeupCallback(WWDG_HandleTypeDef* hwwdg)
{
/* NOTE: This function Should not be modified, when the callback is needed,
the HAL_WWDG_WakeupCallback could be implemented in the user file
*/
}
/**
* @}
*/
/** @defgroup WWDG_Group3 Peripheral State functions
* @brief Peripheral State functions.
*
@verbatim
==============================================================================
##### Peripheral State functions #####
==============================================================================
[..]
This subsection permits to get in run-time the status of the peripheral
and the data flow.
@endverbatim
* @{
*/
/**
* @brief Returns the WWDG state.
* @param hwwdg: pointer to a WWDG_HandleTypeDef structure that contains
* the configuration information for the specified WWDG module.
* @retval HAL state
*/
HAL_WWDG_StateTypeDef HAL_WWDG_GetState(WWDG_HandleTypeDef *hwwdg)
{
return hwwdg->State;
}
/**
* @}
*/
/**
* @}
*/
#endif /* HAL_WWDG_MODULE_ENABLED */
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,293 @@
/**
******************************************************************************
* @file stm32l0xx_hal_wwdg.h
* @author MCD Application Team
* @version V1.1.0
* @date 18-June-2014
* @brief Header file of WWDG HAL module.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32L0xx_HAL_WWDG_H
#define __STM32L0xx_HAL_WWDG_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32l0xx_hal_def.h"
/** @addtogroup STM32L0xx_HAL_Driver
* @{
*/
/** @addtogroup WWDG
* @{
*/
/* Exported types ------------------------------------------------------------*/
/** @defgroup WWDG_Exported_Types WWDG Exported Types
* @{
*/
/**
* @brief WWDG HAL State Structure definition
*/
typedef enum
{
HAL_WWDG_STATE_RESET = 0x00, /*!< WWDG not yet initialized or disabled */
HAL_WWDG_STATE_READY = 0x01, /*!< WWDG initialized and ready for use */
HAL_WWDG_STATE_BUSY = 0x02, /*!< WWDG internal process is ongoing */
HAL_WWDG_STATE_TIMEOUT = 0x03, /*!< WWDG timeout state */
HAL_WWDG_STATE_ERROR = 0x04 /*!< WWDG error state */
}HAL_WWDG_StateTypeDef;
/**
* @brief WWDG Init structure definition
*/
typedef struct
{
uint32_t Prescaler; /*!< Specifies the prescaler value of the WWDG.
This parameter can be a value of @ref WWDG_Prescaler */
uint32_t Window; /*!< Specifies the WWDG window value to be compared to the downcounter.
This parameter must be a number lower than Max_Data = 0x80 */
uint32_t Counter; /*!< Specifies the WWDG free-running downcounter value.
This parameter must be a number between Min_Data = 0x40 and Max_Data = 0x7F */
}WWDG_InitTypeDef;
/**
* @brief WWDG handle Structure definition
*/
typedef struct
{
WWDG_TypeDef *Instance; /*!< Register base address */
WWDG_InitTypeDef Init; /*!< WWDG required parameters */
HAL_LockTypeDef Lock; /*!< WWDG locking object */
__IO HAL_WWDG_StateTypeDef State; /*!< WWDG communication state */
}WWDG_HandleTypeDef;
/**
* @}
*/
/* Exported constants --------------------------------------------------------*/
/** @defgroup WWDG_Exported_Constants WWDG Exported Constants
* @{
*/
/** @defgroup WWDG_BitAddress_AliasRegion WWDG BitAddress AliasRegion
* @brief WWDG registers bit address in the alias region
* @{
*/
/* --- CFR Register ---*/
/* Alias word address of EWI bit */
#define CFR_BASE (uint32_t)(WWDG_BASE + 0x04)
/**
* @}
*/
/** @defgroup WWDG_Interrupt_definition WWDG Interrupt definition
* @{
*/
#define WWDG_IT_EWI ((uint32_t)WWDG_CFR_EWI)
#define IS_WWDG_IT(__IT__) ((__IT__) == WWDG_IT_EWI)
/**
* @}
*/
/** @defgroup WWDG_Flag_definition WWDG Flag definition
* @brief WWDG Flag definition
* @{
*/
#define WWDG_FLAG_EWIF ((uint32_t)WWDG_SR_EWIF) /*!< Early wakeup interrupt flag */
#define IS_WWDG_FLAG(__FLAG__) ((__FLAG__) == WWDG_FLAG_EWIF))
/**
* @}
*/
/** @defgroup WWDG_Prescaler WWDG Prescaler
* @{
*/
#define WWDG_PRESCALER_1 ((uint32_t)0x00000000) /*!< WWDG counter clock = (PCLK1/4096)/1 */
#define WWDG_PRESCALER_2 ((uint32_t)WWDG_CFR_WDGTB0) /*!< WWDG counter clock = (PCLK1/4096)/2 */
#define WWDG_PRESCALER_4 ((uint32_t)WWDG_CFR_WDGTB1) /*!< WWDG counter clock = (PCLK1/4096)/4 */
#define WWDG_PRESCALER_8 ((uint32_t)WWDG_CFR_WDGTB) /*!< WWDG counter clock = (PCLK1/4096)/8 */
#define IS_WWDG_PRESCALER(__PRESCALER__) (((__PRESCALER__) == WWDG_PRESCALER_1) || \
((__PRESCALER__) == WWDG_PRESCALER_2) || \
((__PRESCALER__) == WWDG_PRESCALER_4) || \
((__PRESCALER__) == WWDG_PRESCALER_8))
/**
* @}
*/
/** @defgroup WWDG_Window WWDG Window
* @{
*/
#define IS_WWDG_WINDOW(__WINDOW__) ((__WINDOW__) <= 0x7F)
/**
* @}
*/
/** @defgroup WWDG_Counter WWDG Counter
* @{
*/
#define IS_WWDG_COUNTER(__COUNTER__) (((__COUNTER__) >= 0x40) && ((__COUNTER__) <= 0x7F))
/**
* @}
*/
/**
* @}
*/
/* Exported macro ------------------------------------------------------------*/
/** @defgroup WWDG_Exported_Macros WWDG Exported Macros
* @{
*/
/** @brief Reset WWDG handle state
* @param __HANDLE__: WWDG handle
* @retval None
*/
#define __HAL_WWDG_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_WWDG_STATE_RESET)
/**
* @brief Enables the WWDG peripheral.
* @param __HANDLE__: WWDG handle
* @retval None
*/
#define __HAL_WWDG_ENABLE(__HANDLE__) SET_BIT((__HANDLE__)->Instance->CR, WWDG_CR_WDGA)
/**
* @brief Gets the selected WWDG's flag status.
* @param __HANDLE__: WWDG handle
* @param __FLAG__: specifies the flag to check.
* This parameter can be one of the following values:
* @arg WWDG_FLAG_EWIF: Early wakeup interrupt flag
* @retval The new state of WWDG_FLAG (SET or RESET).
*/
#define __HAL_WWDG_GET_FLAG(__HANDLE__, __FLAG__) (((__HANDLE__)->Instance->SR & (__FLAG__)) == (__FLAG__))
/**
* @brief Clears the WWDG's pending flags.
* @param __HANDLE__: WWDG handle
* @param __FLAG__: specifies the flag to clear.
* This parameter can be one of the following values:
* @arg WWDG_FLAG_EWIF: Early wakeup interrupt flag
* @retval None
*/
#define __HAL_WWDG_CLEAR_FLAG(__HANDLE__, __FLAG__) (((__HANDLE__)->Instance->SR) = ~(__FLAG__))
/**
* @brief Enables the WWDG early wakeup interrupt.
* @param __INTERRUPT__: specifies the interrupt to enable.
* This parameter can be one of the following values:
* @arg WWDG_IT_EWI: Early wakeup interrupt
* @note Once enabled this interrupt cannot be disabled except by a system reset.
* @retval None
*/
#define __HAL_WWDG_ENABLE_IT(__INTERRUPT__) (*(__IO uint32_t *) CFR_BASE |= (__INTERRUPT__))
/** @brief Clear the WWDG's interrupt pending bits
* bits to clear the selected interrupt pending bits.
* @param __HANDLE__: WWDG handle
* @param __INTERRUPT__: specifies the interrupt pending bit to clear.
* This parameter can be one of the following values:
* @arg WWDG_FLAG_EWIF: Early wakeup interrupt flag
*/
#define __HAL_WWDG_CLEAR_IT(__HANDLE__, __INTERRUPT__) __HAL_WWDG_CLEAR_FLAG((__HANDLE__), (__INTERRUPT__))
/**
* @}
*/
/* Exported functions --------------------------------------------------------*/
/** @addtogroup WWDG_Exported_Functions
* @{
*/
/* Initialization/de-initialization functions **********************************/
HAL_StatusTypeDef HAL_WWDG_Init(WWDG_HandleTypeDef *hwwdg);
HAL_StatusTypeDef HAL_WWDG_DeInit(WWDG_HandleTypeDef *hwwdg);
void HAL_WWDG_MspInit(WWDG_HandleTypeDef *hwwdg);
void HAL_WWDG_MspDeInit(WWDG_HandleTypeDef *hwwdg);
void HAL_WWDG_WakeupCallback(WWDG_HandleTypeDef* hwwdg);
/* I/O operation functions ******************************************************/
HAL_StatusTypeDef HAL_WWDG_Start(WWDG_HandleTypeDef *hwwdg);
HAL_StatusTypeDef HAL_WWDG_Start_IT(WWDG_HandleTypeDef *hwwdg);
HAL_StatusTypeDef HAL_WWDG_Refresh(WWDG_HandleTypeDef *hwwdg, uint32_t Counter);
void HAL_WWDG_IRQHandler(WWDG_HandleTypeDef *hwwdg);
/* Peripheral State functions **************************************************/
HAL_WWDG_StateTypeDef HAL_WWDG_GetState(WWDG_HandleTypeDef *hwwdg);
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif /* __STM32L0xx_HAL_WWDG_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/