@@ -11,6 +11,7 @@ PROGEXT = .elf | |||
SRCS = main.c | |||
SRCS+= board.c | |||
SRCS+= misc.c | |||
SRCS+= strobe_rng_init.c | |||
CFLAGS+= -I$(.CURDIR) | |||
@@ -23,6 +24,18 @@ CFLAGS+= -I$(.CURDIR)/strobe | |||
SRCS+= strobe.c \ | |||
x25519.c | |||
# LoRamac (SX1276) radio code | |||
LORAMAC_SRC = $(.CURDIR)/loramac/src | |||
.PATH: $(LORAMAC_SRC)/radio/sx1276 $(LORAMAC_SRC)/system $(LORAMAC_SRC)/boards/mcu $(LORAMAC_SRC)/boards/NucleoL152 | |||
CFLAGS+= -I$(LORAMAC_SRC)/boards | |||
CFLAGS+= -I$(LORAMAC_SRC)/system | |||
CFLAGS+= -I$(LORAMAC_SRC)/radio | |||
CFLAGS+= -DUSE_HAL_DRIVER -DSX1276MB1LAS | |||
SRCS+= sx1276.c | |||
SRCS+= utilities.c | |||
SRCS+= adc.c timer.c delay.c gpio.c uart.c fifo.c | |||
SRCS+= adc-board.c delay-board.c gpio-board.c rtc-board.c lpm-board.c sx1276mb1las-board.c spi-board.c uart-board.c | |||
# Microcontroller | |||
STM32=$(.CURDIR)/stm32 | |||
.PATH: $(STM32)/l151ccux | |||
@@ -30,12 +43,21 @@ LINKER_SCRIPT=$(STM32)/l151ccux/STM32L151CCUX_FLASH.ld | |||
SRCS+= \ | |||
startup_stm32l151ccux.s \ | |||
stm32l1xx_hal.c \ | |||
stm32l1xx_hal_adc.c \ | |||
stm32l1xx_hal_adc_ex.c \ | |||
stm32l1xx_hal_cortex.c \ | |||
stm32l1xx_hal_dma.c \ | |||
stm32l1xx_hal_gpio.c \ | |||
stm32l1xx_hal_spi.c \ | |||
stm32l1xx_hal_pwr.c \ | |||
stm32l1xx_hal_pwr_ex.c \ | |||
stm32l1xx_hal_pcd.c \ | |||
stm32l1xx_hal_pcd_ex.c \ | |||
stm32l1xx_hal_rcc.c \ | |||
stm32l1xx_hal_rcc_ex.c \ | |||
stm32l1xx_hal_rtc.c \ | |||
stm32l1xx_hal_rtc_ex.c \ | |||
stm32l1xx_hal_uart.c \ | |||
system_stm32l1xx.c | |||
SRCS+= \ | |||
@@ -78,8 +100,8 @@ $(PROG).list: $(PROG)$(PROGEXT) | |||
$(ARMOBJDUMP) -h -S $(.ALLSRC) > $@ || rm -f $@ | |||
.PHONY: runbuild | |||
runbuild: | |||
for i in $(.MAKEFILE_LIST) $$(gsed ':x; /\\$$/ { N; s/\\\n//; tx }' < .depend | sed -e 's/^[^:]*://'); do echo $$i; done | entr -d sh -c 'cd $(.CURDIR) && $(MAKE) depend && $(MAKE) all' | |||
runbuild: $(SRCS) | |||
for i in $(.MAKEFILE_LIST) $(.ALLSRC) $$(gsed ':x; /\\$$/ { N; s/\\\n//; tx }' < .depend | sed -e 's/^[^:]*://'); do echo $$i; done | entr -d sh -c 'echo starting...; cd $(.CURDIR) && $(MAKE) depend && $(MAKE) all' | |||
.PHONY: runtests | |||
runtests: | |||
@@ -0,0 +1,96 @@ | |||
/*! | |||
* \file board-config.h | |||
* | |||
* \brief Board configuration | |||
* | |||
* \copyright Revised BSD License, see section \ref LICENSE. | |||
* | |||
* \code | |||
* ______ _ | |||
* / _____) _ | | | |||
* ( (____ _____ ____ _| |_ _____ ____| |__ | |||
* \____ \| ___ | (_ _) ___ |/ ___) _ \ | |||
* _____) ) ____| | | || |_| ____( (___| | | | | |||
* (______/|_____)_|_|_| \__)_____)\____)_| |_| | |||
* (C)2013-2017 Semtech | |||
* | |||
* ___ _____ _ ___ _ _____ ___ ___ ___ ___ | |||
* / __|_ _/_\ / __| |/ / __/ _ \| _ \/ __| __| | |||
* \__ \ | |/ _ \ (__| ' <| _| (_) | / (__| _| | |||
* |___/ |_/_/ \_\___|_|\_\_| \___/|_|_\\___|___| | |||
* embedded.connectivity.solutions=============== | |||
* | |||
* \endcode | |||
* | |||
* \author Miguel Luis ( Semtech ) | |||
* | |||
* \author Gregory Cristian ( Semtech ) | |||
* | |||
* \author Daniel Jaeckle ( STACKFORCE ) | |||
* | |||
* \author Johannes Bruder ( STACKFORCE ) | |||
*/ | |||
#ifndef __BOARD_CONFIG_H__ | |||
#define __BOARD_CONFIG_H__ | |||
#ifdef __cplusplus | |||
extern "C" | |||
{ | |||
#endif | |||
/*! | |||
* Defines the time required for the TCXO to wakeup [ms]. | |||
*/ | |||
#if defined( SX1262MBXDAS ) | |||
#define BOARD_TCXO_WAKEUP_TIME 5 | |||
#else | |||
#define BOARD_TCXO_WAKEUP_TIME 0 | |||
#endif | |||
/*! | |||
* Board MCU pins definitions | |||
*/ | |||
#define RADIO_RESET PA_3 | |||
#define RADIO_MOSI PA_7 | |||
#define RADIO_MISO PA_6 | |||
#define RADIO_SCLK PA_5 | |||
#define RADIO_NSS PA_4 | |||
#define RADIO_DIO_0 PB_11 | |||
#define RADIO_DIO_1 PB_10 | |||
#define RADIO_DIO_2 PB_1 | |||
#define RADIO_DIO_3 PB_0 | |||
#define RADIO_DIO_4 NC | |||
#define RADIO_DIO_5 NC | |||
#define RADIO_ANT_SWITCH NC | |||
#define LED_1 NC | |||
#define LED_2 NC | |||
// Debug pins definition. | |||
#define RADIO_DBG_PIN_TX NC | |||
#define RADIO_DBG_PIN_RX NC | |||
#define OSC_LSE_IN PC_14 | |||
#define OSC_LSE_OUT PC_15 | |||
#define OSC_HSE_IN PH_0 | |||
#define OSC_HSE_OUT PH_1 | |||
#define SWCLK PA_14 | |||
#define SWDAT PA_13 | |||
#define I2C_SCL NC | |||
#define I2C_SDA NC | |||
#define UART_TX NC | |||
#define UART_RX NC | |||
#ifdef __cplusplus | |||
} | |||
#endif | |||
#endif // __BOARD_CONFIG_H__ |
@@ -1,94 +1,135 @@ | |||
#include <stm32l1xx_hal.h> | |||
/*! | |||
* \file board.c | |||
* | |||
* \brief Target board general functions implementation | |||
* | |||
* \copyright Revised BSD License, see section \ref LICENSE. | |||
* | |||
* \code | |||
* ______ _ | |||
* / _____) _ | | | |||
* ( (____ _____ ____ _| |_ _____ ____| |__ | |||
* \____ \| ___ | (_ _) ___ |/ ___) _ \ | |||
* _____) ) ____| | | || |_| ____( (___| | | | | |||
* (______/|_____)_|_|_| \__)_____)\____)_| |_| | |||
* (C)2013-2017 Semtech | |||
* | |||
* \endcode | |||
* | |||
* \author Miguel Luis ( Semtech ) | |||
* | |||
* \author Gregory Cristian ( Semtech ) | |||
*/ | |||
#include "stm32l1xx.h" | |||
#include "utilities.h" | |||
#include "gpio.h" | |||
#include "adc.h" | |||
#include "spi.h" | |||
#include "i2c.h" | |||
#include "uart.h" | |||
#include "timer.h" | |||
#include "sysIrqHandlers.h" | |||
#include "board-config.h" | |||
#include "lpm-board.h" | |||
#include "rtc-board.h" | |||
#if defined( SX1261MBXBAS ) || defined( SX1262MBXCAS ) || defined( SX1262MBXDAS ) | |||
#include "sx126x-board.h" | |||
#elif defined( LR1110MB1XXS ) | |||
#include "lr1110-board.h" | |||
#elif defined( SX1272MB2DAS) | |||
#include "sx1272-board.h" | |||
#elif defined( SX1276MB1LAS ) || defined( SX1276MB1MAS ) | |||
#include "sx1276-board.h" | |||
#endif | |||
#include "board.h" | |||
#include <usbd_cdc_if.h> | |||
#include <usb_device.h> | |||
#include <board.h> | |||
/*! | |||
* Unique Devices IDs register set ( STM32L152x ) | |||
*/ | |||
#define ID1 ( 0x1FF800D0 ) | |||
#define ID2 ( 0x1FF800D4 ) | |||
#define ID3 ( 0x1FF800E4 ) | |||
static void gpio_init(void); | |||
static void clock_config(void); | |||
/*! | |||
* LED GPIO pins objects | |||
*/ | |||
Gpio_t Led1; | |||
Gpio_t Led2; | |||
void | |||
board_init(void) | |||
{ | |||
/* | |||
* MCU objects | |||
*/ | |||
Adc_t Adc; | |||
Uart_t Uart2; | |||
HAL_Init(); | |||
clock_config(); | |||
gpio_init(); | |||
MX_USB_DEVICE_Init(); | |||
} | |||
#if defined( LR1110MB1XXS ) | |||
extern lr1110_t LR1110; | |||
#endif | |||
/* | |||
* Wait for a device to connect to the VCP | |||
/*! | |||
* Initializes the unused GPIO to a know status | |||
*/ | |||
void | |||
wait_for_vcp(void) | |||
{ | |||
static void BoardUnusedIoInit( void ); | |||
for (;;) { | |||
if (vcp_status(&hUsbDeviceFS.request)) | |||
break; | |||
} | |||
} | |||
/*! | |||
* System Clock Configuration | |||
*/ | |||
static void SystemClockConfig( void ); | |||
void | |||
Error_Handler(void) | |||
{ | |||
/* XXX - handle error */ | |||
} | |||
/*! | |||
* System Clock Re-Configuration when waking up from STOP mode | |||
*/ | |||
static void SystemClockReConfig( void ); | |||
static void | |||
clock_config(void) | |||
{ | |||
RCC_OscInitTypeDef RCC_OscInitStruct; | |||
RCC_ClkInitTypeDef RCC_ClkInitStruct; | |||
RCC_PeriphCLKInitTypeDef PeriphClkInit; | |||
/*! | |||
* Flag to indicate if the MCU is Initialized | |||
*/ | |||
static bool McuInitialized = false; | |||
/* Configure internal regulator output voltage */ | |||
__HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1); | |||
/*! | |||
* Flag used to indicate if board is powered from the USB | |||
*/ | |||
static bool UsbIsConnected = false; | |||
/* Initializes CPU, AHB and APB busses clocks */ | |||
RCC_OscInitStruct = (RCC_OscInitTypeDef){ | |||
.OscillatorType = RCC_OSCILLATORTYPE_LSI|RCC_OSCILLATORTYPE_HSE, | |||
.HSEState = RCC_HSE_ON, | |||
.LSIState = RCC_LSI_ON, | |||
.PLL.PLLState = RCC_PLL_ON, | |||
.PLL.PLLSource = RCC_PLLSOURCE_HSE, | |||
.PLL.PLLMUL = RCC_PLL_MUL12, | |||
.PLL.PLLDIV = RCC_PLL_DIV3, | |||
}; | |||
/*! | |||
* UART2 FIFO buffers size | |||
*/ | |||
#define UART2_FIFO_TX_SIZE 1024 | |||
#define UART2_FIFO_RX_SIZE 1024 | |||
if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK) { | |||
Error_Handler(); | |||
} | |||
uint8_t Uart2TxBuffer[UART2_FIFO_TX_SIZE]; | |||
uint8_t Uart2RxBuffer[UART2_FIFO_RX_SIZE]; | |||
/* Initializes CPU, AHB and APB busses clocks */ | |||
RCC_ClkInitStruct = (RCC_ClkInitTypeDef){ | |||
.ClockType = RCC_CLOCKTYPE_HCLK|RCC_CLOCKTYPE_SYSCLK | |||
|RCC_CLOCKTYPE_PCLK1|RCC_CLOCKTYPE_PCLK2, | |||
.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK, | |||
.AHBCLKDivider = RCC_SYSCLK_DIV1, | |||
.APB1CLKDivider = RCC_HCLK_DIV1, | |||
.APB2CLKDivider = RCC_HCLK_DIV1, | |||
}; | |||
void BoardCriticalSectionBegin( uint32_t *mask ) | |||
{ | |||
*mask = __get_PRIMASK( ); | |||
__disable_irq( ); | |||
} | |||
if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_1) != HAL_OK) { | |||
Error_Handler(); | |||
} | |||
void BoardCriticalSectionEnd( uint32_t *mask ) | |||
{ | |||
__set_PRIMASK( *mask ); | |||
} | |||
PeriphClkInit = (RCC_PeriphCLKInitTypeDef){ | |||
.PeriphClockSelection = RCC_PERIPHCLK_RTC, | |||
.RTCClockSelection = RCC_RTCCLKSOURCE_LSI, | |||
}; | |||
void BoardInitPeriph( void ) | |||
{ | |||
if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit) != HAL_OK) { | |||
Error_Handler(); | |||
} | |||
} | |||
static void | |||
gpio_init(void) | |||
void BoardInitMcu( void ) | |||
{ | |||
if( McuInitialized == false ) | |||
{ | |||
HAL_Init( ); | |||
#if 0 | |||
// LEDs | |||
GpioInit( &Led1, LED_1, PIN_OUTPUT, PIN_PUSH_PULL, PIN_NO_PULL, 0 ); | |||
GpioInit( &Led2, LED_2, PIN_OUTPUT, PIN_PUSH_PULL, PIN_NO_PULL, 0 ); | |||
#else | |||
GPIO_InitTypeDef GPIO_InitStruct; | |||
__HAL_RCC_GPIOC_CLK_ENABLE(); | |||
@@ -126,4 +167,462 @@ gpio_init(void) | |||
.Speed = GPIO_SPEED_FREQ_LOW, | |||
}; | |||
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct); | |||
#endif | |||
SystemClockConfig( ); | |||
UsbIsConnected = true; | |||
FifoInit( &Uart2.FifoTx, Uart2TxBuffer, UART2_FIFO_TX_SIZE ); | |||
FifoInit( &Uart2.FifoRx, Uart2RxBuffer, UART2_FIFO_RX_SIZE ); | |||
// Configure your terminal for 8 Bits data (7 data bit + 1 parity bit), no parity and no flow ctrl | |||
UartInit( &Uart2, UART_2, UART_TX, UART_RX ); | |||
UartConfig( &Uart2, RX_TX, 921600, UART_8_BIT, UART_1_STOP_BIT, NO_PARITY, NO_FLOW_CTRL ); | |||
RtcInit( ); | |||
BoardUnusedIoInit( ); | |||
if( GetBoardPowerSource( ) == BATTERY_POWER ) | |||
{ | |||
// Disables OFF mode - Enables lowest power mode (STOP) | |||
LpmSetOffMode( LPM_APPLI_ID, LPM_DISABLE ); | |||
} | |||
} | |||
else | |||
{ | |||
SystemClockReConfig( ); | |||
} | |||
MX_USB_DEVICE_Init(); | |||
AdcInit( &Adc, NC ); // Just initialize ADC | |||
#if defined( SX1261MBXBAS ) || defined( SX1262MBXCAS ) || defined( SX1262MBXDAS ) | |||
SpiInit( &SX126x.Spi, SPI_1, RADIO_MOSI, RADIO_MISO, RADIO_SCLK, NC ); | |||
SX126xIoInit( ); | |||
#elif defined( LR1110MB1XXS ) | |||
SpiInit( &LR1110.spi, SPI_1, RADIO_MOSI, RADIO_MISO, RADIO_SCLK, NC ); | |||
lr1110_board_init_io( &LR1110 ); | |||
#elif defined( SX1272MB2DAS ) | |||
SpiInit( &SX1272.Spi, SPI_1, RADIO_MOSI, RADIO_MISO, RADIO_SCLK, NC ); | |||
SX1272IoInit( ); | |||
#elif defined( SX1276MB1LAS ) || defined( SX1276MB1MAS ) | |||
SpiInit( &SX1276.Spi, SPI_1, RADIO_MOSI, RADIO_MISO, RADIO_SCLK, NC ); | |||
SX1276IoInit( ); | |||
#endif | |||
if( McuInitialized == false ) | |||
{ | |||
McuInitialized = true; | |||
#if defined( SX1261MBXBAS ) || defined( SX1262MBXCAS ) || defined( SX1262MBXDAS ) | |||
SX126xIoDbgInit( ); | |||
// WARNING: If necessary the TCXO control is initialized by SX126xInit function. | |||
#elif defined( LR1110MB1XXS ) | |||
lr1110_board_init_dbg_io( &LR1110 ); | |||
// WARNING: If necessary the TCXO control is initialized by SX126xInit function. | |||
#elif defined( SX1272MB2DAS ) | |||
SX1272IoDbgInit( ); | |||
SX1272IoTcxoInit( ); | |||
#elif defined( SX1276MB1LAS ) || defined( SX1276MB1MAS ) | |||
SX1276IoDbgInit( ); | |||
SX1276IoTcxoInit( ); | |||
#endif | |||
} | |||
} | |||
void BoardResetMcu( void ) | |||
{ | |||
CRITICAL_SECTION_BEGIN( ); | |||
//Restart system | |||
NVIC_SystemReset( ); | |||
} | |||
void BoardDeInitMcu( void ) | |||
{ | |||
AdcDeInit( &Adc ); | |||
#if defined( SX1261MBXBAS ) || defined( SX1262MBXCAS ) || defined( SX1262MBXDAS ) | |||
SpiDeInit( &SX126x.Spi ); | |||
SX126xIoDeInit( ); | |||
#elif defined( LR1110MB1XXS ) | |||
SpiDeInit( &LR1110.spi ); | |||
lr1110_board_deinit_io( &LR1110 ); | |||
#elif defined( SX1272MB2DAS ) | |||
SpiDeInit( &SX1272.Spi ); | |||
SX1272IoDeInit( ); | |||
#elif defined( SX1276MB1LAS ) || defined( SX1276MB1MAS ) | |||
SpiDeInit( &SX1276.Spi ); | |||
SX1276IoDeInit( ); | |||
#endif | |||
} | |||
uint32_t BoardGetRandomSeed( void ) | |||
{ | |||
return ( ( *( uint32_t* )ID1 ) ^ ( *( uint32_t* )ID2 ) ^ ( *( uint32_t* )ID3 ) ); | |||
} | |||
void BoardGetUniqueId( uint8_t *id ) | |||
{ | |||
id[7] = ( ( *( uint32_t* )ID1 )+ ( *( uint32_t* )ID3 ) ) >> 24; | |||
id[6] = ( ( *( uint32_t* )ID1 )+ ( *( uint32_t* )ID3 ) ) >> 16; | |||
id[5] = ( ( *( uint32_t* )ID1 )+ ( *( uint32_t* )ID3 ) ) >> 8; | |||
id[4] = ( ( *( uint32_t* )ID1 )+ ( *( uint32_t* )ID3 ) ); | |||
id[3] = ( ( *( uint32_t* )ID2 ) ) >> 24; | |||
id[2] = ( ( *( uint32_t* )ID2 ) ) >> 16; | |||
id[1] = ( ( *( uint32_t* )ID2 ) ) >> 8; | |||
id[0] = ( ( *( uint32_t* )ID2 ) ); | |||
} | |||
/*! | |||
* Factory power supply | |||
*/ | |||
#define VDDA_VREFINT_CAL ( ( uint32_t ) 3000 ) // mV | |||
/*! | |||
* VREF calibration value | |||
*/ | |||
#define VREFINT_CAL ( *( uint16_t* ) ( ( uint32_t ) 0x1FF800F8 ) ) | |||
/* | |||
* Internal temperature sensor, parameter TS_CAL1: TS ADC raw data acquired at | |||
* a temperature of 110 DegC (+-5 DegC), VDDA = 3.3 V (+-10 mV). | |||
*/ | |||
#define TEMP30_CAL_ADDR ( *( uint16_t* ) ( ( uint32_t ) 0x1FF8007A ) ) | |||
/* Internal temperature sensor, parameter TS_CAL2: TS ADC raw data acquired at | |||
*a temperature of 30 DegC (+-5 DegC), VDDA = 3.3 V (+-10 mV). */ | |||
#define TEMP110_CAL_ADDR ( *( uint16_t* ) ( ( uint32_t ) 0x1FF8007E ) ) | |||
/* Vdda value with which temperature sensor has been calibrated in production | |||
(+-10 mV). */ | |||
#define VDDA_TEMP_CAL ( ( uint32_t ) 3000 ) | |||
/*! | |||
* Battery thresholds | |||
*/ | |||
#define BATTERY_MAX_LEVEL 3000 // mV | |||
#define BATTERY_MIN_LEVEL 2400 // mV | |||
#define BATTERY_SHUTDOWN_LEVEL 2300 // mV | |||
#define BATTERY_LORAWAN_UNKNOWN_LEVEL 255 | |||
#define BATTERY_LORAWAN_MAX_LEVEL 254 | |||
#define BATTERY_LORAWAN_MIN_LEVEL 1 | |||
#define BATTERY_LORAWAN_EXT_PWR 0 | |||
#define COMPUTE_TEMPERATURE( TS_ADC_DATA, VDDA_APPLI ) \ | |||
( ( ( ( ( ( ( int32_t )( ( TS_ADC_DATA * VDDA_APPLI ) / VDDA_TEMP_CAL ) - ( int32_t ) TEMP30_CAL_ADDR ) ) * \ | |||
( int32_t )( 110 - 30 ) ) \ | |||
<< 8 ) / \ | |||
( int32_t )( TEMP110_CAL_ADDR - TEMP30_CAL_ADDR ) ) + \ | |||
( 30 << 8 ) ) | |||
static uint16_t BatteryVoltage = BATTERY_MAX_LEVEL; | |||
uint16_t BoardBatteryMeasureVoltage( void ) | |||
{ | |||
uint16_t vref = 0; | |||
// Read the current Voltage | |||
vref = AdcReadChannel( &Adc, ADC_CHANNEL_VREFINT ); | |||
// Compute and return the Voltage in millivolt | |||
return ( ( ( uint32_t ) VDDA_VREFINT_CAL * VREFINT_CAL ) / vref ); | |||
} | |||
uint32_t BoardGetBatteryVoltage( void ) | |||
{ | |||
return BatteryVoltage; | |||
} | |||
uint8_t BoardGetBatteryLevel( void ) | |||
{ | |||
uint8_t batteryLevel = 0; | |||
BatteryVoltage = BoardBatteryMeasureVoltage( ); | |||
if( GetBoardPowerSource( ) == USB_POWER ) | |||
{ | |||
batteryLevel = BATTERY_LORAWAN_EXT_PWR; | |||
} | |||
else | |||
{ | |||
if( BatteryVoltage >= BATTERY_MAX_LEVEL ) | |||
{ | |||
batteryLevel = BATTERY_LORAWAN_MAX_LEVEL; | |||
} | |||
else if( ( BatteryVoltage > BATTERY_MIN_LEVEL ) && ( BatteryVoltage < BATTERY_MAX_LEVEL ) ) | |||
{ | |||
batteryLevel = | |||
( ( 253 * ( BatteryVoltage - BATTERY_MIN_LEVEL ) ) / ( BATTERY_MAX_LEVEL - BATTERY_MIN_LEVEL ) ) + 1; | |||
} | |||
else if( ( BatteryVoltage > BATTERY_SHUTDOWN_LEVEL ) && ( BatteryVoltage <= BATTERY_MIN_LEVEL ) ) | |||
{ | |||
batteryLevel = 1; | |||
} | |||
else // if( BatteryVoltage <= BATTERY_SHUTDOWN_LEVEL ) | |||
{ | |||
batteryLevel = BATTERY_LORAWAN_UNKNOWN_LEVEL; | |||
} | |||
} | |||
return batteryLevel; | |||
} | |||
int16_t BoardGetTemperature( void ) | |||
{ | |||
uint16_t tempRaw = 0; | |||
BatteryVoltage = BoardBatteryMeasureVoltage( ); | |||
tempRaw = AdcReadChannel( &Adc, ADC_CHANNEL_TEMPSENSOR ); | |||
// Compute and return the temperature in degree celcius * 256 | |||
return ( int16_t ) COMPUTE_TEMPERATURE( tempRaw, BatteryVoltage ); | |||
} | |||
static void BoardUnusedIoInit( void ) | |||
{ | |||
HAL_DBGMCU_EnableDBGSleepMode( ); | |||
HAL_DBGMCU_EnableDBGStopMode( ); | |||
HAL_DBGMCU_EnableDBGStandbyMode( ); | |||
} | |||
void SystemClockConfig( void ) | |||
{ | |||
RCC_OscInitTypeDef RCC_OscInitStruct = { 0 }; | |||
RCC_ClkInitTypeDef RCC_ClkInitStruct = { 0 }; | |||
RCC_PeriphCLKInitTypeDef PeriphClkInit = { 0 }; | |||
__HAL_RCC_PWR_CLK_ENABLE( ); | |||
__HAL_PWR_VOLTAGESCALING_CONFIG( PWR_REGULATOR_VOLTAGE_SCALE1 ); | |||
RCC_OscInitStruct = (RCC_OscInitTypeDef){ | |||
.OscillatorType = RCC_OSCILLATORTYPE_LSI|RCC_OSCILLATORTYPE_HSE, | |||
.HSEState = RCC_HSE_ON, | |||
.LSIState = RCC_LSI_ON, | |||
.PLL.PLLState = RCC_PLL_ON, | |||
.PLL.PLLSource = RCC_PLLSOURCE_HSE, | |||
.PLL.PLLMUL = RCC_PLL_MUL12, | |||
.PLL.PLLDIV = RCC_PLL_DIV3, | |||
}; | |||
if( HAL_RCC_OscConfig( &RCC_OscInitStruct ) != HAL_OK ) | |||
{ | |||
assert_param( LMN_STATUS_ERROR ); | |||
} | |||
RCC_ClkInitStruct = (RCC_ClkInitTypeDef){ | |||
.ClockType = RCC_CLOCKTYPE_HCLK|RCC_CLOCKTYPE_SYSCLK | |||
|RCC_CLOCKTYPE_PCLK1|RCC_CLOCKTYPE_PCLK2, | |||
.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK, | |||
.AHBCLKDivider = RCC_SYSCLK_DIV1, | |||
.APB1CLKDivider = RCC_HCLK_DIV1, | |||
.APB2CLKDivider = RCC_HCLK_DIV1, | |||
}; | |||
if( HAL_RCC_ClockConfig( &RCC_ClkInitStruct, FLASH_LATENCY_1 ) != HAL_OK ) | |||
{ | |||
assert_param( LMN_STATUS_ERROR ); | |||
} | |||
PeriphClkInit = (RCC_PeriphCLKInitTypeDef){ | |||
.PeriphClockSelection = RCC_PERIPHCLK_RTC, | |||
.RTCClockSelection = RCC_RTCCLKSOURCE_LSI, | |||
}; | |||
if( HAL_RCCEx_PeriphCLKConfig( &PeriphClkInit ) != HAL_OK ) | |||
{ | |||
assert_param( LMN_STATUS_ERROR ); | |||
} | |||
HAL_SYSTICK_Config( HAL_RCC_GetHCLKFreq( ) / 1000 ); | |||
HAL_SYSTICK_CLKSourceConfig( SYSTICK_CLKSOURCE_HCLK ); | |||
// SysTick_IRQn interrupt configuration | |||
HAL_NVIC_SetPriority( SysTick_IRQn, 0, 0 ); | |||
} | |||
void SystemClockReConfig( void ) | |||
{ | |||
__HAL_RCC_PWR_CLK_ENABLE( ); | |||
__HAL_PWR_VOLTAGESCALING_CONFIG( PWR_REGULATOR_VOLTAGE_SCALE1 ); | |||
// Enable HSI | |||
__HAL_RCC_HSI_ENABLE( ); | |||
// Wait till HSI is ready | |||
while( __HAL_RCC_GET_FLAG( RCC_FLAG_HSIRDY ) == RESET ) | |||
{ | |||
} | |||
// Enable PLL | |||
__HAL_RCC_PLL_ENABLE( ); | |||
// Wait till PLL is ready | |||
while( __HAL_RCC_GET_FLAG( RCC_FLAG_PLLRDY ) == RESET ) | |||
{ | |||
} | |||
// Select PLL as system clock source | |||
__HAL_RCC_SYSCLK_CONFIG ( RCC_SYSCLKSOURCE_PLLCLK ); | |||
// Wait till PLL is used as system clock source | |||
while( __HAL_RCC_GET_SYSCLK_SOURCE( ) != RCC_SYSCLKSOURCE_STATUS_PLLCLK ) | |||
{ | |||
} | |||
} | |||
void SysTick_Handler( void ) | |||
{ | |||
HAL_IncTick( ); | |||
HAL_SYSTICK_IRQHandler( ); | |||
} | |||
uint8_t GetBoardPowerSource( void ) | |||
{ | |||
if( UsbIsConnected == false ) | |||
{ | |||
return BATTERY_POWER; | |||
} | |||
else | |||
{ | |||
return USB_POWER; | |||
} | |||
} | |||
/** | |||
* \brief Enters Low Power Stop Mode | |||
* | |||
* \note ARM exists the function when waking up | |||
*/ | |||
void LpmEnterStopMode( void) | |||
{ | |||
CRITICAL_SECTION_BEGIN( ); | |||
BoardDeInitMcu( ); | |||
// Disable the Power Voltage Detector | |||
HAL_PWR_DisablePVD( ); | |||
// Clear wake up flag | |||
SET_BIT( PWR->CR, PWR_CR_CWUF ); | |||
// Enable Ultra low power mode | |||
HAL_PWREx_EnableUltraLowPower( ); | |||
// Enable the fast wake up from Ultra low power mode | |||
HAL_PWREx_EnableFastWakeUp( ); | |||
CRITICAL_SECTION_END( ); | |||
// Enter Stop Mode | |||
HAL_PWR_EnterSTOPMode( PWR_LOWPOWERREGULATOR_ON, PWR_STOPENTRY_WFI ); | |||
} | |||
/*! | |||
* \brief Exists Low Power Stop Mode | |||
*/ | |||
void LpmExitStopMode( void ) | |||
{ | |||
// Disable IRQ while the MCU is not running on HSI | |||
CRITICAL_SECTION_BEGIN( ); | |||
// Initilizes the peripherals | |||
BoardInitMcu( ); | |||
CRITICAL_SECTION_END( ); | |||
} | |||
/*! | |||
* \brief Enters Low Power Sleep Mode | |||
* | |||
* \note ARM exits the function when waking up | |||
*/ | |||
void LpmEnterSleepMode( void) | |||
{ | |||
HAL_PWR_EnterSLEEPMode(PWR_MAINREGULATOR_ON, PWR_SLEEPENTRY_WFI); | |||
} | |||
void BoardLowPowerHandler( void ) | |||
{ | |||
__disable_irq( ); | |||
/*! | |||
* If an interrupt has occurred after __disable_irq( ), it is kept pending | |||
* and cortex will not enter low power anyway | |||
*/ | |||
LpmEnterLowPower( ); | |||
__enable_irq( ); | |||
} | |||
#if !defined ( __CC_ARM ) | |||
/* | |||
* Function to be used by stdout for printf etc | |||
*/ | |||
int _write( int fd, const void *buf, size_t count ) | |||
{ | |||
while( UartPutBuffer( &Uart2, ( uint8_t* )buf, ( uint16_t )count ) != 0 ){ }; | |||
return count; | |||
} | |||
/* | |||
* Function to be used by stdin for scanf etc | |||
*/ | |||
int _read( int fd, const void *buf, size_t count ) | |||
{ | |||
size_t bytesRead = 0; | |||
while( UartGetBuffer( &Uart2, ( uint8_t* )buf, count, ( uint16_t* )&bytesRead ) != 0 ){ }; | |||
// Echo back the character | |||
while( UartPutBuffer( &Uart2, ( uint8_t* )buf, ( uint16_t )bytesRead ) != 0 ){ }; | |||
return bytesRead; | |||
} | |||
#else | |||
#include <stdio.h> | |||
// Keil compiler | |||
int fputc( int c, FILE *stream ) | |||
{ | |||
while( UartPutChar( &Uart2, ( uint8_t )c ) != 0 ); | |||
return c; | |||
} | |||
int fgetc( FILE *stream ) | |||
{ | |||
uint8_t c = 0; | |||
while( UartGetChar( &Uart2, &c ) != 0 ); | |||
// Echo back the character | |||
while( UartPutChar( &Uart2, c ) != 0 ); | |||
return ( int )c; | |||
} | |||
#endif | |||
#ifdef USE_FULL_ASSERT | |||
#include <stdio.h> | |||
/* | |||
* Function Name : assert_failed | |||
* Description : Reports the name of the source file and the source line number | |||
* where the assert_param error has occurred. | |||
* Input : - file: pointer to the source file name | |||
* - line: assert_param error line source number | |||
* Output : None | |||
* Return : None | |||
*/ | |||
void assert_failed( uint8_t* file, uint32_t line ) | |||
{ | |||
/* User can add his own implementation to report the file name and line number, | |||
ex: printf("Wrong parameters value: file %s on line %lu\n", file, line) */ | |||
printf( "Wrong parameters value: file %s on line %lu\n", ( const char* )file, line ); | |||
/* Infinite loop */ | |||
while( 1 ) | |||
{ | |||
} | |||
} | |||
#endif |
@@ -3,6 +3,9 @@ | |||
#include <strobe_rng_init.h> | |||
#include <board.h> | |||
#include <misc.h> | |||
#include <radio.h> | |||
#include <delay.h> | |||
void | |||
hexdump(uint8_t *ptr, size_t len) | |||
@@ -13,6 +16,50 @@ hexdump(uint8_t *ptr, size_t len) | |||
usb_printf("%02x", ptr[i]); | |||
} | |||
void | |||
txdone(void) | |||
{ | |||
usb_printf("txdone\r\n"); | |||
} | |||
void | |||
txtimeout(void) | |||
{ | |||
usb_printf("txtimeout\r\n"); | |||
} | |||
void | |||
rxdone(uint8_t *payload, uint16_t size, int16_t rssi, int8_t snr) | |||
{ | |||
usb_printf("rxdone: size: %hu, rssi: %hd, snr: %d\r\ndata: ", size, rssi, snr); | |||
hexdump(payload, size); | |||
usb_printf("\r\n"); | |||
} | |||
void | |||
rxtimeout(void) | |||
{ | |||
usb_printf("rxtimeout\r\n"); | |||
} | |||
void | |||
rxerr(void) | |||
{ | |||
usb_printf("rxerr\r\n"); | |||
} | |||
RadioEvents_t revents = { | |||
.TxDone = txdone, | |||
.TxTimeout = txtimeout, | |||
.RxDone = rxdone, | |||
.RxTimeout = rxtimeout, | |||
.RxError = rxerr, | |||
}; | |||
int | |||
main(void) | |||
{ | |||
@@ -20,10 +67,11 @@ main(void) | |||
strobe_rng_init(); | |||
board_init(); | |||
BoardInitMcu(); | |||
HAL_GPIO_WritePin(GPIOB, GPIO_PIN_8, GPIO_PIN_SET); | |||
#if 1 | |||
wait_for_vcp(); | |||
usb_printf("starting...\r\n"); | |||
@@ -31,4 +79,64 @@ main(void) | |||
bare_strobe_randomize(bytes, sizeof bytes); | |||
hexdump(bytes, sizeof bytes); | |||
usb_printf("\r\n"); | |||
#endif | |||
Radio.Init(&revents); | |||
usb_printf("foo\r\n"); | |||
Radio.ReadBuffer(0x00, bytes, sizeof bytes); | |||
usb_printf("regs 0x00: "); | |||
hexdump(bytes, sizeof bytes); | |||
usb_printf("\r\n"); | |||
Radio.ReadBuffer(0x40, bytes, sizeof bytes); | |||
usb_printf("regs 0x40: "); | |||
hexdump(bytes, sizeof bytes); | |||
usb_printf("\r\n"); | |||
uint32_t v; | |||
v = Radio.Random(); | |||
usb_printf("rr: %#x\r\n", v); | |||
v = Radio.Random(); | |||
usb_printf("rr: %#x\r\n", v); | |||
v = Radio.Random(); | |||
usb_printf("rr: %#x\r\n", v); | |||
usb_printf("gs: %#x\r\n", Radio.GetStatus()); | |||
usb_printf("set modem\r\n", v); | |||
Radio.SetModem(MODEM_LORA); | |||
usb_printf("check rffreq: %d\r\n", (int)Radio.CheckRfFrequency(914350 * 1000)); | |||
usb_printf("set channel\r\n", v); | |||
Radio.SetChannel(914350 * 1000); | |||
v = Radio.Random(); | |||
usb_printf("rr: %#x\r\n", v); | |||
usb_printf("rssi: %#hx\r\n", Radio.Rssi(MODEM_LORA)); | |||
Radio.SetRxConfig(MODEM_LORA, 0/*bandwidth*/, 7/*datarate*/, 1/*coderate*/, 0/*afc*/, 8/*preamblen*/, 5/*symTimeout*/, 0/*fixLen*/, 0/*payloadlen*/, 1/*crcOn*/, 0/*freqHop*/, 0/*hopPeriod*/, false/*iqInverted*/, true/*rxcont*/); | |||
Radio.SetTxConfig(MODEM_LORA, 11/*power*/, 0/*fdev*/, 0/*bandwidth*/, 7/*datarate*/, 1/*coderate*/, 8/*preamblen*/, 0/*fixLen*/, 1/*crcOn*/, 0/*freqHop*/, 0/*hopPeriod*/, false/*iqInverted*/, 1000/*timeout*/); | |||
uint8_t sendmsg[] = "testing lora123"; | |||
usb_printf("sending...\r\n"); | |||
Radio.Send(sendmsg, sizeof sendmsg); | |||
DelayMs(200); | |||
Radio.Send(sendmsg, sizeof sendmsg); | |||
DelayMs(200); | |||
Radio.Send(sendmsg, sizeof sendmsg); | |||
DelayMs(200); | |||
usb_printf("rx(0)...\r\n"); | |||
Radio.Rx(0); | |||
loop: | |||
BoardLowPowerHandler(); | |||
if (Radio.IrqProcess != NULL) | |||
Radio.IrqProcess(); | |||
goto loop; | |||
} |
@@ -0,0 +1,24 @@ | |||
#include "misc.h" | |||
#include <usbd_cdc_if.h> | |||
#include <usb_device.h> | |||
void | |||
Error_Handler(void) | |||
{ | |||
/* XXX - handle error */ | |||
} | |||
/* | |||
* Wait for a device to connect to the VCP | |||
*/ | |||
void | |||
wait_for_vcp(void) | |||
{ | |||
for (;;) { | |||
if (vcp_status(&hUsbDeviceFS.request)) | |||
break; | |||
} | |||
} | |||
@@ -1,3 +1,2 @@ | |||
void board_init(void); | |||
void Error_Handler(void); | |||
void wait_for_vcp(void); | |||
void Error_Handler(void); |
@@ -0,0 +1,867 @@ | |||
/** | |||
****************************************************************************** | |||
* @file stm32l1xx_hal_adc_ex.c | |||
* @author MCD Application Team | |||
* @brief This file provides firmware functions to manage the following | |||
* functionalities of the Analog to Digital Convertor (ADC) | |||
* peripheral: | |||
* + Operation functions | |||
* ++ Start, stop, get result of conversions of injected | |||
* group, using 2 possible modes: polling, interruption. | |||
* + Control functions | |||
* ++ Channels configuration on injected group | |||
* Other functions (generic functions) are available in file | |||
* "stm32l1xx_hal_adc.c". | |||
* | |||
@verbatim | |||
[..] | |||
(@) Sections "ADC peripheral features" and "How to use this driver" are | |||
available in file of generic functions "stm32l1xx_hal_adc.c". | |||
[..] | |||
@endverbatim | |||
****************************************************************************** | |||
* @attention | |||
* | |||
* <h2><center>© Copyright (c) 2017 STMicroelectronics. | |||
* All rights reserved.</center></h2> | |||
* | |||
* This software component is licensed by ST under BSD 3-Clause license, | |||
* the "License"; You may not use this file except in compliance with the | |||
* License. You may obtain a copy of the License at: | |||
* opensource.org/licenses/BSD-3-Clause | |||
* | |||
****************************************************************************** | |||
*/ | |||
/* Includes ------------------------------------------------------------------*/ | |||
#include "stm32l1xx_hal.h" | |||
/** @addtogroup STM32L1xx_HAL_Driver | |||
* @{ | |||
*/ | |||
/** @defgroup ADCEx ADCEx | |||
* @brief ADC Extension HAL module driver | |||
* @{ | |||
*/ | |||
#ifdef HAL_ADC_MODULE_ENABLED | |||
/* Private typedef -----------------------------------------------------------*/ | |||
/* Private define ------------------------------------------------------------*/ | |||
/** @defgroup ADCEx_Private_Constants ADCEx Private Constants | |||
* @{ | |||
*/ | |||
/* ADC conversion cycles (unit: ADC clock cycles) */ | |||
/* (selected sampling time + conversion time of 12 ADC clock cycles, with */ | |||
/* resolution 12 bits) */ | |||
#define ADC_CONVERSIONCLOCKCYCLES_SAMPLETIME_4CYCLE5 ( 16U) | |||
#define ADC_CONVERSIONCLOCKCYCLES_SAMPLETIME_9CYCLES ( 21U) | |||
#define ADC_CONVERSIONCLOCKCYCLES_SAMPLETIME_16CYCLES ( 28U) | |||
#define ADC_CONVERSIONCLOCKCYCLES_SAMPLETIME_24CYCLES ( 36U) | |||
#define ADC_CONVERSIONCLOCKCYCLES_SAMPLETIME_48CYCLES ( 60U) | |||
#define ADC_CONVERSIONCLOCKCYCLES_SAMPLETIME_96CYCLES (108U) | |||
#define ADC_CONVERSIONCLOCKCYCLES_SAMPLETIME_192CYCLES (204U) | |||
#define ADC_CONVERSIONCLOCKCYCLES_SAMPLETIME_384CYCLES (396U) | |||
/* Delay for temperature sensor stabilization time. */ | |||
/* Maximum delay is 10us (refer to device datasheet, parameter tSTART). */ | |||
/* Unit: us */ | |||
#define ADC_TEMPSENSOR_DELAY_US (10U) | |||
/** | |||
* @} | |||
*/ | |||
/* Private macro -------------------------------------------------------------*/ | |||
/* Private variables ---------------------------------------------------------*/ | |||
/* Private function prototypes -----------------------------------------------*/ | |||
/* Private functions ---------------------------------------------------------*/ | |||
/** @defgroup ADCEx_Exported_Functions ADCEx Exported Functions | |||
* @{ | |||
*/ | |||
/** @defgroup ADCEx_Exported_Functions_Group1 ADC Extended IO operation functions | |||
* @brief ADC Extended Input and Output operation functions | |||
* | |||
@verbatim | |||
=============================================================================== | |||
##### IO operation functions ##### | |||
=============================================================================== | |||
[..] This section provides functions allowing to: | |||
(+) Start conversion of injected group. | |||
(+) Stop conversion of injected group. | |||
(+) Poll for conversion complete on injected group. | |||
(+) Get result of injected channel conversion. | |||
(+) Start conversion of injected group and enable interruptions. | |||
(+) Stop conversion of injected group and disable interruptions. | |||
@endverbatim | |||
* @{ | |||
*/ | |||
/** | |||
* @brief Enables ADC, starts conversion of injected group. | |||
* Interruptions enabled in this function: None. | |||
* @param hadc ADC handle | |||
* @retval HAL status | |||
*/ | |||
HAL_StatusTypeDef HAL_ADCEx_InjectedStart(ADC_HandleTypeDef* hadc) | |||
{ | |||
HAL_StatusTypeDef tmp_hal_status = HAL_OK; | |||
/* Check the parameters */ | |||
assert_param(IS_ADC_ALL_INSTANCE(hadc->Instance)); | |||
/* Process locked */ | |||
__HAL_LOCK(hadc); | |||
/* Enable the ADC peripheral */ | |||
tmp_hal_status = ADC_Enable(hadc); | |||
/* Start conversion if ADC is effectively enabled */ | |||
if (tmp_hal_status == HAL_OK) | |||
{ | |||
/* Set ADC state */ | |||
/* - Clear state bitfield related to injected group conversion results */ | |||
/* - Set state bitfield related to injected operation */ | |||
ADC_STATE_CLR_SET(hadc->State, | |||
HAL_ADC_STATE_READY | HAL_ADC_STATE_INJ_EOC, | |||
HAL_ADC_STATE_INJ_BUSY); | |||
/* Check if a regular conversion is ongoing */ | |||
/* Note: On this device, there is no ADC error code fields related to */ | |||
/* conversions on group injected only. In case of conversion on */ | |||
/* going on group regular, no error code is reset. */ | |||
if (HAL_IS_BIT_CLR(hadc->State, HAL_ADC_STATE_REG_BUSY)) | |||
{ | |||
/* Reset ADC all error code fields */ | |||
ADC_CLEAR_ERRORCODE(hadc); | |||
} | |||
/* Process unlocked */ | |||
/* Unlock before starting ADC conversions: in case of potential */ | |||
/* interruption, to let the process to ADC IRQ Handler. */ | |||
__HAL_UNLOCK(hadc); | |||
/* Clear injected group conversion flag */ | |||
/* (To ensure of no unknown state from potential previous ADC operations) */ | |||
__HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_JEOC); | |||
/* Enable conversion of injected group. */ | |||
/* If software start has been selected, conversion starts immediately. */ | |||
/* If external trigger has been selected, conversion will start at next */ | |||
/* trigger event. */ | |||
/* If automatic injected conversion is enabled, conversion will start */ | |||
/* after next regular group conversion. */ | |||
if (ADC_IS_SOFTWARE_START_INJECTED(hadc) && | |||
HAL_IS_BIT_CLR(hadc->Instance->CR1, ADC_CR1_JAUTO) ) | |||
{ | |||
/* Enable ADC software conversion for injected channels */ | |||
SET_BIT(hadc->Instance->CR2, ADC_CR2_JSWSTART); | |||
} | |||
} | |||
/* Return function status */ | |||
return tmp_hal_status; | |||
} | |||
/** | |||
* @brief Stop conversion of injected channels. Disable ADC peripheral if | |||
* no regular conversion is on going. | |||
* @note If ADC must be disabled and if conversion is on going on | |||
* regular group, function HAL_ADC_Stop must be used to stop both | |||
* injected and regular groups, and disable the ADC. | |||
* @note If injected group mode auto-injection is enabled, | |||
* function HAL_ADC_Stop must be used. | |||
* @note In case of auto-injection mode, HAL_ADC_Stop must be used. | |||
* @param hadc ADC handle | |||
* @retval None | |||
*/ | |||
HAL_StatusTypeDef HAL_ADCEx_InjectedStop(ADC_HandleTypeDef* hadc) | |||
{ | |||
HAL_StatusTypeDef tmp_hal_status = HAL_OK; | |||
/* Check the parameters */ | |||
assert_param(IS_ADC_ALL_INSTANCE(hadc->Instance)); | |||
/* Process locked */ | |||
__HAL_LOCK(hadc); | |||
/* Stop potential conversion and disable ADC peripheral */ | |||
/* Conditioned to: */ | |||
/* - No conversion on the other group (regular group) is intended to */ | |||
/* continue (injected and regular groups stop conversion and ADC disable */ | |||
/* are common) */ | |||
/* - In case of auto-injection mode, HAL_ADC_Stop must be used. */ | |||
if(((hadc->State & HAL_ADC_STATE_REG_BUSY) == RESET) && | |||
HAL_IS_BIT_CLR(hadc->Instance->CR1, ADC_CR1_JAUTO) ) | |||
{ | |||
/* Stop potential conversion on going, on regular and injected groups */ | |||
/* Disable ADC peripheral */ | |||
tmp_hal_status = ADC_ConversionStop_Disable(hadc); | |||
/* Check if ADC is effectively disabled */ | |||
if (tmp_hal_status == HAL_OK) | |||
{ | |||
/* Set ADC state */ | |||
ADC_STATE_CLR_SET(hadc->State, | |||
HAL_ADC_STATE_REG_BUSY | HAL_ADC_STATE_INJ_BUSY, | |||
HAL_ADC_STATE_READY); | |||
} | |||
} | |||
else | |||
{ | |||
/* Update ADC state machine to error */ | |||
SET_BIT(hadc->State, HAL_ADC_STATE_ERROR_CONFIG); | |||
tmp_hal_status = HAL_ERROR; | |||
} | |||
/* Process unlocked */ | |||
__HAL_UNLOCK(hadc); | |||
/* Return function status */ | |||
return tmp_hal_status; | |||
} | |||
/** | |||
* @brief Wait for injected group conversion to be completed. | |||
* @param hadc ADC handle | |||
* @param Timeout Timeout value in millisecond. | |||
* @retval HAL status | |||
*/ | |||
HAL_StatusTypeDef HAL_ADCEx_InjectedPollForConversion(ADC_HandleTypeDef* hadc, uint32_t Timeout) | |||
{ | |||
uint32_t tickstart; | |||
/* Variables for polling in case of scan mode enabled and polling for each */ | |||
/* conversion. */ | |||
/* Note: Variable "conversion_timeout_cpu_cycles" set to offset 28 CPU */ | |||
/* cycles to compensate number of CPU cycles for processing of variable */ | |||
/* "conversion_timeout_cpu_cycles_max" */ | |||
uint32_t conversion_timeout_cpu_cycles = 28; | |||
uint32_t conversion_timeout_cpu_cycles_max = 0; | |||
/* Check the parameters */ | |||
assert_param(IS_ADC_ALL_INSTANCE(hadc->Instance)); | |||
/* Get timeout */ | |||
tickstart = HAL_GetTick(); | |||
/* Polling for end of conversion: differentiation if single/sequence */ | |||
/* conversion. */ | |||
/* For injected group, flag JEOC is set only at the end of the sequence, */ | |||
/* not for each conversion within the sequence. */ | |||
/* If setting "EOCSelection" is set to poll for each single conversion, */ | |||
/* management of polling depends on setting of injected group sequencer: */ | |||
/* - If single conversion for injected group (scan mode disabled or */ | |||
/* InjectedNbrOfConversion ==1), flag JEOC is used to determine the */ | |||
/* conversion completion. */ | |||
/* - If sequence conversion for injected group (scan mode enabled and */ | |||
/* InjectedNbrOfConversion >=2), flag JEOC is set only at the end of the */ | |||
/* sequence. */ | |||
/* To poll for each conversion, the maximum conversion time is computed */ | |||
/* from ADC conversion time (selected sampling time + conversion time of */ | |||
/* 12 ADC clock cycles) and APB2/ADC clock prescalers (depending on */ | |||
/* settings, conversion time range can vary from 8 to several thousands */ | |||
/* of CPU cycles). */ | |||
/* Note: On STM32L1, setting "EOCSelection" is related to regular group */ | |||
/* only, by hardware. For compatibility with other STM32 devices, */ | |||
/* this setting is related also to injected group by software. */ | |||
if (((hadc->Instance->JSQR & ADC_JSQR_JL) == RESET) || | |||
(hadc->Init.EOCSelection != ADC_EOC_SINGLE_CONV) ) | |||
{ | |||
/* Wait until End of Conversion flag is raised */ | |||
while(HAL_IS_BIT_CLR(hadc->Instance->SR, ADC_FLAG_JEOC)) | |||
{ | |||
/* Check if timeout is disabled (set to infinite wait) */ | |||
if(Timeout != HAL_MAX_DELAY) | |||
{ | |||
if((Timeout == 0) || ((HAL_GetTick() - tickstart ) > Timeout)) | |||
{ | |||
/* Update ADC state machine to timeout */ | |||
SET_BIT(hadc->State, HAL_ADC_STATE_TIMEOUT); | |||
/* Process unlocked */ | |||
__HAL_UNLOCK(hadc); | |||
return HAL_TIMEOUT; | |||
} | |||
} | |||
} | |||
} | |||
else | |||
{ | |||
/* Computation of CPU cycles corresponding to ADC conversion cycles. */ | |||
/* Retrieve ADC clock prescaler and ADC maximum conversion cycles on all */ | |||
/* channels. */ | |||
conversion_timeout_cpu_cycles_max = ADC_GET_CLOCK_PRESCALER_DECIMAL(hadc); | |||
conversion_timeout_cpu_cycles_max *= ADC_CONVCYCLES_MAX_RANGE(hadc); | |||
/* Poll with maximum conversion time */ | |||
while(conversion_timeout_cpu_cycles < conversion_timeout_cpu_cycles_max) | |||
{ | |||
/* Check if timeout is disabled (set to infinite wait) */ | |||
if(Timeout != HAL_MAX_DELAY) | |||
{ | |||
if((Timeout == 0) || ((HAL_GetTick() - tickstart ) > Timeout)) | |||
{ | |||
/* Update ADC state machine to timeout */ | |||
SET_BIT(hadc->State, HAL_ADC_STATE_TIMEOUT); | |||
/* Process unlocked */ | |||
__HAL_UNLOCK(hadc); | |||
return HAL_TIMEOUT; | |||
} | |||
} | |||
conversion_timeout_cpu_cycles ++; | |||
} | |||
} | |||
/* Clear end of conversion flag of injected group if low power feature */ | |||
/* "Auto Wait" is disabled, to not interfere with this feature until data */ | |||
/* register is read using function HAL_ADCEx_InjectedGetValue(). */ | |||
if (hadc->Init.LowPowerAutoWait == DISABLE) | |||
{ | |||
/* Clear injected group conversion flag */ | |||
__HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_JSTRT | ADC_FLAG_JEOC); | |||
} | |||
/* Update ADC state machine */ | |||
SET_BIT(hadc->State, HAL_ADC_STATE_INJ_EOC); | |||
/* Determine whether any further conversion upcoming on group injected */ | |||
/* by external trigger, continuous mode or scan sequence on going. */ | |||
/* Note: On STM32L1, there is no independent flag of end of sequence. */ | |||
/* The test of scan sequence on going is done either with scan */ | |||
/* sequence disabled or with end of conversion flag set to */ | |||
/* of end of sequence. */ | |||
if(ADC_IS_SOFTWARE_START_INJECTED(hadc) && | |||
(HAL_IS_BIT_CLR(hadc->Instance->JSQR, ADC_JSQR_JL) || | |||
HAL_IS_BIT_CLR(hadc->Instance->CR2, ADC_CR2_EOCS) ) && | |||
(HAL_IS_BIT_CLR(hadc->Instance->CR1, ADC_CR1_JAUTO) && | |||
(ADC_IS_SOFTWARE_START_REGULAR(hadc) && | |||
(hadc->Init.ContinuousConvMode == DISABLE) ) ) ) | |||
{ | |||
/* Set ADC state */ | |||
CLEAR_BIT(hadc->State, HAL_ADC_STATE_INJ_BUSY); | |||
if (HAL_IS_BIT_CLR(hadc->State, HAL_ADC_STATE_REG_BUSY)) | |||
{ | |||
SET_BIT(hadc->State, HAL_ADC_STATE_READY); | |||
} | |||
} | |||
/* Return ADC state */ | |||
return HAL_OK; | |||
} | |||
/** | |||
* @brief Enables ADC, starts conversion of injected group with interruption. | |||
* - JEOC (end of conversion of injected group) | |||
* Each of these interruptions has its dedicated callback function. | |||
* @param hadc ADC handle | |||
* @retval HAL status. | |||
*/ | |||
HAL_StatusTypeDef HAL_ADCEx_InjectedStart_IT(ADC_HandleTypeDef* hadc) | |||
{ | |||
HAL_StatusTypeDef tmp_hal_status = HAL_OK; | |||
/* Check the parameters */ | |||
assert_param(IS_ADC_ALL_INSTANCE(hadc->Instance)); | |||
/* Process locked */ | |||
__HAL_LOCK(hadc); | |||
/* Enable the ADC peripheral */ | |||
tmp_hal_status = ADC_Enable(hadc); | |||
/* Start conversion if ADC is effectively enabled */ | |||
if (tmp_hal_status == HAL_OK) | |||
{ | |||
/* Set ADC state */ | |||
/* - Clear state bitfield related to injected group conversion results */ | |||
/* - Set state bitfield related to injected operation */ | |||
ADC_STATE_CLR_SET(hadc->State, | |||
HAL_ADC_STATE_READY | HAL_ADC_STATE_INJ_EOC, | |||
HAL_ADC_STATE_INJ_BUSY); | |||
/* Check if a regular conversion is ongoing */ | |||
/* Note: On this device, there is no ADC error code fields related to */ | |||
/* conversions on group injected only. In case of conversion on */ | |||
/* going on group regular, no error code is reset. */ | |||
if (HAL_IS_BIT_CLR(hadc->State, HAL_ADC_STATE_REG_BUSY)) | |||
{ | |||
/* Reset ADC all error code fields */ | |||
ADC_CLEAR_ERRORCODE(hadc); | |||
} | |||
/* Process unlocked */ | |||
/* Unlock before starting ADC conversions: in case of potential */ | |||
/* interruption, to let the process to ADC IRQ Handler. */ | |||
__HAL_UNLOCK(hadc); | |||
/* Clear injected group conversion flag */ | |||
/* (To ensure of no unknown state from potential previous ADC operations) */ | |||
__HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_JEOC); | |||
/* Enable end of conversion interrupt for injected channels */ | |||
__HAL_ADC_ENABLE_IT(hadc, ADC_IT_JEOC); | |||
/* Enable conversion of injected group. */ | |||
/* If software start has been selected, conversion starts immediately. */ | |||
/* If external trigger has been selected, conversion will start at next */ | |||
/* trigger event. */ | |||
/* If automatic injected conversion is enabled, conversion will start */ | |||
/* after next regular group conversion. */ | |||
if (ADC_IS_SOFTWARE_START_INJECTED(hadc) && | |||
HAL_IS_BIT_CLR(hadc->Instance->CR1, ADC_CR1_JAUTO) ) | |||
{ | |||
/* Enable ADC software conversion for injected channels */ | |||
SET_BIT(hadc->Instance->CR2, ADC_CR2_JSWSTART); | |||
} | |||
} | |||
/* Return function status */ | |||
return tmp_hal_status; | |||
} | |||
/** | |||
* @brief Stop conversion of injected channels, disable interruption of | |||
* end-of-conversion. Disable ADC peripheral if no regular conversion | |||
* is on going. | |||
* @note If ADC must be disabled and if conversion is on going on | |||
* regular group, function HAL_ADC_Stop must be used to stop both | |||
* injected and regular groups, and disable the ADC. | |||
* @note If injected group mode auto-injection is enabled, | |||
* function HAL_ADC_Stop must be used. | |||
* @param hadc ADC handle | |||
* @retval None | |||
*/ | |||
HAL_StatusTypeDef HAL_ADCEx_InjectedStop_IT(ADC_HandleTypeDef* hadc) | |||
{ | |||
HAL_StatusTypeDef tmp_hal_status = HAL_OK; | |||
/* Check the parameters */ | |||
assert_param(IS_ADC_ALL_INSTANCE(hadc->Instance)); | |||
/* Process locked */ | |||
__HAL_LOCK(hadc); | |||
/* Stop potential conversion and disable ADC peripheral */ | |||
/* Conditioned to: */ | |||
/* - No conversion on the other group (regular group) is intended to */ | |||
/* continue (injected and regular groups stop conversion and ADC disable */ | |||
/* are common) */ | |||
/* - In case of auto-injection mode, HAL_ADC_Stop must be used. */ | |||
if(((hadc->State & HAL_ADC_STATE_REG_BUSY) == RESET) && | |||
HAL_IS_BIT_CLR(hadc->Instance->CR1, ADC_CR1_JAUTO) ) | |||
{ | |||
/* Stop potential conversion on going, on regular and injected groups */ | |||
/* Disable ADC peripheral */ | |||
tmp_hal_status = ADC_ConversionStop_Disable(hadc); | |||
/* Check if ADC is effectively disabled */ | |||
if (tmp_hal_status == HAL_OK) | |||
{ | |||
/* Disable ADC end of conversion interrupt for injected channels */ | |||
__HAL_ADC_DISABLE_IT(hadc, ADC_IT_JEOC); | |||
/* Set ADC state */ | |||
ADC_STATE_CLR_SET(hadc->State, | |||
HAL_ADC_STATE_REG_BUSY | HAL_ADC_STATE_INJ_BUSY, | |||
HAL_ADC_STATE_READY); | |||
} | |||
} | |||
else | |||
{ | |||
/* Update ADC state machine to error */ | |||
SET_BIT(hadc->State, HAL_ADC_STATE_ERROR_CONFIG); | |||
tmp_hal_status = HAL_ERROR; | |||
} | |||
/* Process unlocked */ | |||
__HAL_UNLOCK(hadc); | |||
/* Return function status */ | |||
return tmp_hal_status; | |||
} | |||
/** | |||
* @brief Get ADC injected group conversion result. | |||
* @note Reading register JDRx automatically clears ADC flag JEOC | |||
* (ADC group injected end of unitary conversion). | |||
* @note This function does not clear ADC flag JEOS | |||
* (ADC group injected end of sequence conversion) | |||
* Occurrence of flag JEOS rising: | |||
* - If sequencer is composed of 1 rank, flag JEOS is equivalent | |||
* to flag JEOC. | |||
* - If sequencer is composed of several ranks, during the scan | |||
* sequence flag JEOC only is raised, at the end of the scan sequence | |||
* both flags JEOC and EOS are raised. | |||
* Flag JEOS must not be cleared by this function because | |||
* it would not be compliant with low power features | |||
* (feature low power auto-wait, not available on all STM32 families). | |||
* To clear this flag, either use function: | |||
* in programming model IT: @ref HAL_ADC_IRQHandler(), in programming | |||
* model polling: @ref HAL_ADCEx_InjectedPollForConversion() | |||
* or @ref __HAL_ADC_CLEAR_FLAG(&hadc, ADC_FLAG_JEOS). | |||
* @param hadc ADC handle | |||
* @param InjectedRank the converted ADC injected rank. | |||
* This parameter can be one of the following values: | |||
* @arg ADC_INJECTED_RANK_1: Injected Channel1 selected | |||
* @arg ADC_INJECTED_RANK_2: Injected Channel2 selected | |||
* @arg ADC_INJECTED_RANK_3: Injected Channel3 selected | |||
* @arg ADC_INJECTED_RANK_4: Injected Channel4 selected | |||
* @retval ADC group injected conversion data | |||
*/ | |||
uint32_t HAL_ADCEx_InjectedGetValue(ADC_HandleTypeDef* hadc, uint32_t InjectedRank) | |||
{ | |||
uint32_t tmp_jdr = 0; | |||
/* Check the parameters */ | |||
assert_param(IS_ADC_ALL_INSTANCE(hadc->Instance)); | |||
assert_param(IS_ADC_INJECTED_RANK(InjectedRank)); | |||
/* Get ADC converted value */ | |||
switch(InjectedRank) | |||
{ | |||
case ADC_INJECTED_RANK_4: | |||
tmp_jdr = hadc->Instance->JDR4; | |||
break; | |||
case ADC_INJECTED_RANK_3: | |||
tmp_jdr = hadc->Instance->JDR3; | |||
break; | |||
case ADC_INJECTED_RANK_2: | |||
tmp_jdr = hadc->Instance->JDR2; | |||
break; | |||
case ADC_INJECTED_RANK_1: | |||
default: | |||
tmp_jdr = hadc->Instance->JDR1; | |||
break; | |||
} | |||
/* Return ADC converted value */ | |||
return tmp_jdr; | |||
} | |||
/** | |||
* @brief Injected conversion complete callback in non blocking mode | |||
* @param hadc ADC handle | |||
* @retval None | |||
*/ | |||
__weak void HAL_ADCEx_InjectedConvCpltCallback(ADC_HandleTypeDef* hadc) | |||
{ | |||
/* Prevent unused argument(s) compilation warning */ | |||
UNUSED(hadc); | |||
/* NOTE : This function Should not be modified, when the callback is needed, | |||
the HAL_ADCEx_InjectedConvCpltCallback could be implemented in the user file | |||
*/ | |||
} | |||
/** | |||
* @} | |||
*/ | |||
/** @defgroup ADCEx_Exported_Functions_Group2 ADC Extended Peripheral Control functions | |||
* @brief ADC Extended Peripheral Control functions | |||
* | |||
@verbatim | |||
=============================================================================== | |||
##### Peripheral Control functions ##### | |||
=============================================================================== | |||
[..] This section provides functions allowing to: | |||
(+) Configure channels on injected group | |||
@endverbatim | |||
* @{ | |||
*/ | |||
/** | |||
* @brief Configures the ADC injected group and the selected channel to be | |||
* linked to the injected group. | |||
* @note Possibility to update parameters on the fly: | |||
* This function initializes injected group, following calls to this | |||
* function can be used to reconfigure some parameters of structure | |||
* "ADC_InjectionConfTypeDef" on the fly, without reseting the ADC. | |||
* The setting of these parameters is conditioned to ADC state: | |||
* this function must be called when ADC is not under conversion. | |||
* @param hadc ADC handle | |||
* @param sConfigInjected Structure of ADC injected group and ADC channel for | |||
* injected group. | |||
* @retval None | |||
*/ | |||
HAL_StatusTypeDef HAL_ADCEx_InjectedConfigChannel(ADC_HandleTypeDef* hadc, ADC_InjectionConfTypeDef* sConfigInjected) | |||
{ | |||
HAL_StatusTypeDef tmp_hal_status = HAL_OK; | |||
__IO uint32_t wait_loop_index = 0; | |||
/* Check the parameters */ | |||
assert_param(IS_ADC_ALL_INSTANCE(hadc->Instance)); | |||
assert_param(IS_ADC_CHANNEL(sConfigInjected->InjectedChannel)); | |||
assert_param(IS_ADC_SAMPLE_TIME(sConfigInjected->InjectedSamplingTime)); | |||
assert_param(IS_FUNCTIONAL_STATE(sConfigInjected->AutoInjectedConv)); | |||
assert_param(IS_ADC_EXTTRIGINJEC(sConfigInjected->ExternalTrigInjecConv)); | |||
assert_param(IS_ADC_RANGE(ADC_RESOLUTION_12B, sConfigInjected->InjectedOffset)); | |||
if(hadc->Init.ScanConvMode != ADC_SCAN_DISABLE) | |||
{ | |||
assert_param(IS_ADC_INJECTED_RANK(sConfigInjected->InjectedRank)); | |||
assert_param(IS_ADC_INJECTED_NB_CONV(sConfigInjected->InjectedNbrOfConversion)); | |||
assert_param(IS_FUNCTIONAL_STATE(sConfigInjected->InjectedDiscontinuousConvMode)); | |||
} | |||
if(sConfigInjected->ExternalTrigInjecConv != ADC_INJECTED_SOFTWARE_START) | |||
{ | |||
assert_param(IS_ADC_EXTTRIGINJEC_EDGE(sConfigInjected->ExternalTrigInjecConvEdge)); | |||
} | |||
/* Process locked */ | |||
__HAL_LOCK(hadc); | |||
/* Configuration of injected group sequencer: */ | |||
/* - if scan mode is disabled, injected channels sequence length is set to */ | |||
/* 0x00: 1 channel converted (channel on regular rank 1) */ | |||
/* Parameter "InjectedNbrOfConversion" is discarded. */ | |||
/* Note: Scan mode is present by hardware on this device and, if */ | |||
/* disabled, discards automatically nb of conversions. Anyway, nb of */ | |||
/* conversions is forced to 0x00 for alignment over all STM32 devices. */ | |||
/* - if scan mode is enabled, injected channels sequence length is set to */ | |||
/* parameter ""InjectedNbrOfConversion". */ | |||
if (hadc->Init.ScanConvMode == ADC_SCAN_DISABLE) | |||
{ | |||
if (sConfigInjected->InjectedRank == ADC_INJECTED_RANK_1) | |||
{ | |||
/* Clear the old SQx bits for all injected ranks */ | |||
MODIFY_REG(hadc->Instance->JSQR , | |||
ADC_JSQR_JL | | |||
ADC_JSQR_JSQ4 | | |||
ADC_JSQR_JSQ3 | | |||
ADC_JSQR_JSQ2 | | |||
ADC_JSQR_JSQ1 , | |||
ADC_JSQR_RK_JL(sConfigInjected->InjectedChannel, | |||
ADC_INJECTED_RANK_1, | |||
0x01) ); | |||
} | |||
/* If another injected rank than rank1 was intended to be set, and could */ | |||
/* not due to ScanConvMode disabled, error is reported. */ | |||
else | |||
{ | |||
/* Update ADC state machine to error */ | |||
SET_BIT(hadc->State, HAL_ADC_STATE_ERROR_CONFIG); | |||
tmp_hal_status = HAL_ERROR; | |||
} | |||
} | |||
else | |||
{ | |||
/* Since injected channels rank conv. order depends on total number of */ | |||
/* injected conversions, selected rank must be below or equal to total */ | |||
/* number of injected conversions to be updated. */ | |||
if (sConfigInjected->InjectedRank <= sConfigInjected->InjectedNbrOfConversion) | |||
{ | |||
/* Clear the old SQx bits for the selected rank */ | |||
/* Set the SQx bits for the selected rank */ | |||
MODIFY_REG(hadc->Instance->JSQR , | |||
ADC_JSQR_JL | | |||
ADC_JSQR_RK_JL(ADC_JSQR_JSQ1, | |||
sConfigInjected->InjectedRank, | |||
sConfigInjected->InjectedNbrOfConversion) , | |||
ADC_JSQR_JL_SHIFT(sConfigInjected->InjectedNbrOfConversion) | | |||
ADC_JSQR_RK_JL(sConfigInjected->InjectedChannel, | |||
sConfigInjected->InjectedRank, | |||
sConfigInjected->InjectedNbrOfConversion) ); | |||
} | |||
else | |||
{ | |||
/* Clear the old SQx bits for the selected rank */ | |||
MODIFY_REG(hadc->Instance->JSQR , | |||
ADC_JSQR_JL | | |||
ADC_JSQR_RK_JL(ADC_JSQR_JSQ1, | |||
sConfigInjected->InjectedRank, | |||
sConfigInjected->InjectedNbrOfConversion) , | |||
0x00000000 ); | |||
} | |||
} | |||
/* Enable external trigger if trigger selection is different of software */ | |||
/* start. */ | |||
/* Note: This configuration keeps the hardware feature of parameter */ | |||
/* ExternalTrigConvEdge "trigger edge none" equivalent to */ | |||
/* software start. */ | |||
if (sConfigInjected->ExternalTrigInjecConv != ADC_INJECTED_SOFTWARE_START) | |||
{ | |||
MODIFY_REG(hadc->Instance->CR2 , | |||
ADC_CR2_JEXTEN | | |||
ADC_CR2_JEXTSEL , | |||
sConfigInjected->ExternalTrigInjecConv | | |||
sConfigInjected->ExternalTrigInjecConvEdge ); | |||
} | |||
else | |||
{ | |||
MODIFY_REG(hadc->Instance->CR2, | |||
ADC_CR2_JEXTEN | | |||
ADC_CR2_JEXTSEL , | |||
0x00000000 ); | |||
} | |||
/* Configuration of injected group */ | |||
/* Parameters update conditioned to ADC state: */ | |||
/* Parameters that can be updated only when ADC is disabled: */ | |||
/* - Automatic injected conversion */ | |||
/* - Injected discontinuous mode */ | |||
if ((ADC_IS_ENABLE(hadc) == RESET)) | |||
{ | |||
hadc->Instance->CR1 &= ~(ADC_CR1_JAUTO | | |||
ADC_CR1_JDISCEN ); | |||
/* Automatic injected conversion can be enabled if injected group */ | |||
/* external triggers are disabled. */ | |||
if (sConfigInjected->AutoInjectedConv == ENABLE) | |||
{ | |||
if (sConfigInjected->ExternalTrigInjecConv == ADC_INJECTED_SOFTWARE_START) | |||
{ | |||
SET_BIT(hadc->Instance->CR1, ADC_CR1_JAUTO); | |||
} | |||
else | |||
{ | |||
/* Update ADC state machine to error */ | |||
SET_BIT(hadc->State, HAL_ADC_STATE_ERROR_CONFIG); | |||
tmp_hal_status = HAL_ERROR; | |||
} | |||
} | |||
/* Injected discontinuous can be enabled only if auto-injected mode is */ | |||
/* disabled. */ | |||
if (sConfigInjected->InjectedDiscontinuousConvMode == ENABLE) | |||
{ | |||
if (sConfigInjected->AutoInjectedConv == DISABLE) | |||
{ | |||
SET_BIT(hadc->Instance->CR1, ADC_CR1_JDISCEN); | |||
} | |||
else | |||
{ | |||
/* Update ADC state machine to error */ | |||
SET_BIT(hadc->State, HAL_ADC_STATE_ERROR_CONFIG); | |||
tmp_hal_status = HAL_ERROR; | |||
} | |||
} | |||
} | |||
/* Channel sampling time configuration */ | |||
/* For InjectedChannels 0 to 9 */ | |||
if (sConfigInjected->InjectedChannel < ADC_CHANNEL_10) | |||
{ | |||
MODIFY_REG(hadc->Instance->SMPR3, | |||
ADC_SMPR3(ADC_SMPR3_SMP0, sConfigInjected->InjectedChannel), | |||
ADC_SMPR3(sConfigInjected->InjectedSamplingTime, sConfigInjected->InjectedChannel) ); | |||
} | |||
/* For InjectedChannels 10 to 19 */ | |||
else if (sConfigInjected->InjectedChannel < ADC_CHANNEL_20) | |||
{ | |||
MODIFY_REG(hadc->Instance->SMPR2, | |||
ADC_SMPR2(ADC_SMPR2_SMP10, sConfigInjected->InjectedChannel), | |||
ADC_SMPR2(sConfigInjected->InjectedSamplingTime, sConfigInjected->InjectedChannel) ); | |||
} | |||
/* For InjectedChannels 20 to 26 for devices Cat.1, Cat.2, Cat.3 */ | |||
/* For InjectedChannels 20 to 29 for devices Cat4, Cat.5 */ | |||
else if (sConfigInjected->InjectedChannel <= ADC_SMPR1_CHANNEL_MAX) | |||
{ | |||
MODIFY_REG(hadc->Instance->SMPR1, | |||
ADC_SMPR1(ADC_SMPR1_SMP20, sConfigInjected->InjectedChannel), | |||
ADC_SMPR1(sConfigInjected->InjectedSamplingTime, sConfigInjected->InjectedChannel) ); | |||
} | |||
/* For InjectedChannels 30 to 31 for devices Cat4, Cat.5 */ | |||
else | |||
{ | |||
ADC_SMPR0_CHANNEL_SET(hadc, sConfigInjected->InjectedSamplingTime, sConfigInjected->InjectedChannel); | |||
} | |||
/* Configure the offset: offset enable/disable, InjectedChannel, offset value */ | |||
switch(sConfigInjected->InjectedRank) | |||
{ | |||
case 1: | |||
/* Set injected channel 1 offset */ | |||
MODIFY_REG(hadc->Instance->JOFR1, | |||
ADC_JOFR1_JOFFSET1, | |||
sConfigInjected->InjectedOffset); | |||
break; | |||
case 2: | |||
/* Set injected channel 2 offset */ | |||
MODIFY_REG(hadc->Instance->JOFR2, | |||
ADC_JOFR2_JOFFSET2, | |||
sConfigInjected->InjectedOffset); | |||
break; | |||
case 3: | |||
/* Set injected channel 3 offset */ | |||
MODIFY_REG(hadc->Instance->JOFR3, | |||
ADC_JOFR3_JOFFSET3, | |||
sConfigInjected->InjectedOffset); | |||
break; | |||
case 4: | |||
default: | |||
MODIFY_REG(hadc->Instance->JOFR4, | |||
ADC_JOFR4_JOFFSET4, | |||
sConfigInjected->InjectedOffset); | |||
break; | |||
} | |||
/* If ADC1 Channel_16 or Channel_17 is selected, enable Temperature sensor */ | |||
/* and VREFINT measurement path. */ | |||
if ((sConfigInjected->InjectedChannel == ADC_CHANNEL_TEMPSENSOR) || | |||
(sConfigInjected->InjectedChannel == ADC_CHANNEL_VREFINT) ) | |||
{ | |||
SET_BIT(ADC->CCR, ADC_CCR_TSVREFE); | |||
if ((sConfigInjected->InjectedChannel == ADC_CHANNEL_TEMPSENSOR)) | |||
{ | |||
/* Delay for temperature sensor stabilization time */ | |||
/* Compute number of CPU cycles to wait for */ | |||
wait_loop_index = (ADC_TEMPSENSOR_DELAY_US * (SystemCoreClock / 1000000)); | |||
while(wait_loop_index != 0) | |||
{ | |||
wait_loop_index--; | |||
} | |||
} | |||
} | |||
/* Process unlocked */ | |||
__HAL_UNLOCK(hadc); | |||
/* Return function status */ | |||
return tmp_hal_status; | |||
} | |||
/** | |||
* @} | |||
*/ | |||
/** | |||
* @} | |||
*/ | |||
#endif /* HAL_ADC_MODULE_ENABLED */ | |||
/** | |||
* @} | |||
*/ | |||
/** | |||
* @} | |||
*/ | |||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ |
@@ -0,0 +1,572 @@ | |||
/** | |||
****************************************************************************** | |||
* @file stm32l1xx_hal_adc_ex.h | |||
* @author MCD Application Team | |||
* @brief Header file of ADC HAL Extension module. | |||
****************************************************************************** | |||
* @attention | |||
* | |||
* <h2><center>© Copyright (c) 2017 STMicroelectronics. | |||
* All rights reserved.</center></h2> | |||
* | |||
* This software component is licensed by ST under BSD 3-Clause license, | |||
* the "License"; You may not use this file except in compliance with the | |||
* License. You may obtain a copy of the License at: | |||
* opensource.org/licenses/BSD-3-Clause | |||
* | |||
****************************************************************************** | |||
*/ | |||
/* Define to prevent recursive inclusion -------------------------------------*/ | |||
#ifndef __STM32L1xx_HAL_ADC_EX_H | |||
#define __STM32L1xx_HAL_ADC_EX_H | |||
#ifdef __cplusplus | |||
extern "C" { | |||
#endif | |||
/* Includes ------------------------------------------------------------------*/ | |||
#include "stm32l1xx_hal_def.h" | |||
/** @addtogroup STM32L1xx_HAL_Driver | |||
* @{ | |||
*/ | |||
/** @addtogroup ADCEx | |||
* @{ | |||
*/ | |||
/* Exported types ------------------------------------------------------------*/ | |||
/** @defgroup ADCEx_Exported_Types ADCEx Exported Types | |||
* @{ | |||
*/ | |||
/** | |||
* @brief ADC Configuration injected Channel structure definition | |||
* @note Parameters of this structure are shared within 2 scopes: | |||
* - Scope channel: InjectedChannel, InjectedRank, InjectedSamplingTime, InjectedOffset | |||
* - Scope injected group (affects all channels of injected group): InjectedNbrOfConversion, InjectedDiscontinuousConvMode, | |||
* AutoInjectedConv, ExternalTrigInjecConvEdge, ExternalTrigInjecConv. | |||
* @note The setting of these parameters with function HAL_ADCEx_InjectedConfigChannel() is conditioned to ADC state. | |||
* ADC state can be either: | |||
* - For all parameters: ADC disabled | |||
* - For all except parameters 'InjectedDiscontinuousConvMode' and 'AutoInjectedConv': ADC enabled without conversion on going on injected group. | |||
* - For parameters 'ExternalTrigInjecConv' and 'ExternalTrigInjecConvEdge': ADC enabled, even with conversion on going on injected group. | |||
*/ | |||
typedef struct | |||
{ | |||
uint32_t InjectedChannel; /*!< Selection of ADC channel to configure | |||
This parameter can be a value of @ref ADC_channels | |||
Note: Depending on devices, some channels may not be available on package pins. Refer to device datasheet for channels availability. */ | |||
uint32_t InjectedRank; /*!< Rank in the injected group sequencer | |||
This parameter must be a value of @ref ADCEx_injected_rank | |||
Note: In case of need to disable a channel or change order of conversion sequencer, rank containing a previous channel setting can be overwritten by the new channel setting (or parameter number of conversions can be adjusted) */ | |||
uint32_t InjectedSamplingTime; /*!< Sampling time value to be set for the selected channel. | |||
Unit: ADC clock cycles | |||
Conversion time is the addition of sampling time and processing time (12 ADC clock cycles at ADC resolution 12 bits, 11 cycles at 10 bits, 9 cycles at 8 bits, 7 cycles at 6 bits). | |||
This parameter can be a value of @ref ADC_sampling_times | |||
Caution: This parameter updates the parameter property of the channel, that can be used into regular and/or injected groups. | |||
If this same channel has been previously configured in the other group (regular/injected), it will be updated to last setting. | |||
Note: In case of usage of internal measurement channels (VrefInt/Vbat/TempSensor), | |||
sampling time constraints must be respected (sampling time can be adjusted in function of ADC clock frequency and sampling time setting) | |||
Refer to device datasheet for timings values, parameters TS_vrefint, TS_temp (values rough order: 4us min). */ | |||
uint32_t InjectedOffset; /*!< Defines the offset to be subtracted from the raw converted data (for channels set on injected group only). | |||
Offset value must be a positive number. | |||
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 InjectedNbrOfConversion; /*!< Specifies the number of ranks that will be converted within the injected group sequencer. | |||
To use the injected group sequencer and convert several ranks, parameter 'ScanConvMode' must be enabled. | |||
This parameter must be a number between Min_Data = 1 and Max_Data = 4. | |||
Caution: this setting impacts the entire injected group. Therefore, call of HAL_ADCEx_InjectedConfigChannel() to | |||
configure a channel on injected group can impact the configuration of other channels previously set. */ | |||
FunctionalState InjectedDiscontinuousConvMode; /*!< Specifies whether the conversions sequence of injected group is performed in Complete-sequence/Discontinuous-sequence (main sequence subdivided in successive parts). | |||
Discontinuous mode is used only if sequencer is enabled (parameter 'ScanConvMode'). If sequencer is disabled, this parameter is discarded. | |||
Discontinuous mode can be enabled only if continuous mode is disabled. If continuous mode is enabled, this parameter setting is discarded. | |||
This parameter can be set to ENABLE or DISABLE. | |||
Note: For injected group, number of discontinuous ranks increment is fixed to one-by-one. | |||
Caution: this setting impacts the entire injected group. Therefore, call of HAL_ADCEx_InjectedConfigChannel() to | |||
configure a channel on injected group can impact the configuration of other channels previously set. */ | |||
FunctionalState AutoInjectedConv; /*!< Enables or disables the selected ADC automatic injected group conversion after regular one | |||
This parameter can be set to ENABLE or DISABLE. | |||
Note: To use Automatic injected conversion, discontinuous mode must be disabled ('DiscontinuousConvMode' and 'InjectedDiscontinuousConvMode' set to DISABLE) | |||
Note: To use Automatic injected conversion, injected group external triggers must be disabled ('ExternalTrigInjecConv' set to ADC_SOFTWARE_START) | |||
Note: In case of DMA used with regular group: if DMA configured in normal mode (single shot) JAUTO will be stopped upon DMA transfer complete. | |||
To maintain JAUTO always enabled, DMA must be configured in circular mode. | |||
Caution: this setting impacts the entire injected group. Therefore, call of HAL_ADCEx_InjectedConfigChannel() to | |||
configure a channel on injected group can impact the configuration of other channels previously set. */ | |||
uint32_t ExternalTrigInjecConv; /*!< Selects the external event used to trigger the conversion start of injected group. | |||
If set to ADC_INJECTED_SOFTWARE_START, external triggers are disabled. | |||
If set to external trigger source, triggering is on event rising edge. | |||
This parameter can be a value of @ref ADCEx_External_trigger_source_Injected | |||
Note: This parameter must be modified when ADC is disabled (before ADC start conversion or after ADC stop conversion). | |||
If ADC is enabled, this parameter setting is bypassed without error reporting (as it can be the expected behaviour in case of another parameter update on the fly) | |||
Caution: this setting impacts the entire injected group. Therefore, call of HAL_ADCEx_InjectedConfigChannel() to | |||
configure a channel on injected group can impact the configuration of other channels previously set. */ | |||
uint32_t ExternalTrigInjecConvEdge; /*!< Selects the external trigger edge of injected group. | |||
This parameter can be a value of @ref ADCEx_External_trigger_edge_Injected. | |||
If trigger is set to ADC_INJECTED_SOFTWARE_START, this parameter is discarded. | |||
Caution: this setting impacts the entire injected group. Therefore, call of HAL_ADCEx_InjectedConfigChannel() to | |||
configure a channel on injected group can impact the configuration of other channels previously set. */ | |||
}ADC_InjectionConfTypeDef; | |||
/** | |||
* @} | |||
*/ | |||
/* Exported constants --------------------------------------------------------*/ | |||
/** @defgroup ADCEx_Exported_Constants ADCEx Exported Constants | |||
* @{ | |||
*/ | |||
/** @defgroup ADCEx_injected_rank ADCEx rank into injected group | |||
* @{ | |||
*/ | |||
#define ADC_INJECTED_RANK_1 (0x00000001U) | |||
#define ADC_INJECTED_RANK_2 (0x00000002U) | |||
#define ADC_INJECTED_RANK_3 (0x00000003U) | |||
#define ADC_INJECTED_RANK_4 (0x00000004U) | |||
/** | |||
* @} | |||
*/ | |||
/** @defgroup ADCEx_External_trigger_edge_Injected ADCEx external trigger enable for injected group | |||
* @{ | |||
*/ | |||
#define ADC_EXTERNALTRIGINJECCONV_EDGE_NONE (0x00000000U) | |||
#define ADC_EXTERNALTRIGINJECCONV_EDGE_RISING ((uint32_t)ADC_CR2_JEXTEN_0) | |||
#define ADC_EXTERNALTRIGINJECCONV_EDGE_FALLING ((uint32_t)ADC_CR2_JEXTEN_1) | |||
#define ADC_EXTERNALTRIGINJECCONV_EDGE_RISINGFALLING ((uint32_t)ADC_CR2_JEXTEN) | |||
/** | |||
* @} | |||
*/ | |||
/** @defgroup ADCEx_External_trigger_source_Injected ADCEx External trigger source Injected | |||
* @{ | |||
*/ | |||
/* External triggers for injected groups of ADC1 */ | |||
#define ADC_EXTERNALTRIGINJECCONV_T2_CC1 ADC_EXTERNALTRIGINJEC_T2_CC1 | |||
#define ADC_EXTERNALTRIGINJECCONV_T2_TRGO ADC_EXTERNALTRIGINJEC_T2_TRGO | |||
#define ADC_EXTERNALTRIGINJECCONV_T3_CC4 ADC_EXTERNALTRIGINJEC_T3_CC4 | |||
#define ADC_EXTERNALTRIGINJECCONV_T4_TRGO ADC_EXTERNALTRIGINJEC_T4_TRGO | |||
#define ADC_EXTERNALTRIGINJECCONV_T4_CC1 ADC_EXTERNALTRIGINJEC_T4_CC1 | |||
#define ADC_EXTERNALTRIGINJECCONV_T4_CC2 ADC_EXTERNALTRIGINJEC_T4_CC2 | |||
#define ADC_EXTERNALTRIGINJECCONV_T4_CC3 ADC_EXTERNALTRIGINJEC_T4_CC3 | |||
#define ADC_EXTERNALTRIGINJECCONV_T7_TRGO ADC_EXTERNALTRIGINJEC_T7_TRGO | |||
#define ADC_EXTERNALTRIGINJECCONV_T9_CC1 ADC_EXTERNALTRIGINJEC_T9_CC1 | |||
#define ADC_EXTERNALTRIGINJECCONV_T9_TRGO ADC_EXTERNALTRIGINJEC_T9_TRGO | |||
#define ADC_EXTERNALTRIGINJECCONV_T10_CC1 ADC_EXTERNALTRIGINJEC_T10_CC1 | |||
#define ADC_EXTERNALTRIGINJECCONV_EXT_IT15 ADC_EXTERNALTRIGINJEC_EXT_IT15 | |||
#define ADC_INJECTED_SOFTWARE_START (0x00000010U) | |||
/** | |||
* @} | |||
*/ | |||
/** | |||
* @} | |||
*/ | |||
/* Private constants ---------------------------------------------------------*/ | |||
/** @addtogroup ADCEx_Private_Constants ADCEx Private Constants | |||
* @{ | |||
*/ | |||
/** @defgroup ADCEx_Internal_HAL_driver_Ext_trig_src_Injected ADCEx Internal HAL driver Ext trig src Injected | |||
* @{ | |||
*/ | |||
/* List of external triggers of injected group for ADC1: */ | |||
/* (used internally by HAL driver. To not use into HAL structure parameters) */ | |||
#define ADC_EXTERNALTRIGINJEC_T9_CC1 (0x00000000U) | |||
#define ADC_EXTERNALTRIGINJEC_T9_TRGO ((uint32_t)( ADC_CR2_JEXTSEL_0)) | |||
#define ADC_EXTERNALTRIGINJEC_T2_TRGO ((uint32_t)( ADC_CR2_JEXTSEL_1 )) | |||
#define ADC_EXTERNALTRIGINJEC_T2_CC1 ((uint32_t)( ADC_CR2_JEXTSEL_1 | ADC_CR2_JEXTSEL_0)) | |||
#define ADC_EXTERNALTRIGINJEC_T3_CC4 ((uint32_t)( ADC_CR2_JEXTSEL_2 )) | |||
#define ADC_EXTERNALTRIGINJEC_T4_TRGO ((uint32_t)( ADC_CR2_JEXTSEL_2 | ADC_CR2_JEXTSEL_0)) | |||
#define ADC_EXTERNALTRIGINJEC_T4_CC1 ((uint32_t)( ADC_CR2_JEXTSEL_2 | ADC_CR2_JEXTSEL_1 )) | |||
#define ADC_EXTERNALTRIGINJEC_T4_CC2 ((uint32_t)( ADC_CR2_JEXTSEL_2 | ADC_CR2_JEXTSEL_1 | ADC_CR2_JEXTSEL_0)) | |||
#define ADC_EXTERNALTRIGINJEC_T4_CC3 ((uint32_t)(ADC_CR2_JEXTSEL_3 )) | |||
#define ADC_EXTERNALTRIGINJEC_T10_CC1 ((uint32_t)(ADC_CR2_JEXTSEL_3 | ADC_CR2_JEXTSEL_0)) | |||
#define ADC_EXTERNALTRIGINJEC_T7_TRGO ((uint32_t)(ADC_CR2_JEXTSEL_3 | ADC_CR2_JEXTSEL_1 )) | |||
#define ADC_EXTERNALTRIGINJEC_EXT_IT15 ((uint32_t)(ADC_CR2_JEXTSEL_3 | ADC_CR2_JEXTSEL_2 | ADC_CR2_JEXTSEL_1 | ADC_CR2_JEXTSEL_0)) | |||
/** | |||
* @} | |||
*/ | |||
/** | |||
* @} | |||
*/ | |||
/* Exported macro ------------------------------------------------------------*/ | |||
/** @defgroup ADCEx_Exported_Macros ADCEx Exported Macros | |||
* @{ | |||
*/ | |||
/* Macro for internal HAL driver usage, and possibly can be used into code of */ | |||
/* final user. */ | |||
/** | |||
* @brief Selection of channels bank. | |||
* Note: Banks availability depends on devices categories. | |||
* This macro is intended to change bank selection quickly on the fly, | |||
* without going through ADC init structure update and execution of function | |||
* 'HAL_ADC_Init()'. | |||
* @param __HANDLE__: ADC handle | |||
* @param __BANK__: Bank selection. This parameter can be a value of @ref ADC_ChannelsBank. | |||
* @retval None | |||
*/ | |||
#define __HAL_ADC_CHANNELS_BANK(__HANDLE__, __BANK__) \ | |||
MODIFY_REG((__HANDLE__)->Instance->CR2, ADC_CR2_CFG, (__BANK__)) | |||
#if defined(STM32L100xC) || defined (STM32L151xC) || defined (STM32L152xC) || defined (STM32L162xC) || defined(STM32L151xCA) || defined (STM32L151xD) || defined (STM32L152xCA) || defined (STM32L152xD) || defined (STM32L162xCA) || defined (STM32L162xD) || defined(STM32L151xE) || defined(STM32L151xDX) || defined (STM32L152xE) || defined (STM32L152xDX) || defined (STM32L162xE) || defined (STM32L162xDX) | |||
/** | |||
* @brief Configures the ADC channels speed. | |||
* Limited to channels 3, 8, 13 and to devices category Cat.3, Cat.4, Cat.5. | |||
* - For ADC_CHANNEL_3: Used as ADC direct channel (fast channel) if OPAMP1 is | |||
* in power down mode. | |||
* - For ADC_CHANNEL_8: Used as ADC direct channel (fast channel) if OPAMP2 is | |||
* in power down mode. | |||
* - For ADC_CHANNEL_13: Used as ADC re-routed channel if OPAMP3 is in | |||
* power down mode. Otherwise, channel 13 is connected to OPAMP3 output and | |||
* routed through switches COMP1_SW1 and VCOMP to ADC switch matrix. | |||
* (Note: OPAMP3 is available on STM32L1 Cat.4 only). | |||
* @param __CHANNEL__: ADC channel | |||
* This parameter can be one of the following values: | |||
* @arg ADC_CHANNEL_3: Channel 3 is selected. | |||
* @arg ADC_CHANNEL_8: Channel 8 is selected. | |||
* @arg ADC_CHANNEL_13: Channel 13 is selected. | |||
* @retval None | |||
*/ | |||
#define __HAL_ADC_CHANNEL_SPEED_FAST(__CHANNEL__) \ | |||
( ( ((__CHANNEL__) == ADC_CHANNEL_3) \ | |||
)? \ | |||
(SET_BIT(COMP->CSR, COMP_CSR_FCH3)) \ | |||
: \ | |||
( ( ((__CHANNEL__) == ADC_CHANNEL_8) \ | |||
)? \ | |||
(SET_BIT(COMP->CSR, COMP_CSR_FCH8)) \ | |||
: \ | |||
( ( ((__CHANNEL__) == ADC_CHANNEL_13) \ | |||
)? \ | |||
(SET_BIT(COMP->CSR, COMP_CSR_RCH13)) \ | |||
: \ | |||
(SET_BIT(COMP->CSR, 0x00000000)) \ | |||
) \ | |||
) \ | |||
) | |||
#define __HAL_ADC_CHANNEL_SPEED_SLOW(__CHANNEL__) \ | |||
( ( ((__CHANNEL__) == ADC_CHANNEL_3) \ | |||
)? \ | |||
(CLEAR_BIT(COMP->CSR, COMP_CSR_FCH3)) \ | |||
: \ | |||
( ( ((__CHANNEL__) == ADC_CHANNEL_8) \ | |||
)? \ | |||
(CLEAR_BIT(COMP->CSR, COMP_CSR_FCH8)) \ | |||
: \ | |||
( ( ((__CHANNEL__) == ADC_CHANNEL_13) \ | |||
)? \ | |||
(CLEAR_BIT(COMP->CSR, COMP_CSR_RCH13)) \ | |||
: \ | |||
(SET_BIT(COMP->CSR, 0x00000000)) \ | |||
) \ | |||
) \ | |||
) | |||
#endif /* STM32L100xC || STM32L151xC || STM32L152xC || STM32L162xC || STM32L151xCA || STM32L151xD || STM32L152xCA || STM32L152xD || STM32L162xCA || STM32L162xD || STM32L151xE || STM32L151xDX || STM32L152xE || STM32L152xDX || STM32L162xE || STM32L162xDX */ | |||
/** | |||
* @} | |||
*/ | |||
/* Private macro ------------------------------------------------------------*/ | |||
/** @defgroup ADCEx_Private_Macro ADCEx Private Macro | |||
* @{ | |||
*/ | |||
/* Macro reserved for internal HAL driver usage, not intended to be used in */ | |||
/* code of final user. */ | |||
/** | |||
* @brief Set ADC ranks available in register SQR1. | |||
* Register SQR1 bits availability depends on device category. | |||
* @param _NbrOfConversion_: Regular channel sequence length | |||
* @retval None | |||
*/ | |||
#if defined(STM32L100xC) || defined (STM32L151xC) || defined (STM32L152xC) || defined (STM32L162xC) || defined(STM32L151xCA) || defined (STM32L151xD) || defined (STM32L152xCA) || defined (STM32L152xD) || defined (STM32L162xCA) || defined (STM32L162xD) || defined(STM32L151xE) || defined(STM32L151xDX) || defined (STM32L152xE) || defined (STM32L152xDX) || defined (STM32L162xE) || defined (STM32L162xDX) | |||
#define __ADC_SQR1_SQXX (ADC_SQR1_SQ28 | ADC_SQR1_SQ27 | ADC_SQR1_SQ26 | ADC_SQR1_SQ25) | |||
#else | |||
#define __ADC_SQR1_SQXX (ADC_SQR1_SQ27 | ADC_SQR1_SQ26 | ADC_SQR1_SQ25) | |||
#endif /* STM32L100xC || STM32L151xC || STM32L152xC || STM32L162xC || STM32L151xCA || STM32L151xD || STM32L152xCA || STM32L152xD || STM32L162xCA || STM32L162xD || STM32L151xE || STM32L151xDX || STM32L152xE || STM32L152xDX || STM32L162xE || STM32L162xDX */ | |||
/** | |||
* @brief Set the ADC's sample time for channel numbers between 30 and 31. | |||
* Register SMPR0 availability depends on device category. If register is not | |||
* available on the current device, this macro does nothing. | |||
* @retval None | |||
* @param _SAMPLETIME_: Sample time parameter. | |||
* @param _CHANNELNB_: Channel number. | |||
* @retval None | |||
*/ | |||
#if defined(STM32L151xCA) || defined (STM32L151xD) || defined (STM32L152xCA) || defined (STM32L152xD) || defined (STM32L162xCA) || defined (STM32L162xD) || defined(STM32L151xE) || defined(STM32L151xDX) || defined (STM32L152xE) || defined (STM32L152xDX) || defined (STM32L162xE) || defined (STM32L162xDX) | |||
#define ADC_SMPR0(_SAMPLETIME_, _CHANNELNB_) \ | |||
((_SAMPLETIME_) << (3 * ((_CHANNELNB_) - 30))) | |||
#else | |||
#define ADC_SMPR0(_SAMPLETIME_, _CHANNELNB_) \ | |||
(0x00000000U) | |||
#endif /* STM32L151xCA || STM32L151xD || STM32L152xCA || STM32L152xD || STM32L162xCA || STM32L162xD || STM32L151xE || STM32L151xDX || STM32L152xE || STM32L152xDX || STM32L162xE || STM32L162xDX */ | |||
#if defined(STM32L151xCA) || defined (STM32L151xD) || defined (STM32L152xCA) || defined (STM32L152xD) || defined (STM32L162xCA) || defined (STM32L162xD) || defined(STM32L151xE) || defined(STM32L151xDX) || defined (STM32L152xE) || defined (STM32L152xDX) || defined (STM32L162xE) || defined (STM32L162xDX) | |||
/** | |||
* @brief Set the ADC's sample time for channel numbers between 20 and 29. | |||
* @param _SAMPLETIME_: Sample time parameter. | |||
* @param _CHANNELNB_: Channel number. | |||
* @retval None | |||
*/ | |||
#define ADC_SMPR1(_SAMPLETIME_, _CHANNELNB_) \ | |||
((_SAMPLETIME_) << (3 * ((_CHANNELNB_) - 20))) | |||
#else | |||
/** | |||
* @brief Set the ADC's sample time for channel numbers between 20 and 26. | |||
* @param _SAMPLETIME_: Sample time parameter. | |||
* @param _CHANNELNB_: Channel number. | |||
* @retval None | |||
*/ | |||
#define ADC_SMPR1(_SAMPLETIME_, _CHANNELNB_) \ | |||
((_SAMPLETIME_) << (3 * ((_CHANNELNB_) - 20))) | |||
#endif /* STM32L151xCA || STM32L151xD || STM32L152xCA || STM32L152xD || STM32L162xCA || STM32L162xD || STM32L151xE || STM32L151xDX || STM32L152xE || STM32L152xDX || STM32L162xE || STM32L162xDX */ | |||
/** | |||
* @brief Defines the highest channel available in register SMPR1. Channels | |||
* availability depends on device category: | |||
* Highest channel in register SMPR1 is channel 26 for devices Cat.1, Cat.2, Cat.3 | |||
* Highest channel in register SMPR1 is channel 29 for devices Cat.4, Cat.5 | |||
* @param None | |||
* @retval None | |||
*/ | |||
#if defined(STM32L151xCA) || defined (STM32L151xD) || defined (STM32L152xCA) || defined (STM32L152xD) || defined (STM32L162xCA) || defined (STM32L162xD) || defined(STM32L151xE) || defined(STM32L151xDX) || defined (STM32L152xE) || defined (STM32L152xDX) || defined (STM32L162xE) || defined (STM32L162xDX) | |||
#define ADC_SMPR1_CHANNEL_MAX ADC_CHANNEL_29 | |||
#else | |||
#define ADC_SMPR1_CHANNEL_MAX ADC_CHANNEL_26 | |||
#endif /* STM32L151xCA || STM32L151xD || STM32L152xCA || STM32L152xD || STM32L162xCA || STM32L162xD || STM32L151xE || STM32L151xDX || STM32L152xE || STM32L152xDX || STM32L162xE || STM32L162xDX */ | |||
/** | |||
* @brief Define mask of configuration bits of ADC and regular group in | |||
* register CR2 (bits of ADC enable, conversion start and injected group are | |||
* excluded of this mask). | |||
* @retval None | |||
*/ | |||
#if defined (STM32L100xC) || defined (STM32L151xC) || defined (STM32L152xC) || defined (STM32L162xC) || defined (STM32L151xCA) || defined (STM32L151xD) || defined (STM32L152xCA) || defined (STM32L152xD) || defined (STM32L162xCA) || defined (STM32L162xD) || defined (STM32L151xE) || defined (STM32L151xDX) || defined (STM32L152xE) || defined (STM32L152xDX) || defined (STM32L162xE) || defined (STM32L162xDX) | |||
#define ADC_CR2_MASK_ADCINIT() \ | |||
(ADC_CR2_EXTEN | ADC_CR2_EXTSEL | ADC_CR2_ALIGN | ADC_CR2_EOCS | ADC_CR2_DDS | ADC_CR2_DELS | ADC_CR2_CFG | ADC_CR2_CONT) | |||
#else | |||
#define ADC_CR2_MASK_ADCINIT() \ | |||
(ADC_CR2_EXTEN | ADC_CR2_EXTSEL | ADC_CR2_ALIGN | ADC_CR2_EOCS | ADC_CR2_DDS | ADC_CR2_DELS | ADC_CR2_CONT) | |||
#endif | |||
/** | |||
* @brief Get the maximum ADC conversion cycles on all channels. | |||
* Returns the selected sampling time + conversion time (12.5 ADC clock cycles) | |||
* Approximation of sampling time within 2 ranges, returns the highest value: | |||
* below 24 cycles {4 cycles; 9 cycles; 16 cycles; 24 cycles} | |||
* between 48 cycles and 384 cycles {48 cycles; 96 cycles; 192 cycles; 384 cycles} | |||
* Unit: ADC clock cycles | |||
* @param __HANDLE__: ADC handle | |||
* @retval ADC conversion cycles on all channels | |||
*/ | |||
#if defined(STM32L151xCA) || defined (STM32L151xD) || defined (STM32L152xCA) || defined (STM32L152xD) || defined (STM32L162xCA) || defined (STM32L162xD) || defined(STM32L151xE) || defined(STM32L151xDX) || defined (STM32L152xE) || defined (STM32L152xDX) || defined (STM32L162xE) || defined (STM32L162xDX) | |||
#define ADC_CONVCYCLES_MAX_RANGE(__HANDLE__) \ | |||
(( (((__HANDLE__)->Instance->SMPR3 & ADC_SAMPLETIME_ALLCHANNELS_SMPR3BIT2) == RESET) && \ | |||
(((__HANDLE__)->Instance->SMPR2 & ADC_SAMPLETIME_ALLCHANNELS_SMPR2BIT2) == RESET) && \ | |||
(((__HANDLE__)->Instance->SMPR1 & ADC_SAMPLETIME_ALLCHANNELS_SMPR1BIT2) == RESET) && \ | |||
(((__HANDLE__)->Instance->SMPR0 & ADC_SAMPLETIME_ALLCHANNELS_SMPR0BIT2) == RESET) ) ? \ | |||
\ | |||
ADC_CONVERSIONCLOCKCYCLES_SAMPLETIME_24CYCLES : ADC_CONVERSIONCLOCKCYCLES_SAMPLETIME_384CYCLES \ | |||
) | |||
#else | |||
#define ADC_CONVCYCLES_MAX_RANGE(__HANDLE__) \ | |||
(( (((__HANDLE__)->Instance->SMPR3 & ADC_SAMPLETIME_ALLCHANNELS_SMPR3BIT2) == RESET) && \ | |||
(((__HANDLE__)->Instance->SMPR2 & ADC_SAMPLETIME_ALLCHANNELS_SMPR2BIT2) == RESET) && \ | |||
(((__HANDLE__)->Instance->SMPR1 & ADC_SAMPLETIME_ALLCHANNELS_SMPR1BIT2) == RESET) ) ? \ | |||
\ | |||
ADC_CONVERSIONCLOCKCYCLES_SAMPLETIME_24CYCLES : ADC_CONVERSIONCLOCKCYCLES_SAMPLETIME_384CYCLES \ | |||
) | |||
#endif /* STM32L151xCA || STM32L151xD || STM32L152xCA || STM32L152xD || STM32L162xCA || STM32L162xD || STM32L151xE || STM32L151xDX || STM32L152xE || STM32L152xDX || STM32L162xE || STM32L162xDX */ | |||
/** | |||
* @brief Get the ADC clock prescaler from ADC common control register | |||
* and convert it to its decimal number setting (refer to reference manual) | |||
* @retval None | |||
*/ | |||
#define ADC_GET_CLOCK_PRESCALER_DECIMAL(__HANDLE__) \ | |||
((0x01) << ((ADC->CCR & ADC_CCR_ADCPRE) >> POSITION_VAL(ADC_CCR_ADCPRE))) | |||
/** | |||
* @brief Clear register SMPR0. | |||
* Register SMPR0 availability depends on device category. If register is not | |||
* available on the current device, this macro performs no action. | |||
* @param __HANDLE__: ADC handle | |||
* @retval None | |||
*/ | |||
#if defined(STM32L151xCA) || defined (STM32L151xD) || defined (STM32L152xCA) || defined (STM32L152xD) || defined (STM32L162xCA) || defined (STM32L162xD) || defined(STM32L151xE) || defined(STM32L151xDX) || defined (STM32L152xE) || defined (STM32L152xDX) || defined (STM32L162xE) || defined (STM32L162xDX) | |||
#define ADC_SMPR1_CLEAR(__HANDLE__) \ | |||
CLEAR_BIT((__HANDLE__)->Instance->SMPR1, (ADC_SMPR1_SMP29 | ADC_SMPR1_SMP28 | ADC_SMPR1_SMP27 | \ | |||
ADC_SMPR1_SMP26 | ADC_SMPR1_SMP25 | ADC_SMPR1_SMP24 | \ | |||
ADC_SMPR1_SMP23 | ADC_SMPR1_SMP22 | ADC_SMPR1_SMP21 | \ | |||
ADC_SMPR1_SMP20 )) | |||
#define ADC_SMPR0_CLEAR(__HANDLE__) \ | |||
(CLEAR_BIT((__HANDLE__)->Instance->SMPR0, (ADC_SMPR0_SMP31 | ADC_SMPR0_SMP30))) | |||
#else | |||
#define ADC_SMPR1_CLEAR(__HANDLE__) \ | |||
CLEAR_BIT((__HANDLE__)->Instance->SMPR1, (ADC_SMPR1_SMP26 | ADC_SMPR1_SMP25 | ADC_SMPR1_SMP24 | \ | |||
ADC_SMPR1_SMP23 | ADC_SMPR1_SMP22 | ADC_SMPR1_SMP21 | \ | |||
ADC_SMPR1_SMP20 )) | |||
#define ADC_SMPR0_CLEAR(__HANDLE__) __NOP() | |||
#endif /* STM32L151xCA || STM32L151xD || STM32L152xCA || STM32L152xD || STM32L162xCA || STM32L162xD || STM32L151xE || STM32L151xDX || STM32L152xE || STM32L152xDX || STM32L162xE || STM32L162xDX */ | |||
/** | |||
* @brief Clear register CR2. | |||
* @param __HANDLE__: ADC handle | |||
* @retval None | |||
*/ | |||
#if defined(STM32L151xCA) || defined (STM32L151xD) || defined (STM32L152xCA) || defined (STM32L152xD) || defined (STM32L162xCA) || defined (STM32L162xD) || defined(STM32L151xE) || defined(STM32L151xDX) || defined (STM32L152xE) || defined (STM32L152xDX) || defined (STM32L162xE) || defined (STM32L162xDX) | |||
#define ADC_CR2_CLEAR(__HANDLE__) \ | |||
(CLEAR_BIT((__HANDLE__)->Instance->CR2, (ADC_CR2_SWSTART | ADC_CR2_EXTEN | ADC_CR2_EXTSEL | \ | |||
ADC_CR2_JSWSTART | ADC_CR2_JEXTEN | ADC_CR2_JEXTSEL | \ | |||
ADC_CR2_ALIGN | ADC_CR2_EOCS | ADC_CR2_DDS | \ | |||
ADC_CR2_DMA | ADC_CR2_DELS | ADC_CR2_CFG | \ | |||
ADC_CR2_CONT | ADC_CR2_ADON )) \ | |||
) | |||
#else | |||
#define ADC_CR2_CLEAR(__HANDLE__) \ | |||
(CLEAR_BIT((__HANDLE__)->Instance->CR2, (ADC_CR2_SWSTART | ADC_CR2_EXTEN | ADC_CR2_EXTSEL | \ | |||
ADC_CR2_JSWSTART | ADC_CR2_JEXTEN | ADC_CR2_JEXTSEL | \ | |||
ADC_CR2_ALIGN | ADC_CR2_EOCS | ADC_CR2_DDS | \ | |||
ADC_CR2_DMA | ADC_CR2_DELS | \ | |||
ADC_CR2_CONT | ADC_CR2_ADON )) \ | |||
) | |||
#endif /* STM32L151xCA || STM32L151xD || STM32L152xCA || STM32L152xD || STM32L162xCA || STM32L162xD || STM32L151xE || STM32L151xDX || STM32L152xE || STM32L152xDX || STM32L162xE || STM32L162xDX */ | |||
/** | |||
* @brief Set the sampling time of selected channel on register SMPR0 | |||
* Register SMPR0 availability depends on device category. If register is not | |||
* available on the current device, this macro performs no action. | |||
* @param __HANDLE__: ADC handle | |||
* @param _SAMPLETIME_: Sample time parameter. | |||
* @param __CHANNEL__: Channel number. | |||
* @retval None | |||
*/ | |||
#if defined(STM32L151xCA) || defined (STM32L151xD) || defined (STM32L152xCA) || defined (STM32L152xD) || defined (STM32L162xCA) || defined (STM32L162xD) || defined(STM32L151xE) || defined(STM32L151xDX) || defined (STM32L152xE) || defined (STM32L152xDX) || defined (STM32L162xE) || defined (STM32L162xDX) | |||
#define ADC_SMPR0_CHANNEL_SET(__HANDLE__, _SAMPLETIME_, __CHANNEL__) \ | |||
MODIFY_REG((__HANDLE__)->Instance->SMPR0, \ | |||
ADC_SMPR0(ADC_SMPR0_SMP30, (__CHANNEL__)), \ | |||
ADC_SMPR0((_SAMPLETIME_), (__CHANNEL__)) ) | |||
#else | |||
#define ADC_SMPR0_CHANNEL_SET(__HANDLE__, _SAMPLETIME_, __CHANNEL__) __NOP() | |||
#endif /* STM32L151xCA || STM32L151xD || STM32L152xCA || STM32L152xD || STM32L162xCA || STM32L162xD || STM32L151xE || STM32L151xDX || STM32L152xE || STM32L152xDX || STM32L162xE || STM32L162xDX */ | |||
#define IS_ADC_INJECTED_RANK(CHANNEL) (((CHANNEL) == ADC_INJECTED_RANK_1) || \ | |||
((CHANNEL) == ADC_INJECTED_RANK_2) || \ | |||
((CHANNEL) == ADC_INJECTED_RANK_3) || \ | |||
((CHANNEL) == ADC_INJECTED_RANK_4) ) | |||
#define IS_ADC_EXTTRIGINJEC_EDGE(EDGE) (((EDGE) == ADC_EXTERNALTRIGINJECCONV_EDGE_NONE) || \ | |||
((EDGE) == ADC_EXTERNALTRIGINJECCONV_EDGE_RISING) || \ | |||
((EDGE) == ADC_EXTERNALTRIGINJECCONV_EDGE_FALLING) || \ | |||
((EDGE) == ADC_EXTERNALTRIGINJECCONV_EDGE_RISINGFALLING) ) | |||
#define IS_ADC_EXTTRIGINJEC(REGTRIG) (((REGTRIG) == ADC_EXTERNALTRIGINJECCONV_T2_CC1) || \ | |||
((REGTRIG) == ADC_EXTERNALTRIGINJECCONV_T2_TRGO) || \ | |||
((REGTRIG) == ADC_EXTERNALTRIGINJECCONV_T3_CC4) || \ | |||
((REGTRIG) == ADC_EXTERNALTRIGINJECCONV_T4_TRGO) || \ | |||
((REGTRIG) == ADC_EXTERNALTRIGINJECCONV_T4_CC1) || \ | |||
((REGTRIG) == ADC_EXTERNALTRIGINJECCONV_T4_CC2) || \ | |||
((REGTRIG) == ADC_EXTERNALTRIGINJECCONV_T4_CC3) || \ | |||
((REGTRIG) == ADC_EXTERNALTRIGINJECCONV_T7_TRGO) || \ | |||
((REGTRIG) == ADC_EXTERNALTRIGINJECCONV_T9_CC1) || \ | |||
((REGTRIG) == ADC_EXTERNALTRIGINJECCONV_T9_TRGO) || \ | |||
((REGTRIG) == ADC_EXTERNALTRIGINJECCONV_T10_CC1) || \ | |||
((REGTRIG) == ADC_EXTERNALTRIGINJECCONV_EXT_IT15) || \ | |||
((REGTRIG) == ADC_SOFTWARE_START) ) | |||
/** @defgroup ADCEx_injected_nb_conv_verification ADCEx injected nb conv verification | |||
* @{ | |||
*/ | |||
#define IS_ADC_INJECTED_NB_CONV(LENGTH) (((LENGTH) >= (1U)) && ((LENGTH) <= (4U))) | |||
/** | |||
* @} | |||
*/ | |||
/** | |||
* @} | |||
*/ | |||
/* Exported functions --------------------------------------------------------*/ | |||
/** @addtogroup ADCEx_Exported_Functions | |||
* @{ | |||
*/ | |||
/* IO operation functions *****************************************************/ | |||
/** @addtogroup ADCEx_Exported_Functions_Group1 | |||
* @{ | |||
*/ | |||
/* Blocking mode: Polling */ | |||
HAL_StatusTypeDef HAL_ADCEx_InjectedStart(ADC_HandleTypeDef* hadc); | |||
HAL_StatusTypeDef HAL_ADCEx_InjectedStop(ADC_HandleTypeDef* hadc); | |||
HAL_StatusTypeDef HAL_ADCEx_InjectedPollForConversion(ADC_HandleTypeDef* hadc, uint32_t Timeout); | |||
/* Non-blocking mode: Interruption */ | |||
HAL_StatusTypeDef HAL_ADCEx_InjectedStart_IT(ADC_HandleTypeDef* hadc); | |||
HAL_StatusTypeDef HAL_ADCEx_InjectedStop_IT(ADC_HandleTypeDef* hadc); | |||
/* ADC retrieve conversion value intended to be used with polling or interruption */ | |||
uint32_t HAL_ADCEx_InjectedGetValue(ADC_HandleTypeDef* hadc, uint32_t InjectedRank); | |||
/* ADC IRQHandler and Callbacks used in non-blocking modes (Interruption) */ | |||
void HAL_ADCEx_InjectedConvCpltCallback(ADC_HandleTypeDef* hadc); | |||
/** | |||
* @} | |||
*/ | |||
/* Peripheral Control functions ***********************************************/ | |||
/** @addtogroup ADCEx_Exported_Functions_Group2 | |||
* @{ | |||
*/ | |||
HAL_StatusTypeDef HAL_ADCEx_InjectedConfigChannel(ADC_HandleTypeDef* hadc,ADC_InjectionConfTypeDef* sConfigInjected); | |||
/** | |||
* @} | |||
*/ | |||
/** | |||
* @} | |||
*/ | |||
/** | |||
* @} | |||
*/ | |||
/** | |||
* @} | |||
*/ | |||
#ifdef __cplusplus | |||
} | |||
#endif | |||
#endif /* __STM32L1xx_HAL_ADC_EX_H */ | |||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ |
@@ -49,7 +49,7 @@ | |||
*/ | |||
#define HAL_MODULE_ENABLED | |||
/*#define HAL_ADC_MODULE_ENABLED */ | |||
#define HAL_ADC_MODULE_ENABLED | |||
/*#define HAL_CRYP_MODULE_ENABLED */ | |||
/*#define HAL_COMP_MODULE_ENABLED */ | |||
/*#define HAL_CRC_MODULE_ENABLED */ | |||
@@ -69,7 +69,7 @@ | |||
#define HAL_SPI_MODULE_ENABLED | |||
/*#define HAL_SRAM_MODULE_ENABLED */ | |||
#define HAL_TIM_MODULE_ENABLED | |||
/*#define HAL_UART_MODULE_ENABLED */ | |||
#define HAL_UART_MODULE_ENABLED | |||
/*#define HAL_USART_MODULE_ENABLED */ | |||
/*#define HAL_WWDG_MODULE_ENABLED */ | |||
/*#define HAL_EXTI_MODULE_ENABLED */ | |||
@@ -0,0 +1,908 @@ | |||
/** | |||
****************************************************************************** | |||
* @file stm32l1xx_hal_dma.c | |||
* @author MCD Application Team | |||
* @brief DMA HAL module driver. | |||
* This file provides firmware functions to manage the following | |||
* functionalities of the Direct Memory Access (DMA) peripheral: | |||
* + Initialization and de-initialization functions | |||
* + IO operation functions | |||
* + Peripheral State and errors 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). Please refer to the Reference manual for connection between peripherals | |||
and DMA requests. | |||
(#) For a given Channel, program the required configuration through the following parameters: | |||
Channel request, Transfer Direction, Source and Destination data formats, | |||
Circular or Normal mode, Channel Priority level, Source and Destination Increment mode | |||
using HAL_DMA_Init() function. | |||
(#) 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. | |||
*** 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 to register callbacks with HAL_DMA_RegisterCallback(). | |||
*** DMA HAL driver macros list *** | |||
============================================= | |||
[..] | |||
Below the list of macros in DMA HAL driver. | |||
(+) __HAL_DMA_ENABLE: Enable the specified DMA Channel. | |||
(+) __HAL_DMA_DISABLE: Disable the specified DMA Channel. | |||
(+) __HAL_DMA_GET_FLAG: Get the DMA Channel pending flags. | |||
(+) __HAL_DMA_CLEAR_FLAG: Clear the DMA Channel pending flags. | |||
(+) __HAL_DMA_ENABLE_IT: Enable the specified DMA Channel interrupts. | |||
(+) __HAL_DMA_DISABLE_IT: Disable the specified DMA Channel interrupts. | |||
(+) __HAL_DMA_GET_IT_SOURCE: Check whether the specified DMA Channel interrupt is enabled or not. | |||
[..] | |||
(@) You can refer to the DMA HAL driver header file for more useful macros | |||
@endverbatim | |||
****************************************************************************** | |||
* @attention | |||
* | |||
* <h2><center>© Copyright (c) 2017 STMicroelectronics. | |||
* All rights reserved.</center></h2> | |||
* | |||
* This software component is licensed by ST under BSD 3-Clause license, | |||
* the "License"; You may not use this file except in compliance with the | |||
* License. You may obtain a copy of the License at: | |||
* opensource.org/licenses/BSD-3-Clause | |||
* | |||
****************************************************************************** | |||
*/ | |||
/* Includes ------------------------------------------------------------------*/ | |||
#include "stm32l1xx_hal.h" | |||
/** @addtogroup STM32L1xx_HAL_Driver | |||
* @{ | |||
*/ | |||
/** @defgroup DMA DMA | |||
* @brief DMA HAL module driver | |||
* @{ | |||
*/ | |||
#ifdef HAL_DMA_MODULE_ENABLED | |||
/* Private typedef -----------------------------------------------------------*/ | |||
/* Private define ------------------------------------------------------------*/ | |||
/* Private macro -------------------------------------------------------------*/ | |||
/* Private variables ---------------------------------------------------------*/ | |||
/* Private function prototypes -----------------------------------------------*/ | |||
/** @defgroup DMA_Private_Functions DMA Private Functions | |||
* @{ | |||
*/ | |||
static void DMA_SetConfig(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t DataLength); | |||
/** | |||
* @} | |||
*/ | |||
/* Exported functions ---------------------------------------------------------*/ | |||
/** @defgroup DMA_Exported_Functions DMA Exported Functions | |||
* @{ | |||
*/ | |||
/** @defgroup DMA_Exported_Functions_Group1 Initialization and de-initialization functions | |||
* @brief Initialization and de-initialization functions | |||
* | |||
@verbatim | |||
=============================================================================== | |||
##### Initialization and de-initialization functions ##### | |||
=============================================================================== | |||
[..] | |||
This section provides functions allowing to initialize the DMA Channel source | |||
and destination addresses, incrementation and data sizes, transfer direction, | |||
circular/normal mode selection, memory-to-memory mode selection and Channel priority value. | |||
[..] | |||
The HAL_DMA_Init() function follows the DMA configuration procedures as described in | |||
reference manual. | |||
@endverbatim | |||
* @{ | |||
*/ | |||
/** | |||
* @brief Initialize the DMA according to the specified | |||
* parameters in the DMA_InitTypeDef and initialize 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; | |||
/* Check the DMA handle allocation */ | |||
if(hdma == NULL) | |||
{ | |||
return HAL_ERROR; | |||
} | |||
/* Check the parameters */ | |||
assert_param(IS_DMA_ALL_INSTANCE(hdma->Instance)); | |||
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)); | |||
#if defined (DMA2) | |||
/* Compute the channel index */ | |||
if ((uint32_t)(hdma->Instance) < (uint32_t)(DMA2_Channel1)) | |||
{ | |||
/* DMA1 */ | |||
hdma->ChannelIndex = (((uint32_t)hdma->Instance - (uint32_t)DMA1_Channel1) / ((uint32_t)DMA1_Channel2 - (uint32_t)DMA1_Channel1)) << 2U; | |||
hdma->DmaBaseAddress = DMA1; | |||
} | |||
else | |||
{ | |||
/* DMA2 */ | |||
hdma->ChannelIndex = (((uint32_t)hdma->Instance - (uint32_t)DMA2_Channel1) / ((uint32_t)DMA2_Channel2 - (uint32_t)DMA2_Channel1)) << 2U; | |||
hdma->DmaBaseAddress = DMA2; | |||
} | |||
#else | |||
/* calculation of the channel index */ | |||
/* DMA1 */ | |||
hdma->ChannelIndex = (((uint32_t)hdma->Instance - (uint32_t)DMA1_Channel1) / ((uint32_t)DMA1_Channel2 - (uint32_t)DMA1_Channel1)) << 2U; | |||
hdma->DmaBaseAddress = DMA1; | |||
#endif | |||
/* 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 and MEM2MEM 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 | DMA_CCR_MEM2MEM)); | |||
/* 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; | |||
/* Initialise the error code */ | |||
hdma->ErrorCode = HAL_DMA_ERROR_NONE; | |||
/* Initialize the DMA state*/ | |||
hdma->State = HAL_DMA_STATE_READY; | |||
/* Allocate lock resource and initialize it */ | |||
hdma->Lock = HAL_UNLOCKED; | |||
return HAL_OK; | |||
} | |||
/** | |||
* @brief DeInitialize 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 handle allocation */ | |||
if (NULL == hdma ) | |||
{ | |||
return HAL_ERROR; | |||
} | |||
/* Check the parameters */ | |||
assert_param(IS_DMA_ALL_INSTANCE(hdma->Instance)); | |||
/* Disable the selected DMA Channelx */ | |||
__HAL_DMA_DISABLE(hdma); | |||
#if defined (DMA2) | |||
/* Compute the channel index */ | |||
if ((uint32_t)(hdma->Instance) < (uint32_t)(DMA2_Channel1)) | |||
{ | |||
/* DMA1 */ | |||
hdma->ChannelIndex = (((uint32_t)hdma->Instance - (uint32_t)DMA1_Channel1) / ((uint32_t)DMA1_Channel2 - (uint32_t)DMA1_Channel1)) << 2U; | |||
hdma->DmaBaseAddress = DMA1; | |||
} | |||
else | |||
{ | |||
/* DMA2 */ | |||
hdma->ChannelIndex = (((uint32_t)hdma->Instance - (uint32_t)DMA2_Channel1) / ((uint32_t)DMA2_Channel2 - (uint32_t)DMA2_Channel1)) << 2U; | |||
hdma->DmaBaseAddress = DMA2; | |||
} | |||
#else | |||
/* calculation of the channel index */ | |||
/* DMA1 */ | |||
hdma->ChannelIndex = (((uint32_t)hdma->Instance - (uint32_t)DMA1_Channel1) / ((uint32_t)DMA1_Channel2 - (uint32_t)DMA1_Channel1)) << 2U; | |||
hdma->DmaBaseAddress = DMA1; | |||
#endif | |||
/* Reset DMA Channel CR register */ | |||
hdma->Instance->CCR = 0U; | |||
/* Clear all flags */ | |||
hdma->DmaBaseAddress->IFCR = (DMA_ISR_GIF1 << (hdma->ChannelIndex & 0x1CU)); | |||
/* Clean callbacks */ | |||
hdma->XferCpltCallback = NULL; | |||
hdma->XferHalfCpltCallback = NULL; | |||
hdma->XferErrorCallback = NULL; | |||
hdma->XferAbortCallback = NULL; | |||
/* 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_Exported_Functions_Group2 Input and Output operation functions | |||
* @brief Input and Output 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 Start 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) | |||
{ | |||
HAL_StatusTypeDef status = HAL_OK; | |||
/* Check the parameters */ | |||
assert_param(IS_DMA_BUFFER_SIZE(DataLength)); | |||
/* Process locked */ | |||
__HAL_LOCK(hdma); | |||
if(HAL_DMA_STATE_READY == hdma->State) | |||
{ | |||
/* Change DMA peripheral state */ | |||
hdma->State = HAL_DMA_STATE_BUSY; | |||
hdma->ErrorCode = HAL_DMA_ERROR_NONE; | |||
/* Disable the peripheral */ | |||
__HAL_DMA_DISABLE(hdma); | |||
/* Configure the source, destination address and the data length & clear flags*/ | |||
DMA_SetConfig(hdma, SrcAddress, DstAddress, DataLength); | |||
/* Enable the Peripheral */ | |||
__HAL_DMA_ENABLE(hdma); | |||
} | |||
else | |||
{ | |||
/* Process Unlocked */ | |||
__HAL_UNLOCK(hdma); | |||
status = HAL_BUSY; | |||
} | |||
return status; | |||
} | |||
/** | |||
* @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) | |||
{ | |||
HAL_StatusTypeDef status = HAL_OK; | |||
/* Check the parameters */ | |||
assert_param(IS_DMA_BUFFER_SIZE(DataLength)); | |||
/* Process locked */ | |||
__HAL_LOCK(hdma); | |||
if(HAL_DMA_STATE_READY == hdma->State) | |||
{ | |||
/* Change DMA peripheral state */ | |||
hdma->State = HAL_DMA_STATE_BUSY; | |||
hdma->ErrorCode = HAL_DMA_ERROR_NONE; | |||
/* Disable the peripheral */ | |||
__HAL_DMA_DISABLE(hdma); | |||
/* Configure the source, destination address and the data length & clear flags*/ | |||
DMA_SetConfig(hdma, SrcAddress, DstAddress, DataLength); | |||
/* Enable the transfer complete interrupt */ | |||
/* Enable the transfer Error interrupt */ | |||
if(NULL != hdma->XferHalfCpltCallback ) | |||
{ | |||
/* Enable the Half transfer complete interrupt as well */ | |||
__HAL_DMA_ENABLE_IT(hdma, (DMA_IT_TC | DMA_IT_HT | DMA_IT_TE)); | |||
} | |||
else | |||
{ | |||
__HAL_DMA_DISABLE_IT(hdma, DMA_IT_HT); | |||
__HAL_DMA_ENABLE_IT(hdma, (DMA_IT_TC | DMA_IT_TE)); | |||
} | |||
/* Enable the Peripheral */ | |||
__HAL_DMA_ENABLE(hdma); | |||
} | |||
else | |||
{ | |||
/* Process Unlocked */ | |||
__HAL_UNLOCK(hdma); | |||
/* Remain BUSY */ | |||
status = HAL_BUSY; | |||
} | |||
return status; | |||
} | |||
/** | |||
* @brief Abort the DMA Transfer. | |||
* @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_Abort(DMA_HandleTypeDef *hdma) | |||
{ | |||
HAL_StatusTypeDef status = HAL_OK; | |||
/* Check the DMA peripheral state */ | |||
if(hdma->State != HAL_DMA_STATE_BUSY) | |||
{ | |||
hdma->ErrorCode = HAL_DMA_ERROR_NO_XFER; | |||
/* Process Unlocked */ | |||
__HAL_UNLOCK(hdma); | |||
return HAL_ERROR; | |||
} | |||
else | |||
{ | |||
/* Disable DMA IT */ | |||
__HAL_DMA_DISABLE_IT(hdma, (DMA_IT_TC | DMA_IT_HT | DMA_IT_TE)); | |||
/* Disable the channel */ | |||
__HAL_DMA_DISABLE(hdma); | |||
/* Clear all flags */ | |||
hdma->DmaBaseAddress->IFCR = (DMA_ISR_GIF1 << (hdma->ChannelIndex & 0x1CU)); | |||
/* Change the DMA state */ | |||
hdma->State = HAL_DMA_STATE_READY; | |||
/* Process Unlocked */ | |||
__HAL_UNLOCK(hdma); | |||
return status; | |||
} | |||
} | |||
/** | |||
* @brief Aborts the DMA Transfer in Interrupt mode. | |||
* @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_Abort_IT(DMA_HandleTypeDef *hdma) | |||
{ | |||
HAL_StatusTypeDef status = HAL_OK; | |||
if(HAL_DMA_STATE_BUSY != hdma->State) | |||
{ | |||
/* no transfer ongoing */ | |||
hdma->ErrorCode = HAL_DMA_ERROR_NO_XFER; | |||
status = HAL_ERROR; | |||
} | |||
else | |||
{ | |||
/* Disable DMA IT */ | |||
__HAL_DMA_DISABLE_IT(hdma, (DMA_IT_TC | DMA_IT_HT | DMA_IT_TE)); | |||
/* Disable the channel */ | |||
__HAL_DMA_DISABLE(hdma); | |||
/* Clear all flags */ | |||
hdma->DmaBaseAddress->IFCR = (DMA_ISR_GIF1 << (hdma->ChannelIndex & 0x1CU)); | |||
/* Change the DMA state */ | |||
hdma->State = HAL_DMA_STATE_READY; | |||
/* Process Unlocked */ | |||
__HAL_UNLOCK(hdma); | |||
/* Call User Abort callback */ | |||
if(hdma->XferAbortCallback != NULL) | |||
{ | |||
hdma->XferAbortCallback(hdma); | |||
} | |||
} | |||
return status; | |||
} | |||
/** | |||
* @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, HAL_DMA_LevelCompleteTypeDef CompleteLevel, uint32_t Timeout) | |||
{ | |||
uint32_t temp; | |||
uint32_t tickstart; | |||
if(HAL_DMA_STATE_BUSY != hdma->State) | |||
{ | |||
/* no transfer ongoing */ | |||
hdma->ErrorCode = HAL_DMA_ERROR_NO_XFER; | |||
__HAL_UNLOCK(hdma); | |||
return HAL_ERROR; | |||
} | |||
/* Polling mode not supported in circular mode */ | |||
if ((hdma->Instance->CCR & DMA_CCR_CIRC) != 0U) | |||
{ | |||
hdma->ErrorCode = HAL_DMA_ERROR_NOT_SUPPORTED; | |||
return HAL_ERROR; | |||
} | |||
/* Get the level transfer complete flag */ | |||
if (HAL_DMA_FULL_TRANSFER == CompleteLevel) | |||
{ | |||
/* Transfer Complete flag */ | |||
temp = DMA_FLAG_TC1 << (hdma->ChannelIndex & 0x1CU); | |||
} | |||
else | |||
{ | |||
/* Half Transfer Complete flag */ | |||
temp = DMA_FLAG_HT1 << (hdma->ChannelIndex & 0x1CU); | |||
} | |||
/* Get tick */ | |||
tickstart = HAL_GetTick(); | |||
while((hdma->DmaBaseAddress->ISR & temp) == 0U) | |||
{ | |||
if((hdma->DmaBaseAddress->ISR & (DMA_FLAG_TE1 << (hdma->ChannelIndex& 0x1CU))) != 0U) | |||
{ | |||
/* When a DMA transfer error occurs */ | |||
/* A hardware clear of its EN bits is performed */ | |||
/* Clear all flags */ | |||
hdma->DmaBaseAddress->IFCR = (DMA_ISR_GIF1 << (hdma->ChannelIndex & 0x1CU)); | |||
/* Update error code */ | |||
hdma->ErrorCode = HAL_DMA_ERROR_TE; | |||
/* Change the DMA state */ | |||
hdma->State= HAL_DMA_STATE_READY; | |||
/* Process Unlocked */ | |||
__HAL_UNLOCK(hdma); | |||
return HAL_ERROR; | |||
} | |||
/* Check for the Timeout */ | |||
if(Timeout != HAL_MAX_DELAY) | |||
{ | |||
if(((HAL_GetTick() - tickstart) > Timeout) || (Timeout == 0U)) | |||
{ | |||
/* Update error code */ | |||
hdma->ErrorCode = HAL_DMA_ERROR_TIMEOUT; | |||
/* Change the DMA state */ | |||
hdma->State = HAL_DMA_STATE_READY; | |||
/* Process Unlocked */ | |||
__HAL_UNLOCK(hdma); | |||
return HAL_ERROR; | |||
} | |||
} | |||
} | |||
if(HAL_DMA_FULL_TRANSFER == CompleteLevel) | |||
{ | |||
/* Clear the transfer complete flag */ | |||
hdma->DmaBaseAddress->IFCR = (DMA_FLAG_TC1 << (hdma->ChannelIndex& 0x1CU)); | |||
/* The selected Channelx EN bit is cleared (DMA is disabled and | |||
all transfers are complete) */ | |||
hdma->State = HAL_DMA_STATE_READY; | |||
} | |||
else | |||
{ | |||
/* Clear the half transfer complete flag */ | |||
hdma->DmaBaseAddress->IFCR = (DMA_FLAG_HT1 << (hdma->ChannelIndex & 0x1CU)); | |||
} | |||
/* Process unlocked */ | |||
__HAL_UNLOCK(hdma); | |||
return HAL_OK; | |||
} | |||
/** | |||
* @brief Handle 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) | |||
{ | |||
uint32_t flag_it = hdma->DmaBaseAddress->ISR; | |||
uint32_t source_it = hdma->Instance->CCR; | |||
/* Half Transfer Complete Interrupt management ******************************/ | |||
if (((flag_it & (DMA_FLAG_HT1 << (hdma->ChannelIndex & 0x1CU))) != 0U) && ((source_it & DMA_IT_HT) != 0U)) | |||
{ | |||
/* Disable the half transfer interrupt if the DMA mode is not CIRCULAR */ | |||
if((hdma->Instance->CCR & DMA_CCR_CIRC) == 0U) | |||
{ | |||
/* Disable the half transfer interrupt */ | |||
__HAL_DMA_DISABLE_IT(hdma, DMA_IT_HT); | |||
} | |||
/* Clear the half transfer complete flag */ | |||
hdma->DmaBaseAddress->IFCR = DMA_ISR_HTIF1 << (hdma->ChannelIndex & 0x1CU); | |||
/* DMA peripheral state is not updated in Half Transfer */ | |||
/* but in Transfer Complete case */ | |||
if(hdma->XferHalfCpltCallback != NULL) | |||
{ | |||
/* Half transfer callback */ | |||
hdma->XferHalfCpltCallback(hdma); | |||
} | |||
} | |||
/* Transfer Complete Interrupt management ***********************************/ | |||
else if (((flag_it & (DMA_FLAG_TC1 << (hdma->ChannelIndex & 0x1CU))) != 0U) && ((source_it & DMA_IT_TC) != 0U)) | |||
{ | |||
if((hdma->Instance->CCR & DMA_CCR_CIRC) == 0U) | |||
{ | |||
/* Disable the transfer complete interrupt if the DMA mode is not CIRCULAR */ | |||
/* Disable the transfer complete and error interrupt */ | |||
/* if the DMA mode is not CIRCULAR */ | |||
__HAL_DMA_DISABLE_IT(hdma, DMA_IT_TE | DMA_IT_TC); | |||
/* Change the DMA state */ | |||
hdma->State = HAL_DMA_STATE_READY; | |||
} | |||
/* Clear the transfer complete flag */ | |||
hdma->DmaBaseAddress->IFCR = (DMA_ISR_TCIF1 << (hdma->ChannelIndex & 0x1CU)); | |||
/* Process Unlocked */ | |||
__HAL_UNLOCK(hdma); | |||
if(hdma->XferCpltCallback != NULL) | |||
{ | |||
/* Transfer complete callback */ | |||
hdma->XferCpltCallback(hdma); | |||
} | |||
} | |||
/* Transfer Error Interrupt management **************************************/ | |||
else if (((flag_it & (DMA_FLAG_TE1 << (hdma->ChannelIndex & 0x1CU))) != 0U) && ((source_it & DMA_IT_TE) != 0U)) | |||
{ | |||
/* When a DMA transfer error occurs */ | |||
/* A hardware clear of its EN bits is performed */ | |||
/* Disable ALL DMA IT */ | |||
__HAL_DMA_DISABLE_IT(hdma, (DMA_IT_TC | DMA_IT_HT | DMA_IT_TE)); | |||
/* Clear all flags */ | |||
hdma->DmaBaseAddress->IFCR = (DMA_ISR_GIF1 << (hdma->ChannelIndex & 0x1CU)); | |||
/* Update error code */ | |||
hdma->ErrorCode = HAL_DMA_ERROR_TE; | |||
/* Change the DMA state */ | |||
hdma->State = HAL_DMA_STATE_READY; | |||
/* Process Unlocked */ | |||
__HAL_UNLOCK(hdma); | |||
if (hdma->XferErrorCallback != NULL) | |||
{ | |||
/* Transfer error callback */ | |||
hdma->XferErrorCallback(hdma); | |||
} | |||
} | |||
else | |||
{ | |||
/* Nothing To Do */ | |||
} | |||
return; | |||
} | |||
/** | |||
* @brief Register callbacks | |||
* @param hdma pointer to a DMA_HandleTypeDef structure that contains | |||
* the configuration information for the specified DMA Channel. | |||
* @param CallbackID User Callback identifer | |||
* a HAL_DMA_CallbackIDTypeDef ENUM as parameter. | |||
* @param pCallback pointer to private callbacsk function which has pointer to | |||
* a DMA_HandleTypeDef structure as parameter. | |||
* @retval HAL status | |||
*/ | |||
HAL_StatusTypeDef HAL_DMA_RegisterCallback(DMA_HandleTypeDef *hdma, HAL_DMA_CallbackIDTypeDef CallbackID, void (* pCallback)( DMA_HandleTypeDef * _hdma)) | |||
{ | |||
HAL_StatusTypeDef status = HAL_OK; | |||
/* Process locked */ | |||
__HAL_LOCK(hdma); | |||
if(HAL_DMA_STATE_READY == hdma->State) | |||
{ | |||
switch (CallbackID) | |||
{ | |||
case HAL_DMA_XFER_CPLT_CB_ID: | |||
hdma->XferCpltCallback = pCallback; | |||
break; | |||
case HAL_DMA_XFER_HALFCPLT_CB_ID: | |||
hdma->XferHalfCpltCallback = pCallback; | |||
break; | |||
case HAL_DMA_XFER_ERROR_CB_ID: | |||
hdma->XferErrorCallback = pCallback; | |||
break; | |||
case HAL_DMA_XFER_ABORT_CB_ID: | |||
hdma->XferAbortCallback = pCallback; | |||
break; | |||
default: | |||
status = HAL_ERROR; | |||
break; | |||
} | |||
} | |||
else | |||
{ | |||
status = HAL_ERROR; | |||
} | |||
/* Release Lock */ | |||
__HAL_UNLOCK(hdma); | |||
return status; | |||
} | |||
/** | |||
* @brief UnRegister callbacks | |||
* @param hdma pointer to a DMA_HandleTypeDef structure that contains | |||
* the configuration information for the specified DMA Channel. | |||
* @param CallbackID User Callback identifer | |||
* a HAL_DMA_CallbackIDTypeDef ENUM as parameter. | |||
* @retval HAL status | |||
*/ | |||
HAL_StatusTypeDef HAL_DMA_UnRegisterCallback(DMA_HandleTypeDef *hdma, HAL_DMA_CallbackIDTypeDef CallbackID) | |||
{ | |||
HAL_StatusTypeDef status = HAL_OK; | |||
/* Process locked */ | |||
__HAL_LOCK(hdma); | |||
if(HAL_DMA_STATE_READY == hdma->State) | |||
{ | |||
switch (CallbackID) | |||
{ | |||
case HAL_DMA_XFER_CPLT_CB_ID: | |||
hdma->XferCpltCallback = NULL; | |||
break; | |||
case HAL_DMA_XFER_HALFCPLT_CB_ID: | |||
hdma->XferHalfCpltCallback = NULL; | |||
break; | |||
case HAL_DMA_XFER_ERROR_CB_ID: | |||
hdma->XferErrorCallback = NULL; | |||
break; | |||
case HAL_DMA_XFER_ABORT_CB_ID: | |||
hdma->XferAbortCallback = NULL; | |||
break; | |||
case HAL_DMA_XFER_ALL_CB_ID: | |||
hdma->XferCpltCallback = NULL; | |||
hdma->XferHalfCpltCallback = NULL; | |||
hdma->XferErrorCallback = NULL; | |||
hdma->XferAbortCallback = NULL; | |||
break; | |||
default: | |||
status = HAL_ERROR; | |||
break; | |||
} | |||
} | |||
else | |||
{ | |||
status = HAL_ERROR; | |||
} | |||
/* Release Lock */ | |||
__HAL_UNLOCK(hdma); | |||
return status; | |||
} | |||
/** | |||
* @} | |||
*/ | |||
/** @defgroup DMA_Exported_Functions_Group3 Peripheral State and Errors functions | |||
* @brief Peripheral State and Errors functions | |||
* | |||
@verbatim | |||
=============================================================================== | |||
##### Peripheral State and Errors functions ##### | |||
=============================================================================== | |||
[..] | |||
This subsection provides functions allowing to | |||
(+) Check the DMA state | |||
(+) Get error code | |||
@endverbatim | |||
* @{ | |||
*/ | |||
/** | |||
* @brief Return the DMA handle 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 DMA handle state */ | |||
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; | |||
} | |||
/** | |||
* @} | |||
*/ | |||
/** | |||
* @} | |||
*/ | |||
/** @addtogroup DMA_Private_Functions | |||
* @{ | |||
*/ | |||
/** | |||
* @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) | |||
{ | |||
/* Clear all flags */ | |||
hdma->DmaBaseAddress->IFCR = (DMA_ISR_GIF1 << (hdma->ChannelIndex & 0x1CU)); | |||
/* Configure DMA Channel data length */ | |||
hdma->Instance->CNDTR = DataLength; | |||
/* Memory to Peripheral */ | |||
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; | |||
} | |||
/* Peripheral to Memory */ | |||
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****/ |
@@ -0,0 +1,650 @@ | |||
/** | |||
****************************************************************************** | |||
* @file stm32l1xx_hal_pwr.c | |||
* @author MCD Application Team | |||
* @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 | |||
* | |||
****************************************************************************** | |||
* @attention | |||
* | |||
* <h2><center>© Copyright (c) 2017 STMicroelectronics. | |||
* All rights reserved.</center></h2> | |||
* | |||
* This software component is licensed by ST under BSD 3-Clause license, | |||
* the "License"; You may not use this file except in compliance with the | |||
* License. You may obtain a copy of the License at: | |||
* opensource.org/licenses/BSD-3-Clause | |||
* | |||
****************************************************************************** | |||
*/ | |||
/* Includes ------------------------------------------------------------------*/ | |||
#include "stm32l1xx_hal.h" | |||
/** @addtogroup STM32L1xx_HAL_Driver | |||
* @{ | |||
*/ | |||
/** @defgroup PWR PWR | |||
* @brief PWR HAL module driver | |||
* @{ | |||
*/ | |||
#ifdef HAL_PWR_MODULE_ENABLED | |||
/* Private typedef -----------------------------------------------------------*/ | |||
/* Private define ------------------------------------------------------------*/ | |||
#define PVD_MODE_IT (0x00010000U) | |||
#define PVD_MODE_EVT (0x00020000U) | |||
#define PVD_RISING_EDGE (0x00000001U) | |||
#define PVD_FALLING_EDGE (0x00000002U) | |||
/* Private macro -------------------------------------------------------------*/ | |||
/* Private variables ---------------------------------------------------------*/ | |||
/* Private function prototypes -----------------------------------------------*/ | |||
/* Private functions ---------------------------------------------------------*/ | |||
/** @defgroup PWR_Exported_Functions PWR Exported Functions | |||
* @{ | |||
*/ | |||
/** @defgroup PWR_Exported_Functions_Group1 Initialization and de-initialization functions | |||
* @brief Initialization and de-initialization 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 | |||
__HAL_RCC_PWR_CLK_ENABLE() macro. | |||
(+) Enable access to RTC domain using the HAL_PWR_EnableBkUpAccess() function. | |||
@endverbatim | |||
* @{ | |||
*/ | |||
/** | |||
* @brief Deinitializes the PWR peripheral registers to their default reset values. | |||
* @note Before calling this function, the VOS[1:0] bits should be configured | |||
* to "10" and the system frequency has to be configured accordingly. | |||
* To configure the VOS[1:0] bits, use the PWR_VoltageScalingConfig() | |||
* function. | |||
* @note ULP and FWU bits are not reset by this function. | |||
* @retval None | |||
*/ | |||
void HAL_PWR_DeInit(void) | |||
{ | |||
__HAL_RCC_PWR_FORCE_RESET(); | |||
__HAL_RCC_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. | |||
* @retval None | |||
*/ | |||
void HAL_PWR_EnableBkUpAccess(void) | |||
{ | |||
/* Enable access to RTC and backup registers */ | |||
*(__IO uint32_t *) CR_DBP_BB = (uint32_t)ENABLE; | |||
} | |||
/** | |||
* @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. | |||
* @retval None | |||
*/ | |||
void HAL_PWR_DisableBkUpAccess(void) | |||
{ | |||
/* Disable access to RTC and backup registers */ | |||
*(__IO uint32_t *) CR_DBP_BB = (uint32_t)DISABLE; | |||
} | |||
/** | |||
* @} | |||
*/ | |||
/** @defgroup PWR_Exported_Functions_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_PWR_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 or three WakeUp pins: | |||
WakeUp Pin 1 on PA.00. | |||
WakeUp Pin 2 on PC.13. | |||
WakeUp Pin 3 on PE.06. : Only on product with GPIOE available | |||
[..] | |||
*** 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-M3 core stopped, peripherals kept running. | |||
(+) Low power sleep mode: Cortex-M3 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-M3 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 RC oscillator is selected as system clock. | |||
*** Standby mode *** | |||
==================== | |||
[..] | |||
The Standby mode allows to achieve the lowest power consumption. It is based on the | |||
Cortex-M3 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) and Enable the RTC Alarm Interrupt using the HAL_RTC_SetAlarm_IT() | |||
function | |||
(+++) Configure the RTC to generate the RTC alarm using the HAL_RTC_Init() | |||
and HAL_RTC_SetTime() 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) and | |||
Enable the RTC Tamper or time stamp Interrupt using the HAL_RTCEx_SetTamper_IT() | |||
or HAL_RTCEx_SetTimeStamp_IT() 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) and | |||
Enable the RTC WakeUp Interrupt using the HAL_RTCEx_SetWakeUpTimer_IT() function. | |||
(+++) Configure the RTC to generate the RTC WakeUp event using the HAL_RTCEx_SetWakeUpTimer() | |||
function. | |||
(+) 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 HAL_RTC_SetAlarm_IT() function. | |||
(+++) Configure the RTC to generate the RTC alarm using the HAL_RTC_Init() | |||
and HAL_RTC_SetTime() 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 and Configure the RTC to | |||
detect the tamper or time stamp event using the HAL_RTCEx_SetTimeStamp_IT() | |||
or HAL_RTCEx_SetTamper_IT()functions. | |||
(++) To wake up from the Standby mode with an RTC WakeUp event, it is necessary to: | |||
(+++) Enable the RTC WakeUp Interrupt and Configure the RTC to generate the RTC WakeUp event | |||
using the HAL_RTCEx_SetWakeUpTimer_IT() and HAL_RTCEx_SetWakeUpTimer() 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 or EXTI Line 22 for comparator to be sensitive to to the | |||
selected edges (falling, rising or falling and rising) (Interrupt or Event modes) using | |||
the COMP functions. | |||
(+++) 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_ConfigPVD(PWR_PVDTypeDef *sConfigPVD) | |||
{ | |||
/* Check the parameters */ | |||
assert_param(IS_PWR_PVD_LEVEL(sConfigPVD->PVDLevel)); | |||
assert_param(IS_PWR_PVD_MODE(sConfigPVD->Mode)); | |||
/* Set PLS[7:5] bits according to PVDLevel value */ | |||
MODIFY_REG(PWR->CR, PWR_CR_PLS, sConfigPVD->PVDLevel); | |||
/* Clear any previous config. Keep it clear if no event or IT mode is selected */ | |||
__HAL_PWR_PVD_EXTI_DISABLE_EVENT(); | |||
__HAL_PWR_PVD_EXTI_DISABLE_IT(); | |||
__HAL_PWR_PVD_EXTI_DISABLE_RISING_FALLING_EDGE(); | |||
/* Configure interrupt mode */ | |||
if((sConfigPVD->Mode & PVD_MODE_IT) == PVD_MODE_IT) | |||
{ | |||
__HAL_PWR_PVD_EXTI_ENABLE_IT(); | |||
} | |||
/* Configure event mode */ | |||
if((sConfigPVD->Mode & PVD_MODE_EVT) == PVD_MODE_EVT) | |||
{ | |||
__HAL_PWR_PVD_EXTI_ENABLE_EVENT(); | |||
} | |||
/* Configure the edge */ | |||
if((sConfigPVD->Mode & PVD_RISING_EDGE) == PVD_RISING_EDGE) | |||
{ | |||
__HAL_PWR_PVD_EXTI_ENABLE_RISING_EDGE(); | |||
} | |||
if((sConfigPVD->Mode & PVD_FALLING_EDGE) == PVD_FALLING_EDGE) | |||
{ | |||
__HAL_PWR_PVD_EXTI_ENABLE_FALLING_EDGE(); | |||
} | |||
} | |||
/** | |||
* @brief Enables the Power Voltage Detector(PVD). | |||
* @retval None | |||
*/ | |||
void HAL_PWR_EnablePVD(void) | |||
{ | |||
/* Enable the power voltage detector */ | |||
*(__IO uint32_t *) CR_PVDE_BB = (uint32_t)ENABLE; | |||
} | |||
/** | |||
* @brief Disables the Power Voltage Detector(PVD). | |||
* @retval None | |||
*/ | |||
void HAL_PWR_DisablePVD(void) | |||
{ | |||
/* Disable the power voltage detector */ | |||
*(__IO uint32_t *) CR_PVDE_BB = (uint32_t)DISABLE; | |||
} | |||
/** | |||
* @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 | |||
* @arg PWR_WAKEUP_PIN3: Only on product with GPIOE available | |||
* @retval None | |||
*/ | |||
void HAL_PWR_EnableWakeUpPin(uint32_t WakeUpPinx) | |||
{ | |||
/* Check the parameter */ | |||
assert_param(IS_PWR_WAKEUP_PIN(WakeUpPinx)); | |||
/* Enable the EWUPx pin */ | |||
*(__IO uint32_t *) CSR_EWUP_BB(WakeUpPinx) = (uint32_t)ENABLE; | |||
} | |||
/** | |||
* @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 | |||
* @arg PWR_WAKEUP_PIN3: Only on product with GPIOE available | |||
* @retval None | |||
*/ | |||
void HAL_PWR_DisableWakeUpPin(uint32_t WakeUpPinx) | |||
{ | |||
/* Check the parameter */ | |||
assert_param(IS_PWR_WAKEUP_PIN(WakeUpPinx)); | |||
/* Disable the EWUPx pin */ | |||
*(__IO uint32_t *) CSR_EWUP_BB(WakeUpPinx) = (uint32_t)DISABLE; | |||
} | |||
/** | |||
* @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) | |||
{ | |||
/* Check the parameters */ | |||
assert_param(IS_PWR_REGULATOR(Regulator)); | |||
assert_param(IS_PWR_SLEEP_ENTRY(SLEEPEntry)); | |||
/* Select the regulator state in Sleep mode: Set PDDS and LPSDSR bit according to PWR_Regulator value */ | |||
MODIFY_REG(PWR->CR, (PWR_CR_PDDS | PWR_CR_LPSDSR), Regulator); | |||
/* Clear SLEEPDEEP bit of Cortex System Control Register */ | |||
CLEAR_BIT(SCB->SCR, ((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 using an interrupt or a wakeup event, | |||
* MSI RC oscillator is selected as system clock. | |||
* @note When the voltage regulator operates in low power mode, an additional | |||
* startup delay is incurred when waking up from Stop mode. | |||
* By keeping the internal regulator ON during Stop mode, the consumption | |||
* is higher although the startup time is reduced. | |||
* @param 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) | |||
{ | |||
/* Check the parameters */ | |||
assert_param(IS_PWR_REGULATOR(Regulator)); | |||
assert_param(IS_PWR_STOP_ENTRY(STOPEntry)); | |||
/* Select the regulator state in Stop mode: Set PDDS and LPSDSR bit according to PWR_Regulator value */ | |||
MODIFY_REG(PWR->CR, (PWR_CR_PDDS | PWR_CR_LPSDSR), Regulator); | |||
/* Set SLEEPDEEP bit of Cortex System Control Register */ | |||
SET_BIT(SCB->SCR, ((uint32_t)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 */ | |||
CLEAR_BIT(SCB->SCR, ((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. | |||
* - WKUP pin 1 (PA0) if enabled. | |||
* - WKUP pin 2 (PC13) if enabled. | |||
* - WKUP pin 3 (PE6) if enabled. | |||
* @retval None | |||
*/ | |||
void HAL_PWR_EnterSTANDBYMode(void) | |||
{ | |||
/* Select Standby mode */ | |||
SET_BIT(PWR->CR, PWR_CR_PDDS); | |||
/* Set SLEEPDEEP bit of Cortex System Control Register */ | |||
SET_BIT(SCB->SCR, ((uint32_t)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 Indicates Sleep-On-Exit when returning from Handler mode to Thread mode. | |||
* @note Set SLEEPONEXIT bit of SCR register. When this bit is set, the processor | |||
* re-enters SLEEP mode when an interruption handling is over. | |||
* Setting this bit is useful when the processor is expected to run only on | |||
* interruptions handling. | |||
* @retval None | |||
*/ | |||
void HAL_PWR_EnableSleepOnExit(void) | |||
{ | |||
/* Set SLEEPONEXIT bit of Cortex System Control Register */ | |||
SET_BIT(SCB->SCR, ((uint32_t)SCB_SCR_SLEEPONEXIT_Msk)); | |||
} | |||
/** | |||
* @brief Disables Sleep-On-Exit feature when returning from Handler mode to Thread mode. | |||
* @note Clears SLEEPONEXIT bit of SCR register. When this bit is set, the processor | |||
* re-enters SLEEP mode when an interruption handling is over. | |||
* @retval None | |||
*/ | |||
void HAL_PWR_DisableSleepOnExit(void) | |||
{ | |||
/* Clear SLEEPONEXIT bit of Cortex System Control Register */ | |||
CLEAR_BIT(SCB->SCR, ((uint32_t)SCB_SCR_SLEEPONEXIT_Msk)); | |||
} | |||
/** | |||
* @brief Enables CORTEX M3 SEVONPEND bit. | |||
* @note Sets SEVONPEND bit of SCR register. When this bit is set, this causes | |||
* WFE to wake up when an interrupt moves from inactive to pended. | |||
* @retval None | |||
*/ | |||
void HAL_PWR_EnableSEVOnPend(void) | |||
{ | |||
/* Set SEVONPEND bit of Cortex System Control Register */ | |||
SET_BIT(SCB->SCR, ((uint32_t)SCB_SCR_SEVONPEND_Msk)); | |||
} | |||
/** | |||
* @brief Disables CORTEX M3 SEVONPEND bit. | |||
* @note Clears SEVONPEND bit of SCR register. When this bit is set, this causes | |||
* WFE to wake up when an interrupt moves from inactive to pended. | |||
* @retval None | |||
*/ | |||
void HAL_PWR_DisableSEVOnPend(void) | |||
{ | |||
/* Clear SEVONPEND bit of Cortex System Control Register */ | |||
CLEAR_BIT(SCB->SCR, ((uint32_t)SCB_SCR_SEVONPEND_Msk)); | |||
} | |||
/** | |||
* @brief This function handles the PWR PVD interrupt request. | |||
* @note This API should be called under the PVD_IRQHandler(). | |||
* @retval None | |||
*/ | |||
void HAL_PWR_PVD_IRQHandler(void) | |||
{ | |||
/* Check PWR exti flag */ | |||
if(__HAL_PWR_PVD_EXTI_GET_FLAG() != RESET) | |||
{ | |||
/* PWR PVD interrupt user callback */ | |||
HAL_PWR_PVDCallback(); | |||
/* Clear PWR Exti pending bit */ | |||
__HAL_PWR_PVD_EXTI_CLEAR_FLAG(); | |||
} | |||
} | |||
/** | |||
* @brief PWR PVD interrupt callback | |||
* @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****/ |
@@ -0,0 +1,161 @@ | |||
/** | |||
****************************************************************************** | |||
* @file stm32l1xx_hal_pwr_ex.c | |||
* @author MCD Application Team | |||
* @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>© Copyright (c) 2017 STMicroelectronics. | |||
* All rights reserved.</center></h2> | |||
* | |||
* This software component is licensed by ST under BSD 3-Clause license, | |||
* the "License"; You may not use this file except in compliance with the | |||
* License. You may obtain a copy of the License at: | |||
* opensource.org/licenses/BSD-3-Clause | |||
* | |||
****************************************************************************** | |||
*/ | |||
/* Includes ------------------------------------------------------------------*/ | |||
#include "stm32l1xx_hal.h" | |||
/** @addtogroup STM32L1xx_HAL_Driver | |||
* @{ | |||
*/ | |||
/** @defgroup PWREx 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_Exported_Functions PWREx Exported Functions | |||
* @{ | |||
*/ | |||
/** @defgroup PWREx_Exported_Functions_Group1 Peripheral Extended Features Functions | |||
* @brief Low Power modes configuration functions | |||
* | |||
@verbatim | |||
=============================================================================== | |||
##### Peripheral extended features functions ##### | |||
=============================================================================== | |||
@endverbatim | |||
* @{ | |||
*/ | |||
/** | |||
* @brief Return Voltage Scaling Range. | |||
* @retval VOS bit field (PWR_REGULATOR_VOLTAGE_SCALE1, PWR_REGULATOR_VOLTAGE_SCALE2 or PWR_REGULATOR_VOLTAGE_SCALE3) | |||
*/ | |||
uint32_t HAL_PWREx_GetVoltageRange(void) | |||
{ | |||
return (PWR->CR & PWR_CR_VOS); | |||
} | |||
/** | |||
* @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. | |||
* @retval None | |||
*/ | |||
void HAL_PWREx_EnableFastWakeUp(void) | |||
{ | |||
/* Enable the fast wake up */ | |||
*(__IO uint32_t *) CR_FWU_BB = (uint32_t)ENABLE; | |||
} | |||
/** | |||
* @brief Disables the Fast WakeUp from Ultra Low Power mode. | |||
* @retval None | |||
*/ | |||
void HAL_PWREx_DisableFastWakeUp(void) | |||
{ | |||
/* Disable the fast wake up */ | |||
*(__IO uint32_t *) CR_FWU_BB = (uint32_t)DISABLE; | |||
} | |||
/** | |||
* @brief Enables the Ultra Low Power mode | |||
* @retval None | |||
*/ | |||
void HAL_PWREx_EnableUltraLowPower(void) | |||
{ | |||
/* Enable the Ultra Low Power mode */ | |||
*(__IO uint32_t *) CR_ULP_BB = (uint32_t)ENABLE; | |||
} | |||
/** | |||
* @brief Disables the Ultra Low Power mode | |||
* @retval None | |||
*/ | |||
void HAL_PWREx_DisableUltraLowPower(void) | |||
{ | |||
/* Disable the Ultra Low Power mode */ | |||
*(__IO uint32_t *) CR_ULP_BB = (uint32_t)DISABLE; | |||
} | |||
/** | |||
* @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. | |||
* @retval None | |||
*/ | |||
void HAL_PWREx_EnableLowPowerRunMode(void) | |||
{ | |||
/* Enters the Low Power Run mode */ | |||
*(__IO uint32_t *) CR_LPSDSR_BB = (uint32_t)ENABLE; | |||
*(__IO uint32_t *) CR_LPRUN_BB = (uint32_t)ENABLE; | |||
} | |||
/** | |||
* @brief Exits the Low Power Run mode. | |||
* @retval None | |||
*/ | |||
HAL_StatusTypeDef HAL_PWREx_DisableLowPowerRunMode(void) | |||
{ | |||
/* Exits the Low Power Run mode */ | |||
*(__IO uint32_t *) CR_LPRUN_BB = (uint32_t)DISABLE; | |||
*(__IO uint32_t *) CR_LPSDSR_BB = (uint32_t)DISABLE; | |||
return HAL_OK; | |||
} | |||
/** | |||
* @} | |||
*/ | |||
/** | |||
* @} | |||
*/ | |||
#endif /* HAL_PWR_MODULE_ENABLED */ | |||
/** | |||
* @} | |||
*/ | |||
/** | |||
* @} | |||
*/ | |||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ |
@@ -0,0 +1,765 @@ | |||
/** | |||
****************************************************************************** | |||
* @file stm32l1xx_hal_uart.h | |||
* @author MCD Application Team | |||
* @brief This file contains all the functions prototypes for the UART | |||
* firmware library. | |||
****************************************************************************** | |||
* @attention | |||
* | |||
* <h2><center>© COPYRIGHT(c) 2017 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 __STM32L1xx_HAL_UART_H | |||
#define __STM32L1xx_HAL_UART_H | |||
#ifdef __cplusplus | |||
extern "C" { | |||
#endif | |||
/* Includes ------------------------------------------------------------------*/ | |||
#include "stm32l1xx_hal_def.h" | |||
/** @addtogroup STM32L1xx_HAL_Driver | |||
* @{ | |||
*/ | |||
/** @addtogroup UART | |||
* @{ | |||
*/ | |||
/* Exported types ------------------------------------------------------------*/ | |||
/** @defgroup UART_Exported_Types UART Exported Types | |||
* @{ | |||
*/ | |||
/** | |||
* @brief UART Init Structure definition | |||
*/ | |||
typedef struct | |||
{ | |||
uint32_t BaudRate; /*!< This member configures the UART communication baud rate. | |||
The baud rate is computed using the following formula: | |||
- IntegerDivider = ((PCLKx) / (8 * (OVR8+1) * (huart->Init.BaudRate))) | |||
- FractionalDivider = ((IntegerDivider - ((uint32_t) IntegerDivider)) * 8 * (OVR8+1)) + 0.5 | |||
Where OVR8 is the "oversampling by 8 mode" configuration bit in the CR1 register. */ | |||
uint32_t WordLength; /*!< Specifies the number of data bits transmitted or received in a frame. | |||
This parameter can be a value of @ref UART_Word_Length */ | |||
uint32_t StopBits; /*!< Specifies the number of stop bits transmitted. | |||
This parameter can be a value of @ref UART_Stop_Bits */ | |||
uint32_t Parity; /*!< Specifies the parity mode. | |||
This parameter can be a value of @ref UART_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 UART_Mode */ | |||
uint32_t HwFlowCtl; /*!< Specifies wether the hardware flow control mode is enabled | |||
or disabled. | |||
This parameter can be a value of @ref UART_Hardware_Flow_Control */ | |||
uint32_t OverSampling; /*!< Specifies wether the Over sampling 8 is enabled or disabled, to achieve higher speed (up to fPCLK/8). | |||
This parameter can be a value of @ref UART_Over_Sampling */ | |||
}UART_InitTypeDef; | |||
/** | |||
* @brief HAL UART State structures definition | |||
*/ | |||
typedef enum | |||
{ | |||
HAL_UART_STATE_RESET = 0x00, /*!< Peripheral is not initialized */ | |||
HAL_UART_STATE_READY = 0x01, /*!< Peripheral Initialized and ready for use */ | |||
HAL_UART_STATE_BUSY = 0x02, /*!< an internal process is ongoing */ | |||
HAL_UART_STATE_BUSY_TX = 0x12, /*!< Data Transmission process is ongoing */ | |||
HAL_UART_STATE_BUSY_RX = 0x22, /*!< Data Reception process is ongoing */ | |||
HAL_UART_STATE_BUSY_TX_RX = 0x32, /*!< Data Transmission and Reception process is ongoing */ | |||
HAL_UART_STATE_TIMEOUT = 0x03, /*!< Timeout state */ | |||
HAL_UART_STATE_ERROR = 0x04 /*!< Error */ | |||
}HAL_UART_StateTypeDef; | |||
/** | |||
* @brief UART handle Structure definition | |||
*/ | |||
typedef struct | |||
{ | |||
USART_TypeDef *Instance; /*!< UART registers base address */ | |||
UART_InitTypeDef Init; /*!< UART communication parameters */ | |||
uint8_t *pTxBuffPtr; /*!< Pointer to UART Tx transfer Buffer */ | |||
uint16_t TxXferSize; /*!< UART Tx Transfer size */ | |||
uint16_t TxXferCount; /*!< UART Tx Transfer Counter */ | |||
uint8_t *pRxBuffPtr; /*!< Pointer to UART Rx transfer Buffer */ | |||
uint16_t RxXferSize; /*!< UART Rx Transfer size */ | |||
uint16_t RxXferCount; /*!< UART Rx Transfer Counter */ | |||
DMA_HandleTypeDef *hdmatx; /*!< UART Tx DMA Handle parameters */ | |||
DMA_HandleTypeDef *hdmarx; /*!< UART Rx DMA Handle parameters */ | |||
HAL_LockTypeDef Lock; /*!< Locking object */ | |||
__IO HAL_UART_StateTypeDef State; /*!< UART communication state */ | |||
__IO uint32_t ErrorCode; /*!< UART Error code */ | |||
}UART_HandleTypeDef; | |||
/** | |||
* @} | |||
*/ | |||
/* Exported constants --------------------------------------------------------*/ | |||
/** @defgroup UART_Exported_Constants UART Exported constants | |||
* @{ | |||
*/ | |||
/** @defgroup UART_Error_Codes UART Error Codes | |||
* @{ | |||
*/ | |||
#define HAL_UART_ERROR_NONE (0x00U) /*!< No error */ | |||
#define HAL_UART_ERROR_PE (0x01U) /*!< Parity error */ | |||
#define HAL_UART_ERROR_NE (0x02U) /*!< Noise error */ | |||
#define HAL_UART_ERROR_FE (0x04U) /*!< frame error */ | |||
#define HAL_UART_ERROR_ORE (0x08U) /*!< Overrun error */ | |||
#define HAL_UART_ERROR_DMA (0x10U) /*!< DMA transfer error */ | |||
/** | |||
* @} | |||
*/ | |||
/** @defgroup UART_Word_Length UART Word Length | |||
* @{ | |||
*/ | |||
#define UART_WORDLENGTH_8B (0x00000000U) | |||
#define UART_WORDLENGTH_9B ((uint32_t)USART_CR1_M) | |||
/** | |||
* @} | |||
*/ | |||
/** @defgroup UART_Stop_Bits UART Number of Stop Bits | |||
* @{ | |||
*/ | |||
#define UART_STOPBITS_1 (0x00000000U) | |||
#define UART_STOPBITS_2 ((uint32_t)USART_CR2_STOP_1) | |||
/** | |||
* @} | |||
*/ | |||
/** @defgroup UART_Parity UART Parity | |||
* @{ | |||
*/ | |||
#define UART_PARITY_NONE (0x00000000U) | |||
#define UART_PARITY_EVEN ((uint32_t)USART_CR1_PCE) | |||
#define UART_PARITY_ODD ((uint32_t)(USART_CR1_PCE | USART_CR1_PS)) | |||
/** | |||
* @} | |||
*/ | |||
/** @defgroup UART_Hardware_Flow_Control UART Hardware Flow Control | |||
* @{ | |||
*/ | |||
#define UART_HWCONTROL_NONE (0x00000000U) | |||
#define UART_HWCONTROL_RTS ((uint32_t)USART_CR3_RTSE) | |||
#define UART_HWCONTROL_CTS ((uint32_t)USART_CR3_CTSE) | |||
#define UART_HWCONTROL_RTS_CTS ((uint32_t)(USART_CR3_RTSE | USART_CR3_CTSE)) | |||
/** | |||
* @} | |||
*/ | |||
/** @defgroup UART_Mode UART Transfer Mode | |||
* @{ | |||
*/ | |||
#define UART_MODE_RX ((uint32_t)USART_CR1_RE) | |||
#define UART_MODE_TX ((uint32_t)USART_CR1_TE) | |||
#define UART_MODE_TX_RX ((uint32_t)(USART_CR1_TE |USART_CR1_RE)) | |||
/** | |||
* @} | |||
*/ | |||
/** @defgroup UART_State UART State | |||
* @{ | |||
*/ | |||
#define UART_STATE_DISABLE (0x00000000U) | |||
#define UART_STATE_ENABLE ((uint32_t)USART_CR1_UE) | |||
/** | |||
* @} | |||
*/ | |||
/** @defgroup UART_Over_Sampling UART Over Sampling | |||
* @{ | |||
*/ | |||
#define UART_OVERSAMPLING_16 (0x00000000U) | |||
#define UART_OVERSAMPLING_8 ((uint32_t)USART_CR1_OVER8) | |||
/** | |||
* @} | |||
*/ | |||
/** @defgroup UART_LIN_Break_Detection_Length UART LIN Break Detection Length | |||
* @{ | |||
*/ | |||
#define UART_LINBREAKDETECTLENGTH_10B (0x00000000U) | |||
#define UART_LINBREAKDETECTLENGTH_11B ((uint32_t)USART_CR2_LBDL) | |||
/** | |||
* @} | |||
*/ | |||
/** @defgroup UART_WakeUp_functions UART Wakeup Functions | |||
* @{ | |||
*/ | |||
#define UART_WAKEUPMETHOD_IDLELINE (0x00000000U) | |||
#define UART_WAKEUPMETHOD_ADDRESSMARK ((uint32_t)USART_CR1_WAKE) | |||
/** | |||
* @} | |||
*/ | |||
/** @defgroup UART_Flags UART FLags | |||
* Elements values convention: 0xXXXX | |||
* - 0xXXXX : Flag mask in the SR register | |||
* @{ | |||
*/ | |||
#define UART_FLAG_CTS ((uint32_t)USART_SR_CTS) | |||
#define UART_FLAG_LBD ((uint32_t)USART_SR_LBD) | |||
#define UART_FLAG_TXE ((uint32_t)USART_SR_TXE) | |||
#define UART_FLAG_TC ((uint32_t)USART_SR_TC) | |||
#define UART_FLAG_RXNE ((uint32_t)USART_SR_RXNE) | |||
#define UART_FLAG_IDLE ((uint32_t)USART_SR_IDLE) | |||
#define UART_FLAG_ORE ((uint32_t)USART_SR_ORE) | |||
#define UART_FLAG_NE ((uint32_t)USART_SR_NE) | |||
#define UART_FLAG_FE ((uint32_t)USART_SR_FE) | |||
#define UART_FLAG_PE ((uint32_t)USART_SR_PE) | |||
/** | |||
* @} | |||
*/ | |||
/** @defgroup UART_Interrupt_definition UART Interrupt Definitions | |||
* Elements values convention: 0xY000XXXX | |||
* - XXXX : Interrupt mask (16 bits) in the Y register | |||
* - Y : Interrupt source register (2bits) | |||
* - 0001: CR1 register | |||
* - 0010: CR2 register | |||
* - 0011: CR3 register | |||
* | |||
* @{ | |||
*/ | |||
#define UART_IT_PE ((uint32_t)(UART_CR1_REG_INDEX << 28 | USART_CR1_PEIE)) | |||
#define UART_IT_TXE ((uint32_t)(UART_CR1_REG_INDEX << 28 | USART_CR1_TXEIE)) | |||
#define UART_IT_TC ((uint32_t)(UART_CR1_REG_INDEX << 28 | USART_CR1_TCIE)) | |||
#define UART_IT_RXNE ((uint32_t)(UART_CR1_REG_INDEX << 28 | USART_CR1_RXNEIE)) | |||
#define UART_IT_IDLE ((uint32_t)(UART_CR1_REG_INDEX << 28 | USART_CR1_IDLEIE)) | |||
#define UART_IT_LBD ((uint32_t)(UART_CR2_REG_INDEX << 28 | USART_CR2_LBDIE)) | |||
#define UART_IT_CTS ((uint32_t)(UART_CR3_REG_INDEX << 28 | USART_CR3_CTSIE)) | |||
#define UART_IT_ERR ((uint32_t)(UART_CR3_REG_INDEX << 28 | USART_CR3_EIE)) | |||
/** | |||
* @} | |||
*/ | |||
/** | |||
* @} | |||
*/ | |||
/* Exported macro ------------------------------------------------------------*/ | |||
/** @defgroup UART_Exported_Macros UART Exported Macros | |||
* @{ | |||
*/ | |||
/** @brief Reset UART handle state | |||
* @param __HANDLE__: specifies the UART Handle. | |||
* UART Handle selects the USARTx or UARTy peripheral | |||
* (USART,UART availability and x,y values depending on device). | |||
* @retval None | |||
*/ | |||
#define __HAL_UART_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_UART_STATE_RESET) | |||
/** @brief Flush the UART DR register | |||
* @param __HANDLE__: specifies the UART Handle. | |||
* UART Handle selects the USARTx or UARTy peripheral | |||
* (USART,UART availability and x,y values depending on device). | |||
*/ | |||
#define __HAL_UART_FLUSH_DRREGISTER(__HANDLE__) ((__HANDLE__)->Instance->DR) | |||
/** @brief Check whether the specified UART flag is set or not. | |||
* @param __HANDLE__: specifies the UART Handle. | |||
* UART Handle selects the USARTx or UARTy peripheral | |||
* (USART,UART availability and x,y values depending on device). | |||
* @param __FLAG__: specifies the flag to check. | |||
* This parameter can be one of the following values: | |||
* @arg UART_FLAG_CTS: CTS Change flag (not available for UART4 and UART5) | |||
* @arg UART_FLAG_LBD: LIN Break detection flag | |||
* @arg UART_FLAG_TXE: Transmit data register empty flag | |||
* @arg UART_FLAG_TC: Transmission Complete flag | |||
* @arg UART_FLAG_RXNE: Receive data register not empty flag | |||
* @arg UART_FLAG_IDLE: Idle Line detection flag | |||
* @arg UART_FLAG_ORE: OverRun Error flag | |||
* @arg UART_FLAG_NE: Noise Error flag | |||
* @arg UART_FLAG_FE: Framing Error flag | |||
* @arg UART_FLAG_PE: Parity Error flag | |||
* @retval The new state of __FLAG__ (TRUE or FALSE). | |||
*/ | |||
#define __HAL_UART_GET_FLAG(__HANDLE__, __FLAG__) (((__HANDLE__)->Instance->SR & (__FLAG__)) == (__FLAG__)) | |||
/** @brief Clear the specified UART pending flag. | |||
* @param __HANDLE__: specifies the UART Handle. | |||
* UART Handle selects the USARTx or UARTy peripheral | |||
* (USART,UART availability and x,y values depending on device). | |||
* @param __FLAG__: specifies the flag to check. | |||
* This parameter can be any combination of the following values: | |||
* @arg UART_FLAG_CTS: CTS Change flag (not available for UART4 and UART5). | |||
* @arg UART_FLAG_LBD: LIN Break detection flag. | |||
* @arg UART_FLAG_TC: Transmission Complete flag. | |||
* @arg UART_FLAG_RXNE: Receive data register not empty flag. | |||
* | |||
* @note PE (Parity error), FE (Framing error), NE (Noise error), ORE (OverRun | |||
* error) and IDLE (Idle line detected) flags are cleared by software | |||
* sequence: a read operation to USART_SR register followed by a read | |||
* operation to USART_DR register. | |||
* @note RXNE flag can be also cleared by a read to the USART_DR register. | |||
* @note TC flag can be also cleared by software sequence: a read operation to | |||
* USART_SR register followed by a write operation to USART_DR register. | |||
* @note TXE flag is cleared only by a write to the USART_DR register. | |||
* | |||
* @retval None | |||
*/ | |||
#define __HAL_UART_CLEAR_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->SR = ~(__FLAG__)) | |||
/** @brief Clear the UART PE pending flag. | |||
* @param __HANDLE__: specifies the UART Handle. | |||
* UART Handle selects the USARTx or UARTy peripheral | |||
* (USART,UART availability and x,y values depending on device). | |||
* @retval None | |||
*/ | |||
#define __HAL_UART_CLEAR_PEFLAG(__HANDLE__) \ | |||
do{ \ | |||
__IO uint32_t tmpreg; \ | |||
tmpreg = (__HANDLE__)->Instance->SR; \ | |||
tmpreg = (__HANDLE__)->Instance->DR; \ | |||
UNUSED(tmpreg); \ | |||
}while(0) | |||
/** @brief Clear the UART FE pending flag. | |||
* @param __HANDLE__: specifies the UART Handle. | |||
* UART Handle selects the USARTx or UARTy peripheral | |||
* (USART,UART availability and x,y values depending on device). | |||
* @retval None | |||
*/ | |||
#define __HAL_UART_CLEAR_FEFLAG(__HANDLE__) __HAL_UART_CLEAR_PEFLAG(__HANDLE__) | |||
/** @brief Clear the UART NE pending flag. | |||
* @param __HANDLE__: specifies the UART Handle. | |||
* UART Handle selects the USARTx or UARTy peripheral | |||
* (USART,UART availability and x,y values depending on device). | |||
* @retval None | |||
*/ | |||
#define __HAL_UART_CLEAR_NEFLAG(__HANDLE__) __HAL_UART_CLEAR_PEFLAG(__HANDLE__) | |||
/** @brief Clear the UART ORE pending flag. | |||
* @param __HANDLE__: specifies the UART Handle. | |||
* UART Handle selects the USARTx or UARTy peripheral | |||
* (USART,UART availability and x,y values depending on device). | |||
* @retval None | |||
*/ | |||
#define __HAL_UART_CLEAR_OREFLAG(__HANDLE__) __HAL_UART_CLEAR_PEFLAG(__HANDLE__) | |||
/** @brief Clear the UART IDLE pending flag. | |||
* @param __HANDLE__: specifies the UART Handle. | |||
* UART Handle selects the USARTx or UARTy peripheral | |||
* (USART,UART availability and x,y values depending on device). | |||
* @retval None | |||
*/ | |||
#define __HAL_UART_CLEAR_IDLEFLAG(__HANDLE__) __HAL_UART_CLEAR_PEFLAG(__HANDLE__) | |||
/** @brief Enable the specified UART interrupt. | |||
* @param __HANDLE__: specifies the UART Handle. | |||
* UART Handle selects the USARTx or UARTy peripheral | |||
* (USART,UART availability and x,y values depending on device). | |||
* @param __INTERRUPT__: specifies the UART interrupt source to enable. | |||
* This parameter can be one of the following values: | |||
* @arg UART_IT_CTS: CTS change interrupt | |||
* @arg UART_IT_LBD: LIN Break detection interrupt | |||
* @arg UART_IT_TXE: Transmit Data Register empty interrupt | |||
* @arg UART_IT_TC: Transmission complete interrupt | |||
* @arg UART_IT_RXNE: Receive Data register not empty interrupt | |||
* @arg UART_IT_IDLE: Idle line detection interrupt | |||
* @arg UART_IT_PE: Parity Error interrupt | |||
* @arg UART_IT_ERR: Error interrupt(Frame error, noise error, overrun error) | |||
* @retval None | |||
*/ | |||
#define __HAL_UART_ENABLE_IT(__HANDLE__, __INTERRUPT__) ((((__INTERRUPT__) >> 28) == UART_CR1_REG_INDEX)? ((__HANDLE__)->Instance->CR1 |= ((__INTERRUPT__) & UART_IT_MASK)): \ | |||
(((__INTERRUPT__) >> 28) == UART_CR2_REG_INDEX)? ((__HANDLE__)->Instance->CR2 |= ((__INTERRUPT__) & UART_IT_MASK)): \ | |||
((__HANDLE__)->Instance->CR3 |= ((__INTERRUPT__) & UART_IT_MASK))) | |||
/** @brief Disable the specified UART interrupt. | |||
* @param __HANDLE__: specifies the UART Handle. | |||
* UART Handle selects the USARTx or UARTy peripheral | |||
* (USART,UART availability and x,y values depending on device). | |||
* @param __INTERRUPT__: specifies the UART interrupt source to disable. | |||
* This parameter can be one of the following values: | |||
* @arg UART_IT_CTS: CTS change interrupt | |||
* @arg UART_IT_LBD: LIN Break detection interrupt | |||
* @arg UART_IT_TXE: Transmit Data Register empty interrupt | |||
* @arg UART_IT_TC: Transmission complete interrupt | |||
* @arg UART_IT_RXNE: Receive Data register not empty interrupt | |||
* @arg UART_IT_IDLE: Idle line detection interrupt | |||
* @arg UART_IT_PE: Parity Error interrupt | |||
* @arg UART_IT_ERR: Error interrupt(Frame error, noise error, overrun error) | |||
* @retval None | |||
*/ | |||
#define __HAL_UART_DISABLE_IT(__HANDLE__, __INTERRUPT__) ((((__INTERRUPT__) >> 28) == UART_CR1_REG_INDEX)? ((__HANDLE__)->Instance->CR1 &= ~((__INTERRUPT__) & UART_IT_MASK)): \ | |||
(((__INTERRUPT__) >> 28) == UART_CR2_REG_INDEX)? ((__HANDLE__)->Instance->CR2 &= ~((__INTERRUPT__) & UART_IT_MASK)): \ | |||
((__HANDLE__)->Instance->CR3 &= ~ ((__INTERRUPT__) & UART_IT_MASK))) | |||
/** @brief Check whether the specified UART interrupt has occurred or not. | |||
* @param __HANDLE__: specifies the UART Handle. | |||
* UART Handle selects the USARTx or UARTy peripheral | |||
* (USART,UART availability and x,y values depending on device). | |||
* @param __IT__: specifies the UART interrupt source to check. | |||
* This parameter can be one of the following values: | |||
* @arg UART_IT_CTS: CTS change interrupt (not available for UART4 and UART5) | |||
* @arg UART_IT_LBD: LIN Break detection interrupt | |||
* @arg UART_IT_TXE: Transmit Data Register empty interrupt | |||
* @arg UART_IT_TC: Transmission complete interrupt | |||
* @arg UART_IT_RXNE: Receive Data register not empty interrupt | |||
* @arg UART_IT_IDLE: Idle line detection interrupt | |||
* @arg UART_IT_ERR: Error interrupt | |||
* @retval The new state of __IT__ (TRUE or FALSE). | |||
*/ | |||
#define __HAL_UART_GET_IT_SOURCE(__HANDLE__, __IT__) (((((__IT__) >> 28) == UART_CR1_REG_INDEX)? (__HANDLE__)->Instance->CR1:(((((uint32_t)(__IT__)) >> 28) == UART_CR2_REG_INDEX)? \ | |||
(__HANDLE__)->Instance->CR2 : (__HANDLE__)->Instance->CR3)) & (((uint32_t)(__IT__)) & UART_IT_MASK)) | |||
/** @brief macros to enables or disables the UART's one bit sampling method | |||
* @param __HANDLE__: specifies the UART Handle. | |||
* This parameter can be USARTx with x: 1, 2 or 3, or UARTy with y:4 or 5 to select the USART or | |||
* UART peripheral (availability depending on device for UARTy). | |||
* @retval None | |||
*/ | |||
#define __HAL_UART_ONE_BIT_SAMPLE_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR3|= USART_CR3_ONEBIT) | |||
#define __HAL_UART_ONE_BIT_SAMPLE_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR3 &= (uint16_t)~((uint16_t)USART_CR3_ONEBIT)) | |||
/** @brief Enable CTS flow control | |||
* This macro allows to enable CTS hardware flow control for a given UART instance, | |||
* without need to call HAL_UART_Init() function. | |||
* As involving direct access to UART registers, usage of this macro should be fully endorsed by user. | |||
* @note As macro is expected to be used for modifying CTS Hw flow control feature activation, without need | |||
* for USART instance Deinit/Init, following conditions for macro call should be fulfilled : | |||
* - UART instance should have already been initialised (through call of HAL_UART_Init() ) | |||
* - macro could only be called when corresponding UART instance is disabled (i.e __HAL_UART_DISABLE(__HANDLE__)) | |||
* and should be followed by an Enable macro (i.e __HAL_UART_ENABLE(__HANDLE__)). | |||
* @param __HANDLE__: specifies the UART Handle. | |||
* This parameter can be any USARTx (supporting the HW Flow control feature). | |||
* It is used to select the USART peripheral (USART availability and x value depending on device). | |||
* @retval None | |||
*/ | |||
#define __HAL_UART_HWCONTROL_CTS_ENABLE(__HANDLE__) \ | |||
do{ \ | |||
SET_BIT((__HANDLE__)->Instance->CR3, USART_CR3_CTSE); \ | |||
(__HANDLE__)->Init.HwFlowCtl |= USART_CR3_CTSE; \ | |||
} while(0) | |||
/** @brief Disable CTS flow control | |||
* This macro allows to disable CTS hardware flow control for a given UART instance, | |||
* without need to call HAL_UART_Init() function. | |||
* As involving direct access to UART registers, usage of this macro should be fully endorsed by user. | |||
* @note As macro is expected to be used for modifying CTS Hw flow control feature activation, without need | |||
* for USART instance Deinit/Init, following conditions for macro call should be fulfilled : | |||
* - UART instance should have already been initialised (through call of HAL_UART_Init() ) | |||
* - macro could only be called when corresponding UART instance is disabled (i.e __HAL_UART_DISABLE(__HANDLE__)) | |||
* and should be followed by an Enable macro (i.e __HAL_UART_ENABLE(__HANDLE__)). | |||
* @param __HANDLE__: specifies the UART Handle. | |||
* This parameter can be any USARTx (supporting the HW Flow control feature). | |||
* It is used to select the USART peripheral (USART availability and x value depending on device). | |||
* @retval None | |||
*/ | |||
#define __HAL_UART_HWCONTROL_CTS_DISABLE(__HANDLE__) \ | |||
do{ \ | |||
CLEAR_BIT((__HANDLE__)->Instance->CR3, USART_CR3_CTSE); \ | |||
(__HANDLE__)->Init.HwFlowCtl &= ~(USART_CR3_CTSE); \ | |||
} while(0) | |||
/** @brief Enable RTS flow control | |||
* This macro allows to enable RTS hardware flow control for a given UART instance, | |||
* without need to call HAL_UART_Init() function. | |||
* As involving direct access to UART registers, usage of this macro should be fully endorsed by user. | |||
* @note As macro is expected to be used for modifying RTS Hw flow control feature activation, without need | |||
* for USART instance Deinit/Init, following conditions for macro call should be fulfilled : | |||
* - UART instance should have already been initialised (through call of HAL_UART_Init() ) | |||
* - macro could only be called when corresponding UART instance is disabled (i.e __HAL_UART_DISABLE(__HANDLE__)) | |||
* and should be followed by an Enable macro (i.e __HAL_UART_ENABLE(__HANDLE__)). | |||
* @param __HANDLE__: specifies the UART Handle. | |||
* This parameter can be any USARTx (supporting the HW Flow control feature). | |||
* It is used to select the USART peripheral (USART availability and x value depending on device). | |||
* @retval None | |||
*/ | |||
#define __HAL_UART_HWCONTROL_RTS_ENABLE(__HANDLE__) \ | |||
do{ \ | |||
SET_BIT((__HANDLE__)->Instance->CR3, USART_CR3_RTSE); \ | |||
(__HANDLE__)->Init.HwFlowCtl |= USART_CR3_RTSE; \ | |||
} while(0) | |||
/** @brief Disable RTS flow control | |||
* This macro allows to disable RTS hardware flow control for a given UART instance, | |||
* without need to call HAL_UART_Init() function. | |||
* As involving direct access to UART registers, usage of this macro should be fully endorsed by user. | |||
* @note As macro is expected to be used for modifying RTS Hw flow control feature activation, without need | |||
* for USART instance Deinit/Init, following conditions for macro call should be fulfilled : | |||
* - UART instance should have already been initialised (through call of HAL_UART_Init() ) | |||
* - macro could only be called when corresponding UART instance is disabled (i.e __HAL_UART_DISABLE(__HANDLE__)) | |||
* and should be followed by an Enable macro (i.e __HAL_UART_ENABLE(__HANDLE__)). | |||
* @param __HANDLE__: specifies the UART Handle. | |||
* This parameter can be any USARTx (supporting the HW Flow control feature). | |||
* It is used to select the USART peripheral (USART availability and x value depending on device). | |||
* @retval None | |||
*/ | |||
#define __HAL_UART_HWCONTROL_RTS_DISABLE(__HANDLE__) \ | |||
do{ \ | |||
CLEAR_BIT((__HANDLE__)->Instance->CR3, USART_CR3_RTSE);\ | |||
(__HANDLE__)->Init.HwFlowCtl &= ~(USART_CR3_RTSE); \ | |||
} while(0) | |||
/** @brief Enable UART | |||
* @param __HANDLE__: specifies the UART Handle. | |||
* UART Handle selects the USARTx or UARTy peripheral | |||
* (USART,UART availability and x,y values depending on device). | |||
* @retval None | |||
*/ | |||
#define __HAL_UART_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR1 |= USART_CR1_UE) | |||
/** @brief Disable UART | |||
* UART Handle selects the USARTx or UARTy peripheral | |||
* (USART,UART availability and x,y values depending on device). | |||
* @retval None | |||
*/ | |||
#define __HAL_UART_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR1 &= ~USART_CR1_UE) | |||
/** | |||
* @} | |||
*/ | |||
/* Private macros --------------------------------------------------------*/ | |||
/** @defgroup UART_Private_Macros UART Private Macros | |||
* @{ | |||
*/ | |||
#define UART_CR1_REG_INDEX 1 | |||
#define UART_CR2_REG_INDEX 2 | |||
#define UART_CR3_REG_INDEX 3 | |||
#define UART_DIV_SAMPLING16(_PCLK_, _BAUD_) (((_PCLK_)*25)/(4*(_BAUD_))) | |||
#define UART_DIVMANT_SAMPLING16(_PCLK_, _BAUD_) (UART_DIV_SAMPLING16((_PCLK_), (_BAUD_))/100) | |||
#define UART_DIVFRAQ_SAMPLING16(_PCLK_, _BAUD_) (((UART_DIV_SAMPLING16((_PCLK_), (_BAUD_)) - (UART_DIVMANT_SAMPLING16((_PCLK_), (_BAUD_)) * 100)) * 16 + 50) / 100) | |||
/* UART BRR = mantissa + overflow + fraction | |||
= (UART DIVMANT << 4) + (UART DIVFRAQ & 0xF0) + (UART DIVFRAQ & 0x0F) */ | |||
#define UART_BRR_SAMPLING16(_PCLK_, _BAUD_) (((UART_DIVMANT_SAMPLING16((_PCLK_), (_BAUD_)) << 4) + \ | |||
(UART_DIVFRAQ_SAMPLING16((_PCLK_), (_BAUD_)) & 0xF0)) + \ | |||
(UART_DIVFRAQ_SAMPLING16((_PCLK_), (_BAUD_)) & 0x0F)) | |||
#define UART_DIV_SAMPLING8(_PCLK_, _BAUD_) (((_PCLK_)*25)/(2*(_BAUD_))) | |||
#define UART_DIVMANT_SAMPLING8(_PCLK_, _BAUD_) (UART_DIV_SAMPLING8((_PCLK_), (_BAUD_))/100) | |||
#define UART_DIVFRAQ_SAMPLING8(_PCLK_, _BAUD_) (((UART_DIV_SAMPLING8((_PCLK_), (_BAUD_)) - (UART_DIVMANT_SAMPLING8((_PCLK_), (_BAUD_)) * 100)) * 8 + 50) / 100) | |||
/* UART BRR = mantissa + overflow + fraction | |||
= (UART DIVMANT << 4) + ((UART DIVFRAQ & 0xF8) << 1) + (UART DIVFRAQ & 0x07) */ | |||
#define UART_BRR_SAMPLING8(_PCLK_, _BAUD_) (((UART_DIVMANT_SAMPLING8((_PCLK_), (_BAUD_)) << 4) + \ | |||
((UART_DIVFRAQ_SAMPLING8((_PCLK_), (_BAUD_)) & 0xF8) << 1)) + \ | |||
(UART_DIVFRAQ_SAMPLING8((_PCLK_), (_BAUD_)) & 0x07)) | |||
#define IS_UART_WORD_LENGTH(LENGTH) (((LENGTH) == UART_WORDLENGTH_8B) || \ | |||
((LENGTH) == UART_WORDLENGTH_9B)) | |||
#define IS_UART_LIN_WORD_LENGTH(LENGTH) ((LENGTH) == UART_WORDLENGTH_8B) | |||
#define IS_UART_STOPBITS(STOPBITS) (((STOPBITS) == UART_STOPBITS_1) || \ | |||
((STOPBITS) == UART_STOPBITS_2)) | |||
#define IS_UART_PARITY(PARITY) (((PARITY) == UART_PARITY_NONE) || \ | |||
((PARITY) == UART_PARITY_EVEN) || \ | |||
((PARITY) == UART_PARITY_ODD)) | |||
#define IS_UART_HARDWARE_FLOW_CONTROL(CONTROL)\ | |||
(((CONTROL) == UART_HWCONTROL_NONE) || \ | |||
((CONTROL) == UART_HWCONTROL_RTS) || \ | |||
((CONTROL) == UART_HWCONTROL_CTS) || \ | |||
((CONTROL) == UART_HWCONTROL_RTS_CTS)) | |||
#define IS_UART_MODE(MODE) ((((MODE) & (~((uint32_t)UART_MODE_TX_RX))) == 0x00U) && \ | |||
((MODE) != 0x00000000U)) | |||
#define IS_UART_STATE(STATE) (((STATE) == UART_STATE_DISABLE) || \ | |||
((STATE) == UART_STATE_ENABLE)) | |||
#define IS_UART_OVERSAMPLING(SAMPLING) (((SAMPLING) == UART_OVERSAMPLING_16) || \ | |||
((SAMPLING) == UART_OVERSAMPLING_8)) | |||
#define IS_UART_LIN_OVERSAMPLING(SAMPLING) ((SAMPLING) == UART_OVERSAMPLING_16) | |||
#define IS_UART_LIN_BREAK_DETECT_LENGTH(LENGTH) (((LENGTH) == UART_LINBREAKDETECTLENGTH_10B) || \ | |||
((LENGTH) == UART_LINBREAKDETECTLENGTH_11B)) | |||
#define IS_UART_WAKEUPMETHOD(WAKEUP) (((WAKEUP) == UART_WAKEUPMETHOD_IDLELINE) || \ | |||
((WAKEUP) == UART_WAKEUPMETHOD_ADDRESSMARK)) | |||
/** Check UART Baud rate | |||
* __BAUDRATE__: Baudrate specified by the user | |||
* The maximum Baud Rate is derived from the maximum clock on APB (i.e. 32 MHz) | |||
* divided by the smallest oversampling used on the USART (i.e. 8) | |||
* Return : TRUE or FALSE | |||
*/ | |||
#define IS_UART_BAUDRATE(__BAUDRATE__) ((__BAUDRATE__) < 4000001) | |||
/** Check UART Node Address | |||
* __ADDRESS__: UART Node address specified by the user | |||
* UART Node address is used in Multi processor communication for wakeup | |||
* with address mark detection. | |||
* This parameter must be a number between Min_Data = 0 and Max_Data = 15 | |||
* Return : TRUE or FALSE | |||
*/ | |||
#define IS_UART_ADDRESS(__ADDRESS__) ((__ADDRESS__) <= 0xF) | |||
/** UART interruptions flag mask | |||
*/ | |||
#define UART_IT_MASK ((uint32_t) USART_CR1_PEIE | USART_CR1_TXEIE | USART_CR1_TCIE | USART_CR1_RXNEIE | \ | |||
USART_CR1_IDLEIE | USART_CR2_LBDIE | USART_CR3_CTSIE | USART_CR3_EIE ) | |||
/** | |||
* @} | |||
*/ | |||
/* Exported functions --------------------------------------------------------*/ | |||
/** @addtogroup UART_Exported_Functions UART Exported Functions | |||
* @{ | |||
*/ | |||
/** @addtogroup UART_Exported_Functions_Group1 Initialization and de-initialization functions | |||
* @{ | |||
*/ | |||
/* Initialization and de-initialization functions ****************************/ | |||
HAL_StatusTypeDef HAL_UART_Init(UART_HandleTypeDef *huart); | |||
HAL_StatusTypeDef HAL_HalfDuplex_Init(UART_HandleTypeDef *huart); | |||
HAL_StatusTypeDef HAL_LIN_Init(UART_HandleTypeDef *huart, uint32_t BreakDetectLength); | |||
HAL_StatusTypeDef HAL_MultiProcessor_Init(UART_HandleTypeDef *huart, uint8_t Address, uint32_t WakeUpMethod); | |||
HAL_StatusTypeDef HAL_UART_DeInit (UART_HandleTypeDef *huart); | |||
void HAL_UART_MspInit(UART_HandleTypeDef *huart); | |||
void HAL_UART_MspDeInit(UART_HandleTypeDef *huart); | |||
/** | |||
* @} | |||
*/ | |||
/** @addtogroup UART_Exported_Functions_Group2 IO operation functions | |||
* @{ | |||
*/ | |||
/* IO operation functions *****************************************************/ | |||
HAL_StatusTypeDef HAL_UART_Transmit(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size, uint32_t Timeout); | |||
HAL_StatusTypeDef HAL_UART_Receive(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size, uint32_t Timeout); | |||
HAL_StatusTypeDef HAL_UART_Transmit_IT(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size); | |||
HAL_StatusTypeDef HAL_UART_Receive_IT(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size); | |||
HAL_StatusTypeDef HAL_UART_Transmit_DMA(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size); | |||
HAL_StatusTypeDef HAL_UART_Receive_DMA(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size); | |||
HAL_StatusTypeDef HAL_UART_DMAPause(UART_HandleTypeDef *huart); | |||
HAL_StatusTypeDef HAL_UART_DMAResume(UART_HandleTypeDef *huart); | |||
HAL_StatusTypeDef HAL_UART_DMAStop(UART_HandleTypeDef *huart); | |||
void HAL_UART_IRQHandler(UART_HandleTypeDef *huart); | |||
void HAL_UART_TxCpltCallback(UART_HandleTypeDef *huart); | |||
void HAL_UART_TxHalfCpltCallback(UART_HandleTypeDef *huart); | |||
void HAL_UART_RxCpltCallback(UART_HandleTypeDef *huart); | |||
void HAL_UART_RxHalfCpltCallback(UART_HandleTypeDef *huart); | |||
void HAL_UART_ErrorCallback(UART_HandleTypeDef *huart); | |||
/** | |||
* @} | |||
*/ | |||
/** @addtogroup UART_Exported_Functions_Group3 Peripheral Control functions | |||
* @{ | |||
*/ | |||
/* Peripheral Control functions ************************************************/ | |||
HAL_StatusTypeDef HAL_LIN_SendBreak(UART_HandleTypeDef *huart); | |||
HAL_StatusTypeDef HAL_MultiProcessor_EnterMuteMode(UART_HandleTypeDef *huart); | |||
HAL_StatusTypeDef HAL_MultiProcessor_ExitMuteMode(UART_HandleTypeDef *huart); | |||
HAL_StatusTypeDef HAL_HalfDuplex_EnableTransmitter(UART_HandleTypeDef *huart); | |||
HAL_StatusTypeDef HAL_HalfDuplex_EnableReceiver(UART_HandleTypeDef *huart); | |||
/** | |||
* @} | |||
*/ | |||
/** @addtogroup UART_Exported_Functions_Group4 Peripheral State and Errors functions | |||
* @{ | |||
*/ | |||
/* Peripheral State and Errors functions **************************************************/ | |||
HAL_UART_StateTypeDef HAL_UART_GetState(UART_HandleTypeDef *huart); | |||
uint32_t HAL_UART_GetError(UART_HandleTypeDef *huart); | |||
/** | |||
* @} | |||
*/ | |||
/** | |||
* @} | |||
*/ | |||
/** | |||
* @} | |||
*/ | |||
/** | |||
* @} | |||
*/ | |||
#ifdef __cplusplus | |||
} | |||
#endif | |||
#endif /* __STM32L1xx_HAL_UART_H */ | |||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ |
@@ -177,20 +177,6 @@ void PendSV_Handler(void) | |||
/* USER CODE END PendSV_IRQn 1 */ | |||
} | |||
/** | |||
* @brief This function handles System tick timer. | |||
*/ | |||
void SysTick_Handler(void) | |||
{ | |||
/* USER CODE BEGIN SysTick_IRQn 0 */ | |||
/* USER CODE END SysTick_IRQn 0 */ | |||
HAL_IncTick(); | |||
/* USER CODE BEGIN SysTick_IRQn 1 */ | |||
/* USER CODE END SysTick_IRQn 1 */ | |||
} | |||
/******************************************************************************/ | |||
/* STM32L1xx Peripheral Interrupt Handlers */ | |||
/* Add here the Interrupt Handlers for the used peripherals. */ | |||
@@ -274,8 +274,12 @@ typedef struct _USBD_HandleTypeDef | |||
#define LOBYTE(x) ((uint8_t)(x & 0x00FFU)) | |||
#define HIBYTE(x) ((uint8_t)((x & 0xFF00U) >> 8U)) | |||
#ifndef MIN | |||
#define MIN(a, b) (((a) < (b)) ? (a) : (b)) | |||
#endif | |||
#ifndef MAX | |||
#define MAX(a, b) (((a) > (b)) ? (a) : (b)) | |||
#endif | |||
#if defined ( __GNUC__ ) | |||
@@ -0,0 +1,62 @@ | |||
/*! | |||
* \file sysIrqHandlers.h | |||
* | |||
* \brief Default IRQ handlers | |||
* | |||
* \copyright Revised BSD License, see section \ref LICENSE. | |||
* | |||
* \code | |||
* ______ _ | |||
* / _____) _ | | | |||
* ( (____ _____ ____ _| |_ _____ ____| |__ | |||
* \____ \| ___ | (_ _) ___ |/ ___) _ \ | |||
* _____) ) ____| | | || |_| ____( (___| | | | | |||
* (______/|_____)_|_|_| \__)_____)\____)_| |_| | |||
* (C)2013-2020 Semtech | |||
* | |||
* \endcode | |||
*/ | |||
#ifndef SYS_IRQ_HANDLERS_H | |||
#define SYS_IRQ_HANDLERS_H | |||
#ifdef __cplusplus | |||
extern "C" { | |||
#endif | |||
void NMI_Handler( void ); | |||
void HardFault_Handler( void ); | |||
void MemManage_Handler( void ); | |||
void BusFault_Handler( void ); | |||
void UsageFault_Handler( void ); | |||
void DebugMon_Handler( void ); | |||
void SysTick_Handler( void ); | |||
void EXTI0_IRQHandler( void ); | |||
void EXTI1_IRQHandler( void ); | |||
void EXTI2_IRQHandler( void ); | |||
void EXTI3_IRQHandler( void ); | |||
void EXTI4_IRQHandler( void ); | |||
void EXTI9_5_IRQHandler( void ); | |||
void EXTI15_10_IRQHandler( void ); | |||
void RTC_Alarm_IRQHandler( void ); | |||
void USART2_IRQHandler( void ); | |||
#ifdef __cplusplus | |||
} | |||
#endif | |||
#endif // SYS_IRQ_HANDLERS_H |