diff --git a/peripherals/cc48x6/firmware/Drivers/CMSIS/Device/ST/STM32F0xx/Include/stm32f030x8.h b/peripherals/cc48x6/firmware/Drivers/CMSIS/Device/ST/STM32F0xx/Include/stm32f030x8.h
new file mode 100644
index 0000000..d784500
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Drivers/CMSIS/Device/ST/STM32F0xx/Include/stm32f030x8.h
@@ -0,0 +1,5435 @@
+/**
+ ******************************************************************************
+ * @file stm32f030x8.h
+ * @author MCD Application Team
+ * @brief CMSIS Cortex-M0 Device Peripheral Access Layer Header File.
+ * This file contains all the peripheral register's definitions, bits
+ * definitions and memory mapping for STM32F0xx devices.
+ *
+ * This file contains:
+ * - Data structures and the address mapping for all peripherals
+ * - Peripheral's registers declarations and bits definition
+ * - Macros to access peripherals registers hardware
+ *
+ ******************************************************************************
+ * @attention
+ *
+ *
© Copyright (c) 2016 STMicroelectronics.
+ * All rights reserved.
+ *
+ * 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
+ *
+ ******************************************************************************
+ */
+
+/** @addtogroup CMSIS
+ * @{
+ */
+
+/** @addtogroup stm32f030x8
+ * @{
+ */
+
+#ifndef __STM32F030x8_H
+#define __STM32F030x8_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif /* __cplusplus */
+
+/** @addtogroup Configuration_section_for_CMSIS
+ * @{
+ */
+/**
+ * @brief Configuration of the Cortex-M0 Processor and Core Peripherals
+ */
+#define __CM0_REV 0 /*!< Core Revision r0p0 */
+#define __MPU_PRESENT 0 /*!< STM32F0xx do not provide MPU */
+#define __NVIC_PRIO_BITS 2 /*!< STM32F0xx uses 2 Bits for the Priority Levels */
+#define __Vendor_SysTickConfig 0 /*!< Set to 1 if different SysTick Config is used */
+
+/**
+ * @}
+ */
+
+/** @addtogroup Peripheral_interrupt_number_definition
+ * @{
+ */
+
+/**
+ * @brief STM32F0xx Interrupt Number Definition, according to the selected device
+ * in @ref Library_configuration_section
+ */
+
+/*!< Interrupt Number Definition */
+typedef enum
+{
+/****** Cortex-M0 Processor Exceptions Numbers **************************************************************/
+ NonMaskableInt_IRQn = -14, /*!< 2 Non Maskable Interrupt */
+ HardFault_IRQn = -13, /*!< 3 Cortex-M0 Hard Fault Interrupt */
+ SVC_IRQn = -5, /*!< 11 Cortex-M0 SV Call Interrupt */
+ PendSV_IRQn = -2, /*!< 14 Cortex-M0 Pend SV Interrupt */
+ SysTick_IRQn = -1, /*!< 15 Cortex-M0 System Tick Interrupt */
+
+/****** STM32F0 specific Interrupt Numbers ******************************************************************/
+ WWDG_IRQn = 0, /*!< Window WatchDog Interrupt */
+ RTC_IRQn = 2, /*!< RTC Interrupt through EXTI Lines 17, 19 and 20 */
+ FLASH_IRQn = 3, /*!< FLASH global Interrupt */
+ RCC_IRQn = 4, /*!< RCC global Interrupt */
+ EXTI0_1_IRQn = 5, /*!< EXTI Line 0 and 1 Interrupt */
+ EXTI2_3_IRQn = 6, /*!< EXTI Line 2 and 3 Interrupt */
+ EXTI4_15_IRQn = 7, /*!< EXTI Line 4 to 15 Interrupt */
+ DMA1_Channel1_IRQn = 9, /*!< DMA1 Channel 1 Interrupt */
+ DMA1_Channel2_3_IRQn = 10, /*!< DMA1 Channel 2 and Channel 3 Interrupt */
+ DMA1_Channel4_5_IRQn = 11, /*!< DMA1 Channel 4 and Channel 5 Interrupt */
+ ADC1_IRQn = 12, /*!< ADC1 Interrupt */
+ TIM1_BRK_UP_TRG_COM_IRQn = 13, /*!< TIM1 Break, Update, Trigger and Commutation Interrupt */
+ TIM1_CC_IRQn = 14, /*!< TIM1 Capture Compare Interrupt */
+ TIM3_IRQn = 16, /*!< TIM3 global Interrupt */
+ TIM6_IRQn = 17, /*!< TIM6 global Interrupt */
+ TIM14_IRQn = 19, /*!< TIM14 global Interrupt */
+ TIM15_IRQn = 20, /*!< TIM15 global Interrupt */
+ TIM16_IRQn = 21, /*!< TIM16 global Interrupt */
+ TIM17_IRQn = 22, /*!< TIM17 global Interrupt */
+ I2C1_IRQn = 23, /*!< I2C1 Event Interrupt */
+ I2C2_IRQn = 24, /*!< I2C2 Event Interrupt */
+ SPI1_IRQn = 25, /*!< SPI1 global Interrupt */
+ SPI2_IRQn = 26, /*!< SPI2 global Interrupt */
+ USART1_IRQn = 27, /*!< USART1 global Interrupt */
+ USART2_IRQn = 28 /*!< USART2 global Interrupt */
+} IRQn_Type;
+
+/**
+ * @}
+ */
+
+#include "core_cm0.h" /* Cortex-M0 processor and core peripherals */
+#include "system_stm32f0xx.h" /* STM32F0xx System Header */
+#include
+
+/** @addtogroup Peripheral_registers_structures
+ * @{
+ */
+
+/**
+ * @brief Analog to Digital Converter
+ */
+
+typedef struct
+{
+ __IO uint32_t ISR; /*!< ADC interrupt and status register, Address offset: 0x00 */
+ __IO uint32_t IER; /*!< ADC interrupt enable register, Address offset: 0x04 */
+ __IO uint32_t CR; /*!< ADC control register, Address offset: 0x08 */
+ __IO uint32_t CFGR1; /*!< ADC configuration register 1, Address offset: 0x0C */
+ __IO uint32_t CFGR2; /*!< ADC configuration register 2, Address offset: 0x10 */
+ __IO uint32_t SMPR; /*!< ADC sampling time register, Address offset: 0x14 */
+ uint32_t RESERVED1; /*!< Reserved, 0x18 */
+ uint32_t RESERVED2; /*!< Reserved, 0x1C */
+ __IO uint32_t TR; /*!< ADC analog watchdog 1 threshold register, Address offset: 0x20 */
+ uint32_t RESERVED3; /*!< Reserved, 0x24 */
+ __IO uint32_t CHSELR; /*!< ADC group regular sequencer register, Address offset: 0x28 */
+ uint32_t RESERVED4[5]; /*!< Reserved, 0x2C */
+ __IO uint32_t DR; /*!< ADC group regular data register, Address offset: 0x40 */
+} ADC_TypeDef;
+
+typedef struct
+{
+ __IO uint32_t CCR; /*!< ADC common configuration register, Address offset: ADC1 base address + 0x308 */
+} ADC_Common_TypeDef;
+
+/**
+ * @brief CRC calculation unit
+ */
+
+typedef struct
+{
+ __IO uint32_t DR; /*!< CRC Data register, Address offset: 0x00 */
+ __IO uint8_t IDR; /*!< CRC Independent data register, Address offset: 0x04 */
+ uint8_t RESERVED0; /*!< Reserved, 0x05 */
+ uint16_t RESERVED1; /*!< Reserved, 0x06 */
+ __IO uint32_t CR; /*!< CRC Control register, Address offset: 0x08 */
+ uint32_t RESERVED2; /*!< Reserved, 0x0C */
+ __IO uint32_t INIT; /*!< Initial CRC value register, Address offset: 0x10 */
+ __IO uint32_t RESERVED3; /*!< Reserved, 0x14 */
+} CRC_TypeDef;
+
+/**
+ * @brief Debug MCU
+ */
+
+typedef struct
+{
+ __IO uint32_t IDCODE; /*!< MCU device ID code, Address offset: 0x00 */
+ __IO uint32_t CR; /*!< Debug MCU configuration register, Address offset: 0x04 */
+ __IO uint32_t APB1FZ; /*!< Debug MCU APB1 freeze register, Address offset: 0x08 */
+ __IO uint32_t APB2FZ; /*!< Debug MCU APB2 freeze register, Address offset: 0x0C */
+}DBGMCU_TypeDef;
+
+/**
+ * @brief DMA Controller
+ */
+
+typedef struct
+{
+ __IO uint32_t CCR; /*!< DMA channel x configuration register */
+ __IO uint32_t CNDTR; /*!< DMA channel x number of data register */
+ __IO uint32_t CPAR; /*!< DMA channel x peripheral address register */
+ __IO uint32_t CMAR; /*!< DMA channel x memory address register */
+} DMA_Channel_TypeDef;
+
+typedef struct
+{
+ __IO uint32_t ISR; /*!< DMA interrupt status register, Address offset: 0x00 */
+ __IO uint32_t IFCR; /*!< DMA interrupt flag clear register, Address offset: 0x04 */
+} DMA_TypeDef;
+
+/**
+ * @brief External Interrupt/Event Controller
+ */
+
+typedef struct
+{
+ __IO uint32_t IMR; /*!© Copyright (c) 2016 STMicroelectronics.
+ * All rights reserved.
+ *
+ * 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
+ *
+ ******************************************************************************
+ */
+
+/** @addtogroup CMSIS
+ * @{
+ */
+
+/** @addtogroup stm32f0xx
+ * @{
+ */
+
+#ifndef __STM32F0xx_H
+#define __STM32F0xx_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif /* __cplusplus */
+
+/** @addtogroup Library_configuration_section
+ * @{
+ */
+
+/**
+ * @brief STM32 Family
+ */
+#if !defined (STM32F0)
+#define STM32F0
+#endif /* STM32F0 */
+
+/** Uncomment the line below according to the target STM32 device used in your application.
+ * stm32f0xxxx.h file contains:
+ * - All the peripheral register's definitions, bits definitions and memory mapping for STM32F0xxxx devices
+ * - IRQ channel definition
+ * - Peripheral memory mapping and physical registers address definition
+ * - Peripheral pointer declaration and driver header file inclusion
+ * - Product miscellaneous configuration: assert macros
+ * Note: These CMSIS drivers (stm32f0xxxx.h) are always supporting features of the sub-familys superset.
+ */
+
+#if !defined (STM32F030x6) && !defined (STM32F030x8) && \
+ !defined (STM32F031x6) && !defined (STM32F038xx) && \
+ !defined (STM32F042x6) && !defined (STM32F048xx) && !defined (STM32F070x6) && \
+ !defined (STM32F051x8) && !defined (STM32F058xx) && \
+ !defined (STM32F071xB) && !defined (STM32F072xB) && !defined (STM32F078xx) && !defined (STM32F070xB) && \
+ !defined (STM32F091xC) && !defined (STM32F098xx) && !defined (STM32F030xC)
+ /* #define STM32F030x6 */ /*!< STM32F030x4, STM32F030x6 Devices (STM32F030xx microcontrollers where the Flash memory ranges between 16 and 32 Kbytes) */
+ /* #define STM32F030x8 */ /*!< STM32F030x8 Devices (STM32F030xx microcontrollers where the Flash memory is 64 Kbytes) */
+ /* #define STM32F031x6 */ /*!< STM32F031x4, STM32F031x6 Devices (STM32F031xx microcontrollers where the Flash memory ranges between 16 and 32 Kbytes) */
+ /* #define STM32F038xx */ /*!< STM32F038xx Devices (STM32F038xx microcontrollers where the Flash memory is 32 Kbytes) */
+ /* #define STM32F042x6 */ /*!< STM32F042x4, STM32F042x6 Devices (STM32F042xx microcontrollers where the Flash memory ranges between 16 and 32 Kbytes) */
+ /* #define STM32F048xx */ /*!< STM32F048xx Devices (STM32F048xx microcontrollers where the Flash memory is 32 Kbytes) */
+ /* #define STM32F051x8 */ /*!< STM32F051x4, STM32F051x6, STM32F051x8 Devices (STM32F051xx microcontrollers where the Flash memory ranges between 16 and 64 Kbytes) */
+ /* #define STM32F058xx */ /*!< STM32F058xx Devices (STM32F058xx microcontrollers where the Flash memory is 64 Kbytes) */
+ /* #define STM32F070x6 */ /*!< STM32F070x6 Devices (STM32F070x6 microcontrollers where the Flash memory ranges between 16 and 32 Kbytes) */
+ /* #define STM32F070xB */ /*!< STM32F070xB Devices (STM32F070xB microcontrollers where the Flash memory ranges between 64 and 128 Kbytes) */
+ /* #define STM32F071xB */ /*!< STM32F071x8, STM32F071xB Devices (STM32F071xx microcontrollers where the Flash memory ranges between 64 and 128 Kbytes) */
+ /* #define STM32F072xB */ /*!< STM32F072x8, STM32F072xB Devices (STM32F072xx microcontrollers where the Flash memory ranges between 64 and 128 Kbytes) */
+ /* #define STM32F078xx */ /*!< STM32F078xx Devices (STM32F078xx microcontrollers where the Flash memory is 128 Kbytes) */
+ /* #define STM32F030xC */ /*!< STM32F030xC Devices (STM32F030xC microcontrollers where the Flash memory is 256 Kbytes) */
+ /* #define STM32F091xC */ /*!< STM32F091xB, STM32F091xC Devices (STM32F091xx microcontrollers where the Flash memory ranges between 128 and 256 Kbytes) */
+ /* #define STM32F098xx */ /*!< STM32F098xx Devices (STM32F098xx microcontrollers where the Flash memory is 256 Kbytes) */
+#endif
+/* Legacy aliases */
+#if defined (STM32F048x6)
+ #define STM32F048xx
+#endif /* STM32F048x6 */
+
+/* Tip: To avoid modifying this file each time you need to switch between these
+ devices, you can define the device in your toolchain compiler preprocessor.
+ */
+#if !defined (USE_HAL_DRIVER)
+/**
+ * @brief Comment the line below if you will not use the peripherals drivers.
+ In this case, these drivers will not be included and the application code will
+ be based on direct access to peripherals registers
+ */
+ /*#define USE_HAL_DRIVER */
+#endif /* USE_HAL_DRIVER */
+
+/**
+ * @brief CMSIS Device version number V2.3.6
+ */
+#define __STM32F0_DEVICE_VERSION_MAIN (0x02) /*!< [31:24] main version */
+#define __STM32F0_DEVICE_VERSION_SUB1 (0x03) /*!< [23:16] sub1 version */
+#define __STM32F0_DEVICE_VERSION_SUB2 (0x06) /*!< [15:8] sub2 version */
+#define __STM32F0_DEVICE_VERSION_RC (0x00) /*!< [7:0] release candidate */
+#define __STM32F0_DEVICE_VERSION ((__STM32F0_DEVICE_VERSION_MAIN << 24)\
+ |(__STM32F0_DEVICE_VERSION_SUB1 << 16)\
+ |(__STM32F0_DEVICE_VERSION_SUB2 << 8 )\
+ |(__STM32F0_DEVICE_VERSION_RC))
+
+/**
+ * @}
+ */
+
+/** @addtogroup Device_Included
+ * @{
+ */
+
+#if defined(STM32F030x6)
+ #include "stm32f030x6.h"
+#elif defined(STM32F030x8)
+ #include "stm32f030x8.h"
+#elif defined(STM32F031x6)
+ #include "stm32f031x6.h"
+#elif defined(STM32F038xx)
+ #include "stm32f038xx.h"
+#elif defined(STM32F042x6)
+ #include "stm32f042x6.h"
+#elif defined(STM32F048xx)
+ #include "stm32f048xx.h"
+#elif defined(STM32F051x8)
+ #include "stm32f051x8.h"
+#elif defined(STM32F058xx)
+ #include "stm32f058xx.h"
+#elif defined(STM32F070x6)
+ #include "stm32f070x6.h"
+#elif defined(STM32F070xB)
+ #include "stm32f070xb.h"
+#elif defined(STM32F071xB)
+ #include "stm32f071xb.h"
+#elif defined(STM32F072xB)
+ #include "stm32f072xb.h"
+#elif defined(STM32F078xx)
+ #include "stm32f078xx.h"
+#elif defined(STM32F091xC)
+ #include "stm32f091xc.h"
+#elif defined(STM32F098xx)
+ #include "stm32f098xx.h"
+#elif defined(STM32F030xC)
+ #include "stm32f030xc.h"
+#else
+ #error "Please select first the target STM32F0xx device used in your application (in stm32f0xx.h file)"
+#endif
+
+/**
+ * @}
+ */
+
+/** @addtogroup Exported_types
+ * @{
+ */
+typedef enum
+{
+ RESET = 0U,
+ SET = !RESET
+} FlagStatus, ITStatus;
+
+typedef enum
+{
+ DISABLE = 0U,
+ ENABLE = !DISABLE
+} FunctionalState;
+#define IS_FUNCTIONAL_STATE(STATE) (((STATE) == DISABLE) || ((STATE) == ENABLE))
+
+typedef enum
+{
+ SUCCESS = 0U,
+ ERROR = !SUCCESS
+} ErrorStatus;
+
+/**
+ * @}
+ */
+
+
+/** @addtogroup Exported_macros
+ * @{
+ */
+#define SET_BIT(REG, BIT) ((REG) |= (BIT))
+
+#define CLEAR_BIT(REG, BIT) ((REG) &= ~(BIT))
+
+#define READ_BIT(REG, BIT) ((REG) & (BIT))
+
+#define CLEAR_REG(REG) ((REG) = (0x0))
+
+#define WRITE_REG(REG, VAL) ((REG) = (VAL))
+
+#define READ_REG(REG) ((REG))
+
+#define MODIFY_REG(REG, CLEARMASK, SETMASK) WRITE_REG((REG), (((READ_REG(REG)) & (~(CLEARMASK))) | (SETMASK)))
+
+/* Use of interrupt control for register exclusive access */
+/* Atomic 32-bit register access macro to set one or several bits */
+#define ATOMIC_SET_BIT(REG, BIT) \
+ do { \
+ uint32_t primask; \
+ primask = __get_PRIMASK(); \
+ __set_PRIMASK(1); \
+ SET_BIT((REG), (BIT)); \
+ __set_PRIMASK(primask); \
+ } while(0)
+
+/* Atomic 32-bit register access macro to clear one or several bits */
+#define ATOMIC_CLEAR_BIT(REG, BIT) \
+ do { \
+ uint32_t primask; \
+ primask = __get_PRIMASK(); \
+ __set_PRIMASK(1); \
+ CLEAR_BIT((REG), (BIT)); \
+ __set_PRIMASK(primask); \
+ } while(0)
+
+/* Atomic 32-bit register access macro to clear and set one or several bits */
+#define ATOMIC_MODIFY_REG(REG, CLEARMSK, SETMASK) \
+ do { \
+ uint32_t primask; \
+ primask = __get_PRIMASK(); \
+ __set_PRIMASK(1); \
+ MODIFY_REG((REG), (CLEARMSK), (SETMASK)); \
+ __set_PRIMASK(primask); \
+ } while(0)
+
+/* Atomic 16-bit register access macro to set one or several bits */
+#define ATOMIC_SETH_BIT(REG, BIT) ATOMIC_SET_BIT(REG, BIT) \
+
+/* Atomic 16-bit register access macro to clear one or several bits */
+#define ATOMIC_CLEARH_BIT(REG, BIT) ATOMIC_CLEAR_BIT(REG, BIT) \
+
+/* Atomic 16-bit register access macro to clear and set one or several bits */
+#define ATOMIC_MODIFYH_REG(REG, CLEARMSK, SETMASK) ATOMIC_MODIFY_REG(REG, CLEARMSK, SETMASK) \
+
+/**
+ * @}
+ */
+
+#if defined (USE_HAL_DRIVER)
+ #include "stm32f0xx_hal.h"
+#endif /* USE_HAL_DRIVER */
+
+
+#ifdef __cplusplus
+}
+#endif /* __cplusplus */
+
+#endif /* __STM32F0xx_H */
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+
+
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/peripherals/cc48x6/firmware/Drivers/CMSIS/Device/ST/STM32F0xx/Include/system_stm32f0xx.h b/peripherals/cc48x6/firmware/Drivers/CMSIS/Device/ST/STM32F0xx/Include/system_stm32f0xx.h
new file mode 100644
index 0000000..3b71cfe
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Drivers/CMSIS/Device/ST/STM32F0xx/Include/system_stm32f0xx.h
@@ -0,0 +1,105 @@
+/**
+ ******************************************************************************
+ * @file system_stm32f0xx.h
+ * @author MCD Application Team
+ * @brief CMSIS Cortex-M0 Device System Source File for STM32F0xx devices.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2016 STMicroelectronics.
+ * All rights reserved.
+ *
+ * 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
+ *
+ ******************************************************************************
+ */
+
+/** @addtogroup CMSIS
+ * @{
+ */
+
+/** @addtogroup stm32f0xx_system
+ * @{
+ */
+
+/**
+ * @brief Define to prevent recursive inclusion
+ */
+#ifndef __SYSTEM_STM32F0XX_H
+#define __SYSTEM_STM32F0XX_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/** @addtogroup STM32F0xx_System_Includes
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+
+/** @addtogroup STM32F0xx_System_Exported_types
+ * @{
+ */
+ /* This variable is updated in three ways:
+ 1) by calling CMSIS function SystemCoreClockUpdate()
+ 3) by calling HAL API function HAL_RCC_GetHCLKFreq()
+ 3) by calling HAL API function HAL_RCC_ClockConfig()
+ Note: If you use this function to configure the system clock; then there
+ is no need to call the 2 first functions listed above, since SystemCoreClock
+ variable is updated automatically.
+ */
+extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */
+extern const uint8_t AHBPrescTable[16]; /*!< AHB prescalers table values */
+extern const uint8_t APBPrescTable[8]; /*!< APB prescalers table values */
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F0xx_System_Exported_Constants
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F0xx_System_Exported_Macros
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F0xx_System_Exported_Functions
+ * @{
+ */
+
+extern void SystemInit(void);
+extern void SystemCoreClockUpdate(void);
+/**
+ * @}
+ */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /*__SYSTEM_STM32F0XX_H */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/peripherals/cc48x6/firmware/Drivers/CMSIS/Include/cmsis_compiler.h b/peripherals/cc48x6/firmware/Drivers/CMSIS/Include/cmsis_compiler.h
new file mode 100644
index 0000000..94212eb
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Drivers/CMSIS/Include/cmsis_compiler.h
@@ -0,0 +1,266 @@
+/**************************************************************************//**
+ * @file cmsis_compiler.h
+ * @brief CMSIS compiler generic header file
+ * @version V5.0.4
+ * @date 10. January 2018
+ ******************************************************************************/
+/*
+ * Copyright (c) 2009-2018 Arm Limited. All rights reserved.
+ *
+ * SPDX-License-Identifier: Apache-2.0
+ *
+ * Licensed under the Apache License, Version 2.0 (the License); you may
+ * not use this file except in compliance with the License.
+ * You may obtain a copy of the License at
+ *
+ * www.apache.org/licenses/LICENSE-2.0
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an AS IS BASIS, WITHOUT
+ * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+ * See the License for the specific language governing permissions and
+ * limitations under the License.
+ */
+
+#ifndef __CMSIS_COMPILER_H
+#define __CMSIS_COMPILER_H
+
+#include
+
+/*
+ * Arm Compiler 4/5
+ */
+#if defined ( __CC_ARM )
+ #include "cmsis_armcc.h"
+
+
+/*
+ * Arm Compiler 6 (armclang)
+ */
+#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
+ #include "cmsis_armclang.h"
+
+
+/*
+ * GNU Compiler
+ */
+#elif defined ( __GNUC__ )
+ #include "cmsis_gcc.h"
+
+
+/*
+ * IAR Compiler
+ */
+#elif defined ( __ICCARM__ )
+ #include
+
+
+/*
+ * TI Arm Compiler
+ */
+#elif defined ( __TI_ARM__ )
+ #include
+
+ #ifndef __ASM
+ #define __ASM __asm
+ #endif
+ #ifndef __INLINE
+ #define __INLINE inline
+ #endif
+ #ifndef __STATIC_INLINE
+ #define __STATIC_INLINE static inline
+ #endif
+ #ifndef __STATIC_FORCEINLINE
+ #define __STATIC_FORCEINLINE __STATIC_INLINE
+ #endif
+ #ifndef __NO_RETURN
+ #define __NO_RETURN __attribute__((noreturn))
+ #endif
+ #ifndef __USED
+ #define __USED __attribute__((used))
+ #endif
+ #ifndef __WEAK
+ #define __WEAK __attribute__((weak))
+ #endif
+ #ifndef __PACKED
+ #define __PACKED __attribute__((packed))
+ #endif
+ #ifndef __PACKED_STRUCT
+ #define __PACKED_STRUCT struct __attribute__((packed))
+ #endif
+ #ifndef __PACKED_UNION
+ #define __PACKED_UNION union __attribute__((packed))
+ #endif
+ #ifndef __UNALIGNED_UINT32 /* deprecated */
+ struct __attribute__((packed)) T_UINT32 { uint32_t v; };
+ #define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v)
+ #endif
+ #ifndef __UNALIGNED_UINT16_WRITE
+ __PACKED_STRUCT T_UINT16_WRITE { uint16_t v; };
+ #define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void*)(addr))->v) = (val))
+ #endif
+ #ifndef __UNALIGNED_UINT16_READ
+ __PACKED_STRUCT T_UINT16_READ { uint16_t v; };
+ #define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v)
+ #endif
+ #ifndef __UNALIGNED_UINT32_WRITE
+ __PACKED_STRUCT T_UINT32_WRITE { uint32_t v; };
+ #define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val))
+ #endif
+ #ifndef __UNALIGNED_UINT32_READ
+ __PACKED_STRUCT T_UINT32_READ { uint32_t v; };
+ #define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v)
+ #endif
+ #ifndef __ALIGNED
+ #define __ALIGNED(x) __attribute__((aligned(x)))
+ #endif
+ #ifndef __RESTRICT
+ #warning No compiler specific solution for __RESTRICT. __RESTRICT is ignored.
+ #define __RESTRICT
+ #endif
+
+
+/*
+ * TASKING Compiler
+ */
+#elif defined ( __TASKING__ )
+ /*
+ * The CMSIS functions have been implemented as intrinsics in the compiler.
+ * Please use "carm -?i" to get an up to date list of all intrinsics,
+ * Including the CMSIS ones.
+ */
+
+ #ifndef __ASM
+ #define __ASM __asm
+ #endif
+ #ifndef __INLINE
+ #define __INLINE inline
+ #endif
+ #ifndef __STATIC_INLINE
+ #define __STATIC_INLINE static inline
+ #endif
+ #ifndef __STATIC_FORCEINLINE
+ #define __STATIC_FORCEINLINE __STATIC_INLINE
+ #endif
+ #ifndef __NO_RETURN
+ #define __NO_RETURN __attribute__((noreturn))
+ #endif
+ #ifndef __USED
+ #define __USED __attribute__((used))
+ #endif
+ #ifndef __WEAK
+ #define __WEAK __attribute__((weak))
+ #endif
+ #ifndef __PACKED
+ #define __PACKED __packed__
+ #endif
+ #ifndef __PACKED_STRUCT
+ #define __PACKED_STRUCT struct __packed__
+ #endif
+ #ifndef __PACKED_UNION
+ #define __PACKED_UNION union __packed__
+ #endif
+ #ifndef __UNALIGNED_UINT32 /* deprecated */
+ struct __packed__ T_UINT32 { uint32_t v; };
+ #define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v)
+ #endif
+ #ifndef __UNALIGNED_UINT16_WRITE
+ __PACKED_STRUCT T_UINT16_WRITE { uint16_t v; };
+ #define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void *)(addr))->v) = (val))
+ #endif
+ #ifndef __UNALIGNED_UINT16_READ
+ __PACKED_STRUCT T_UINT16_READ { uint16_t v; };
+ #define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v)
+ #endif
+ #ifndef __UNALIGNED_UINT32_WRITE
+ __PACKED_STRUCT T_UINT32_WRITE { uint32_t v; };
+ #define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val))
+ #endif
+ #ifndef __UNALIGNED_UINT32_READ
+ __PACKED_STRUCT T_UINT32_READ { uint32_t v; };
+ #define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v)
+ #endif
+ #ifndef __ALIGNED
+ #define __ALIGNED(x) __align(x)
+ #endif
+ #ifndef __RESTRICT
+ #warning No compiler specific solution for __RESTRICT. __RESTRICT is ignored.
+ #define __RESTRICT
+ #endif
+
+
+/*
+ * COSMIC Compiler
+ */
+#elif defined ( __CSMC__ )
+ #include
+
+ #ifndef __ASM
+ #define __ASM _asm
+ #endif
+ #ifndef __INLINE
+ #define __INLINE inline
+ #endif
+ #ifndef __STATIC_INLINE
+ #define __STATIC_INLINE static inline
+ #endif
+ #ifndef __STATIC_FORCEINLINE
+ #define __STATIC_FORCEINLINE __STATIC_INLINE
+ #endif
+ #ifndef __NO_RETURN
+ // NO RETURN is automatically detected hence no warning here
+ #define __NO_RETURN
+ #endif
+ #ifndef __USED
+ #warning No compiler specific solution for __USED. __USED is ignored.
+ #define __USED
+ #endif
+ #ifndef __WEAK
+ #define __WEAK __weak
+ #endif
+ #ifndef __PACKED
+ #define __PACKED @packed
+ #endif
+ #ifndef __PACKED_STRUCT
+ #define __PACKED_STRUCT @packed struct
+ #endif
+ #ifndef __PACKED_UNION
+ #define __PACKED_UNION @packed union
+ #endif
+ #ifndef __UNALIGNED_UINT32 /* deprecated */
+ @packed struct T_UINT32 { uint32_t v; };
+ #define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v)
+ #endif
+ #ifndef __UNALIGNED_UINT16_WRITE
+ __PACKED_STRUCT T_UINT16_WRITE { uint16_t v; };
+ #define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void *)(addr))->v) = (val))
+ #endif
+ #ifndef __UNALIGNED_UINT16_READ
+ __PACKED_STRUCT T_UINT16_READ { uint16_t v; };
+ #define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v)
+ #endif
+ #ifndef __UNALIGNED_UINT32_WRITE
+ __PACKED_STRUCT T_UINT32_WRITE { uint32_t v; };
+ #define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val))
+ #endif
+ #ifndef __UNALIGNED_UINT32_READ
+ __PACKED_STRUCT T_UINT32_READ { uint32_t v; };
+ #define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v)
+ #endif
+ #ifndef __ALIGNED
+ #warning No compiler specific solution for __ALIGNED. __ALIGNED is ignored.
+ #define __ALIGNED(x)
+ #endif
+ #ifndef __RESTRICT
+ #warning No compiler specific solution for __RESTRICT. __RESTRICT is ignored.
+ #define __RESTRICT
+ #endif
+
+
+#else
+ #error Unknown compiler.
+#endif
+
+
+#endif /* __CMSIS_COMPILER_H */
+
diff --git a/peripherals/cc48x6/firmware/Drivers/CMSIS/Include/cmsis_gcc.h b/peripherals/cc48x6/firmware/Drivers/CMSIS/Include/cmsis_gcc.h
new file mode 100644
index 0000000..2d9db15
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Drivers/CMSIS/Include/cmsis_gcc.h
@@ -0,0 +1,2085 @@
+/**************************************************************************//**
+ * @file cmsis_gcc.h
+ * @brief CMSIS compiler GCC header file
+ * @version V5.0.4
+ * @date 09. April 2018
+ ******************************************************************************/
+/*
+ * Copyright (c) 2009-2018 Arm Limited. All rights reserved.
+ *
+ * SPDX-License-Identifier: Apache-2.0
+ *
+ * Licensed under the Apache License, Version 2.0 (the License); you may
+ * not use this file except in compliance with the License.
+ * You may obtain a copy of the License at
+ *
+ * www.apache.org/licenses/LICENSE-2.0
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an AS IS BASIS, WITHOUT
+ * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+ * See the License for the specific language governing permissions and
+ * limitations under the License.
+ */
+
+#ifndef __CMSIS_GCC_H
+#define __CMSIS_GCC_H
+
+/* ignore some GCC warnings */
+#pragma GCC diagnostic push
+#pragma GCC diagnostic ignored "-Wsign-conversion"
+#pragma GCC diagnostic ignored "-Wconversion"
+#pragma GCC diagnostic ignored "-Wunused-parameter"
+
+/* Fallback for __has_builtin */
+#ifndef __has_builtin
+ #define __has_builtin(x) (0)
+#endif
+
+/* CMSIS compiler specific defines */
+#ifndef __ASM
+ #define __ASM __asm
+#endif
+#ifndef __INLINE
+ #define __INLINE inline
+#endif
+#ifndef __STATIC_INLINE
+ #define __STATIC_INLINE static inline
+#endif
+#ifndef __STATIC_FORCEINLINE
+ #define __STATIC_FORCEINLINE __attribute__((always_inline)) static inline
+#endif
+#ifndef __NO_RETURN
+ #define __NO_RETURN __attribute__((__noreturn__))
+#endif
+#ifndef __USED
+ #define __USED __attribute__((used))
+#endif
+#ifndef __WEAK
+ #define __WEAK __attribute__((weak))
+#endif
+#ifndef __PACKED
+ #define __PACKED __attribute__((packed, aligned(1)))
+#endif
+#ifndef __PACKED_STRUCT
+ #define __PACKED_STRUCT struct __attribute__((packed, aligned(1)))
+#endif
+#ifndef __PACKED_UNION
+ #define __PACKED_UNION union __attribute__((packed, aligned(1)))
+#endif
+#ifndef __UNALIGNED_UINT32 /* deprecated */
+ #pragma GCC diagnostic push
+ #pragma GCC diagnostic ignored "-Wpacked"
+ #pragma GCC diagnostic ignored "-Wattributes"
+ struct __attribute__((packed)) T_UINT32 { uint32_t v; };
+ #pragma GCC diagnostic pop
+ #define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v)
+#endif
+#ifndef __UNALIGNED_UINT16_WRITE
+ #pragma GCC diagnostic push
+ #pragma GCC diagnostic ignored "-Wpacked"
+ #pragma GCC diagnostic ignored "-Wattributes"
+ __PACKED_STRUCT T_UINT16_WRITE { uint16_t v; };
+ #pragma GCC diagnostic pop
+ #define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void *)(addr))->v) = (val))
+#endif
+#ifndef __UNALIGNED_UINT16_READ
+ #pragma GCC diagnostic push
+ #pragma GCC diagnostic ignored "-Wpacked"
+ #pragma GCC diagnostic ignored "-Wattributes"
+ __PACKED_STRUCT T_UINT16_READ { uint16_t v; };
+ #pragma GCC diagnostic pop
+ #define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v)
+#endif
+#ifndef __UNALIGNED_UINT32_WRITE
+ #pragma GCC diagnostic push
+ #pragma GCC diagnostic ignored "-Wpacked"
+ #pragma GCC diagnostic ignored "-Wattributes"
+ __PACKED_STRUCT T_UINT32_WRITE { uint32_t v; };
+ #pragma GCC diagnostic pop
+ #define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val))
+#endif
+#ifndef __UNALIGNED_UINT32_READ
+ #pragma GCC diagnostic push
+ #pragma GCC diagnostic ignored "-Wpacked"
+ #pragma GCC diagnostic ignored "-Wattributes"
+ __PACKED_STRUCT T_UINT32_READ { uint32_t v; };
+ #pragma GCC diagnostic pop
+ #define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v)
+#endif
+#ifndef __ALIGNED
+ #define __ALIGNED(x) __attribute__((aligned(x)))
+#endif
+#ifndef __RESTRICT
+ #define __RESTRICT __restrict
+#endif
+
+
+/* ########################### Core Function Access ########################### */
+/** \ingroup CMSIS_Core_FunctionInterface
+ \defgroup CMSIS_Core_RegAccFunctions CMSIS Core Register Access Functions
+ @{
+ */
+
+/**
+ \brief Enable IRQ Interrupts
+ \details Enables IRQ interrupts by clearing the I-bit in the CPSR.
+ Can only be executed in Privileged modes.
+ */
+__STATIC_FORCEINLINE void __enable_irq(void)
+{
+ __ASM volatile ("cpsie i" : : : "memory");
+}
+
+
+/**
+ \brief Disable IRQ Interrupts
+ \details Disables IRQ interrupts by setting the I-bit in the CPSR.
+ Can only be executed in Privileged modes.
+ */
+__STATIC_FORCEINLINE void __disable_irq(void)
+{
+ __ASM volatile ("cpsid i" : : : "memory");
+}
+
+
+/**
+ \brief Get Control Register
+ \details Returns the content of the Control Register.
+ \return Control Register value
+ */
+__STATIC_FORCEINLINE uint32_t __get_CONTROL(void)
+{
+ uint32_t result;
+
+ __ASM volatile ("MRS %0, control" : "=r" (result) );
+ return(result);
+}
+
+
+#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3))
+/**
+ \brief Get Control Register (non-secure)
+ \details Returns the content of the non-secure Control Register when in secure mode.
+ \return non-secure Control Register value
+ */
+__STATIC_FORCEINLINE uint32_t __TZ_get_CONTROL_NS(void)
+{
+ uint32_t result;
+
+ __ASM volatile ("MRS %0, control_ns" : "=r" (result) );
+ return(result);
+}
+#endif
+
+
+/**
+ \brief Set Control Register
+ \details Writes the given value to the Control Register.
+ \param [in] control Control Register value to set
+ */
+__STATIC_FORCEINLINE void __set_CONTROL(uint32_t control)
+{
+ __ASM volatile ("MSR control, %0" : : "r" (control) : "memory");
+}
+
+
+#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3))
+/**
+ \brief Set Control Register (non-secure)
+ \details Writes the given value to the non-secure Control Register when in secure state.
+ \param [in] control Control Register value to set
+ */
+__STATIC_FORCEINLINE void __TZ_set_CONTROL_NS(uint32_t control)
+{
+ __ASM volatile ("MSR control_ns, %0" : : "r" (control) : "memory");
+}
+#endif
+
+
+/**
+ \brief Get IPSR Register
+ \details Returns the content of the IPSR Register.
+ \return IPSR Register value
+ */
+__STATIC_FORCEINLINE uint32_t __get_IPSR(void)
+{
+ uint32_t result;
+
+ __ASM volatile ("MRS %0, ipsr" : "=r" (result) );
+ return(result);
+}
+
+
+/**
+ \brief Get APSR Register
+ \details Returns the content of the APSR Register.
+ \return APSR Register value
+ */
+__STATIC_FORCEINLINE uint32_t __get_APSR(void)
+{
+ uint32_t result;
+
+ __ASM volatile ("MRS %0, apsr" : "=r" (result) );
+ return(result);
+}
+
+
+/**
+ \brief Get xPSR Register
+ \details Returns the content of the xPSR Register.
+ \return xPSR Register value
+ */
+__STATIC_FORCEINLINE uint32_t __get_xPSR(void)
+{
+ uint32_t result;
+
+ __ASM volatile ("MRS %0, xpsr" : "=r" (result) );
+ return(result);
+}
+
+
+/**
+ \brief Get Process Stack Pointer
+ \details Returns the current value of the Process Stack Pointer (PSP).
+ \return PSP Register value
+ */
+__STATIC_FORCEINLINE uint32_t __get_PSP(void)
+{
+ uint32_t result;
+
+ __ASM volatile ("MRS %0, psp" : "=r" (result) );
+ return(result);
+}
+
+
+#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3))
+/**
+ \brief Get Process Stack Pointer (non-secure)
+ \details Returns the current value of the non-secure Process Stack Pointer (PSP) when in secure state.
+ \return PSP Register value
+ */
+__STATIC_FORCEINLINE uint32_t __TZ_get_PSP_NS(void)
+{
+ uint32_t result;
+
+ __ASM volatile ("MRS %0, psp_ns" : "=r" (result) );
+ return(result);
+}
+#endif
+
+
+/**
+ \brief Set Process Stack Pointer
+ \details Assigns the given value to the Process Stack Pointer (PSP).
+ \param [in] topOfProcStack Process Stack Pointer value to set
+ */
+__STATIC_FORCEINLINE void __set_PSP(uint32_t topOfProcStack)
+{
+ __ASM volatile ("MSR psp, %0" : : "r" (topOfProcStack) : );
+}
+
+
+#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3))
+/**
+ \brief Set Process Stack Pointer (non-secure)
+ \details Assigns the given value to the non-secure Process Stack Pointer (PSP) when in secure state.
+ \param [in] topOfProcStack Process Stack Pointer value to set
+ */
+__STATIC_FORCEINLINE void __TZ_set_PSP_NS(uint32_t topOfProcStack)
+{
+ __ASM volatile ("MSR psp_ns, %0" : : "r" (topOfProcStack) : );
+}
+#endif
+
+
+/**
+ \brief Get Main Stack Pointer
+ \details Returns the current value of the Main Stack Pointer (MSP).
+ \return MSP Register value
+ */
+__STATIC_FORCEINLINE uint32_t __get_MSP(void)
+{
+ uint32_t result;
+
+ __ASM volatile ("MRS %0, msp" : "=r" (result) );
+ return(result);
+}
+
+
+#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3))
+/**
+ \brief Get Main Stack Pointer (non-secure)
+ \details Returns the current value of the non-secure Main Stack Pointer (MSP) when in secure state.
+ \return MSP Register value
+ */
+__STATIC_FORCEINLINE uint32_t __TZ_get_MSP_NS(void)
+{
+ uint32_t result;
+
+ __ASM volatile ("MRS %0, msp_ns" : "=r" (result) );
+ return(result);
+}
+#endif
+
+
+/**
+ \brief Set Main Stack Pointer
+ \details Assigns the given value to the Main Stack Pointer (MSP).
+ \param [in] topOfMainStack Main Stack Pointer value to set
+ */
+__STATIC_FORCEINLINE void __set_MSP(uint32_t topOfMainStack)
+{
+ __ASM volatile ("MSR msp, %0" : : "r" (topOfMainStack) : );
+}
+
+
+#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3))
+/**
+ \brief Set Main Stack Pointer (non-secure)
+ \details Assigns the given value to the non-secure Main Stack Pointer (MSP) when in secure state.
+ \param [in] topOfMainStack Main Stack Pointer value to set
+ */
+__STATIC_FORCEINLINE void __TZ_set_MSP_NS(uint32_t topOfMainStack)
+{
+ __ASM volatile ("MSR msp_ns, %0" : : "r" (topOfMainStack) : );
+}
+#endif
+
+
+#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3))
+/**
+ \brief Get Stack Pointer (non-secure)
+ \details Returns the current value of the non-secure Stack Pointer (SP) when in secure state.
+ \return SP Register value
+ */
+__STATIC_FORCEINLINE uint32_t __TZ_get_SP_NS(void)
+{
+ uint32_t result;
+
+ __ASM volatile ("MRS %0, sp_ns" : "=r" (result) );
+ return(result);
+}
+
+
+/**
+ \brief Set Stack Pointer (non-secure)
+ \details Assigns the given value to the non-secure Stack Pointer (SP) when in secure state.
+ \param [in] topOfStack Stack Pointer value to set
+ */
+__STATIC_FORCEINLINE void __TZ_set_SP_NS(uint32_t topOfStack)
+{
+ __ASM volatile ("MSR sp_ns, %0" : : "r" (topOfStack) : );
+}
+#endif
+
+
+/**
+ \brief Get Priority Mask
+ \details Returns the current state of the priority mask bit from the Priority Mask Register.
+ \return Priority Mask value
+ */
+__STATIC_FORCEINLINE uint32_t __get_PRIMASK(void)
+{
+ uint32_t result;
+
+ __ASM volatile ("MRS %0, primask" : "=r" (result) :: "memory");
+ return(result);
+}
+
+
+#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3))
+/**
+ \brief Get Priority Mask (non-secure)
+ \details Returns the current state of the non-secure priority mask bit from the Priority Mask Register when in secure state.
+ \return Priority Mask value
+ */
+__STATIC_FORCEINLINE uint32_t __TZ_get_PRIMASK_NS(void)
+{
+ uint32_t result;
+
+ __ASM volatile ("MRS %0, primask_ns" : "=r" (result) :: "memory");
+ return(result);
+}
+#endif
+
+
+/**
+ \brief Set Priority Mask
+ \details Assigns the given value to the Priority Mask Register.
+ \param [in] priMask Priority Mask
+ */
+__STATIC_FORCEINLINE void __set_PRIMASK(uint32_t priMask)
+{
+ __ASM volatile ("MSR primask, %0" : : "r" (priMask) : "memory");
+}
+
+
+#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3))
+/**
+ \brief Set Priority Mask (non-secure)
+ \details Assigns the given value to the non-secure Priority Mask Register when in secure state.
+ \param [in] priMask Priority Mask
+ */
+__STATIC_FORCEINLINE void __TZ_set_PRIMASK_NS(uint32_t priMask)
+{
+ __ASM volatile ("MSR primask_ns, %0" : : "r" (priMask) : "memory");
+}
+#endif
+
+
+#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \
+ (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \
+ (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) )
+/**
+ \brief Enable FIQ
+ \details Enables FIQ interrupts by clearing the F-bit in the CPSR.
+ Can only be executed in Privileged modes.
+ */
+__STATIC_FORCEINLINE void __enable_fault_irq(void)
+{
+ __ASM volatile ("cpsie f" : : : "memory");
+}
+
+
+/**
+ \brief Disable FIQ
+ \details Disables FIQ interrupts by setting the F-bit in the CPSR.
+ Can only be executed in Privileged modes.
+ */
+__STATIC_FORCEINLINE void __disable_fault_irq(void)
+{
+ __ASM volatile ("cpsid f" : : : "memory");
+}
+
+
+/**
+ \brief Get Base Priority
+ \details Returns the current value of the Base Priority register.
+ \return Base Priority register value
+ */
+__STATIC_FORCEINLINE uint32_t __get_BASEPRI(void)
+{
+ uint32_t result;
+
+ __ASM volatile ("MRS %0, basepri" : "=r" (result) );
+ return(result);
+}
+
+
+#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3))
+/**
+ \brief Get Base Priority (non-secure)
+ \details Returns the current value of the non-secure Base Priority register when in secure state.
+ \return Base Priority register value
+ */
+__STATIC_FORCEINLINE uint32_t __TZ_get_BASEPRI_NS(void)
+{
+ uint32_t result;
+
+ __ASM volatile ("MRS %0, basepri_ns" : "=r" (result) );
+ return(result);
+}
+#endif
+
+
+/**
+ \brief Set Base Priority
+ \details Assigns the given value to the Base Priority register.
+ \param [in] basePri Base Priority value to set
+ */
+__STATIC_FORCEINLINE void __set_BASEPRI(uint32_t basePri)
+{
+ __ASM volatile ("MSR basepri, %0" : : "r" (basePri) : "memory");
+}
+
+
+#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3))
+/**
+ \brief Set Base Priority (non-secure)
+ \details Assigns the given value to the non-secure Base Priority register when in secure state.
+ \param [in] basePri Base Priority value to set
+ */
+__STATIC_FORCEINLINE void __TZ_set_BASEPRI_NS(uint32_t basePri)
+{
+ __ASM volatile ("MSR basepri_ns, %0" : : "r" (basePri) : "memory");
+}
+#endif
+
+
+/**
+ \brief Set Base Priority with condition
+ \details Assigns the given value to the Base Priority register only if BASEPRI masking is disabled,
+ or the new value increases the BASEPRI priority level.
+ \param [in] basePri Base Priority value to set
+ */
+__STATIC_FORCEINLINE void __set_BASEPRI_MAX(uint32_t basePri)
+{
+ __ASM volatile ("MSR basepri_max, %0" : : "r" (basePri) : "memory");
+}
+
+
+/**
+ \brief Get Fault Mask
+ \details Returns the current value of the Fault Mask register.
+ \return Fault Mask register value
+ */
+__STATIC_FORCEINLINE uint32_t __get_FAULTMASK(void)
+{
+ uint32_t result;
+
+ __ASM volatile ("MRS %0, faultmask" : "=r" (result) );
+ return(result);
+}
+
+
+#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3))
+/**
+ \brief Get Fault Mask (non-secure)
+ \details Returns the current value of the non-secure Fault Mask register when in secure state.
+ \return Fault Mask register value
+ */
+__STATIC_FORCEINLINE uint32_t __TZ_get_FAULTMASK_NS(void)
+{
+ uint32_t result;
+
+ __ASM volatile ("MRS %0, faultmask_ns" : "=r" (result) );
+ return(result);
+}
+#endif
+
+
+/**
+ \brief Set Fault Mask
+ \details Assigns the given value to the Fault Mask register.
+ \param [in] faultMask Fault Mask value to set
+ */
+__STATIC_FORCEINLINE void __set_FAULTMASK(uint32_t faultMask)
+{
+ __ASM volatile ("MSR faultmask, %0" : : "r" (faultMask) : "memory");
+}
+
+
+#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3))
+/**
+ \brief Set Fault Mask (non-secure)
+ \details Assigns the given value to the non-secure Fault Mask register when in secure state.
+ \param [in] faultMask Fault Mask value to set
+ */
+__STATIC_FORCEINLINE void __TZ_set_FAULTMASK_NS(uint32_t faultMask)
+{
+ __ASM volatile ("MSR faultmask_ns, %0" : : "r" (faultMask) : "memory");
+}
+#endif
+
+#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \
+ (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \
+ (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) */
+
+
+#if ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \
+ (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) )
+
+/**
+ \brief Get Process Stack Pointer Limit
+ Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure
+ Stack Pointer Limit register hence zero is returned always in non-secure
+ mode.
+
+ \details Returns the current value of the Process Stack Pointer Limit (PSPLIM).
+ \return PSPLIM Register value
+ */
+__STATIC_FORCEINLINE uint32_t __get_PSPLIM(void)
+{
+#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \
+ (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3)))
+ // without main extensions, the non-secure PSPLIM is RAZ/WI
+ return 0U;
+#else
+ uint32_t result;
+ __ASM volatile ("MRS %0, psplim" : "=r" (result) );
+ return result;
+#endif
+}
+
+#if (defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3))
+/**
+ \brief Get Process Stack Pointer Limit (non-secure)
+ Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure
+ Stack Pointer Limit register hence zero is returned always.
+
+ \details Returns the current value of the non-secure Process Stack Pointer Limit (PSPLIM) when in secure state.
+ \return PSPLIM Register value
+ */
+__STATIC_FORCEINLINE uint32_t __TZ_get_PSPLIM_NS(void)
+{
+#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)))
+ // without main extensions, the non-secure PSPLIM is RAZ/WI
+ return 0U;
+#else
+ uint32_t result;
+ __ASM volatile ("MRS %0, psplim_ns" : "=r" (result) );
+ return result;
+#endif
+}
+#endif
+
+
+/**
+ \brief Set Process Stack Pointer Limit
+ Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure
+ Stack Pointer Limit register hence the write is silently ignored in non-secure
+ mode.
+
+ \details Assigns the given value to the Process Stack Pointer Limit (PSPLIM).
+ \param [in] ProcStackPtrLimit Process Stack Pointer Limit value to set
+ */
+__STATIC_FORCEINLINE void __set_PSPLIM(uint32_t ProcStackPtrLimit)
+{
+#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \
+ (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3)))
+ // without main extensions, the non-secure PSPLIM is RAZ/WI
+ (void)ProcStackPtrLimit;
+#else
+ __ASM volatile ("MSR psplim, %0" : : "r" (ProcStackPtrLimit));
+#endif
+}
+
+
+#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3))
+/**
+ \brief Set Process Stack Pointer (non-secure)
+ Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure
+ Stack Pointer Limit register hence the write is silently ignored.
+
+ \details Assigns the given value to the non-secure Process Stack Pointer Limit (PSPLIM) when in secure state.
+ \param [in] ProcStackPtrLimit Process Stack Pointer Limit value to set
+ */
+__STATIC_FORCEINLINE void __TZ_set_PSPLIM_NS(uint32_t ProcStackPtrLimit)
+{
+#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)))
+ // without main extensions, the non-secure PSPLIM is RAZ/WI
+ (void)ProcStackPtrLimit;
+#else
+ __ASM volatile ("MSR psplim_ns, %0\n" : : "r" (ProcStackPtrLimit));
+#endif
+}
+#endif
+
+
+/**
+ \brief Get Main Stack Pointer Limit
+ Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure
+ Stack Pointer Limit register hence zero is returned always in non-secure
+ mode.
+
+ \details Returns the current value of the Main Stack Pointer Limit (MSPLIM).
+ \return MSPLIM Register value
+ */
+__STATIC_FORCEINLINE uint32_t __get_MSPLIM(void)
+{
+#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \
+ (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3)))
+ // without main extensions, the non-secure MSPLIM is RAZ/WI
+ return 0U;
+#else
+ uint32_t result;
+ __ASM volatile ("MRS %0, msplim" : "=r" (result) );
+ return result;
+#endif
+}
+
+
+#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3))
+/**
+ \brief Get Main Stack Pointer Limit (non-secure)
+ Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure
+ Stack Pointer Limit register hence zero is returned always.
+
+ \details Returns the current value of the non-secure Main Stack Pointer Limit(MSPLIM) when in secure state.
+ \return MSPLIM Register value
+ */
+__STATIC_FORCEINLINE uint32_t __TZ_get_MSPLIM_NS(void)
+{
+#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)))
+ // without main extensions, the non-secure MSPLIM is RAZ/WI
+ return 0U;
+#else
+ uint32_t result;
+ __ASM volatile ("MRS %0, msplim_ns" : "=r" (result) );
+ return result;
+#endif
+}
+#endif
+
+
+/**
+ \brief Set Main Stack Pointer Limit
+ Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure
+ Stack Pointer Limit register hence the write is silently ignored in non-secure
+ mode.
+
+ \details Assigns the given value to the Main Stack Pointer Limit (MSPLIM).
+ \param [in] MainStackPtrLimit Main Stack Pointer Limit value to set
+ */
+__STATIC_FORCEINLINE void __set_MSPLIM(uint32_t MainStackPtrLimit)
+{
+#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \
+ (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3)))
+ // without main extensions, the non-secure MSPLIM is RAZ/WI
+ (void)MainStackPtrLimit;
+#else
+ __ASM volatile ("MSR msplim, %0" : : "r" (MainStackPtrLimit));
+#endif
+}
+
+
+#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3))
+/**
+ \brief Set Main Stack Pointer Limit (non-secure)
+ Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure
+ Stack Pointer Limit register hence the write is silently ignored.
+
+ \details Assigns the given value to the non-secure Main Stack Pointer Limit (MSPLIM) when in secure state.
+ \param [in] MainStackPtrLimit Main Stack Pointer value to set
+ */
+__STATIC_FORCEINLINE void __TZ_set_MSPLIM_NS(uint32_t MainStackPtrLimit)
+{
+#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)))
+ // without main extensions, the non-secure MSPLIM is RAZ/WI
+ (void)MainStackPtrLimit;
+#else
+ __ASM volatile ("MSR msplim_ns, %0" : : "r" (MainStackPtrLimit));
+#endif
+}
+#endif
+
+#endif /* ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \
+ (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) */
+
+
+/**
+ \brief Get FPSCR
+ \details Returns the current value of the Floating Point Status/Control register.
+ \return Floating Point Status/Control register value
+ */
+__STATIC_FORCEINLINE uint32_t __get_FPSCR(void)
+{
+#if ((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \
+ (defined (__FPU_USED ) && (__FPU_USED == 1U)) )
+#if __has_builtin(__builtin_arm_get_fpscr)
+// Re-enable using built-in when GCC has been fixed
+// || (__GNUC__ > 7) || (__GNUC__ == 7 && __GNUC_MINOR__ >= 2)
+ /* see https://gcc.gnu.org/ml/gcc-patches/2017-04/msg00443.html */
+ return __builtin_arm_get_fpscr();
+#else
+ uint32_t result;
+
+ __ASM volatile ("VMRS %0, fpscr" : "=r" (result) );
+ return(result);
+#endif
+#else
+ return(0U);
+#endif
+}
+
+
+/**
+ \brief Set FPSCR
+ \details Assigns the given value to the Floating Point Status/Control register.
+ \param [in] fpscr Floating Point Status/Control value to set
+ */
+__STATIC_FORCEINLINE void __set_FPSCR(uint32_t fpscr)
+{
+#if ((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \
+ (defined (__FPU_USED ) && (__FPU_USED == 1U)) )
+#if __has_builtin(__builtin_arm_set_fpscr)
+// Re-enable using built-in when GCC has been fixed
+// || (__GNUC__ > 7) || (__GNUC__ == 7 && __GNUC_MINOR__ >= 2)
+ /* see https://gcc.gnu.org/ml/gcc-patches/2017-04/msg00443.html */
+ __builtin_arm_set_fpscr(fpscr);
+#else
+ __ASM volatile ("VMSR fpscr, %0" : : "r" (fpscr) : "vfpcc", "memory");
+#endif
+#else
+ (void)fpscr;
+#endif
+}
+
+
+/*@} end of CMSIS_Core_RegAccFunctions */
+
+
+/* ########################## Core Instruction Access ######################### */
+/** \defgroup CMSIS_Core_InstructionInterface CMSIS Core Instruction Interface
+ Access to dedicated instructions
+ @{
+*/
+
+/* Define macros for porting to both thumb1 and thumb2.
+ * For thumb1, use low register (r0-r7), specified by constraint "l"
+ * Otherwise, use general registers, specified by constraint "r" */
+#if defined (__thumb__) && !defined (__thumb2__)
+#define __CMSIS_GCC_OUT_REG(r) "=l" (r)
+#define __CMSIS_GCC_RW_REG(r) "+l" (r)
+#define __CMSIS_GCC_USE_REG(r) "l" (r)
+#else
+#define __CMSIS_GCC_OUT_REG(r) "=r" (r)
+#define __CMSIS_GCC_RW_REG(r) "+r" (r)
+#define __CMSIS_GCC_USE_REG(r) "r" (r)
+#endif
+
+/**
+ \brief No Operation
+ \details No Operation does nothing. This instruction can be used for code alignment purposes.
+ */
+#define __NOP() __ASM volatile ("nop")
+
+/**
+ \brief Wait For Interrupt
+ \details Wait For Interrupt is a hint instruction that suspends execution until one of a number of events occurs.
+ */
+#define __WFI() __ASM volatile ("wfi")
+
+
+/**
+ \brief Wait For Event
+ \details Wait For Event is a hint instruction that permits the processor to enter
+ a low-power state until one of a number of events occurs.
+ */
+#define __WFE() __ASM volatile ("wfe")
+
+
+/**
+ \brief Send Event
+ \details Send Event is a hint instruction. It causes an event to be signaled to the CPU.
+ */
+#define __SEV() __ASM volatile ("sev")
+
+
+/**
+ \brief Instruction Synchronization Barrier
+ \details Instruction Synchronization Barrier flushes the pipeline in the processor,
+ so that all instructions following the ISB are fetched from cache or memory,
+ after the instruction has been completed.
+ */
+__STATIC_FORCEINLINE void __ISB(void)
+{
+ __ASM volatile ("isb 0xF":::"memory");
+}
+
+
+/**
+ \brief Data Synchronization Barrier
+ \details Acts as a special kind of Data Memory Barrier.
+ It completes when all explicit memory accesses before this instruction complete.
+ */
+__STATIC_FORCEINLINE void __DSB(void)
+{
+ __ASM volatile ("dsb 0xF":::"memory");
+}
+
+
+/**
+ \brief Data Memory Barrier
+ \details Ensures the apparent order of the explicit memory operations before
+ and after the instruction, without ensuring their completion.
+ */
+__STATIC_FORCEINLINE void __DMB(void)
+{
+ __ASM volatile ("dmb 0xF":::"memory");
+}
+
+
+/**
+ \brief Reverse byte order (32 bit)
+ \details Reverses the byte order in unsigned integer value. For example, 0x12345678 becomes 0x78563412.
+ \param [in] value Value to reverse
+ \return Reversed value
+ */
+__STATIC_FORCEINLINE uint32_t __REV(uint32_t value)
+{
+#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 5)
+ return __builtin_bswap32(value);
+#else
+ uint32_t result;
+
+ __ASM volatile ("rev %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) );
+ return result;
+#endif
+}
+
+
+/**
+ \brief Reverse byte order (16 bit)
+ \details Reverses the byte order within each halfword of a word. For example, 0x12345678 becomes 0x34127856.
+ \param [in] value Value to reverse
+ \return Reversed value
+ */
+__STATIC_FORCEINLINE uint32_t __REV16(uint32_t value)
+{
+ uint32_t result;
+
+ __ASM volatile ("rev16 %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) );
+ return result;
+}
+
+
+/**
+ \brief Reverse byte order (16 bit)
+ \details Reverses the byte order in a 16-bit value and returns the signed 16-bit result. For example, 0x0080 becomes 0x8000.
+ \param [in] value Value to reverse
+ \return Reversed value
+ */
+__STATIC_FORCEINLINE int16_t __REVSH(int16_t value)
+{
+#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8)
+ return (int16_t)__builtin_bswap16(value);
+#else
+ int16_t result;
+
+ __ASM volatile ("revsh %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) );
+ return result;
+#endif
+}
+
+
+/**
+ \brief Rotate Right in unsigned value (32 bit)
+ \details Rotate Right (immediate) provides the value of the contents of a register rotated by a variable number of bits.
+ \param [in] op1 Value to rotate
+ \param [in] op2 Number of Bits to rotate
+ \return Rotated value
+ */
+__STATIC_FORCEINLINE uint32_t __ROR(uint32_t op1, uint32_t op2)
+{
+ op2 %= 32U;
+ if (op2 == 0U)
+ {
+ return op1;
+ }
+ return (op1 >> op2) | (op1 << (32U - op2));
+}
+
+
+/**
+ \brief Breakpoint
+ \details Causes the processor to enter Debug state.
+ Debug tools can use this to investigate system state when the instruction at a particular address is reached.
+ \param [in] value is ignored by the processor.
+ If required, a debugger can use it to store additional information about the breakpoint.
+ */
+#define __BKPT(value) __ASM volatile ("bkpt "#value)
+
+
+/**
+ \brief Reverse bit order of value
+ \details Reverses the bit order of the given value.
+ \param [in] value Value to reverse
+ \return Reversed value
+ */
+__STATIC_FORCEINLINE uint32_t __RBIT(uint32_t value)
+{
+ uint32_t result;
+
+#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \
+ (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \
+ (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) )
+ __ASM volatile ("rbit %0, %1" : "=r" (result) : "r" (value) );
+#else
+ uint32_t s = (4U /*sizeof(v)*/ * 8U) - 1U; /* extra shift needed at end */
+
+ result = value; /* r will be reversed bits of v; first get LSB of v */
+ for (value >>= 1U; value != 0U; value >>= 1U)
+ {
+ result <<= 1U;
+ result |= value & 1U;
+ s--;
+ }
+ result <<= s; /* shift when v's highest bits are zero */
+#endif
+ return result;
+}
+
+
+/**
+ \brief Count leading zeros
+ \details Counts the number of leading zeros of a data value.
+ \param [in] value Value to count the leading zeros
+ \return number of leading zeros in value
+ */
+#define __CLZ (uint8_t)__builtin_clz
+
+
+#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \
+ (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \
+ (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \
+ (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) )
+/**
+ \brief LDR Exclusive (8 bit)
+ \details Executes a exclusive LDR instruction for 8 bit value.
+ \param [in] ptr Pointer to data
+ \return value of type uint8_t at (*ptr)
+ */
+__STATIC_FORCEINLINE uint8_t __LDREXB(volatile uint8_t *addr)
+{
+ uint32_t result;
+
+#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8)
+ __ASM volatile ("ldrexb %0, %1" : "=r" (result) : "Q" (*addr) );
+#else
+ /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not
+ accepted by assembler. So has to use following less efficient pattern.
+ */
+ __ASM volatile ("ldrexb %0, [%1]" : "=r" (result) : "r" (addr) : "memory" );
+#endif
+ return ((uint8_t) result); /* Add explicit type cast here */
+}
+
+
+/**
+ \brief LDR Exclusive (16 bit)
+ \details Executes a exclusive LDR instruction for 16 bit values.
+ \param [in] ptr Pointer to data
+ \return value of type uint16_t at (*ptr)
+ */
+__STATIC_FORCEINLINE uint16_t __LDREXH(volatile uint16_t *addr)
+{
+ uint32_t result;
+
+#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8)
+ __ASM volatile ("ldrexh %0, %1" : "=r" (result) : "Q" (*addr) );
+#else
+ /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not
+ accepted by assembler. So has to use following less efficient pattern.
+ */
+ __ASM volatile ("ldrexh %0, [%1]" : "=r" (result) : "r" (addr) : "memory" );
+#endif
+ return ((uint16_t) result); /* Add explicit type cast here */
+}
+
+
+/**
+ \brief LDR Exclusive (32 bit)
+ \details Executes a exclusive LDR instruction for 32 bit values.
+ \param [in] ptr Pointer to data
+ \return value of type uint32_t at (*ptr)
+ */
+__STATIC_FORCEINLINE uint32_t __LDREXW(volatile uint32_t *addr)
+{
+ uint32_t result;
+
+ __ASM volatile ("ldrex %0, %1" : "=r" (result) : "Q" (*addr) );
+ return(result);
+}
+
+
+/**
+ \brief STR Exclusive (8 bit)
+ \details Executes a exclusive STR instruction for 8 bit values.
+ \param [in] value Value to store
+ \param [in] ptr Pointer to location
+ \return 0 Function succeeded
+ \return 1 Function failed
+ */
+__STATIC_FORCEINLINE uint32_t __STREXB(uint8_t value, volatile uint8_t *addr)
+{
+ uint32_t result;
+
+ __ASM volatile ("strexb %0, %2, %1" : "=&r" (result), "=Q" (*addr) : "r" ((uint32_t)value) );
+ return(result);
+}
+
+
+/**
+ \brief STR Exclusive (16 bit)
+ \details Executes a exclusive STR instruction for 16 bit values.
+ \param [in] value Value to store
+ \param [in] ptr Pointer to location
+ \return 0 Function succeeded
+ \return 1 Function failed
+ */
+__STATIC_FORCEINLINE uint32_t __STREXH(uint16_t value, volatile uint16_t *addr)
+{
+ uint32_t result;
+
+ __ASM volatile ("strexh %0, %2, %1" : "=&r" (result), "=Q" (*addr) : "r" ((uint32_t)value) );
+ return(result);
+}
+
+
+/**
+ \brief STR Exclusive (32 bit)
+ \details Executes a exclusive STR instruction for 32 bit values.
+ \param [in] value Value to store
+ \param [in] ptr Pointer to location
+ \return 0 Function succeeded
+ \return 1 Function failed
+ */
+__STATIC_FORCEINLINE uint32_t __STREXW(uint32_t value, volatile uint32_t *addr)
+{
+ uint32_t result;
+
+ __ASM volatile ("strex %0, %2, %1" : "=&r" (result), "=Q" (*addr) : "r" (value) );
+ return(result);
+}
+
+
+/**
+ \brief Remove the exclusive lock
+ \details Removes the exclusive lock which is created by LDREX.
+ */
+__STATIC_FORCEINLINE void __CLREX(void)
+{
+ __ASM volatile ("clrex" ::: "memory");
+}
+
+#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \
+ (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \
+ (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \
+ (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) */
+
+
+#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \
+ (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \
+ (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) )
+/**
+ \brief Signed Saturate
+ \details Saturates a signed value.
+ \param [in] ARG1 Value to be saturated
+ \param [in] ARG2 Bit position to saturate to (1..32)
+ \return Saturated value
+ */
+#define __SSAT(ARG1,ARG2) \
+__extension__ \
+({ \
+ int32_t __RES, __ARG1 = (ARG1); \
+ __ASM ("ssat %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \
+ __RES; \
+ })
+
+
+/**
+ \brief Unsigned Saturate
+ \details Saturates an unsigned value.
+ \param [in] ARG1 Value to be saturated
+ \param [in] ARG2 Bit position to saturate to (0..31)
+ \return Saturated value
+ */
+#define __USAT(ARG1,ARG2) \
+ __extension__ \
+({ \
+ uint32_t __RES, __ARG1 = (ARG1); \
+ __ASM ("usat %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \
+ __RES; \
+ })
+
+
+/**
+ \brief Rotate Right with Extend (32 bit)
+ \details Moves each bit of a bitstring right by one bit.
+ The carry input is shifted in at the left end of the bitstring.
+ \param [in] value Value to rotate
+ \return Rotated value
+ */
+__STATIC_FORCEINLINE uint32_t __RRX(uint32_t value)
+{
+ uint32_t result;
+
+ __ASM volatile ("rrx %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) );
+ return(result);
+}
+
+
+/**
+ \brief LDRT Unprivileged (8 bit)
+ \details Executes a Unprivileged LDRT instruction for 8 bit value.
+ \param [in] ptr Pointer to data
+ \return value of type uint8_t at (*ptr)
+ */
+__STATIC_FORCEINLINE uint8_t __LDRBT(volatile uint8_t *ptr)
+{
+ uint32_t result;
+
+#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8)
+ __ASM volatile ("ldrbt %0, %1" : "=r" (result) : "Q" (*ptr) );
+#else
+ /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not
+ accepted by assembler. So has to use following less efficient pattern.
+ */
+ __ASM volatile ("ldrbt %0, [%1]" : "=r" (result) : "r" (ptr) : "memory" );
+#endif
+ return ((uint8_t) result); /* Add explicit type cast here */
+}
+
+
+/**
+ \brief LDRT Unprivileged (16 bit)
+ \details Executes a Unprivileged LDRT instruction for 16 bit values.
+ \param [in] ptr Pointer to data
+ \return value of type uint16_t at (*ptr)
+ */
+__STATIC_FORCEINLINE uint16_t __LDRHT(volatile uint16_t *ptr)
+{
+ uint32_t result;
+
+#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8)
+ __ASM volatile ("ldrht %0, %1" : "=r" (result) : "Q" (*ptr) );
+#else
+ /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not
+ accepted by assembler. So has to use following less efficient pattern.
+ */
+ __ASM volatile ("ldrht %0, [%1]" : "=r" (result) : "r" (ptr) : "memory" );
+#endif
+ return ((uint16_t) result); /* Add explicit type cast here */
+}
+
+
+/**
+ \brief LDRT Unprivileged (32 bit)
+ \details Executes a Unprivileged LDRT instruction for 32 bit values.
+ \param [in] ptr Pointer to data
+ \return value of type uint32_t at (*ptr)
+ */
+__STATIC_FORCEINLINE uint32_t __LDRT(volatile uint32_t *ptr)
+{
+ uint32_t result;
+
+ __ASM volatile ("ldrt %0, %1" : "=r" (result) : "Q" (*ptr) );
+ return(result);
+}
+
+
+/**
+ \brief STRT Unprivileged (8 bit)
+ \details Executes a Unprivileged STRT instruction for 8 bit values.
+ \param [in] value Value to store
+ \param [in] ptr Pointer to location
+ */
+__STATIC_FORCEINLINE void __STRBT(uint8_t value, volatile uint8_t *ptr)
+{
+ __ASM volatile ("strbt %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) );
+}
+
+
+/**
+ \brief STRT Unprivileged (16 bit)
+ \details Executes a Unprivileged STRT instruction for 16 bit values.
+ \param [in] value Value to store
+ \param [in] ptr Pointer to location
+ */
+__STATIC_FORCEINLINE void __STRHT(uint16_t value, volatile uint16_t *ptr)
+{
+ __ASM volatile ("strht %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) );
+}
+
+
+/**
+ \brief STRT Unprivileged (32 bit)
+ \details Executes a Unprivileged STRT instruction for 32 bit values.
+ \param [in] value Value to store
+ \param [in] ptr Pointer to location
+ */
+__STATIC_FORCEINLINE void __STRT(uint32_t value, volatile uint32_t *ptr)
+{
+ __ASM volatile ("strt %1, %0" : "=Q" (*ptr) : "r" (value) );
+}
+
+#else /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \
+ (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \
+ (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) */
+
+/**
+ \brief Signed Saturate
+ \details Saturates a signed value.
+ \param [in] value Value to be saturated
+ \param [in] sat Bit position to saturate to (1..32)
+ \return Saturated value
+ */
+__STATIC_FORCEINLINE int32_t __SSAT(int32_t val, uint32_t sat)
+{
+ if ((sat >= 1U) && (sat <= 32U))
+ {
+ const int32_t max = (int32_t)((1U << (sat - 1U)) - 1U);
+ const int32_t min = -1 - max ;
+ if (val > max)
+ {
+ return max;
+ }
+ else if (val < min)
+ {
+ return min;
+ }
+ }
+ return val;
+}
+
+/**
+ \brief Unsigned Saturate
+ \details Saturates an unsigned value.
+ \param [in] value Value to be saturated
+ \param [in] sat Bit position to saturate to (0..31)
+ \return Saturated value
+ */
+__STATIC_FORCEINLINE uint32_t __USAT(int32_t val, uint32_t sat)
+{
+ if (sat <= 31U)
+ {
+ const uint32_t max = ((1U << sat) - 1U);
+ if (val > (int32_t)max)
+ {
+ return max;
+ }
+ else if (val < 0)
+ {
+ return 0U;
+ }
+ }
+ return (uint32_t)val;
+}
+
+#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \
+ (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \
+ (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) */
+
+
+#if ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \
+ (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) )
+/**
+ \brief Load-Acquire (8 bit)
+ \details Executes a LDAB instruction for 8 bit value.
+ \param [in] ptr Pointer to data
+ \return value of type uint8_t at (*ptr)
+ */
+__STATIC_FORCEINLINE uint8_t __LDAB(volatile uint8_t *ptr)
+{
+ uint32_t result;
+
+ __ASM volatile ("ldab %0, %1" : "=r" (result) : "Q" (*ptr) );
+ return ((uint8_t) result);
+}
+
+
+/**
+ \brief Load-Acquire (16 bit)
+ \details Executes a LDAH instruction for 16 bit values.
+ \param [in] ptr Pointer to data
+ \return value of type uint16_t at (*ptr)
+ */
+__STATIC_FORCEINLINE uint16_t __LDAH(volatile uint16_t *ptr)
+{
+ uint32_t result;
+
+ __ASM volatile ("ldah %0, %1" : "=r" (result) : "Q" (*ptr) );
+ return ((uint16_t) result);
+}
+
+
+/**
+ \brief Load-Acquire (32 bit)
+ \details Executes a LDA instruction for 32 bit values.
+ \param [in] ptr Pointer to data
+ \return value of type uint32_t at (*ptr)
+ */
+__STATIC_FORCEINLINE uint32_t __LDA(volatile uint32_t *ptr)
+{
+ uint32_t result;
+
+ __ASM volatile ("lda %0, %1" : "=r" (result) : "Q" (*ptr) );
+ return(result);
+}
+
+
+/**
+ \brief Store-Release (8 bit)
+ \details Executes a STLB instruction for 8 bit values.
+ \param [in] value Value to store
+ \param [in] ptr Pointer to location
+ */
+__STATIC_FORCEINLINE void __STLB(uint8_t value, volatile uint8_t *ptr)
+{
+ __ASM volatile ("stlb %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) );
+}
+
+
+/**
+ \brief Store-Release (16 bit)
+ \details Executes a STLH instruction for 16 bit values.
+ \param [in] value Value to store
+ \param [in] ptr Pointer to location
+ */
+__STATIC_FORCEINLINE void __STLH(uint16_t value, volatile uint16_t *ptr)
+{
+ __ASM volatile ("stlh %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) );
+}
+
+
+/**
+ \brief Store-Release (32 bit)
+ \details Executes a STL instruction for 32 bit values.
+ \param [in] value Value to store
+ \param [in] ptr Pointer to location
+ */
+__STATIC_FORCEINLINE void __STL(uint32_t value, volatile uint32_t *ptr)
+{
+ __ASM volatile ("stl %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) );
+}
+
+
+/**
+ \brief Load-Acquire Exclusive (8 bit)
+ \details Executes a LDAB exclusive instruction for 8 bit value.
+ \param [in] ptr Pointer to data
+ \return value of type uint8_t at (*ptr)
+ */
+__STATIC_FORCEINLINE uint8_t __LDAEXB(volatile uint8_t *ptr)
+{
+ uint32_t result;
+
+ __ASM volatile ("ldaexb %0, %1" : "=r" (result) : "Q" (*ptr) );
+ return ((uint8_t) result);
+}
+
+
+/**
+ \brief Load-Acquire Exclusive (16 bit)
+ \details Executes a LDAH exclusive instruction for 16 bit values.
+ \param [in] ptr Pointer to data
+ \return value of type uint16_t at (*ptr)
+ */
+__STATIC_FORCEINLINE uint16_t __LDAEXH(volatile uint16_t *ptr)
+{
+ uint32_t result;
+
+ __ASM volatile ("ldaexh %0, %1" : "=r" (result) : "Q" (*ptr) );
+ return ((uint16_t) result);
+}
+
+
+/**
+ \brief Load-Acquire Exclusive (32 bit)
+ \details Executes a LDA exclusive instruction for 32 bit values.
+ \param [in] ptr Pointer to data
+ \return value of type uint32_t at (*ptr)
+ */
+__STATIC_FORCEINLINE uint32_t __LDAEX(volatile uint32_t *ptr)
+{
+ uint32_t result;
+
+ __ASM volatile ("ldaex %0, %1" : "=r" (result) : "Q" (*ptr) );
+ return(result);
+}
+
+
+/**
+ \brief Store-Release Exclusive (8 bit)
+ \details Executes a STLB exclusive instruction for 8 bit values.
+ \param [in] value Value to store
+ \param [in] ptr Pointer to location
+ \return 0 Function succeeded
+ \return 1 Function failed
+ */
+__STATIC_FORCEINLINE uint32_t __STLEXB(uint8_t value, volatile uint8_t *ptr)
+{
+ uint32_t result;
+
+ __ASM volatile ("stlexb %0, %2, %1" : "=&r" (result), "=Q" (*ptr) : "r" ((uint32_t)value) );
+ return(result);
+}
+
+
+/**
+ \brief Store-Release Exclusive (16 bit)
+ \details Executes a STLH exclusive instruction for 16 bit values.
+ \param [in] value Value to store
+ \param [in] ptr Pointer to location
+ \return 0 Function succeeded
+ \return 1 Function failed
+ */
+__STATIC_FORCEINLINE uint32_t __STLEXH(uint16_t value, volatile uint16_t *ptr)
+{
+ uint32_t result;
+
+ __ASM volatile ("stlexh %0, %2, %1" : "=&r" (result), "=Q" (*ptr) : "r" ((uint32_t)value) );
+ return(result);
+}
+
+
+/**
+ \brief Store-Release Exclusive (32 bit)
+ \details Executes a STL exclusive instruction for 32 bit values.
+ \param [in] value Value to store
+ \param [in] ptr Pointer to location
+ \return 0 Function succeeded
+ \return 1 Function failed
+ */
+__STATIC_FORCEINLINE uint32_t __STLEX(uint32_t value, volatile uint32_t *ptr)
+{
+ uint32_t result;
+
+ __ASM volatile ("stlex %0, %2, %1" : "=&r" (result), "=Q" (*ptr) : "r" ((uint32_t)value) );
+ return(result);
+}
+
+#endif /* ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \
+ (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) */
+
+/*@}*/ /* end of group CMSIS_Core_InstructionInterface */
+
+
+/* ################### Compiler specific Intrinsics ########################### */
+/** \defgroup CMSIS_SIMD_intrinsics CMSIS SIMD Intrinsics
+ Access to dedicated SIMD instructions
+ @{
+*/
+
+#if (defined (__ARM_FEATURE_DSP) && (__ARM_FEATURE_DSP == 1))
+
+__STATIC_FORCEINLINE uint32_t __SADD8(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("sadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__STATIC_FORCEINLINE uint32_t __QADD8(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("qadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__STATIC_FORCEINLINE uint32_t __SHADD8(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("shadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__STATIC_FORCEINLINE uint32_t __UADD8(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("uadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__STATIC_FORCEINLINE uint32_t __UQADD8(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("uqadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__STATIC_FORCEINLINE uint32_t __UHADD8(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("uhadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+
+__STATIC_FORCEINLINE uint32_t __SSUB8(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("ssub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__STATIC_FORCEINLINE uint32_t __QSUB8(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("qsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__STATIC_FORCEINLINE uint32_t __SHSUB8(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("shsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__STATIC_FORCEINLINE uint32_t __USUB8(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("usub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__STATIC_FORCEINLINE uint32_t __UQSUB8(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("uqsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__STATIC_FORCEINLINE uint32_t __UHSUB8(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("uhsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+
+__STATIC_FORCEINLINE uint32_t __SADD16(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("sadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__STATIC_FORCEINLINE uint32_t __QADD16(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("qadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__STATIC_FORCEINLINE uint32_t __SHADD16(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("shadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__STATIC_FORCEINLINE uint32_t __UADD16(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("uadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__STATIC_FORCEINLINE uint32_t __UQADD16(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("uqadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__STATIC_FORCEINLINE uint32_t __UHADD16(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("uhadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__STATIC_FORCEINLINE uint32_t __SSUB16(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("ssub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__STATIC_FORCEINLINE uint32_t __QSUB16(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("qsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__STATIC_FORCEINLINE uint32_t __SHSUB16(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("shsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__STATIC_FORCEINLINE uint32_t __USUB16(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("usub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__STATIC_FORCEINLINE uint32_t __UQSUB16(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("uqsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__STATIC_FORCEINLINE uint32_t __UHSUB16(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("uhsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__STATIC_FORCEINLINE uint32_t __SASX(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("sasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__STATIC_FORCEINLINE uint32_t __QASX(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("qasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__STATIC_FORCEINLINE uint32_t __SHASX(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("shasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__STATIC_FORCEINLINE uint32_t __UASX(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("uasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__STATIC_FORCEINLINE uint32_t __UQASX(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("uqasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__STATIC_FORCEINLINE uint32_t __UHASX(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("uhasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__STATIC_FORCEINLINE uint32_t __SSAX(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("ssax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__STATIC_FORCEINLINE uint32_t __QSAX(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("qsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__STATIC_FORCEINLINE uint32_t __SHSAX(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("shsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__STATIC_FORCEINLINE uint32_t __USAX(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("usax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__STATIC_FORCEINLINE uint32_t __UQSAX(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("uqsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__STATIC_FORCEINLINE uint32_t __UHSAX(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("uhsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__STATIC_FORCEINLINE uint32_t __USAD8(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("usad8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__STATIC_FORCEINLINE uint32_t __USADA8(uint32_t op1, uint32_t op2, uint32_t op3)
+{
+ uint32_t result;
+
+ __ASM volatile ("usada8 %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) );
+ return(result);
+}
+
+#define __SSAT16(ARG1,ARG2) \
+({ \
+ int32_t __RES, __ARG1 = (ARG1); \
+ __ASM ("ssat16 %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \
+ __RES; \
+ })
+
+#define __USAT16(ARG1,ARG2) \
+({ \
+ uint32_t __RES, __ARG1 = (ARG1); \
+ __ASM ("usat16 %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \
+ __RES; \
+ })
+
+__STATIC_FORCEINLINE uint32_t __UXTB16(uint32_t op1)
+{
+ uint32_t result;
+
+ __ASM volatile ("uxtb16 %0, %1" : "=r" (result) : "r" (op1));
+ return(result);
+}
+
+__STATIC_FORCEINLINE uint32_t __UXTAB16(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("uxtab16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__STATIC_FORCEINLINE uint32_t __SXTB16(uint32_t op1)
+{
+ uint32_t result;
+
+ __ASM volatile ("sxtb16 %0, %1" : "=r" (result) : "r" (op1));
+ return(result);
+}
+
+__STATIC_FORCEINLINE uint32_t __SXTAB16(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("sxtab16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__STATIC_FORCEINLINE uint32_t __SMUAD (uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("smuad %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__STATIC_FORCEINLINE uint32_t __SMUADX (uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("smuadx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__STATIC_FORCEINLINE uint32_t __SMLAD (uint32_t op1, uint32_t op2, uint32_t op3)
+{
+ uint32_t result;
+
+ __ASM volatile ("smlad %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) );
+ return(result);
+}
+
+__STATIC_FORCEINLINE uint32_t __SMLADX (uint32_t op1, uint32_t op2, uint32_t op3)
+{
+ uint32_t result;
+
+ __ASM volatile ("smladx %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) );
+ return(result);
+}
+
+__STATIC_FORCEINLINE uint64_t __SMLALD (uint32_t op1, uint32_t op2, uint64_t acc)
+{
+ union llreg_u{
+ uint32_t w32[2];
+ uint64_t w64;
+ } llr;
+ llr.w64 = acc;
+
+#ifndef __ARMEB__ /* Little endian */
+ __ASM volatile ("smlald %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) );
+#else /* Big endian */
+ __ASM volatile ("smlald %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) );
+#endif
+
+ return(llr.w64);
+}
+
+__STATIC_FORCEINLINE uint64_t __SMLALDX (uint32_t op1, uint32_t op2, uint64_t acc)
+{
+ union llreg_u{
+ uint32_t w32[2];
+ uint64_t w64;
+ } llr;
+ llr.w64 = acc;
+
+#ifndef __ARMEB__ /* Little endian */
+ __ASM volatile ("smlaldx %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) );
+#else /* Big endian */
+ __ASM volatile ("smlaldx %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) );
+#endif
+
+ return(llr.w64);
+}
+
+__STATIC_FORCEINLINE uint32_t __SMUSD (uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("smusd %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__STATIC_FORCEINLINE uint32_t __SMUSDX (uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("smusdx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__STATIC_FORCEINLINE uint32_t __SMLSD (uint32_t op1, uint32_t op2, uint32_t op3)
+{
+ uint32_t result;
+
+ __ASM volatile ("smlsd %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) );
+ return(result);
+}
+
+__STATIC_FORCEINLINE uint32_t __SMLSDX (uint32_t op1, uint32_t op2, uint32_t op3)
+{
+ uint32_t result;
+
+ __ASM volatile ("smlsdx %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) );
+ return(result);
+}
+
+__STATIC_FORCEINLINE uint64_t __SMLSLD (uint32_t op1, uint32_t op2, uint64_t acc)
+{
+ union llreg_u{
+ uint32_t w32[2];
+ uint64_t w64;
+ } llr;
+ llr.w64 = acc;
+
+#ifndef __ARMEB__ /* Little endian */
+ __ASM volatile ("smlsld %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) );
+#else /* Big endian */
+ __ASM volatile ("smlsld %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) );
+#endif
+
+ return(llr.w64);
+}
+
+__STATIC_FORCEINLINE uint64_t __SMLSLDX (uint32_t op1, uint32_t op2, uint64_t acc)
+{
+ union llreg_u{
+ uint32_t w32[2];
+ uint64_t w64;
+ } llr;
+ llr.w64 = acc;
+
+#ifndef __ARMEB__ /* Little endian */
+ __ASM volatile ("smlsldx %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) );
+#else /* Big endian */
+ __ASM volatile ("smlsldx %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) );
+#endif
+
+ return(llr.w64);
+}
+
+__STATIC_FORCEINLINE uint32_t __SEL (uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("sel %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__STATIC_FORCEINLINE int32_t __QADD( int32_t op1, int32_t op2)
+{
+ int32_t result;
+
+ __ASM volatile ("qadd %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__STATIC_FORCEINLINE int32_t __QSUB( int32_t op1, int32_t op2)
+{
+ int32_t result;
+
+ __ASM volatile ("qsub %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+#if 0
+#define __PKHBT(ARG1,ARG2,ARG3) \
+({ \
+ uint32_t __RES, __ARG1 = (ARG1), __ARG2 = (ARG2); \
+ __ASM ("pkhbt %0, %1, %2, lsl %3" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2), "I" (ARG3) ); \
+ __RES; \
+ })
+
+#define __PKHTB(ARG1,ARG2,ARG3) \
+({ \
+ uint32_t __RES, __ARG1 = (ARG1), __ARG2 = (ARG2); \
+ if (ARG3 == 0) \
+ __ASM ("pkhtb %0, %1, %2" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2) ); \
+ else \
+ __ASM ("pkhtb %0, %1, %2, asr %3" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2), "I" (ARG3) ); \
+ __RES; \
+ })
+#endif
+
+#define __PKHBT(ARG1,ARG2,ARG3) ( ((((uint32_t)(ARG1)) ) & 0x0000FFFFUL) | \
+ ((((uint32_t)(ARG2)) << (ARG3)) & 0xFFFF0000UL) )
+
+#define __PKHTB(ARG1,ARG2,ARG3) ( ((((uint32_t)(ARG1)) ) & 0xFFFF0000UL) | \
+ ((((uint32_t)(ARG2)) >> (ARG3)) & 0x0000FFFFUL) )
+
+__STATIC_FORCEINLINE int32_t __SMMLA (int32_t op1, int32_t op2, int32_t op3)
+{
+ int32_t result;
+
+ __ASM volatile ("smmla %0, %1, %2, %3" : "=r" (result): "r" (op1), "r" (op2), "r" (op3) );
+ return(result);
+}
+
+#endif /* (__ARM_FEATURE_DSP == 1) */
+/*@} end of group CMSIS_SIMD_intrinsics */
+
+
+#pragma GCC diagnostic pop
+
+#endif /* __CMSIS_GCC_H */
diff --git a/peripherals/cc48x6/firmware/Drivers/CMSIS/Include/cmsis_version.h b/peripherals/cc48x6/firmware/Drivers/CMSIS/Include/cmsis_version.h
new file mode 100644
index 0000000..660f612
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Drivers/CMSIS/Include/cmsis_version.h
@@ -0,0 +1,39 @@
+/**************************************************************************//**
+ * @file cmsis_version.h
+ * @brief CMSIS Core(M) Version definitions
+ * @version V5.0.2
+ * @date 19. April 2017
+ ******************************************************************************/
+/*
+ * Copyright (c) 2009-2017 ARM Limited. All rights reserved.
+ *
+ * SPDX-License-Identifier: Apache-2.0
+ *
+ * Licensed under the Apache License, Version 2.0 (the License); you may
+ * not use this file except in compliance with the License.
+ * You may obtain a copy of the License at
+ *
+ * www.apache.org/licenses/LICENSE-2.0
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an AS IS BASIS, WITHOUT
+ * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+ * See the License for the specific language governing permissions and
+ * limitations under the License.
+ */
+
+#if defined ( __ICCARM__ )
+ #pragma system_include /* treat file as system include file for MISRA check */
+#elif defined (__clang__)
+ #pragma clang system_header /* treat file as system include file */
+#endif
+
+#ifndef __CMSIS_VERSION_H
+#define __CMSIS_VERSION_H
+
+/* CMSIS Version definitions */
+#define __CM_CMSIS_VERSION_MAIN ( 5U) /*!< [31:16] CMSIS Core(M) main version */
+#define __CM_CMSIS_VERSION_SUB ( 1U) /*!< [15:0] CMSIS Core(M) sub version */
+#define __CM_CMSIS_VERSION ((__CM_CMSIS_VERSION_MAIN << 16U) | \
+ __CM_CMSIS_VERSION_SUB ) /*!< CMSIS Core(M) version number */
+#endif
diff --git a/peripherals/cc48x6/firmware/Drivers/CMSIS/Include/core_cm0.h b/peripherals/cc48x6/firmware/Drivers/CMSIS/Include/core_cm0.h
new file mode 100644
index 0000000..f929bba
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Drivers/CMSIS/Include/core_cm0.h
@@ -0,0 +1,949 @@
+/**************************************************************************//**
+ * @file core_cm0.h
+ * @brief CMSIS Cortex-M0 Core Peripheral Access Layer Header File
+ * @version V5.0.5
+ * @date 28. May 2018
+ ******************************************************************************/
+/*
+ * Copyright (c) 2009-2018 Arm Limited. All rights reserved.
+ *
+ * SPDX-License-Identifier: Apache-2.0
+ *
+ * Licensed under the Apache License, Version 2.0 (the License); you may
+ * not use this file except in compliance with the License.
+ * You may obtain a copy of the License at
+ *
+ * www.apache.org/licenses/LICENSE-2.0
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an AS IS BASIS, WITHOUT
+ * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+ * See the License for the specific language governing permissions and
+ * limitations under the License.
+ */
+
+#if defined ( __ICCARM__ )
+ #pragma system_include /* treat file as system include file for MISRA check */
+#elif defined (__clang__)
+ #pragma clang system_header /* treat file as system include file */
+#endif
+
+#ifndef __CORE_CM0_H_GENERIC
+#define __CORE_CM0_H_GENERIC
+
+#include
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/**
+ \page CMSIS_MISRA_Exceptions MISRA-C:2004 Compliance Exceptions
+ CMSIS violates the following MISRA-C:2004 rules:
+
+ \li Required Rule 8.5, object/function definition in header file.
+ Function definitions in header files are used to allow 'inlining'.
+
+ \li Required Rule 18.4, declaration of union type or object of union type: '{...}'.
+ Unions are used for effective representation of core registers.
+
+ \li Advisory Rule 19.7, Function-like macro defined.
+ Function-like macros are used to allow more efficient code.
+ */
+
+
+/*******************************************************************************
+ * CMSIS definitions
+ ******************************************************************************/
+/**
+ \ingroup Cortex_M0
+ @{
+ */
+
+#include "cmsis_version.h"
+
+/* CMSIS CM0 definitions */
+#define __CM0_CMSIS_VERSION_MAIN (__CM_CMSIS_VERSION_MAIN) /*!< \deprecated [31:16] CMSIS HAL main version */
+#define __CM0_CMSIS_VERSION_SUB (__CM_CMSIS_VERSION_SUB) /*!< \deprecated [15:0] CMSIS HAL sub version */
+#define __CM0_CMSIS_VERSION ((__CM0_CMSIS_VERSION_MAIN << 16U) | \
+ __CM0_CMSIS_VERSION_SUB ) /*!< \deprecated CMSIS HAL version number */
+
+#define __CORTEX_M (0U) /*!< Cortex-M Core */
+
+/** __FPU_USED indicates whether an FPU is used or not.
+ This core does not support an FPU at all
+*/
+#define __FPU_USED 0U
+
+#if defined ( __CC_ARM )
+ #if defined __TARGET_FPU_VFP
+ #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)"
+ #endif
+
+#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
+ #if defined __ARM_PCS_VFP
+ #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)"
+ #endif
+
+#elif defined ( __GNUC__ )
+ #if defined (__VFP_FP__) && !defined(__SOFTFP__)
+ #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)"
+ #endif
+
+#elif defined ( __ICCARM__ )
+ #if defined __ARMVFP__
+ #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)"
+ #endif
+
+#elif defined ( __TI_ARM__ )
+ #if defined __TI_VFP_SUPPORT__
+ #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)"
+ #endif
+
+#elif defined ( __TASKING__ )
+ #if defined __FPU_VFP__
+ #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)"
+ #endif
+
+#elif defined ( __CSMC__ )
+ #if ( __CSMC__ & 0x400U)
+ #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)"
+ #endif
+
+#endif
+
+#include "cmsis_compiler.h" /* CMSIS compiler specific defines */
+
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __CORE_CM0_H_GENERIC */
+
+#ifndef __CMSIS_GENERIC
+
+#ifndef __CORE_CM0_H_DEPENDANT
+#define __CORE_CM0_H_DEPENDANT
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* check device defines and use defaults */
+#if defined __CHECK_DEVICE_DEFINES
+ #ifndef __CM0_REV
+ #define __CM0_REV 0x0000U
+ #warning "__CM0_REV not defined in device header file; using default!"
+ #endif
+
+ #ifndef __NVIC_PRIO_BITS
+ #define __NVIC_PRIO_BITS 2U
+ #warning "__NVIC_PRIO_BITS not defined in device header file; using default!"
+ #endif
+
+ #ifndef __Vendor_SysTickConfig
+ #define __Vendor_SysTickConfig 0U
+ #warning "__Vendor_SysTickConfig not defined in device header file; using default!"
+ #endif
+#endif
+
+/* IO definitions (access restrictions to peripheral registers) */
+/**
+ \defgroup CMSIS_glob_defs CMSIS Global Defines
+
+ IO Type Qualifiers are used
+ \li to specify the access to peripheral variables.
+ \li for automatic generation of peripheral register debug information.
+*/
+#ifdef __cplusplus
+ #define __I volatile /*!< Defines 'read only' permissions */
+#else
+ #define __I volatile const /*!< Defines 'read only' permissions */
+#endif
+#define __O volatile /*!< Defines 'write only' permissions */
+#define __IO volatile /*!< Defines 'read / write' permissions */
+
+/* following defines should be used for structure members */
+#define __IM volatile const /*! Defines 'read only' structure member permissions */
+#define __OM volatile /*! Defines 'write only' structure member permissions */
+#define __IOM volatile /*! Defines 'read / write' structure member permissions */
+
+/*@} end of group Cortex_M0 */
+
+
+
+/*******************************************************************************
+ * Register Abstraction
+ Core Register contain:
+ - Core Register
+ - Core NVIC Register
+ - Core SCB Register
+ - Core SysTick Register
+ ******************************************************************************/
+/**
+ \defgroup CMSIS_core_register Defines and Type Definitions
+ \brief Type definitions and defines for Cortex-M processor based devices.
+*/
+
+/**
+ \ingroup CMSIS_core_register
+ \defgroup CMSIS_CORE Status and Control Registers
+ \brief Core Register type definitions.
+ @{
+ */
+
+/**
+ \brief Union type to access the Application Program Status Register (APSR).
+ */
+typedef union
+{
+ struct
+ {
+ uint32_t _reserved0:28; /*!< bit: 0..27 Reserved */
+ uint32_t V:1; /*!< bit: 28 Overflow condition code flag */
+ uint32_t C:1; /*!< bit: 29 Carry condition code flag */
+ uint32_t Z:1; /*!< bit: 30 Zero condition code flag */
+ uint32_t N:1; /*!< bit: 31 Negative condition code flag */
+ } b; /*!< Structure used for bit access */
+ uint32_t w; /*!< Type used for word access */
+} APSR_Type;
+
+/* APSR Register Definitions */
+#define APSR_N_Pos 31U /*!< APSR: N Position */
+#define APSR_N_Msk (1UL << APSR_N_Pos) /*!< APSR: N Mask */
+
+#define APSR_Z_Pos 30U /*!< APSR: Z Position */
+#define APSR_Z_Msk (1UL << APSR_Z_Pos) /*!< APSR: Z Mask */
+
+#define APSR_C_Pos 29U /*!< APSR: C Position */
+#define APSR_C_Msk (1UL << APSR_C_Pos) /*!< APSR: C Mask */
+
+#define APSR_V_Pos 28U /*!< APSR: V Position */
+#define APSR_V_Msk (1UL << APSR_V_Pos) /*!< APSR: V Mask */
+
+
+/**
+ \brief Union type to access the Interrupt Program Status Register (IPSR).
+ */
+typedef union
+{
+ struct
+ {
+ uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */
+ uint32_t _reserved0:23; /*!< bit: 9..31 Reserved */
+ } b; /*!< Structure used for bit access */
+ uint32_t w; /*!< Type used for word access */
+} IPSR_Type;
+
+/* IPSR Register Definitions */
+#define IPSR_ISR_Pos 0U /*!< IPSR: ISR Position */
+#define IPSR_ISR_Msk (0x1FFUL /*<< IPSR_ISR_Pos*/) /*!< IPSR: ISR Mask */
+
+
+/**
+ \brief Union type to access the Special-Purpose Program Status Registers (xPSR).
+ */
+typedef union
+{
+ struct
+ {
+ uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */
+ uint32_t _reserved0:15; /*!< bit: 9..23 Reserved */
+ uint32_t T:1; /*!< bit: 24 Thumb bit (read 0) */
+ uint32_t _reserved1:3; /*!< bit: 25..27 Reserved */
+ uint32_t V:1; /*!< bit: 28 Overflow condition code flag */
+ uint32_t C:1; /*!< bit: 29 Carry condition code flag */
+ uint32_t Z:1; /*!< bit: 30 Zero condition code flag */
+ uint32_t N:1; /*!< bit: 31 Negative condition code flag */
+ } b; /*!< Structure used for bit access */
+ uint32_t w; /*!< Type used for word access */
+} xPSR_Type;
+
+/* xPSR Register Definitions */
+#define xPSR_N_Pos 31U /*!< xPSR: N Position */
+#define xPSR_N_Msk (1UL << xPSR_N_Pos) /*!< xPSR: N Mask */
+
+#define xPSR_Z_Pos 30U /*!< xPSR: Z Position */
+#define xPSR_Z_Msk (1UL << xPSR_Z_Pos) /*!< xPSR: Z Mask */
+
+#define xPSR_C_Pos 29U /*!< xPSR: C Position */
+#define xPSR_C_Msk (1UL << xPSR_C_Pos) /*!< xPSR: C Mask */
+
+#define xPSR_V_Pos 28U /*!< xPSR: V Position */
+#define xPSR_V_Msk (1UL << xPSR_V_Pos) /*!< xPSR: V Mask */
+
+#define xPSR_T_Pos 24U /*!< xPSR: T Position */
+#define xPSR_T_Msk (1UL << xPSR_T_Pos) /*!< xPSR: T Mask */
+
+#define xPSR_ISR_Pos 0U /*!< xPSR: ISR Position */
+#define xPSR_ISR_Msk (0x1FFUL /*<< xPSR_ISR_Pos*/) /*!< xPSR: ISR Mask */
+
+
+/**
+ \brief Union type to access the Control Registers (CONTROL).
+ */
+typedef union
+{
+ struct
+ {
+ uint32_t _reserved0:1; /*!< bit: 0 Reserved */
+ uint32_t SPSEL:1; /*!< bit: 1 Stack to be used */
+ uint32_t _reserved1:30; /*!< bit: 2..31 Reserved */
+ } b; /*!< Structure used for bit access */
+ uint32_t w; /*!< Type used for word access */
+} CONTROL_Type;
+
+/* CONTROL Register Definitions */
+#define CONTROL_SPSEL_Pos 1U /*!< CONTROL: SPSEL Position */
+#define CONTROL_SPSEL_Msk (1UL << CONTROL_SPSEL_Pos) /*!< CONTROL: SPSEL Mask */
+
+/*@} end of group CMSIS_CORE */
+
+
+/**
+ \ingroup CMSIS_core_register
+ \defgroup CMSIS_NVIC Nested Vectored Interrupt Controller (NVIC)
+ \brief Type definitions for the NVIC Registers
+ @{
+ */
+
+/**
+ \brief Structure type to access the Nested Vectored Interrupt Controller (NVIC).
+ */
+typedef struct
+{
+ __IOM uint32_t ISER[1U]; /*!< Offset: 0x000 (R/W) Interrupt Set Enable Register */
+ uint32_t RESERVED0[31U];
+ __IOM uint32_t ICER[1U]; /*!< Offset: 0x080 (R/W) Interrupt Clear Enable Register */
+ uint32_t RSERVED1[31U];
+ __IOM uint32_t ISPR[1U]; /*!< Offset: 0x100 (R/W) Interrupt Set Pending Register */
+ uint32_t RESERVED2[31U];
+ __IOM uint32_t ICPR[1U]; /*!< Offset: 0x180 (R/W) Interrupt Clear Pending Register */
+ uint32_t RESERVED3[31U];
+ uint32_t RESERVED4[64U];
+ __IOM uint32_t IP[8U]; /*!< Offset: 0x300 (R/W) Interrupt Priority Register */
+} NVIC_Type;
+
+/*@} end of group CMSIS_NVIC */
+
+
+/**
+ \ingroup CMSIS_core_register
+ \defgroup CMSIS_SCB System Control Block (SCB)
+ \brief Type definitions for the System Control Block Registers
+ @{
+ */
+
+/**
+ \brief Structure type to access the System Control Block (SCB).
+ */
+typedef struct
+{
+ __IM uint32_t CPUID; /*!< Offset: 0x000 (R/ ) CPUID Base Register */
+ __IOM uint32_t ICSR; /*!< Offset: 0x004 (R/W) Interrupt Control and State Register */
+ uint32_t RESERVED0;
+ __IOM uint32_t AIRCR; /*!< Offset: 0x00C (R/W) Application Interrupt and Reset Control Register */
+ __IOM uint32_t SCR; /*!< Offset: 0x010 (R/W) System Control Register */
+ __IOM uint32_t CCR; /*!< Offset: 0x014 (R/W) Configuration Control Register */
+ uint32_t RESERVED1;
+ __IOM uint32_t SHP[2U]; /*!< Offset: 0x01C (R/W) System Handlers Priority Registers. [0] is RESERVED */
+ __IOM uint32_t SHCSR; /*!< Offset: 0x024 (R/W) System Handler Control and State Register */
+} SCB_Type;
+
+/* SCB CPUID Register Definitions */
+#define SCB_CPUID_IMPLEMENTER_Pos 24U /*!< SCB CPUID: IMPLEMENTER Position */
+#define SCB_CPUID_IMPLEMENTER_Msk (0xFFUL << SCB_CPUID_IMPLEMENTER_Pos) /*!< SCB CPUID: IMPLEMENTER Mask */
+
+#define SCB_CPUID_VARIANT_Pos 20U /*!< SCB CPUID: VARIANT Position */
+#define SCB_CPUID_VARIANT_Msk (0xFUL << SCB_CPUID_VARIANT_Pos) /*!< SCB CPUID: VARIANT Mask */
+
+#define SCB_CPUID_ARCHITECTURE_Pos 16U /*!< SCB CPUID: ARCHITECTURE Position */
+#define SCB_CPUID_ARCHITECTURE_Msk (0xFUL << SCB_CPUID_ARCHITECTURE_Pos) /*!< SCB CPUID: ARCHITECTURE Mask */
+
+#define SCB_CPUID_PARTNO_Pos 4U /*!< SCB CPUID: PARTNO Position */
+#define SCB_CPUID_PARTNO_Msk (0xFFFUL << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */
+
+#define SCB_CPUID_REVISION_Pos 0U /*!< SCB CPUID: REVISION Position */
+#define SCB_CPUID_REVISION_Msk (0xFUL /*<< SCB_CPUID_REVISION_Pos*/) /*!< SCB CPUID: REVISION Mask */
+
+/* SCB Interrupt Control State Register Definitions */
+#define SCB_ICSR_NMIPENDSET_Pos 31U /*!< SCB ICSR: NMIPENDSET Position */
+#define SCB_ICSR_NMIPENDSET_Msk (1UL << SCB_ICSR_NMIPENDSET_Pos) /*!< SCB ICSR: NMIPENDSET Mask */
+
+#define SCB_ICSR_PENDSVSET_Pos 28U /*!< SCB ICSR: PENDSVSET Position */
+#define SCB_ICSR_PENDSVSET_Msk (1UL << SCB_ICSR_PENDSVSET_Pos) /*!< SCB ICSR: PENDSVSET Mask */
+
+#define SCB_ICSR_PENDSVCLR_Pos 27U /*!< SCB ICSR: PENDSVCLR Position */
+#define SCB_ICSR_PENDSVCLR_Msk (1UL << SCB_ICSR_PENDSVCLR_Pos) /*!< SCB ICSR: PENDSVCLR Mask */
+
+#define SCB_ICSR_PENDSTSET_Pos 26U /*!< SCB ICSR: PENDSTSET Position */
+#define SCB_ICSR_PENDSTSET_Msk (1UL << SCB_ICSR_PENDSTSET_Pos) /*!< SCB ICSR: PENDSTSET Mask */
+
+#define SCB_ICSR_PENDSTCLR_Pos 25U /*!< SCB ICSR: PENDSTCLR Position */
+#define SCB_ICSR_PENDSTCLR_Msk (1UL << SCB_ICSR_PENDSTCLR_Pos) /*!< SCB ICSR: PENDSTCLR Mask */
+
+#define SCB_ICSR_ISRPREEMPT_Pos 23U /*!< SCB ICSR: ISRPREEMPT Position */
+#define SCB_ICSR_ISRPREEMPT_Msk (1UL << SCB_ICSR_ISRPREEMPT_Pos) /*!< SCB ICSR: ISRPREEMPT Mask */
+
+#define SCB_ICSR_ISRPENDING_Pos 22U /*!< SCB ICSR: ISRPENDING Position */
+#define SCB_ICSR_ISRPENDING_Msk (1UL << SCB_ICSR_ISRPENDING_Pos) /*!< SCB ICSR: ISRPENDING Mask */
+
+#define SCB_ICSR_VECTPENDING_Pos 12U /*!< SCB ICSR: VECTPENDING Position */
+#define SCB_ICSR_VECTPENDING_Msk (0x1FFUL << SCB_ICSR_VECTPENDING_Pos) /*!< SCB ICSR: VECTPENDING Mask */
+
+#define SCB_ICSR_VECTACTIVE_Pos 0U /*!< SCB ICSR: VECTACTIVE Position */
+#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL /*<< SCB_ICSR_VECTACTIVE_Pos*/) /*!< SCB ICSR: VECTACTIVE Mask */
+
+/* SCB Application Interrupt and Reset Control Register Definitions */
+#define SCB_AIRCR_VECTKEY_Pos 16U /*!< SCB AIRCR: VECTKEY Position */
+#define SCB_AIRCR_VECTKEY_Msk (0xFFFFUL << SCB_AIRCR_VECTKEY_Pos) /*!< SCB AIRCR: VECTKEY Mask */
+
+#define SCB_AIRCR_VECTKEYSTAT_Pos 16U /*!< SCB AIRCR: VECTKEYSTAT Position */
+#define SCB_AIRCR_VECTKEYSTAT_Msk (0xFFFFUL << SCB_AIRCR_VECTKEYSTAT_Pos) /*!< SCB AIRCR: VECTKEYSTAT Mask */
+
+#define SCB_AIRCR_ENDIANESS_Pos 15U /*!< SCB AIRCR: ENDIANESS Position */
+#define SCB_AIRCR_ENDIANESS_Msk (1UL << SCB_AIRCR_ENDIANESS_Pos) /*!< SCB AIRCR: ENDIANESS Mask */
+
+#define SCB_AIRCR_SYSRESETREQ_Pos 2U /*!< SCB AIRCR: SYSRESETREQ Position */
+#define SCB_AIRCR_SYSRESETREQ_Msk (1UL << SCB_AIRCR_SYSRESETREQ_Pos) /*!< SCB AIRCR: SYSRESETREQ Mask */
+
+#define SCB_AIRCR_VECTCLRACTIVE_Pos 1U /*!< SCB AIRCR: VECTCLRACTIVE Position */
+#define SCB_AIRCR_VECTCLRACTIVE_Msk (1UL << SCB_AIRCR_VECTCLRACTIVE_Pos) /*!< SCB AIRCR: VECTCLRACTIVE Mask */
+
+/* SCB System Control Register Definitions */
+#define SCB_SCR_SEVONPEND_Pos 4U /*!< SCB SCR: SEVONPEND Position */
+#define SCB_SCR_SEVONPEND_Msk (1UL << SCB_SCR_SEVONPEND_Pos) /*!< SCB SCR: SEVONPEND Mask */
+
+#define SCB_SCR_SLEEPDEEP_Pos 2U /*!< SCB SCR: SLEEPDEEP Position */
+#define SCB_SCR_SLEEPDEEP_Msk (1UL << SCB_SCR_SLEEPDEEP_Pos) /*!< SCB SCR: SLEEPDEEP Mask */
+
+#define SCB_SCR_SLEEPONEXIT_Pos 1U /*!< SCB SCR: SLEEPONEXIT Position */
+#define SCB_SCR_SLEEPONEXIT_Msk (1UL << SCB_SCR_SLEEPONEXIT_Pos) /*!< SCB SCR: SLEEPONEXIT Mask */
+
+/* SCB Configuration Control Register Definitions */
+#define SCB_CCR_STKALIGN_Pos 9U /*!< SCB CCR: STKALIGN Position */
+#define SCB_CCR_STKALIGN_Msk (1UL << SCB_CCR_STKALIGN_Pos) /*!< SCB CCR: STKALIGN Mask */
+
+#define SCB_CCR_UNALIGN_TRP_Pos 3U /*!< SCB CCR: UNALIGN_TRP Position */
+#define SCB_CCR_UNALIGN_TRP_Msk (1UL << SCB_CCR_UNALIGN_TRP_Pos) /*!< SCB CCR: UNALIGN_TRP Mask */
+
+/* SCB System Handler Control and State Register Definitions */
+#define SCB_SHCSR_SVCALLPENDED_Pos 15U /*!< SCB SHCSR: SVCALLPENDED Position */
+#define SCB_SHCSR_SVCALLPENDED_Msk (1UL << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SHCSR: SVCALLPENDED Mask */
+
+/*@} end of group CMSIS_SCB */
+
+
+/**
+ \ingroup CMSIS_core_register
+ \defgroup CMSIS_SysTick System Tick Timer (SysTick)
+ \brief Type definitions for the System Timer Registers.
+ @{
+ */
+
+/**
+ \brief Structure type to access the System Timer (SysTick).
+ */
+typedef struct
+{
+ __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) SysTick Control and Status Register */
+ __IOM uint32_t LOAD; /*!< Offset: 0x004 (R/W) SysTick Reload Value Register */
+ __IOM uint32_t VAL; /*!< Offset: 0x008 (R/W) SysTick Current Value Register */
+ __IM uint32_t CALIB; /*!< Offset: 0x00C (R/ ) SysTick Calibration Register */
+} SysTick_Type;
+
+/* SysTick Control / Status Register Definitions */
+#define SysTick_CTRL_COUNTFLAG_Pos 16U /*!< SysTick CTRL: COUNTFLAG Position */
+#define SysTick_CTRL_COUNTFLAG_Msk (1UL << SysTick_CTRL_COUNTFLAG_Pos) /*!< SysTick CTRL: COUNTFLAG Mask */
+
+#define SysTick_CTRL_CLKSOURCE_Pos 2U /*!< SysTick CTRL: CLKSOURCE Position */
+#define SysTick_CTRL_CLKSOURCE_Msk (1UL << SysTick_CTRL_CLKSOURCE_Pos) /*!< SysTick CTRL: CLKSOURCE Mask */
+
+#define SysTick_CTRL_TICKINT_Pos 1U /*!< SysTick CTRL: TICKINT Position */
+#define SysTick_CTRL_TICKINT_Msk (1UL << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */
+
+#define SysTick_CTRL_ENABLE_Pos 0U /*!< SysTick CTRL: ENABLE Position */
+#define SysTick_CTRL_ENABLE_Msk (1UL /*<< SysTick_CTRL_ENABLE_Pos*/) /*!< SysTick CTRL: ENABLE Mask */
+
+/* SysTick Reload Register Definitions */
+#define SysTick_LOAD_RELOAD_Pos 0U /*!< SysTick LOAD: RELOAD Position */
+#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL /*<< SysTick_LOAD_RELOAD_Pos*/) /*!< SysTick LOAD: RELOAD Mask */
+
+/* SysTick Current Register Definitions */
+#define SysTick_VAL_CURRENT_Pos 0U /*!< SysTick VAL: CURRENT Position */
+#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL /*<< SysTick_VAL_CURRENT_Pos*/) /*!< SysTick VAL: CURRENT Mask */
+
+/* SysTick Calibration Register Definitions */
+#define SysTick_CALIB_NOREF_Pos 31U /*!< SysTick CALIB: NOREF Position */
+#define SysTick_CALIB_NOREF_Msk (1UL << SysTick_CALIB_NOREF_Pos) /*!< SysTick CALIB: NOREF Mask */
+
+#define SysTick_CALIB_SKEW_Pos 30U /*!< SysTick CALIB: SKEW Position */
+#define SysTick_CALIB_SKEW_Msk (1UL << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */
+
+#define SysTick_CALIB_TENMS_Pos 0U /*!< SysTick CALIB: TENMS Position */
+#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL /*<< SysTick_CALIB_TENMS_Pos*/) /*!< SysTick CALIB: TENMS Mask */
+
+/*@} end of group CMSIS_SysTick */
+
+
+/**
+ \ingroup CMSIS_core_register
+ \defgroup CMSIS_CoreDebug Core Debug Registers (CoreDebug)
+ \brief Cortex-M0 Core Debug Registers (DCB registers, SHCSR, and DFSR) are only accessible over DAP and not via processor.
+ Therefore they are not covered by the Cortex-M0 header file.
+ @{
+ */
+/*@} end of group CMSIS_CoreDebug */
+
+
+/**
+ \ingroup CMSIS_core_register
+ \defgroup CMSIS_core_bitfield Core register bit field macros
+ \brief Macros for use with bit field definitions (xxx_Pos, xxx_Msk).
+ @{
+ */
+
+/**
+ \brief Mask and shift a bit field value for use in a register bit range.
+ \param[in] field Name of the register bit field.
+ \param[in] value Value of the bit field. This parameter is interpreted as an uint32_t type.
+ \return Masked and shifted value.
+*/
+#define _VAL2FLD(field, value) (((uint32_t)(value) << field ## _Pos) & field ## _Msk)
+
+/**
+ \brief Mask and shift a register value to extract a bit filed value.
+ \param[in] field Name of the register bit field.
+ \param[in] value Value of register. This parameter is interpreted as an uint32_t type.
+ \return Masked and shifted bit field value.
+*/
+#define _FLD2VAL(field, value) (((uint32_t)(value) & field ## _Msk) >> field ## _Pos)
+
+/*@} end of group CMSIS_core_bitfield */
+
+
+/**
+ \ingroup CMSIS_core_register
+ \defgroup CMSIS_core_base Core Definitions
+ \brief Definitions for base addresses, unions, and structures.
+ @{
+ */
+
+/* Memory mapping of Core Hardware */
+#define SCS_BASE (0xE000E000UL) /*!< System Control Space Base Address */
+#define SysTick_BASE (SCS_BASE + 0x0010UL) /*!< SysTick Base Address */
+#define NVIC_BASE (SCS_BASE + 0x0100UL) /*!< NVIC Base Address */
+#define SCB_BASE (SCS_BASE + 0x0D00UL) /*!< System Control Block Base Address */
+
+#define SCB ((SCB_Type *) SCB_BASE ) /*!< SCB configuration struct */
+#define SysTick ((SysTick_Type *) SysTick_BASE ) /*!< SysTick configuration struct */
+#define NVIC ((NVIC_Type *) NVIC_BASE ) /*!< NVIC configuration struct */
+
+
+/*@} */
+
+
+
+/*******************************************************************************
+ * Hardware Abstraction Layer
+ Core Function Interface contains:
+ - Core NVIC Functions
+ - Core SysTick Functions
+ - Core Register Access Functions
+ ******************************************************************************/
+/**
+ \defgroup CMSIS_Core_FunctionInterface Functions and Instructions Reference
+*/
+
+
+
+/* ########################## NVIC functions #################################### */
+/**
+ \ingroup CMSIS_Core_FunctionInterface
+ \defgroup CMSIS_Core_NVICFunctions NVIC Functions
+ \brief Functions that manage interrupts and exceptions via the NVIC.
+ @{
+ */
+
+#ifdef CMSIS_NVIC_VIRTUAL
+ #ifndef CMSIS_NVIC_VIRTUAL_HEADER_FILE
+ #define CMSIS_NVIC_VIRTUAL_HEADER_FILE "cmsis_nvic_virtual.h"
+ #endif
+ #include CMSIS_NVIC_VIRTUAL_HEADER_FILE
+#else
+ #define NVIC_SetPriorityGrouping __NVIC_SetPriorityGrouping
+ #define NVIC_GetPriorityGrouping __NVIC_GetPriorityGrouping
+ #define NVIC_EnableIRQ __NVIC_EnableIRQ
+ #define NVIC_GetEnableIRQ __NVIC_GetEnableIRQ
+ #define NVIC_DisableIRQ __NVIC_DisableIRQ
+ #define NVIC_GetPendingIRQ __NVIC_GetPendingIRQ
+ #define NVIC_SetPendingIRQ __NVIC_SetPendingIRQ
+ #define NVIC_ClearPendingIRQ __NVIC_ClearPendingIRQ
+/*#define NVIC_GetActive __NVIC_GetActive not available for Cortex-M0 */
+ #define NVIC_SetPriority __NVIC_SetPriority
+ #define NVIC_GetPriority __NVIC_GetPriority
+ #define NVIC_SystemReset __NVIC_SystemReset
+#endif /* CMSIS_NVIC_VIRTUAL */
+
+#ifdef CMSIS_VECTAB_VIRTUAL
+ #ifndef CMSIS_VECTAB_VIRTUAL_HEADER_FILE
+ #define CMSIS_VECTAB_VIRTUAL_HEADER_FILE "cmsis_vectab_virtual.h"
+ #endif
+ #include CMSIS_VECTAB_VIRTUAL_HEADER_FILE
+#else
+ #define NVIC_SetVector __NVIC_SetVector
+ #define NVIC_GetVector __NVIC_GetVector
+#endif /* (CMSIS_VECTAB_VIRTUAL) */
+
+#define NVIC_USER_IRQ_OFFSET 16
+
+
+/* The following EXC_RETURN values are saved the LR on exception entry */
+#define EXC_RETURN_HANDLER (0xFFFFFFF1UL) /* return to Handler mode, uses MSP after return */
+#define EXC_RETURN_THREAD_MSP (0xFFFFFFF9UL) /* return to Thread mode, uses MSP after return */
+#define EXC_RETURN_THREAD_PSP (0xFFFFFFFDUL) /* return to Thread mode, uses PSP after return */
+
+
+/* Interrupt Priorities are WORD accessible only under Armv6-M */
+/* The following MACROS handle generation of the register offset and byte masks */
+#define _BIT_SHIFT(IRQn) ( ((((uint32_t)(int32_t)(IRQn)) ) & 0x03UL) * 8UL)
+#define _SHP_IDX(IRQn) ( (((((uint32_t)(int32_t)(IRQn)) & 0x0FUL)-8UL) >> 2UL) )
+#define _IP_IDX(IRQn) ( (((uint32_t)(int32_t)(IRQn)) >> 2UL) )
+
+#define __NVIC_SetPriorityGrouping(X) (void)(X)
+#define __NVIC_GetPriorityGrouping() (0U)
+
+/**
+ \brief Enable Interrupt
+ \details Enables a device specific interrupt in the NVIC interrupt controller.
+ \param [in] IRQn Device specific interrupt number.
+ \note IRQn must not be negative.
+ */
+__STATIC_INLINE void __NVIC_EnableIRQ(IRQn_Type IRQn)
+{
+ if ((int32_t)(IRQn) >= 0)
+ {
+ NVIC->ISER[0U] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL));
+ }
+}
+
+
+/**
+ \brief Get Interrupt Enable status
+ \details Returns a device specific interrupt enable status from the NVIC interrupt controller.
+ \param [in] IRQn Device specific interrupt number.
+ \return 0 Interrupt is not enabled.
+ \return 1 Interrupt is enabled.
+ \note IRQn must not be negative.
+ */
+__STATIC_INLINE uint32_t __NVIC_GetEnableIRQ(IRQn_Type IRQn)
+{
+ if ((int32_t)(IRQn) >= 0)
+ {
+ return((uint32_t)(((NVIC->ISER[0U] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL));
+ }
+ else
+ {
+ return(0U);
+ }
+}
+
+
+/**
+ \brief Disable Interrupt
+ \details Disables a device specific interrupt in the NVIC interrupt controller.
+ \param [in] IRQn Device specific interrupt number.
+ \note IRQn must not be negative.
+ */
+__STATIC_INLINE void __NVIC_DisableIRQ(IRQn_Type IRQn)
+{
+ if ((int32_t)(IRQn) >= 0)
+ {
+ NVIC->ICER[0U] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL));
+ __DSB();
+ __ISB();
+ }
+}
+
+
+/**
+ \brief Get Pending Interrupt
+ \details Reads the NVIC pending register and returns the pending bit for the specified device specific interrupt.
+ \param [in] IRQn Device specific interrupt number.
+ \return 0 Interrupt status is not pending.
+ \return 1 Interrupt status is pending.
+ \note IRQn must not be negative.
+ */
+__STATIC_INLINE uint32_t __NVIC_GetPendingIRQ(IRQn_Type IRQn)
+{
+ if ((int32_t)(IRQn) >= 0)
+ {
+ return((uint32_t)(((NVIC->ISPR[0U] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL));
+ }
+ else
+ {
+ return(0U);
+ }
+}
+
+
+/**
+ \brief Set Pending Interrupt
+ \details Sets the pending bit of a device specific interrupt in the NVIC pending register.
+ \param [in] IRQn Device specific interrupt number.
+ \note IRQn must not be negative.
+ */
+__STATIC_INLINE void __NVIC_SetPendingIRQ(IRQn_Type IRQn)
+{
+ if ((int32_t)(IRQn) >= 0)
+ {
+ NVIC->ISPR[0U] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL));
+ }
+}
+
+
+/**
+ \brief Clear Pending Interrupt
+ \details Clears the pending bit of a device specific interrupt in the NVIC pending register.
+ \param [in] IRQn Device specific interrupt number.
+ \note IRQn must not be negative.
+ */
+__STATIC_INLINE void __NVIC_ClearPendingIRQ(IRQn_Type IRQn)
+{
+ if ((int32_t)(IRQn) >= 0)
+ {
+ NVIC->ICPR[0U] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL));
+ }
+}
+
+
+/**
+ \brief Set Interrupt Priority
+ \details Sets the priority of a device specific interrupt or a processor exception.
+ The interrupt number can be positive to specify a device specific interrupt,
+ or negative to specify a processor exception.
+ \param [in] IRQn Interrupt number.
+ \param [in] priority Priority to set.
+ \note The priority cannot be set for every processor exception.
+ */
+__STATIC_INLINE void __NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority)
+{
+ if ((int32_t)(IRQn) >= 0)
+ {
+ NVIC->IP[_IP_IDX(IRQn)] = ((uint32_t)(NVIC->IP[_IP_IDX(IRQn)] & ~(0xFFUL << _BIT_SHIFT(IRQn))) |
+ (((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL) << _BIT_SHIFT(IRQn)));
+ }
+ else
+ {
+ SCB->SHP[_SHP_IDX(IRQn)] = ((uint32_t)(SCB->SHP[_SHP_IDX(IRQn)] & ~(0xFFUL << _BIT_SHIFT(IRQn))) |
+ (((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL) << _BIT_SHIFT(IRQn)));
+ }
+}
+
+
+/**
+ \brief Get Interrupt Priority
+ \details Reads the priority of a device specific interrupt or a processor exception.
+ The interrupt number can be positive to specify a device specific interrupt,
+ or negative to specify a processor exception.
+ \param [in] IRQn Interrupt number.
+ \return Interrupt Priority.
+ Value is aligned automatically to the implemented priority bits of the microcontroller.
+ */
+__STATIC_INLINE uint32_t __NVIC_GetPriority(IRQn_Type IRQn)
+{
+
+ if ((int32_t)(IRQn) >= 0)
+ {
+ return((uint32_t)(((NVIC->IP[ _IP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & (uint32_t)0xFFUL) >> (8U - __NVIC_PRIO_BITS)));
+ }
+ else
+ {
+ return((uint32_t)(((SCB->SHP[_SHP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & (uint32_t)0xFFUL) >> (8U - __NVIC_PRIO_BITS)));
+ }
+}
+
+
+/**
+ \brief Encode Priority
+ \details Encodes the priority for an interrupt with the given priority group,
+ preemptive priority value, and subpriority value.
+ In case of a conflict between priority grouping and available
+ priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set.
+ \param [in] PriorityGroup Used priority group.
+ \param [in] PreemptPriority Preemptive priority value (starting from 0).
+ \param [in] SubPriority Subpriority value (starting from 0).
+ \return Encoded priority. Value can be used in the function \ref NVIC_SetPriority().
+ */
+__STATIC_INLINE uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t PreemptPriority, uint32_t SubPriority)
+{
+ uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */
+ uint32_t PreemptPriorityBits;
+ uint32_t SubPriorityBits;
+
+ PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp);
+ SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS));
+
+ return (
+ ((PreemptPriority & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL)) << SubPriorityBits) |
+ ((SubPriority & (uint32_t)((1UL << (SubPriorityBits )) - 1UL)))
+ );
+}
+
+
+/**
+ \brief Decode Priority
+ \details Decodes an interrupt priority value with a given priority group to
+ preemptive priority value and subpriority value.
+ In case of a conflict between priority grouping and available
+ priority bits (__NVIC_PRIO_BITS) the smallest possible priority group is set.
+ \param [in] Priority Priority value, which can be retrieved with the function \ref NVIC_GetPriority().
+ \param [in] PriorityGroup Used priority group.
+ \param [out] pPreemptPriority Preemptive priority value (starting from 0).
+ \param [out] pSubPriority Subpriority value (starting from 0).
+ */
+__STATIC_INLINE void NVIC_DecodePriority (uint32_t Priority, uint32_t PriorityGroup, uint32_t* const pPreemptPriority, uint32_t* const pSubPriority)
+{
+ uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */
+ uint32_t PreemptPriorityBits;
+ uint32_t SubPriorityBits;
+
+ PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp);
+ SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS));
+
+ *pPreemptPriority = (Priority >> SubPriorityBits) & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL);
+ *pSubPriority = (Priority ) & (uint32_t)((1UL << (SubPriorityBits )) - 1UL);
+}
+
+
+
+/**
+ \brief Set Interrupt Vector
+ \details Sets an interrupt vector in SRAM based interrupt vector table.
+ The interrupt number can be positive to specify a device specific interrupt,
+ or negative to specify a processor exception.
+ Address 0 must be mapped to SRAM.
+ \param [in] IRQn Interrupt number
+ \param [in] vector Address of interrupt handler function
+ */
+__STATIC_INLINE void __NVIC_SetVector(IRQn_Type IRQn, uint32_t vector)
+{
+ uint32_t *vectors = (uint32_t *)0x0U;
+ vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET] = vector;
+}
+
+
+/**
+ \brief Get Interrupt Vector
+ \details Reads an interrupt vector from interrupt vector table.
+ The interrupt number can be positive to specify a device specific interrupt,
+ or negative to specify a processor exception.
+ \param [in] IRQn Interrupt number.
+ \return Address of interrupt handler function
+ */
+__STATIC_INLINE uint32_t __NVIC_GetVector(IRQn_Type IRQn)
+{
+ uint32_t *vectors = (uint32_t *)0x0U;
+ return vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET];
+}
+
+
+/**
+ \brief System Reset
+ \details Initiates a system reset request to reset the MCU.
+ */
+__NO_RETURN __STATIC_INLINE void __NVIC_SystemReset(void)
+{
+ __DSB(); /* Ensure all outstanding memory accesses included
+ buffered write are completed before reset */
+ SCB->AIRCR = ((0x5FAUL << SCB_AIRCR_VECTKEY_Pos) |
+ SCB_AIRCR_SYSRESETREQ_Msk);
+ __DSB(); /* Ensure completion of memory access */
+
+ for(;;) /* wait until reset */
+ {
+ __NOP();
+ }
+}
+
+/*@} end of CMSIS_Core_NVICFunctions */
+
+
+/* ########################## FPU functions #################################### */
+/**
+ \ingroup CMSIS_Core_FunctionInterface
+ \defgroup CMSIS_Core_FpuFunctions FPU Functions
+ \brief Function that provides FPU type.
+ @{
+ */
+
+/**
+ \brief get FPU type
+ \details returns the FPU type
+ \returns
+ - \b 0: No FPU
+ - \b 1: Single precision FPU
+ - \b 2: Double + Single precision FPU
+ */
+__STATIC_INLINE uint32_t SCB_GetFPUType(void)
+{
+ return 0U; /* No FPU */
+}
+
+
+/*@} end of CMSIS_Core_FpuFunctions */
+
+
+
+/* ################################## SysTick function ############################################ */
+/**
+ \ingroup CMSIS_Core_FunctionInterface
+ \defgroup CMSIS_Core_SysTickFunctions SysTick Functions
+ \brief Functions that configure the System.
+ @{
+ */
+
+#if defined (__Vendor_SysTickConfig) && (__Vendor_SysTickConfig == 0U)
+
+/**
+ \brief System Tick Configuration
+ \details Initializes the System Timer and its interrupt, and starts the System Tick Timer.
+ Counter is in free running mode to generate periodic interrupts.
+ \param [in] ticks Number of ticks between two interrupts.
+ \return 0 Function succeeded.
+ \return 1 Function failed.
+ \note When the variable __Vendor_SysTickConfig is set to 1, then the
+ function SysTick_Config is not included. In this case, the file device.h
+ must contain a vendor-specific implementation of this function.
+ */
+__STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks)
+{
+ if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk)
+ {
+ return (1UL); /* Reload value impossible */
+ }
+
+ SysTick->LOAD = (uint32_t)(ticks - 1UL); /* set reload register */
+ NVIC_SetPriority (SysTick_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL); /* set Priority for Systick Interrupt */
+ SysTick->VAL = 0UL; /* Load the SysTick Counter Value */
+ SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk |
+ SysTick_CTRL_TICKINT_Msk |
+ SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */
+ return (0UL); /* Function successful */
+}
+
+#endif
+
+/*@} end of CMSIS_Core_SysTickFunctions */
+
+
+
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __CORE_CM0_H_DEPENDANT */
+
+#endif /* __CMSIS_GENERIC */
diff --git a/peripherals/cc48x6/firmware/Drivers/CMSIS/LICENSE.txt b/peripherals/cc48x6/firmware/Drivers/CMSIS/LICENSE.txt
new file mode 100644
index 0000000..8dada3e
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Drivers/CMSIS/LICENSE.txt
@@ -0,0 +1,201 @@
+ Apache License
+ Version 2.0, January 2004
+ http://www.apache.org/licenses/
+
+ TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION
+
+ 1. Definitions.
+
+ "License" shall mean the terms and conditions for use, reproduction,
+ and distribution as defined by Sections 1 through 9 of this document.
+
+ "Licensor" shall mean the copyright owner or entity authorized by
+ the copyright owner that is granting the License.
+
+ "Legal Entity" shall mean the union of the acting entity and all
+ other entities that control, are controlled by, or are under common
+ control with that entity. For the purposes of this definition,
+ "control" means (i) the power, direct or indirect, to cause the
+ direction or management of such entity, whether by contract or
+ otherwise, or (ii) ownership of fifty percent (50%) or more of the
+ outstanding shares, or (iii) beneficial ownership of such entity.
+
+ "You" (or "Your") shall mean an individual or Legal Entity
+ exercising permissions granted by this License.
+
+ "Source" form shall mean the preferred form for making modifications,
+ including but not limited to software source code, documentation
+ source, and configuration files.
+
+ "Object" form shall mean any form resulting from mechanical
+ transformation or translation of a Source form, including but
+ not limited to compiled object code, generated documentation,
+ and conversions to other media types.
+
+ "Work" shall mean the work of authorship, whether in Source or
+ Object form, made available under the License, as indicated by a
+ copyright notice that is included in or attached to the work
+ (an example is provided in the Appendix below).
+
+ "Derivative Works" shall mean any work, whether in Source or Object
+ form, that is based on (or derived from) the Work and for which the
+ editorial revisions, annotations, elaborations, or other modifications
+ represent, as a whole, an original work of authorship. For the purposes
+ of this License, Derivative Works shall not include works that remain
+ separable from, or merely link (or bind by name) to the interfaces of,
+ the Work and Derivative Works thereof.
+
+ "Contribution" shall mean any work of authorship, including
+ the original version of the Work and any modifications or additions
+ to that Work or Derivative Works thereof, that is intentionally
+ submitted to Licensor for inclusion in the Work by the copyright owner
+ or by an individual or Legal Entity authorized to submit on behalf of
+ the copyright owner. For the purposes of this definition, "submitted"
+ means any form of electronic, verbal, or written communication sent
+ to the Licensor or its representatives, including but not limited to
+ communication on electronic mailing lists, source code control systems,
+ and issue tracking systems that are managed by, or on behalf of, the
+ Licensor for the purpose of discussing and improving the Work, but
+ excluding communication that is conspicuously marked or otherwise
+ designated in writing by the copyright owner as "Not a Contribution."
+
+ "Contributor" shall mean Licensor and any individual or Legal Entity
+ on behalf of whom a Contribution has been received by Licensor and
+ subsequently incorporated within the Work.
+
+ 2. Grant of Copyright License. Subject to the terms and conditions of
+ this License, each Contributor hereby grants to You a perpetual,
+ worldwide, non-exclusive, no-charge, royalty-free, irrevocable
+ copyright license to reproduce, prepare Derivative Works of,
+ publicly display, publicly perform, sublicense, and distribute the
+ Work and such Derivative Works in Source or Object form.
+
+ 3. Grant of Patent License. Subject to the terms and conditions of
+ this License, each Contributor hereby grants to You a perpetual,
+ worldwide, non-exclusive, no-charge, royalty-free, irrevocable
+ (except as stated in this section) patent license to make, have made,
+ use, offer to sell, sell, import, and otherwise transfer the Work,
+ where such license applies only to those patent claims licensable
+ by such Contributor that are necessarily infringed by their
+ Contribution(s) alone or by combination of their Contribution(s)
+ with the Work to which such Contribution(s) was submitted. If You
+ institute patent litigation against any entity (including a
+ cross-claim or counterclaim in a lawsuit) alleging that the Work
+ or a Contribution incorporated within the Work constitutes direct
+ or contributory patent infringement, then any patent licenses
+ granted to You under this License for that Work shall terminate
+ as of the date such litigation is filed.
+
+ 4. Redistribution. You may reproduce and distribute copies of the
+ Work or Derivative Works thereof in any medium, with or without
+ modifications, and in Source or Object form, provided that You
+ meet the following conditions:
+
+ (a) You must give any other recipients of the Work or
+ Derivative Works a copy of this License; and
+
+ (b) You must cause any modified files to carry prominent notices
+ stating that You changed the files; and
+
+ (c) You must retain, in the Source form of any Derivative Works
+ that You distribute, all copyright, patent, trademark, and
+ attribution notices from the Source form of the Work,
+ excluding those notices that do not pertain to any part of
+ the Derivative Works; and
+
+ (d) If the Work includes a "NOTICE" text file as part of its
+ distribution, then any Derivative Works that You distribute must
+ include a readable copy of the attribution notices contained
+ within such NOTICE file, excluding those notices that do not
+ pertain to any part of the Derivative Works, in at least one
+ of the following places: within a NOTICE text file distributed
+ as part of the Derivative Works; within the Source form or
+ documentation, if provided along with the Derivative Works; or,
+ within a display generated by the Derivative Works, if and
+ wherever such third-party notices normally appear. The contents
+ of the NOTICE file are for informational purposes only and
+ do not modify the License. You may add Your own attribution
+ notices within Derivative Works that You distribute, alongside
+ or as an addendum to the NOTICE text from the Work, provided
+ that such additional attribution notices cannot be construed
+ as modifying the License.
+
+ You may add Your own copyright statement to Your modifications and
+ may provide additional or different license terms and conditions
+ for use, reproduction, or distribution of Your modifications, or
+ for any such Derivative Works as a whole, provided Your use,
+ reproduction, and distribution of the Work otherwise complies with
+ the conditions stated in this License.
+
+ 5. Submission of Contributions. Unless You explicitly state otherwise,
+ any Contribution intentionally submitted for inclusion in the Work
+ by You to the Licensor shall be under the terms and conditions of
+ this License, without any additional terms or conditions.
+ Notwithstanding the above, nothing herein shall supersede or modify
+ the terms of any separate license agreement you may have executed
+ with Licensor regarding such Contributions.
+
+ 6. Trademarks. This License does not grant permission to use the trade
+ names, trademarks, service marks, or product names of the Licensor,
+ except as required for reasonable and customary use in describing the
+ origin of the Work and reproducing the content of the NOTICE file.
+
+ 7. Disclaimer of Warranty. Unless required by applicable law or
+ agreed to in writing, Licensor provides the Work (and each
+ Contributor provides its Contributions) on an "AS IS" BASIS,
+ WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or
+ implied, including, without limitation, any warranties or conditions
+ of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A
+ PARTICULAR PURPOSE. You are solely responsible for determining the
+ appropriateness of using or redistributing the Work and assume any
+ risks associated with Your exercise of permissions under this License.
+
+ 8. Limitation of Liability. In no event and under no legal theory,
+ whether in tort (including negligence), contract, or otherwise,
+ unless required by applicable law (such as deliberate and grossly
+ negligent acts) or agreed to in writing, shall any Contributor be
+ liable to You for damages, including any direct, indirect, special,
+ incidental, or consequential damages of any character arising as a
+ result of this License or out of the use or inability to use the
+ Work (including but not limited to damages for loss of goodwill,
+ work stoppage, computer failure or malfunction, or any and all
+ other commercial damages or losses), even if such Contributor
+ has been advised of the possibility of such damages.
+
+ 9. Accepting Warranty or Additional Liability. While redistributing
+ the Work or Derivative Works thereof, You may choose to offer,
+ and charge a fee for, acceptance of support, warranty, indemnity,
+ or other liability obligations and/or rights consistent with this
+ License. However, in accepting such obligations, You may act only
+ on Your own behalf and on Your sole responsibility, not on behalf
+ of any other Contributor, and only if You agree to indemnify,
+ defend, and hold each Contributor harmless for any liability
+ incurred by, or claims asserted against, such Contributor by reason
+ of your accepting any such warranty or additional liability.
+
+ END OF TERMS AND CONDITIONS
+
+ APPENDIX: How to apply the Apache License to your work.
+
+ To apply the Apache License to your work, attach the following
+ boilerplate notice, with the fields enclosed by brackets "{}"
+ replaced with your own identifying information. (Don't include
+ the brackets!) The text should be enclosed in the appropriate
+ comment syntax for the file format. We also recommend that a
+ file or class name and description of purpose be included on the
+ same "printed page" as the copyright notice for easier
+ identification within third-party archives.
+
+ Copyright {yyyy} {name of copyright owner}
+
+ Licensed under the Apache License, Version 2.0 (the "License");
+ you may not use this file except in compliance with the License.
+ You may obtain a copy of the License at
+
+ http://www.apache.org/licenses/LICENSE-2.0
+
+ Unless required by applicable law or agreed to in writing, software
+ distributed under the License is distributed on an "AS IS" BASIS,
+ WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+ See the License for the specific language governing permissions and
+ limitations under the License.
diff --git a/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/Legacy/stm32_hal_legacy.h b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/Legacy/stm32_hal_legacy.h
new file mode 100644
index 0000000..3a1d05e
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/Legacy/stm32_hal_legacy.h
@@ -0,0 +1,3850 @@
+/**
+ ******************************************************************************
+ * @file stm32_hal_legacy.h
+ * @author MCD Application Team
+ * @brief This file contains aliases definition for the STM32Cube HAL constants
+ * macros and functions maintained for legacy purpose.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2019 STMicroelectronics.
+ * All rights reserved.
+ *
+ * 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 STM32_HAL_LEGACY
+#define STM32_HAL_LEGACY
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+
+/** @defgroup HAL_AES_Aliased_Defines HAL CRYP Aliased Defines maintained for legacy purpose
+ * @{
+ */
+#define AES_FLAG_RDERR CRYP_FLAG_RDERR
+#define AES_FLAG_WRERR CRYP_FLAG_WRERR
+#define AES_CLEARFLAG_CCF CRYP_CLEARFLAG_CCF
+#define AES_CLEARFLAG_RDERR CRYP_CLEARFLAG_RDERR
+#define AES_CLEARFLAG_WRERR CRYP_CLEARFLAG_WRERR
+#if defined(STM32U5)
+#define CRYP_DATATYPE_32B CRYP_NO_SWAP
+#define CRYP_DATATYPE_16B CRYP_HALFWORD_SWAP
+#define CRYP_DATATYPE_8B CRYP_BYTE_SWAP
+#define CRYP_DATATYPE_1B CRYP_BIT_SWAP
+#define CRYP_CCF_CLEAR CRYP_CLEAR_CCF
+#define CRYP_ERR_CLEAR CRYP_CLEAR_RWEIF
+#endif /* STM32U5 */
+/**
+ * @}
+ */
+
+/** @defgroup HAL_ADC_Aliased_Defines HAL ADC Aliased Defines maintained for legacy purpose
+ * @{
+ */
+#define ADC_RESOLUTION12b ADC_RESOLUTION_12B
+#define ADC_RESOLUTION10b ADC_RESOLUTION_10B
+#define ADC_RESOLUTION8b ADC_RESOLUTION_8B
+#define ADC_RESOLUTION6b ADC_RESOLUTION_6B
+#define OVR_DATA_OVERWRITTEN ADC_OVR_DATA_OVERWRITTEN
+#define OVR_DATA_PRESERVED ADC_OVR_DATA_PRESERVED
+#define EOC_SINGLE_CONV ADC_EOC_SINGLE_CONV
+#define EOC_SEQ_CONV ADC_EOC_SEQ_CONV
+#define EOC_SINGLE_SEQ_CONV ADC_EOC_SINGLE_SEQ_CONV
+#define REGULAR_GROUP ADC_REGULAR_GROUP
+#define INJECTED_GROUP ADC_INJECTED_GROUP
+#define REGULAR_INJECTED_GROUP ADC_REGULAR_INJECTED_GROUP
+#define AWD_EVENT ADC_AWD_EVENT
+#define AWD1_EVENT ADC_AWD1_EVENT
+#define AWD2_EVENT ADC_AWD2_EVENT
+#define AWD3_EVENT ADC_AWD3_EVENT
+#define OVR_EVENT ADC_OVR_EVENT
+#define JQOVF_EVENT ADC_JQOVF_EVENT
+#define ALL_CHANNELS ADC_ALL_CHANNELS
+#define REGULAR_CHANNELS ADC_REGULAR_CHANNELS
+#define INJECTED_CHANNELS ADC_INJECTED_CHANNELS
+#define SYSCFG_FLAG_SENSOR_ADC ADC_FLAG_SENSOR
+#define SYSCFG_FLAG_VREF_ADC ADC_FLAG_VREFINT
+#define ADC_CLOCKPRESCALER_PCLK_DIV1 ADC_CLOCK_SYNC_PCLK_DIV1
+#define ADC_CLOCKPRESCALER_PCLK_DIV2 ADC_CLOCK_SYNC_PCLK_DIV2
+#define ADC_CLOCKPRESCALER_PCLK_DIV4 ADC_CLOCK_SYNC_PCLK_DIV4
+#define ADC_CLOCKPRESCALER_PCLK_DIV6 ADC_CLOCK_SYNC_PCLK_DIV6
+#define ADC_CLOCKPRESCALER_PCLK_DIV8 ADC_CLOCK_SYNC_PCLK_DIV8
+#define ADC_EXTERNALTRIG0_T6_TRGO ADC_EXTERNALTRIGCONV_T6_TRGO
+#define ADC_EXTERNALTRIG1_T21_CC2 ADC_EXTERNALTRIGCONV_T21_CC2
+#define ADC_EXTERNALTRIG2_T2_TRGO ADC_EXTERNALTRIGCONV_T2_TRGO
+#define ADC_EXTERNALTRIG3_T2_CC4 ADC_EXTERNALTRIGCONV_T2_CC4
+#define ADC_EXTERNALTRIG4_T22_TRGO ADC_EXTERNALTRIGCONV_T22_TRGO
+#define ADC_EXTERNALTRIG7_EXT_IT11 ADC_EXTERNALTRIGCONV_EXT_IT11
+#define ADC_CLOCK_ASYNC ADC_CLOCK_ASYNC_DIV1
+#define ADC_EXTERNALTRIG_EDGE_NONE ADC_EXTERNALTRIGCONVEDGE_NONE
+#define ADC_EXTERNALTRIG_EDGE_RISING ADC_EXTERNALTRIGCONVEDGE_RISING
+#define ADC_EXTERNALTRIG_EDGE_FALLING ADC_EXTERNALTRIGCONVEDGE_FALLING
+#define ADC_EXTERNALTRIG_EDGE_RISINGFALLING ADC_EXTERNALTRIGCONVEDGE_RISINGFALLING
+#define ADC_SAMPLETIME_2CYCLE_5 ADC_SAMPLETIME_2CYCLES_5
+
+#define HAL_ADC_STATE_BUSY_REG HAL_ADC_STATE_REG_BUSY
+#define HAL_ADC_STATE_BUSY_INJ HAL_ADC_STATE_INJ_BUSY
+#define HAL_ADC_STATE_EOC_REG HAL_ADC_STATE_REG_EOC
+#define HAL_ADC_STATE_EOC_INJ HAL_ADC_STATE_INJ_EOC
+#define HAL_ADC_STATE_ERROR HAL_ADC_STATE_ERROR_INTERNAL
+#define HAL_ADC_STATE_BUSY HAL_ADC_STATE_BUSY_INTERNAL
+#define HAL_ADC_STATE_AWD HAL_ADC_STATE_AWD1
+
+#if defined(STM32H7)
+#define ADC_CHANNEL_VBAT_DIV4 ADC_CHANNEL_VBAT
+#endif /* STM32H7 */
+/**
+ * @}
+ */
+
+/** @defgroup HAL_CEC_Aliased_Defines HAL CEC Aliased Defines maintained for legacy purpose
+ * @{
+ */
+
+#define __HAL_CEC_GET_IT __HAL_CEC_GET_FLAG
+
+/**
+ * @}
+ */
+
+/** @defgroup HAL_COMP_Aliased_Defines HAL COMP Aliased Defines maintained for legacy purpose
+ * @{
+ */
+#define COMP_WINDOWMODE_DISABLED COMP_WINDOWMODE_DISABLE
+#define COMP_WINDOWMODE_ENABLED COMP_WINDOWMODE_ENABLE
+#define COMP_EXTI_LINE_COMP1_EVENT COMP_EXTI_LINE_COMP1
+#define COMP_EXTI_LINE_COMP2_EVENT COMP_EXTI_LINE_COMP2
+#define COMP_EXTI_LINE_COMP3_EVENT COMP_EXTI_LINE_COMP3
+#define COMP_EXTI_LINE_COMP4_EVENT COMP_EXTI_LINE_COMP4
+#define COMP_EXTI_LINE_COMP5_EVENT COMP_EXTI_LINE_COMP5
+#define COMP_EXTI_LINE_COMP6_EVENT COMP_EXTI_LINE_COMP6
+#define COMP_EXTI_LINE_COMP7_EVENT COMP_EXTI_LINE_COMP7
+#if defined(STM32L0)
+#define COMP_LPTIMCONNECTION_ENABLED ((uint32_t)0x00000003U) /*!< COMPX output generic naming: connected to LPTIM input 1 for COMP1, LPTIM input 2 for COMP2 */
+#endif
+#define COMP_OUTPUT_COMP6TIM2OCREFCLR COMP_OUTPUT_COMP6_TIM2OCREFCLR
+#if defined(STM32F373xC) || defined(STM32F378xx)
+#define COMP_OUTPUT_TIM3IC1 COMP_OUTPUT_COMP1_TIM3IC1
+#define COMP_OUTPUT_TIM3OCREFCLR COMP_OUTPUT_COMP1_TIM3OCREFCLR
+#endif /* STM32F373xC || STM32F378xx */
+
+#if defined(STM32L0) || defined(STM32L4)
+#define COMP_WINDOWMODE_ENABLE COMP_WINDOWMODE_COMP1_INPUT_PLUS_COMMON
+
+#define COMP_NONINVERTINGINPUT_IO1 COMP_INPUT_PLUS_IO1
+#define COMP_NONINVERTINGINPUT_IO2 COMP_INPUT_PLUS_IO2
+#define COMP_NONINVERTINGINPUT_IO3 COMP_INPUT_PLUS_IO3
+#define COMP_NONINVERTINGINPUT_IO4 COMP_INPUT_PLUS_IO4
+#define COMP_NONINVERTINGINPUT_IO5 COMP_INPUT_PLUS_IO5
+#define COMP_NONINVERTINGINPUT_IO6 COMP_INPUT_PLUS_IO6
+
+#define COMP_INVERTINGINPUT_1_4VREFINT COMP_INPUT_MINUS_1_4VREFINT
+#define COMP_INVERTINGINPUT_1_2VREFINT COMP_INPUT_MINUS_1_2VREFINT
+#define COMP_INVERTINGINPUT_3_4VREFINT COMP_INPUT_MINUS_3_4VREFINT
+#define COMP_INVERTINGINPUT_VREFINT COMP_INPUT_MINUS_VREFINT
+#define COMP_INVERTINGINPUT_DAC1_CH1 COMP_INPUT_MINUS_DAC1_CH1
+#define COMP_INVERTINGINPUT_DAC1_CH2 COMP_INPUT_MINUS_DAC1_CH2
+#define COMP_INVERTINGINPUT_DAC1 COMP_INPUT_MINUS_DAC1_CH1
+#define COMP_INVERTINGINPUT_DAC2 COMP_INPUT_MINUS_DAC1_CH2
+#define COMP_INVERTINGINPUT_IO1 COMP_INPUT_MINUS_IO1
+#if defined(STM32L0)
+/* Issue fixed on STM32L0 COMP driver: only 2 dedicated IO (IO1 and IO2), */
+/* IO2 was wrongly assigned to IO shared with DAC and IO3 was corresponding */
+/* to the second dedicated IO (only for COMP2). */
+#define COMP_INVERTINGINPUT_IO2 COMP_INPUT_MINUS_DAC1_CH2
+#define COMP_INVERTINGINPUT_IO3 COMP_INPUT_MINUS_IO2
+#else
+#define COMP_INVERTINGINPUT_IO2 COMP_INPUT_MINUS_IO2
+#define COMP_INVERTINGINPUT_IO3 COMP_INPUT_MINUS_IO3
+#endif
+#define COMP_INVERTINGINPUT_IO4 COMP_INPUT_MINUS_IO4
+#define COMP_INVERTINGINPUT_IO5 COMP_INPUT_MINUS_IO5
+
+#define COMP_OUTPUTLEVEL_LOW COMP_OUTPUT_LEVEL_LOW
+#define COMP_OUTPUTLEVEL_HIGH COMP_OUTPUT_LEVEL_HIGH
+
+/* Note: Literal "COMP_FLAG_LOCK" kept for legacy purpose. */
+/* To check COMP lock state, use macro "__HAL_COMP_IS_LOCKED()". */
+#if defined(COMP_CSR_LOCK)
+#define COMP_FLAG_LOCK COMP_CSR_LOCK
+#elif defined(COMP_CSR_COMP1LOCK)
+#define COMP_FLAG_LOCK COMP_CSR_COMP1LOCK
+#elif defined(COMP_CSR_COMPxLOCK)
+#define COMP_FLAG_LOCK COMP_CSR_COMPxLOCK
+#endif
+
+#if defined(STM32L4)
+#define COMP_BLANKINGSRCE_TIM1OC5 COMP_BLANKINGSRC_TIM1_OC5_COMP1
+#define COMP_BLANKINGSRCE_TIM2OC3 COMP_BLANKINGSRC_TIM2_OC3_COMP1
+#define COMP_BLANKINGSRCE_TIM3OC3 COMP_BLANKINGSRC_TIM3_OC3_COMP1
+#define COMP_BLANKINGSRCE_TIM3OC4 COMP_BLANKINGSRC_TIM3_OC4_COMP2
+#define COMP_BLANKINGSRCE_TIM8OC5 COMP_BLANKINGSRC_TIM8_OC5_COMP2
+#define COMP_BLANKINGSRCE_TIM15OC1 COMP_BLANKINGSRC_TIM15_OC1_COMP2
+#define COMP_BLANKINGSRCE_NONE COMP_BLANKINGSRC_NONE
+#endif
+
+#if defined(STM32L0)
+#define COMP_MODE_HIGHSPEED COMP_POWERMODE_MEDIUMSPEED
+#define COMP_MODE_LOWSPEED COMP_POWERMODE_ULTRALOWPOWER
+#else
+#define COMP_MODE_HIGHSPEED COMP_POWERMODE_HIGHSPEED
+#define COMP_MODE_MEDIUMSPEED COMP_POWERMODE_MEDIUMSPEED
+#define COMP_MODE_LOWPOWER COMP_POWERMODE_LOWPOWER
+#define COMP_MODE_ULTRALOWPOWER COMP_POWERMODE_ULTRALOWPOWER
+#endif
+
+#endif
+/**
+ * @}
+ */
+
+/** @defgroup HAL_CORTEX_Aliased_Defines HAL CORTEX Aliased Defines maintained for legacy purpose
+ * @{
+ */
+#define __HAL_CORTEX_SYSTICKCLK_CONFIG HAL_SYSTICK_CLKSourceConfig
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/** @defgroup HAL_CRC_Aliased_Defines HAL CRC Aliased Defines maintained for legacy purpose
+ * @{
+ */
+
+#define CRC_OUTPUTDATA_INVERSION_DISABLED CRC_OUTPUTDATA_INVERSION_DISABLE
+#define CRC_OUTPUTDATA_INVERSION_ENABLED CRC_OUTPUTDATA_INVERSION_ENABLE
+
+/**
+ * @}
+ */
+
+/** @defgroup HAL_DAC_Aliased_Defines HAL DAC Aliased Defines maintained for legacy purpose
+ * @{
+ */
+
+#define DAC1_CHANNEL_1 DAC_CHANNEL_1
+#define DAC1_CHANNEL_2 DAC_CHANNEL_2
+#define DAC2_CHANNEL_1 DAC_CHANNEL_1
+#define DAC_WAVE_NONE 0x00000000U
+#define DAC_WAVE_NOISE DAC_CR_WAVE1_0
+#define DAC_WAVE_TRIANGLE DAC_CR_WAVE1_1
+#define DAC_WAVEGENERATION_NONE DAC_WAVE_NONE
+#define DAC_WAVEGENERATION_NOISE DAC_WAVE_NOISE
+#define DAC_WAVEGENERATION_TRIANGLE DAC_WAVE_TRIANGLE
+
+#if defined(STM32G4) || defined(STM32H7) || defined (STM32U5)
+#define DAC_CHIPCONNECT_DISABLE DAC_CHIPCONNECT_EXTERNAL
+#define DAC_CHIPCONNECT_ENABLE DAC_CHIPCONNECT_INTERNAL
+#endif
+
+#if defined(STM32L1) || defined(STM32L4) || defined(STM32G0) || defined(STM32L5) || defined(STM32H7) || defined(STM32F4) || defined(STM32G4)
+#define HAL_DAC_MSP_INIT_CB_ID HAL_DAC_MSPINIT_CB_ID
+#define HAL_DAC_MSP_DEINIT_CB_ID HAL_DAC_MSPDEINIT_CB_ID
+#endif
+
+/**
+ * @}
+ */
+
+/** @defgroup HAL_DMA_Aliased_Defines HAL DMA Aliased Defines maintained for legacy purpose
+ * @{
+ */
+#define HAL_REMAPDMA_ADC_DMA_CH2 DMA_REMAP_ADC_DMA_CH2
+#define HAL_REMAPDMA_USART1_TX_DMA_CH4 DMA_REMAP_USART1_TX_DMA_CH4
+#define HAL_REMAPDMA_USART1_RX_DMA_CH5 DMA_REMAP_USART1_RX_DMA_CH5
+#define HAL_REMAPDMA_TIM16_DMA_CH4 DMA_REMAP_TIM16_DMA_CH4
+#define HAL_REMAPDMA_TIM17_DMA_CH2 DMA_REMAP_TIM17_DMA_CH2
+#define HAL_REMAPDMA_USART3_DMA_CH32 DMA_REMAP_USART3_DMA_CH32
+#define HAL_REMAPDMA_TIM16_DMA_CH6 DMA_REMAP_TIM16_DMA_CH6
+#define HAL_REMAPDMA_TIM17_DMA_CH7 DMA_REMAP_TIM17_DMA_CH7
+#define HAL_REMAPDMA_SPI2_DMA_CH67 DMA_REMAP_SPI2_DMA_CH67
+#define HAL_REMAPDMA_USART2_DMA_CH67 DMA_REMAP_USART2_DMA_CH67
+#define HAL_REMAPDMA_I2C1_DMA_CH76 DMA_REMAP_I2C1_DMA_CH76
+#define HAL_REMAPDMA_TIM1_DMA_CH6 DMA_REMAP_TIM1_DMA_CH6
+#define HAL_REMAPDMA_TIM2_DMA_CH7 DMA_REMAP_TIM2_DMA_CH7
+#define HAL_REMAPDMA_TIM3_DMA_CH6 DMA_REMAP_TIM3_DMA_CH6
+
+#define IS_HAL_REMAPDMA IS_DMA_REMAP
+#define __HAL_REMAPDMA_CHANNEL_ENABLE __HAL_DMA_REMAP_CHANNEL_ENABLE
+#define __HAL_REMAPDMA_CHANNEL_DISABLE __HAL_DMA_REMAP_CHANNEL_DISABLE
+
+#if defined(STM32L4)
+
+#define HAL_DMAMUX1_REQUEST_GEN_EXTI0 HAL_DMAMUX1_REQ_GEN_EXTI0
+#define HAL_DMAMUX1_REQUEST_GEN_EXTI1 HAL_DMAMUX1_REQ_GEN_EXTI1
+#define HAL_DMAMUX1_REQUEST_GEN_EXTI2 HAL_DMAMUX1_REQ_GEN_EXTI2
+#define HAL_DMAMUX1_REQUEST_GEN_EXTI3 HAL_DMAMUX1_REQ_GEN_EXTI3
+#define HAL_DMAMUX1_REQUEST_GEN_EXTI4 HAL_DMAMUX1_REQ_GEN_EXTI4
+#define HAL_DMAMUX1_REQUEST_GEN_EXTI5 HAL_DMAMUX1_REQ_GEN_EXTI5
+#define HAL_DMAMUX1_REQUEST_GEN_EXTI6 HAL_DMAMUX1_REQ_GEN_EXTI6
+#define HAL_DMAMUX1_REQUEST_GEN_EXTI7 HAL_DMAMUX1_REQ_GEN_EXTI7
+#define HAL_DMAMUX1_REQUEST_GEN_EXTI8 HAL_DMAMUX1_REQ_GEN_EXTI8
+#define HAL_DMAMUX1_REQUEST_GEN_EXTI9 HAL_DMAMUX1_REQ_GEN_EXTI9
+#define HAL_DMAMUX1_REQUEST_GEN_EXTI10 HAL_DMAMUX1_REQ_GEN_EXTI10
+#define HAL_DMAMUX1_REQUEST_GEN_EXTI11 HAL_DMAMUX1_REQ_GEN_EXTI11
+#define HAL_DMAMUX1_REQUEST_GEN_EXTI12 HAL_DMAMUX1_REQ_GEN_EXTI12
+#define HAL_DMAMUX1_REQUEST_GEN_EXTI13 HAL_DMAMUX1_REQ_GEN_EXTI13
+#define HAL_DMAMUX1_REQUEST_GEN_EXTI14 HAL_DMAMUX1_REQ_GEN_EXTI14
+#define HAL_DMAMUX1_REQUEST_GEN_EXTI15 HAL_DMAMUX1_REQ_GEN_EXTI15
+#define HAL_DMAMUX1_REQUEST_GEN_DMAMUX1_CH0_EVT HAL_DMAMUX1_REQ_GEN_DMAMUX1_CH0_EVT
+#define HAL_DMAMUX1_REQUEST_GEN_DMAMUX1_CH1_EVT HAL_DMAMUX1_REQ_GEN_DMAMUX1_CH1_EVT
+#define HAL_DMAMUX1_REQUEST_GEN_DMAMUX1_CH2_EVT HAL_DMAMUX1_REQ_GEN_DMAMUX1_CH2_EVT
+#define HAL_DMAMUX1_REQUEST_GEN_DMAMUX1_CH3_EVT HAL_DMAMUX1_REQ_GEN_DMAMUX1_CH3_EVT
+#define HAL_DMAMUX1_REQUEST_GEN_LPTIM1_OUT HAL_DMAMUX1_REQ_GEN_LPTIM1_OUT
+#define HAL_DMAMUX1_REQUEST_GEN_LPTIM2_OUT HAL_DMAMUX1_REQ_GEN_LPTIM2_OUT
+#define HAL_DMAMUX1_REQUEST_GEN_DSI_TE HAL_DMAMUX1_REQ_GEN_DSI_TE
+#define HAL_DMAMUX1_REQUEST_GEN_DSI_EOT HAL_DMAMUX1_REQ_GEN_DSI_EOT
+#define HAL_DMAMUX1_REQUEST_GEN_DMA2D_EOT HAL_DMAMUX1_REQ_GEN_DMA2D_EOT
+#define HAL_DMAMUX1_REQUEST_GEN_LTDC_IT HAL_DMAMUX1_REQ_GEN_LTDC_IT
+
+#define HAL_DMAMUX_REQUEST_GEN_NO_EVENT HAL_DMAMUX_REQ_GEN_NO_EVENT
+#define HAL_DMAMUX_REQUEST_GEN_RISING HAL_DMAMUX_REQ_GEN_RISING
+#define HAL_DMAMUX_REQUEST_GEN_FALLING HAL_DMAMUX_REQ_GEN_FALLING
+#define HAL_DMAMUX_REQUEST_GEN_RISING_FALLING HAL_DMAMUX_REQ_GEN_RISING_FALLING
+
+#if defined(STM32L4R5xx) || defined(STM32L4R9xx) || defined(STM32L4R9xx) || defined(STM32L4S5xx) || defined(STM32L4S7xx) || defined(STM32L4S9xx)
+#define DMA_REQUEST_DCMI_PSSI DMA_REQUEST_DCMI
+#endif
+
+#endif /* STM32L4 */
+
+#if defined(STM32G0)
+#define DMA_REQUEST_DAC1_CHANNEL1 DMA_REQUEST_DAC1_CH1
+#define DMA_REQUEST_DAC1_CHANNEL2 DMA_REQUEST_DAC1_CH2
+#define DMA_REQUEST_TIM16_TRIG_COM DMA_REQUEST_TIM16_COM
+#define DMA_REQUEST_TIM17_TRIG_COM DMA_REQUEST_TIM17_COM
+
+#define LL_DMAMUX_REQ_TIM16_TRIG_COM LL_DMAMUX_REQ_TIM16_COM
+#define LL_DMAMUX_REQ_TIM17_TRIG_COM LL_DMAMUX_REQ_TIM17_COM
+#endif
+
+#if defined(STM32H7)
+
+#define DMA_REQUEST_DAC1 DMA_REQUEST_DAC1_CH1
+#define DMA_REQUEST_DAC2 DMA_REQUEST_DAC1_CH2
+
+#define BDMA_REQUEST_LP_UART1_RX BDMA_REQUEST_LPUART1_RX
+#define BDMA_REQUEST_LP_UART1_TX BDMA_REQUEST_LPUART1_TX
+
+#define HAL_DMAMUX1_REQUEST_GEN_DMAMUX1_CH0_EVT HAL_DMAMUX1_REQ_GEN_DMAMUX1_CH0_EVT
+#define HAL_DMAMUX1_REQUEST_GEN_DMAMUX1_CH1_EVT HAL_DMAMUX1_REQ_GEN_DMAMUX1_CH1_EVT
+#define HAL_DMAMUX1_REQUEST_GEN_DMAMUX1_CH2_EVT HAL_DMAMUX1_REQ_GEN_DMAMUX1_CH2_EVT
+#define HAL_DMAMUX1_REQUEST_GEN_LPTIM1_OUT HAL_DMAMUX1_REQ_GEN_LPTIM1_OUT
+#define HAL_DMAMUX1_REQUEST_GEN_LPTIM2_OUT HAL_DMAMUX1_REQ_GEN_LPTIM2_OUT
+#define HAL_DMAMUX1_REQUEST_GEN_LPTIM3_OUT HAL_DMAMUX1_REQ_GEN_LPTIM3_OUT
+#define HAL_DMAMUX1_REQUEST_GEN_EXTI0 HAL_DMAMUX1_REQ_GEN_EXTI0
+#define HAL_DMAMUX1_REQUEST_GEN_TIM12_TRGO HAL_DMAMUX1_REQ_GEN_TIM12_TRGO
+
+#define HAL_DMAMUX2_REQUEST_GEN_DMAMUX2_CH0_EVT HAL_DMAMUX2_REQ_GEN_DMAMUX2_CH0_EVT
+#define HAL_DMAMUX2_REQUEST_GEN_DMAMUX2_CH1_EVT HAL_DMAMUX2_REQ_GEN_DMAMUX2_CH1_EVT
+#define HAL_DMAMUX2_REQUEST_GEN_DMAMUX2_CH2_EVT HAL_DMAMUX2_REQ_GEN_DMAMUX2_CH2_EVT
+#define HAL_DMAMUX2_REQUEST_GEN_DMAMUX2_CH3_EVT HAL_DMAMUX2_REQ_GEN_DMAMUX2_CH3_EVT
+#define HAL_DMAMUX2_REQUEST_GEN_DMAMUX2_CH4_EVT HAL_DMAMUX2_REQ_GEN_DMAMUX2_CH4_EVT
+#define HAL_DMAMUX2_REQUEST_GEN_DMAMUX2_CH5_EVT HAL_DMAMUX2_REQ_GEN_DMAMUX2_CH5_EVT
+#define HAL_DMAMUX2_REQUEST_GEN_DMAMUX2_CH6_EVT HAL_DMAMUX2_REQ_GEN_DMAMUX2_CH6_EVT
+#define HAL_DMAMUX2_REQUEST_GEN_LPUART1_RX_WKUP HAL_DMAMUX2_REQ_GEN_LPUART1_RX_WKUP
+#define HAL_DMAMUX2_REQUEST_GEN_LPUART1_TX_WKUP HAL_DMAMUX2_REQ_GEN_LPUART1_TX_WKUP
+#define HAL_DMAMUX2_REQUEST_GEN_LPTIM2_WKUP HAL_DMAMUX2_REQ_GEN_LPTIM2_WKUP
+#define HAL_DMAMUX2_REQUEST_GEN_LPTIM2_OUT HAL_DMAMUX2_REQ_GEN_LPTIM2_OUT
+#define HAL_DMAMUX2_REQUEST_GEN_LPTIM3_WKUP HAL_DMAMUX2_REQ_GEN_LPTIM3_WKUP
+#define HAL_DMAMUX2_REQUEST_GEN_LPTIM3_OUT HAL_DMAMUX2_REQ_GEN_LPTIM3_OUT
+#define HAL_DMAMUX2_REQUEST_GEN_LPTIM4_WKUP HAL_DMAMUX2_REQ_GEN_LPTIM4_WKUP
+#define HAL_DMAMUX2_REQUEST_GEN_LPTIM5_WKUP HAL_DMAMUX2_REQ_GEN_LPTIM5_WKUP
+#define HAL_DMAMUX2_REQUEST_GEN_I2C4_WKUP HAL_DMAMUX2_REQ_GEN_I2C4_WKUP
+#define HAL_DMAMUX2_REQUEST_GEN_SPI6_WKUP HAL_DMAMUX2_REQ_GEN_SPI6_WKUP
+#define HAL_DMAMUX2_REQUEST_GEN_COMP1_OUT HAL_DMAMUX2_REQ_GEN_COMP1_OUT
+#define HAL_DMAMUX2_REQUEST_GEN_COMP2_OUT HAL_DMAMUX2_REQ_GEN_COMP2_OUT
+#define HAL_DMAMUX2_REQUEST_GEN_RTC_WKUP HAL_DMAMUX2_REQ_GEN_RTC_WKUP
+#define HAL_DMAMUX2_REQUEST_GEN_EXTI0 HAL_DMAMUX2_REQ_GEN_EXTI0
+#define HAL_DMAMUX2_REQUEST_GEN_EXTI2 HAL_DMAMUX2_REQ_GEN_EXTI2
+#define HAL_DMAMUX2_REQUEST_GEN_I2C4_IT_EVT HAL_DMAMUX2_REQ_GEN_I2C4_IT_EVT
+#define HAL_DMAMUX2_REQUEST_GEN_SPI6_IT HAL_DMAMUX2_REQ_GEN_SPI6_IT
+#define HAL_DMAMUX2_REQUEST_GEN_LPUART1_TX_IT HAL_DMAMUX2_REQ_GEN_LPUART1_TX_IT
+#define HAL_DMAMUX2_REQUEST_GEN_LPUART1_RX_IT HAL_DMAMUX2_REQ_GEN_LPUART1_RX_IT
+#define HAL_DMAMUX2_REQUEST_GEN_ADC3_IT HAL_DMAMUX2_REQ_GEN_ADC3_IT
+#define HAL_DMAMUX2_REQUEST_GEN_ADC3_AWD1_OUT HAL_DMAMUX2_REQ_GEN_ADC3_AWD1_OUT
+#define HAL_DMAMUX2_REQUEST_GEN_BDMA_CH0_IT HAL_DMAMUX2_REQ_GEN_BDMA_CH0_IT
+#define HAL_DMAMUX2_REQUEST_GEN_BDMA_CH1_IT HAL_DMAMUX2_REQ_GEN_BDMA_CH1_IT
+
+#define HAL_DMAMUX_REQUEST_GEN_NO_EVENT HAL_DMAMUX_REQ_GEN_NO_EVENT
+#define HAL_DMAMUX_REQUEST_GEN_RISING HAL_DMAMUX_REQ_GEN_RISING
+#define HAL_DMAMUX_REQUEST_GEN_FALLING HAL_DMAMUX_REQ_GEN_FALLING
+#define HAL_DMAMUX_REQUEST_GEN_RISING_FALLING HAL_DMAMUX_REQ_GEN_RISING_FALLING
+
+#define DFSDM_FILTER_EXT_TRIG_LPTIM1 DFSDM_FILTER_EXT_TRIG_LPTIM1_OUT
+#define DFSDM_FILTER_EXT_TRIG_LPTIM2 DFSDM_FILTER_EXT_TRIG_LPTIM2_OUT
+#define DFSDM_FILTER_EXT_TRIG_LPTIM3 DFSDM_FILTER_EXT_TRIG_LPTIM3_OUT
+
+#define DAC_TRIGGER_LP1_OUT DAC_TRIGGER_LPTIM1_OUT
+#define DAC_TRIGGER_LP2_OUT DAC_TRIGGER_LPTIM2_OUT
+
+#endif /* STM32H7 */
+/**
+ * @}
+ */
+
+/** @defgroup HAL_FLASH_Aliased_Defines HAL FLASH Aliased Defines maintained for legacy purpose
+ * @{
+ */
+
+#define TYPEPROGRAM_BYTE FLASH_TYPEPROGRAM_BYTE
+#define TYPEPROGRAM_HALFWORD FLASH_TYPEPROGRAM_HALFWORD
+#define TYPEPROGRAM_WORD FLASH_TYPEPROGRAM_WORD
+#define TYPEPROGRAM_DOUBLEWORD FLASH_TYPEPROGRAM_DOUBLEWORD
+#define TYPEERASE_SECTORS FLASH_TYPEERASE_SECTORS
+#define TYPEERASE_PAGES FLASH_TYPEERASE_PAGES
+#define TYPEERASE_PAGEERASE FLASH_TYPEERASE_PAGES
+#define TYPEERASE_MASSERASE FLASH_TYPEERASE_MASSERASE
+#define WRPSTATE_DISABLE OB_WRPSTATE_DISABLE
+#define WRPSTATE_ENABLE OB_WRPSTATE_ENABLE
+#define HAL_FLASH_TIMEOUT_VALUE FLASH_TIMEOUT_VALUE
+#define OBEX_PCROP OPTIONBYTE_PCROP
+#define OBEX_BOOTCONFIG OPTIONBYTE_BOOTCONFIG
+#define PCROPSTATE_DISABLE OB_PCROP_STATE_DISABLE
+#define PCROPSTATE_ENABLE OB_PCROP_STATE_ENABLE
+#define TYPEERASEDATA_BYTE FLASH_TYPEERASEDATA_BYTE
+#define TYPEERASEDATA_HALFWORD FLASH_TYPEERASEDATA_HALFWORD
+#define TYPEERASEDATA_WORD FLASH_TYPEERASEDATA_WORD
+#define TYPEPROGRAMDATA_BYTE FLASH_TYPEPROGRAMDATA_BYTE
+#define TYPEPROGRAMDATA_HALFWORD FLASH_TYPEPROGRAMDATA_HALFWORD
+#define TYPEPROGRAMDATA_WORD FLASH_TYPEPROGRAMDATA_WORD
+#define TYPEPROGRAMDATA_FASTBYTE FLASH_TYPEPROGRAMDATA_FASTBYTE
+#define TYPEPROGRAMDATA_FASTHALFWORD FLASH_TYPEPROGRAMDATA_FASTHALFWORD
+#define TYPEPROGRAMDATA_FASTWORD FLASH_TYPEPROGRAMDATA_FASTWORD
+#define PAGESIZE FLASH_PAGE_SIZE
+#define TYPEPROGRAM_FASTBYTE FLASH_TYPEPROGRAM_BYTE
+#define TYPEPROGRAM_FASTHALFWORD FLASH_TYPEPROGRAM_HALFWORD
+#define TYPEPROGRAM_FASTWORD FLASH_TYPEPROGRAM_WORD
+#define VOLTAGE_RANGE_1 FLASH_VOLTAGE_RANGE_1
+#define VOLTAGE_RANGE_2 FLASH_VOLTAGE_RANGE_2
+#define VOLTAGE_RANGE_3 FLASH_VOLTAGE_RANGE_3
+#define VOLTAGE_RANGE_4 FLASH_VOLTAGE_RANGE_4
+#define TYPEPROGRAM_FAST FLASH_TYPEPROGRAM_FAST
+#define TYPEPROGRAM_FAST_AND_LAST FLASH_TYPEPROGRAM_FAST_AND_LAST
+#define WRPAREA_BANK1_AREAA OB_WRPAREA_BANK1_AREAA
+#define WRPAREA_BANK1_AREAB OB_WRPAREA_BANK1_AREAB
+#define WRPAREA_BANK2_AREAA OB_WRPAREA_BANK2_AREAA
+#define WRPAREA_BANK2_AREAB OB_WRPAREA_BANK2_AREAB
+#define IWDG_STDBY_FREEZE OB_IWDG_STDBY_FREEZE
+#define IWDG_STDBY_ACTIVE OB_IWDG_STDBY_RUN
+#define IWDG_STOP_FREEZE OB_IWDG_STOP_FREEZE
+#define IWDG_STOP_ACTIVE OB_IWDG_STOP_RUN
+#define FLASH_ERROR_NONE HAL_FLASH_ERROR_NONE
+#define FLASH_ERROR_RD HAL_FLASH_ERROR_RD
+#define FLASH_ERROR_PG HAL_FLASH_ERROR_PROG
+#define FLASH_ERROR_PGP HAL_FLASH_ERROR_PGS
+#define FLASH_ERROR_WRP HAL_FLASH_ERROR_WRP
+#define FLASH_ERROR_OPTV HAL_FLASH_ERROR_OPTV
+#define FLASH_ERROR_OPTVUSR HAL_FLASH_ERROR_OPTVUSR
+#define FLASH_ERROR_PROG HAL_FLASH_ERROR_PROG
+#define FLASH_ERROR_OP HAL_FLASH_ERROR_OPERATION
+#define FLASH_ERROR_PGA HAL_FLASH_ERROR_PGA
+#define FLASH_ERROR_SIZE HAL_FLASH_ERROR_SIZE
+#define FLASH_ERROR_SIZ HAL_FLASH_ERROR_SIZE
+#define FLASH_ERROR_PGS HAL_FLASH_ERROR_PGS
+#define FLASH_ERROR_MIS HAL_FLASH_ERROR_MIS
+#define FLASH_ERROR_FAST HAL_FLASH_ERROR_FAST
+#define FLASH_ERROR_FWWERR HAL_FLASH_ERROR_FWWERR
+#define FLASH_ERROR_NOTZERO HAL_FLASH_ERROR_NOTZERO
+#define FLASH_ERROR_OPERATION HAL_FLASH_ERROR_OPERATION
+#define FLASH_ERROR_ERS HAL_FLASH_ERROR_ERS
+#define OB_WDG_SW OB_IWDG_SW
+#define OB_WDG_HW OB_IWDG_HW
+#define OB_SDADC12_VDD_MONITOR_SET OB_SDACD_VDD_MONITOR_SET
+#define OB_SDADC12_VDD_MONITOR_RESET OB_SDACD_VDD_MONITOR_RESET
+#define OB_RAM_PARITY_CHECK_SET OB_SRAM_PARITY_SET
+#define OB_RAM_PARITY_CHECK_RESET OB_SRAM_PARITY_RESET
+#define IS_OB_SDADC12_VDD_MONITOR IS_OB_SDACD_VDD_MONITOR
+#define OB_RDP_LEVEL0 OB_RDP_LEVEL_0
+#define OB_RDP_LEVEL1 OB_RDP_LEVEL_1
+#define OB_RDP_LEVEL2 OB_RDP_LEVEL_2
+#if defined(STM32G0)
+#define OB_BOOT_LOCK_DISABLE OB_BOOT_ENTRY_FORCED_NONE
+#define OB_BOOT_LOCK_ENABLE OB_BOOT_ENTRY_FORCED_FLASH
+#else
+#define OB_BOOT_ENTRY_FORCED_NONE OB_BOOT_LOCK_DISABLE
+#define OB_BOOT_ENTRY_FORCED_FLASH OB_BOOT_LOCK_ENABLE
+#endif
+#if defined(STM32H7)
+#define FLASH_FLAG_SNECCE_BANK1RR FLASH_FLAG_SNECCERR_BANK1
+#define FLASH_FLAG_DBECCE_BANK1RR FLASH_FLAG_DBECCERR_BANK1
+#define FLASH_FLAG_STRBER_BANK1R FLASH_FLAG_STRBERR_BANK1
+#define FLASH_FLAG_SNECCE_BANK2RR FLASH_FLAG_SNECCERR_BANK2
+#define FLASH_FLAG_DBECCE_BANK2RR FLASH_FLAG_DBECCERR_BANK2
+#define FLASH_FLAG_STRBER_BANK2R FLASH_FLAG_STRBERR_BANK2
+#define FLASH_FLAG_WDW FLASH_FLAG_WBNE
+#define OB_WRP_SECTOR_All OB_WRP_SECTOR_ALL
+#endif /* STM32H7 */
+#if defined(STM32U5)
+#define OB_USER_nRST_STOP OB_USER_NRST_STOP
+#define OB_USER_nRST_STDBY OB_USER_NRST_STDBY
+#define OB_USER_nRST_SHDW OB_USER_NRST_SHDW
+#define OB_USER_nSWBOOT0 OB_USER_NSWBOOT0
+#define OB_USER_nBOOT0 OB_USER_NBOOT0
+#define OB_nBOOT0_RESET OB_NBOOT0_RESET
+#define OB_nBOOT0_SET OB_NBOOT0_SET
+#endif /* STM32U5 */
+
+/**
+ * @}
+ */
+
+/** @defgroup HAL_JPEG_Aliased_Macros HAL JPEG Aliased Macros maintained for legacy purpose
+ * @{
+ */
+
+#if defined(STM32H7)
+#define __HAL_RCC_JPEG_CLK_ENABLE __HAL_RCC_JPGDECEN_CLK_ENABLE
+#define __HAL_RCC_JPEG_CLK_DISABLE __HAL_RCC_JPGDECEN_CLK_DISABLE
+#define __HAL_RCC_JPEG_FORCE_RESET __HAL_RCC_JPGDECRST_FORCE_RESET
+#define __HAL_RCC_JPEG_RELEASE_RESET __HAL_RCC_JPGDECRST_RELEASE_RESET
+#define __HAL_RCC_JPEG_CLK_SLEEP_ENABLE __HAL_RCC_JPGDEC_CLK_SLEEP_ENABLE
+#define __HAL_RCC_JPEG_CLK_SLEEP_DISABLE __HAL_RCC_JPGDEC_CLK_SLEEP_DISABLE
+#endif /* STM32H7 */
+
+/**
+ * @}
+ */
+
+/** @defgroup HAL_SYSCFG_Aliased_Defines HAL SYSCFG Aliased Defines maintained for legacy purpose
+ * @{
+ */
+
+#define HAL_SYSCFG_FASTMODEPLUS_I2C_PA9 I2C_FASTMODEPLUS_PA9
+#define HAL_SYSCFG_FASTMODEPLUS_I2C_PA10 I2C_FASTMODEPLUS_PA10
+#define HAL_SYSCFG_FASTMODEPLUS_I2C_PB6 I2C_FASTMODEPLUS_PB6
+#define HAL_SYSCFG_FASTMODEPLUS_I2C_PB7 I2C_FASTMODEPLUS_PB7
+#define HAL_SYSCFG_FASTMODEPLUS_I2C_PB8 I2C_FASTMODEPLUS_PB8
+#define HAL_SYSCFG_FASTMODEPLUS_I2C_PB9 I2C_FASTMODEPLUS_PB9
+#define HAL_SYSCFG_FASTMODEPLUS_I2C1 I2C_FASTMODEPLUS_I2C1
+#define HAL_SYSCFG_FASTMODEPLUS_I2C2 I2C_FASTMODEPLUS_I2C2
+#define HAL_SYSCFG_FASTMODEPLUS_I2C3 I2C_FASTMODEPLUS_I2C3
+#if defined(STM32G4)
+
+#define HAL_SYSCFG_EnableIOAnalogSwitchBooster HAL_SYSCFG_EnableIOSwitchBooster
+#define HAL_SYSCFG_DisableIOAnalogSwitchBooster HAL_SYSCFG_DisableIOSwitchBooster
+#define HAL_SYSCFG_EnableIOAnalogSwitchVDD HAL_SYSCFG_EnableIOSwitchVDD
+#define HAL_SYSCFG_DisableIOAnalogSwitchVDD HAL_SYSCFG_DisableIOSwitchVDD
+#endif /* STM32G4 */
+
+/**
+ * @}
+ */
+
+
+/** @defgroup LL_FMC_Aliased_Defines LL FMC Aliased Defines maintained for compatibility purpose
+ * @{
+ */
+#if defined(STM32L4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4)
+#define FMC_NAND_PCC_WAIT_FEATURE_DISABLE FMC_NAND_WAIT_FEATURE_DISABLE
+#define FMC_NAND_PCC_WAIT_FEATURE_ENABLE FMC_NAND_WAIT_FEATURE_ENABLE
+#define FMC_NAND_PCC_MEM_BUS_WIDTH_8 FMC_NAND_MEM_BUS_WIDTH_8
+#define FMC_NAND_PCC_MEM_BUS_WIDTH_16 FMC_NAND_MEM_BUS_WIDTH_16
+#elif defined(STM32F1) || defined(STM32F2) || defined(STM32F3) || defined(STM32F4)
+#define FMC_NAND_WAIT_FEATURE_DISABLE FMC_NAND_PCC_WAIT_FEATURE_DISABLE
+#define FMC_NAND_WAIT_FEATURE_ENABLE FMC_NAND_PCC_WAIT_FEATURE_ENABLE
+#define FMC_NAND_MEM_BUS_WIDTH_8 FMC_NAND_PCC_MEM_BUS_WIDTH_8
+#define FMC_NAND_MEM_BUS_WIDTH_16 FMC_NAND_PCC_MEM_BUS_WIDTH_16
+#endif
+/**
+ * @}
+ */
+
+/** @defgroup LL_FSMC_Aliased_Defines LL FSMC Aliased Defines maintained for legacy purpose
+ * @{
+ */
+
+#define FSMC_NORSRAM_TYPEDEF FSMC_NORSRAM_TypeDef
+#define FSMC_NORSRAM_EXTENDED_TYPEDEF FSMC_NORSRAM_EXTENDED_TypeDef
+/**
+ * @}
+ */
+
+/** @defgroup HAL_GPIO_Aliased_Macros HAL GPIO Aliased Macros maintained for legacy purpose
+ * @{
+ */
+#define GET_GPIO_SOURCE GPIO_GET_INDEX
+#define GET_GPIO_INDEX GPIO_GET_INDEX
+
+#if defined(STM32F4)
+#define GPIO_AF12_SDMMC GPIO_AF12_SDIO
+#define GPIO_AF12_SDMMC1 GPIO_AF12_SDIO
+#endif
+
+#if defined(STM32F7)
+#define GPIO_AF12_SDIO GPIO_AF12_SDMMC1
+#define GPIO_AF12_SDMMC GPIO_AF12_SDMMC1
+#endif
+
+#if defined(STM32L4)
+#define GPIO_AF12_SDIO GPIO_AF12_SDMMC1
+#define GPIO_AF12_SDMMC GPIO_AF12_SDMMC1
+#endif
+
+#if defined(STM32H7)
+#define GPIO_AF7_SDIO1 GPIO_AF7_SDMMC1
+#define GPIO_AF8_SDIO1 GPIO_AF8_SDMMC1
+#define GPIO_AF12_SDIO1 GPIO_AF12_SDMMC1
+#define GPIO_AF9_SDIO2 GPIO_AF9_SDMMC2
+#define GPIO_AF10_SDIO2 GPIO_AF10_SDMMC2
+#define GPIO_AF11_SDIO2 GPIO_AF11_SDMMC2
+
+#if defined (STM32H743xx) || defined (STM32H753xx) || defined (STM32H750xx) || defined (STM32H742xx) || \
+ defined (STM32H745xx) || defined (STM32H755xx) || defined (STM32H747xx) || defined (STM32H757xx)
+#define GPIO_AF10_OTG2_HS GPIO_AF10_OTG2_FS
+#define GPIO_AF10_OTG1_FS GPIO_AF10_OTG1_HS
+#define GPIO_AF12_OTG2_FS GPIO_AF12_OTG1_FS
+#endif /*STM32H743xx || STM32H753xx || STM32H750xx || STM32H742xx || STM32H745xx || STM32H755xx || STM32H747xx || STM32H757xx */
+#endif /* STM32H7 */
+
+#define GPIO_AF0_LPTIM GPIO_AF0_LPTIM1
+#define GPIO_AF1_LPTIM GPIO_AF1_LPTIM1
+#define GPIO_AF2_LPTIM GPIO_AF2_LPTIM1
+
+#if defined(STM32L0) || defined(STM32L4) || defined(STM32F4) || defined(STM32F2) || defined(STM32F7) || defined(STM32G4) || defined(STM32H7) || defined(STM32WB) || defined(STM32U5)
+#define GPIO_SPEED_LOW GPIO_SPEED_FREQ_LOW
+#define GPIO_SPEED_MEDIUM GPIO_SPEED_FREQ_MEDIUM
+#define GPIO_SPEED_FAST GPIO_SPEED_FREQ_HIGH
+#define GPIO_SPEED_HIGH GPIO_SPEED_FREQ_VERY_HIGH
+#endif /* STM32L0 || STM32L4 || STM32F4 || STM32F2 || STM32F7 || STM32G4 || STM32H7 || STM32WB || STM32U5*/
+
+#if defined(STM32L1)
+#define GPIO_SPEED_VERY_LOW GPIO_SPEED_FREQ_LOW
+#define GPIO_SPEED_LOW GPIO_SPEED_FREQ_MEDIUM
+#define GPIO_SPEED_MEDIUM GPIO_SPEED_FREQ_HIGH
+#define GPIO_SPEED_HIGH GPIO_SPEED_FREQ_VERY_HIGH
+#endif /* STM32L1 */
+
+#if defined(STM32F0) || defined(STM32F3) || defined(STM32F1)
+#define GPIO_SPEED_LOW GPIO_SPEED_FREQ_LOW
+#define GPIO_SPEED_MEDIUM GPIO_SPEED_FREQ_MEDIUM
+#define GPIO_SPEED_HIGH GPIO_SPEED_FREQ_HIGH
+#endif /* STM32F0 || STM32F3 || STM32F1 */
+
+#define GPIO_AF6_DFSDM GPIO_AF6_DFSDM1
+/**
+ * @}
+ */
+
+/** @defgroup HAL_HRTIM_Aliased_Macros HAL HRTIM Aliased Macros maintained for legacy purpose
+ * @{
+ */
+#define HRTIM_TIMDELAYEDPROTECTION_DISABLED HRTIM_TIMER_A_B_C_DELAYEDPROTECTION_DISABLED
+#define HRTIM_TIMDELAYEDPROTECTION_DELAYEDOUT1_EEV68 HRTIM_TIMER_A_B_C_DELAYEDPROTECTION_DELAYEDOUT1_EEV6
+#define HRTIM_TIMDELAYEDPROTECTION_DELAYEDOUT2_EEV68 HRTIM_TIMER_A_B_C_DELAYEDPROTECTION_DELAYEDOUT2_EEV6
+#define HRTIM_TIMDELAYEDPROTECTION_DELAYEDBOTH_EEV68 HRTIM_TIMER_A_B_C_DELAYEDPROTECTION_DELAYEDBOTH_EEV6
+#define HRTIM_TIMDELAYEDPROTECTION_BALANCED_EEV68 HRTIM_TIMER_A_B_C_DELAYEDPROTECTION_BALANCED_EEV6
+#define HRTIM_TIMDELAYEDPROTECTION_DELAYEDOUT1_DEEV79 HRTIM_TIMER_A_B_C_DELAYEDPROTECTION_DELAYEDOUT1_DEEV7
+#define HRTIM_TIMDELAYEDPROTECTION_DELAYEDOUT2_DEEV79 HRTIM_TIMER_A_B_C_DELAYEDPROTECTION_DELAYEDOUT2_DEEV7
+#define HRTIM_TIMDELAYEDPROTECTION_DELAYEDBOTH_EEV79 HRTIM_TIMER_A_B_C_DELAYEDPROTECTION_DELAYEDBOTH_EEV7
+#define HRTIM_TIMDELAYEDPROTECTION_BALANCED_EEV79 HRTIM_TIMER_A_B_C_DELAYEDPROTECTION_BALANCED_EEV7
+
+#define __HAL_HRTIM_SetCounter __HAL_HRTIM_SETCOUNTER
+#define __HAL_HRTIM_GetCounter __HAL_HRTIM_GETCOUNTER
+#define __HAL_HRTIM_SetPeriod __HAL_HRTIM_SETPERIOD
+#define __HAL_HRTIM_GetPeriod __HAL_HRTIM_GETPERIOD
+#define __HAL_HRTIM_SetClockPrescaler __HAL_HRTIM_SETCLOCKPRESCALER
+#define __HAL_HRTIM_GetClockPrescaler __HAL_HRTIM_GETCLOCKPRESCALER
+#define __HAL_HRTIM_SetCompare __HAL_HRTIM_SETCOMPARE
+#define __HAL_HRTIM_GetCompare __HAL_HRTIM_GETCOMPARE
+
+#if defined(STM32G4)
+#define HAL_HRTIM_ExternalEventCounterConfig HAL_HRTIM_ExtEventCounterConfig
+#define HAL_HRTIM_ExternalEventCounterEnable HAL_HRTIM_ExtEventCounterEnable
+#define HAL_HRTIM_ExternalEventCounterDisable HAL_HRTIM_ExtEventCounterDisable
+#define HAL_HRTIM_ExternalEventCounterReset HAL_HRTIM_ExtEventCounterReset
+#define HRTIM_TIMEEVENT_A HRTIM_EVENTCOUNTER_A
+#define HRTIM_TIMEEVENT_B HRTIM_EVENTCOUNTER_B
+#define HRTIM_TIMEEVENTRESETMODE_UNCONDITIONAL HRTIM_EVENTCOUNTER_RSTMODE_UNCONDITIONAL
+#define HRTIM_TIMEEVENTRESETMODE_CONDITIONAL HRTIM_EVENTCOUNTER_RSTMODE_CONDITIONAL
+#endif /* STM32G4 */
+
+#if defined(STM32H7)
+#define HRTIM_OUTPUTSET_TIMAEV1_TIMBCMP1 HRTIM_OUTPUTSET_TIMEV_1
+#define HRTIM_OUTPUTSET_TIMAEV2_TIMBCMP2 HRTIM_OUTPUTSET_TIMEV_2
+#define HRTIM_OUTPUTSET_TIMAEV3_TIMCCMP2 HRTIM_OUTPUTSET_TIMEV_3
+#define HRTIM_OUTPUTSET_TIMAEV4_TIMCCMP3 HRTIM_OUTPUTSET_TIMEV_4
+#define HRTIM_OUTPUTSET_TIMAEV5_TIMDCMP1 HRTIM_OUTPUTSET_TIMEV_5
+#define HRTIM_OUTPUTSET_TIMAEV6_TIMDCMP2 HRTIM_OUTPUTSET_TIMEV_6
+#define HRTIM_OUTPUTSET_TIMAEV7_TIMECMP3 HRTIM_OUTPUTSET_TIMEV_7
+#define HRTIM_OUTPUTSET_TIMAEV8_TIMECMP4 HRTIM_OUTPUTSET_TIMEV_8
+#define HRTIM_OUTPUTSET_TIMAEV9_TIMFCMP4 HRTIM_OUTPUTSET_TIMEV_9
+#define HRTIM_OUTPUTSET_TIMBEV1_TIMACMP1 HRTIM_OUTPUTSET_TIMEV_1
+#define HRTIM_OUTPUTSET_TIMBEV2_TIMACMP2 HRTIM_OUTPUTSET_TIMEV_2
+#define HRTIM_OUTPUTSET_TIMBEV3_TIMCCMP3 HRTIM_OUTPUTSET_TIMEV_3
+#define HRTIM_OUTPUTSET_TIMBEV4_TIMCCMP4 HRTIM_OUTPUTSET_TIMEV_4
+#define HRTIM_OUTPUTSET_TIMBEV5_TIMDCMP3 HRTIM_OUTPUTSET_TIMEV_5
+#define HRTIM_OUTPUTSET_TIMBEV6_TIMDCMP4 HRTIM_OUTPUTSET_TIMEV_6
+#define HRTIM_OUTPUTSET_TIMBEV7_TIMECMP1 HRTIM_OUTPUTSET_TIMEV_7
+#define HRTIM_OUTPUTSET_TIMBEV8_TIMECMP2 HRTIM_OUTPUTSET_TIMEV_8
+#define HRTIM_OUTPUTSET_TIMBEV9_TIMFCMP3 HRTIM_OUTPUTSET_TIMEV_9
+#define HRTIM_OUTPUTSET_TIMCEV1_TIMACMP1 HRTIM_OUTPUTSET_TIMEV_1
+#define HRTIM_OUTPUTSET_TIMCEV2_TIMACMP2 HRTIM_OUTPUTSET_TIMEV_2
+#define HRTIM_OUTPUTSET_TIMCEV3_TIMBCMP2 HRTIM_OUTPUTSET_TIMEV_3
+#define HRTIM_OUTPUTSET_TIMCEV4_TIMBCMP3 HRTIM_OUTPUTSET_TIMEV_4
+#define HRTIM_OUTPUTSET_TIMCEV5_TIMDCMP2 HRTIM_OUTPUTSET_TIMEV_5
+#define HRTIM_OUTPUTSET_TIMCEV6_TIMDCMP4 HRTIM_OUTPUTSET_TIMEV_6
+#define HRTIM_OUTPUTSET_TIMCEV7_TIMECMP3 HRTIM_OUTPUTSET_TIMEV_7
+#define HRTIM_OUTPUTSET_TIMCEV8_TIMECMP4 HRTIM_OUTPUTSET_TIMEV_8
+#define HRTIM_OUTPUTSET_TIMCEV9_TIMFCMP2 HRTIM_OUTPUTSET_TIMEV_9
+#define HRTIM_OUTPUTSET_TIMDEV1_TIMACMP1 HRTIM_OUTPUTSET_TIMEV_1
+#define HRTIM_OUTPUTSET_TIMDEV2_TIMACMP4 HRTIM_OUTPUTSET_TIMEV_2
+#define HRTIM_OUTPUTSET_TIMDEV3_TIMBCMP2 HRTIM_OUTPUTSET_TIMEV_3
+#define HRTIM_OUTPUTSET_TIMDEV4_TIMBCMP4 HRTIM_OUTPUTSET_TIMEV_4
+#define HRTIM_OUTPUTSET_TIMDEV5_TIMCCMP4 HRTIM_OUTPUTSET_TIMEV_5
+#define HRTIM_OUTPUTSET_TIMDEV6_TIMECMP1 HRTIM_OUTPUTSET_TIMEV_6
+#define HRTIM_OUTPUTSET_TIMDEV7_TIMECMP4 HRTIM_OUTPUTSET_TIMEV_7
+#define HRTIM_OUTPUTSET_TIMDEV8_TIMFCMP1 HRTIM_OUTPUTSET_TIMEV_8
+#define HRTIM_OUTPUTSET_TIMDEV9_TIMFCMP3 HRTIM_OUTPUTSET_TIMEV_9
+#define HRTIM_OUTPUTSET_TIMEEV1_TIMACMP4 HRTIM_OUTPUTSET_TIMEV_1
+#define HRTIM_OUTPUTSET_TIMEEV2_TIMBCMP3 HRTIM_OUTPUTSET_TIMEV_2
+#define HRTIM_OUTPUTSET_TIMEEV3_TIMBCMP4 HRTIM_OUTPUTSET_TIMEV_3
+#define HRTIM_OUTPUTSET_TIMEEV4_TIMCCMP1 HRTIM_OUTPUTSET_TIMEV_4
+#define HRTIM_OUTPUTSET_TIMEEV5_TIMDCMP2 HRTIM_OUTPUTSET_TIMEV_5
+#define HRTIM_OUTPUTSET_TIMEEV6_TIMDCMP1 HRTIM_OUTPUTSET_TIMEV_6
+#define HRTIM_OUTPUTSET_TIMEEV7_TIMDCMP2 HRTIM_OUTPUTSET_TIMEV_7
+#define HRTIM_OUTPUTSET_TIMEEV8_TIMFCMP3 HRTIM_OUTPUTSET_TIMEV_8
+#define HRTIM_OUTPUTSET_TIMEEV9_TIMFCMP4 HRTIM_OUTPUTSET_TIMEV_9
+#define HRTIM_OUTPUTSET_TIMFEV1_TIMACMP3 HRTIM_OUTPUTSET_TIMEV_1
+#define HRTIM_OUTPUTSET_TIMFEV2_TIMBCMP1 HRTIM_OUTPUTSET_TIMEV_2
+#define HRTIM_OUTPUTSET_TIMFEV3_TIMBCMP4 HRTIM_OUTPUTSET_TIMEV_3
+#define HRTIM_OUTPUTSET_TIMFEV4_TIMCCMP1 HRTIM_OUTPUTSET_TIMEV_4
+#define HRTIM_OUTPUTSET_TIMFEV5_TIMCCMP4 HRTIM_OUTPUTSET_TIMEV_5
+#define HRTIM_OUTPUTSET_TIMFEV6_TIMDCMP3 HRTIM_OUTPUTSET_TIMEV_6
+#define HRTIM_OUTPUTSET_TIMFEV7_TIMDCMP4 HRTIM_OUTPUTSET_TIMEV_7
+#define HRTIM_OUTPUTSET_TIMFEV8_TIMECMP2 HRTIM_OUTPUTSET_TIMEV_8
+#define HRTIM_OUTPUTSET_TIMFEV9_TIMECMP3 HRTIM_OUTPUTSET_TIMEV_9
+
+#define HRTIM_OUTPUTRESET_TIMAEV1_TIMBCMP1 HRTIM_OUTPUTSET_TIMEV_1
+#define HRTIM_OUTPUTRESET_TIMAEV2_TIMBCMP2 HRTIM_OUTPUTSET_TIMEV_2
+#define HRTIM_OUTPUTRESET_TIMAEV3_TIMCCMP2 HRTIM_OUTPUTSET_TIMEV_3
+#define HRTIM_OUTPUTRESET_TIMAEV4_TIMCCMP3 HRTIM_OUTPUTSET_TIMEV_4
+#define HRTIM_OUTPUTRESET_TIMAEV5_TIMDCMP1 HRTIM_OUTPUTSET_TIMEV_5
+#define HRTIM_OUTPUTRESET_TIMAEV6_TIMDCMP2 HRTIM_OUTPUTSET_TIMEV_6
+#define HRTIM_OUTPUTRESET_TIMAEV7_TIMECMP3 HRTIM_OUTPUTSET_TIMEV_7
+#define HRTIM_OUTPUTRESET_TIMAEV8_TIMECMP4 HRTIM_OUTPUTSET_TIMEV_8
+#define HRTIM_OUTPUTRESET_TIMAEV9_TIMFCMP4 HRTIM_OUTPUTSET_TIMEV_9
+#define HRTIM_OUTPUTRESET_TIMBEV1_TIMACMP1 HRTIM_OUTPUTSET_TIMEV_1
+#define HRTIM_OUTPUTRESET_TIMBEV2_TIMACMP2 HRTIM_OUTPUTSET_TIMEV_2
+#define HRTIM_OUTPUTRESET_TIMBEV3_TIMCCMP3 HRTIM_OUTPUTSET_TIMEV_3
+#define HRTIM_OUTPUTRESET_TIMBEV4_TIMCCMP4 HRTIM_OUTPUTSET_TIMEV_4
+#define HRTIM_OUTPUTRESET_TIMBEV5_TIMDCMP3 HRTIM_OUTPUTSET_TIMEV_5
+#define HRTIM_OUTPUTRESET_TIMBEV6_TIMDCMP4 HRTIM_OUTPUTSET_TIMEV_6
+#define HRTIM_OUTPUTRESET_TIMBEV7_TIMECMP1 HRTIM_OUTPUTSET_TIMEV_7
+#define HRTIM_OUTPUTRESET_TIMBEV8_TIMECMP2 HRTIM_OUTPUTSET_TIMEV_8
+#define HRTIM_OUTPUTRESET_TIMBEV9_TIMFCMP3 HRTIM_OUTPUTSET_TIMEV_9
+#define HRTIM_OUTPUTRESET_TIMCEV1_TIMACMP1 HRTIM_OUTPUTSET_TIMEV_1
+#define HRTIM_OUTPUTRESET_TIMCEV2_TIMACMP2 HRTIM_OUTPUTSET_TIMEV_2
+#define HRTIM_OUTPUTRESET_TIMCEV3_TIMBCMP2 HRTIM_OUTPUTSET_TIMEV_3
+#define HRTIM_OUTPUTRESET_TIMCEV4_TIMBCMP3 HRTIM_OUTPUTSET_TIMEV_4
+#define HRTIM_OUTPUTRESET_TIMCEV5_TIMDCMP2 HRTIM_OUTPUTSET_TIMEV_5
+#define HRTIM_OUTPUTRESET_TIMCEV6_TIMDCMP4 HRTIM_OUTPUTSET_TIMEV_6
+#define HRTIM_OUTPUTRESET_TIMCEV7_TIMECMP3 HRTIM_OUTPUTSET_TIMEV_7
+#define HRTIM_OUTPUTRESET_TIMCEV8_TIMECMP4 HRTIM_OUTPUTSET_TIMEV_8
+#define HRTIM_OUTPUTRESET_TIMCEV9_TIMFCMP2 HRTIM_OUTPUTSET_TIMEV_9
+#define HRTIM_OUTPUTRESET_TIMDEV1_TIMACMP1 HRTIM_OUTPUTSET_TIMEV_1
+#define HRTIM_OUTPUTRESET_TIMDEV2_TIMACMP4 HRTIM_OUTPUTSET_TIMEV_2
+#define HRTIM_OUTPUTRESET_TIMDEV3_TIMBCMP2 HRTIM_OUTPUTSET_TIMEV_3
+#define HRTIM_OUTPUTRESET_TIMDEV4_TIMBCMP4 HRTIM_OUTPUTSET_TIMEV_4
+#define HRTIM_OUTPUTRESET_TIMDEV5_TIMCCMP4 HRTIM_OUTPUTSET_TIMEV_5
+#define HRTIM_OUTPUTRESET_TIMDEV6_TIMECMP1 HRTIM_OUTPUTSET_TIMEV_6
+#define HRTIM_OUTPUTRESET_TIMDEV7_TIMECMP4 HRTIM_OUTPUTSET_TIMEV_7
+#define HRTIM_OUTPUTRESET_TIMDEV8_TIMFCMP1 HRTIM_OUTPUTSET_TIMEV_8
+#define HRTIM_OUTPUTRESET_TIMDEV9_TIMFCMP3 HRTIM_OUTPUTSET_TIMEV_9
+#define HRTIM_OUTPUTRESET_TIMEEV1_TIMACMP4 HRTIM_OUTPUTSET_TIMEV_1
+#define HRTIM_OUTPUTRESET_TIMEEV2_TIMBCMP3 HRTIM_OUTPUTSET_TIMEV_2
+#define HRTIM_OUTPUTRESET_TIMEEV3_TIMBCMP4 HRTIM_OUTPUTSET_TIMEV_3
+#define HRTIM_OUTPUTRESET_TIMEEV4_TIMCCMP1 HRTIM_OUTPUTSET_TIMEV_4
+#define HRTIM_OUTPUTRESET_TIMEEV5_TIMDCMP2 HRTIM_OUTPUTSET_TIMEV_5
+#define HRTIM_OUTPUTRESET_TIMEEV6_TIMDCMP1 HRTIM_OUTPUTSET_TIMEV_6
+#define HRTIM_OUTPUTRESET_TIMEEV7_TIMDCMP2 HRTIM_OUTPUTSET_TIMEV_7
+#define HRTIM_OUTPUTRESET_TIMEEV8_TIMFCMP3 HRTIM_OUTPUTSET_TIMEV_8
+#define HRTIM_OUTPUTRESET_TIMEEV9_TIMFCMP4 HRTIM_OUTPUTSET_TIMEV_9
+#define HRTIM_OUTPUTRESET_TIMFEV1_TIMACMP3 HRTIM_OUTPUTSET_TIMEV_1
+#define HRTIM_OUTPUTRESET_TIMFEV2_TIMBCMP1 HRTIM_OUTPUTSET_TIMEV_2
+#define HRTIM_OUTPUTRESET_TIMFEV3_TIMBCMP4 HRTIM_OUTPUTSET_TIMEV_3
+#define HRTIM_OUTPUTRESET_TIMFEV4_TIMCCMP1 HRTIM_OUTPUTSET_TIMEV_4
+#define HRTIM_OUTPUTRESET_TIMFEV5_TIMCCMP4 HRTIM_OUTPUTSET_TIMEV_5
+#define HRTIM_OUTPUTRESET_TIMFEV6_TIMDCMP3 HRTIM_OUTPUTSET_TIMEV_6
+#define HRTIM_OUTPUTRESET_TIMFEV7_TIMDCMP4 HRTIM_OUTPUTSET_TIMEV_7
+#define HRTIM_OUTPUTRESET_TIMFEV8_TIMECMP2 HRTIM_OUTPUTSET_TIMEV_8
+#define HRTIM_OUTPUTRESET_TIMFEV9_TIMECMP3 HRTIM_OUTPUTSET_TIMEV_9
+#endif /* STM32H7 */
+
+#if defined(STM32F3)
+/** @brief Constants defining available sources associated to external events.
+ */
+#define HRTIM_EVENTSRC_1 (0x00000000U)
+#define HRTIM_EVENTSRC_2 (HRTIM_EECR1_EE1SRC_0)
+#define HRTIM_EVENTSRC_3 (HRTIM_EECR1_EE1SRC_1)
+#define HRTIM_EVENTSRC_4 (HRTIM_EECR1_EE1SRC_1 | HRTIM_EECR1_EE1SRC_0)
+
+/** @brief Constants defining the DLL calibration periods (in micro seconds)
+ */
+#define HRTIM_CALIBRATIONRATE_7300 0x00000000U
+#define HRTIM_CALIBRATIONRATE_910 (HRTIM_DLLCR_CALRTE_0)
+#define HRTIM_CALIBRATIONRATE_114 (HRTIM_DLLCR_CALRTE_1)
+#define HRTIM_CALIBRATIONRATE_14 (HRTIM_DLLCR_CALRTE_1 | HRTIM_DLLCR_CALRTE_0)
+
+#endif /* STM32F3 */
+/**
+ * @}
+ */
+
+/** @defgroup HAL_I2C_Aliased_Defines HAL I2C Aliased Defines maintained for legacy purpose
+ * @{
+ */
+#define I2C_DUALADDRESS_DISABLED I2C_DUALADDRESS_DISABLE
+#define I2C_DUALADDRESS_ENABLED I2C_DUALADDRESS_ENABLE
+#define I2C_GENERALCALL_DISABLED I2C_GENERALCALL_DISABLE
+#define I2C_GENERALCALL_ENABLED I2C_GENERALCALL_ENABLE
+#define I2C_NOSTRETCH_DISABLED I2C_NOSTRETCH_DISABLE
+#define I2C_NOSTRETCH_ENABLED I2C_NOSTRETCH_ENABLE
+#define I2C_ANALOGFILTER_ENABLED I2C_ANALOGFILTER_ENABLE
+#define I2C_ANALOGFILTER_DISABLED I2C_ANALOGFILTER_DISABLE
+#if defined(STM32F0) || defined(STM32F1) || defined(STM32F3) || defined(STM32G0) || defined(STM32L4) || defined(STM32L1) || defined(STM32F7)
+#define HAL_I2C_STATE_MEM_BUSY_TX HAL_I2C_STATE_BUSY_TX
+#define HAL_I2C_STATE_MEM_BUSY_RX HAL_I2C_STATE_BUSY_RX
+#define HAL_I2C_STATE_MASTER_BUSY_TX HAL_I2C_STATE_BUSY_TX
+#define HAL_I2C_STATE_MASTER_BUSY_RX HAL_I2C_STATE_BUSY_RX
+#define HAL_I2C_STATE_SLAVE_BUSY_TX HAL_I2C_STATE_BUSY_TX
+#define HAL_I2C_STATE_SLAVE_BUSY_RX HAL_I2C_STATE_BUSY_RX
+#endif
+/**
+ * @}
+ */
+
+/** @defgroup HAL_IRDA_Aliased_Defines HAL IRDA Aliased Defines maintained for legacy purpose
+ * @{
+ */
+#define IRDA_ONE_BIT_SAMPLE_DISABLED IRDA_ONE_BIT_SAMPLE_DISABLE
+#define IRDA_ONE_BIT_SAMPLE_ENABLED IRDA_ONE_BIT_SAMPLE_ENABLE
+
+/**
+ * @}
+ */
+
+/** @defgroup HAL_IWDG_Aliased_Defines HAL IWDG Aliased Defines maintained for legacy purpose
+ * @{
+ */
+#define KR_KEY_RELOAD IWDG_KEY_RELOAD
+#define KR_KEY_ENABLE IWDG_KEY_ENABLE
+#define KR_KEY_EWA IWDG_KEY_WRITE_ACCESS_ENABLE
+#define KR_KEY_DWA IWDG_KEY_WRITE_ACCESS_DISABLE
+/**
+ * @}
+ */
+
+/** @defgroup HAL_LPTIM_Aliased_Defines HAL LPTIM Aliased Defines maintained for legacy purpose
+ * @{
+ */
+
+#define LPTIM_CLOCKSAMPLETIME_DIRECTTRANSISTION LPTIM_CLOCKSAMPLETIME_DIRECTTRANSITION
+#define LPTIM_CLOCKSAMPLETIME_2TRANSISTIONS LPTIM_CLOCKSAMPLETIME_2TRANSITIONS
+#define LPTIM_CLOCKSAMPLETIME_4TRANSISTIONS LPTIM_CLOCKSAMPLETIME_4TRANSITIONS
+#define LPTIM_CLOCKSAMPLETIME_8TRANSISTIONS LPTIM_CLOCKSAMPLETIME_8TRANSITIONS
+
+#define LPTIM_CLOCKPOLARITY_RISINGEDGE LPTIM_CLOCKPOLARITY_RISING
+#define LPTIM_CLOCKPOLARITY_FALLINGEDGE LPTIM_CLOCKPOLARITY_FALLING
+#define LPTIM_CLOCKPOLARITY_BOTHEDGES LPTIM_CLOCKPOLARITY_RISING_FALLING
+
+#define LPTIM_TRIGSAMPLETIME_DIRECTTRANSISTION LPTIM_TRIGSAMPLETIME_DIRECTTRANSITION
+#define LPTIM_TRIGSAMPLETIME_2TRANSISTIONS LPTIM_TRIGSAMPLETIME_2TRANSITIONS
+#define LPTIM_TRIGSAMPLETIME_4TRANSISTIONS LPTIM_TRIGSAMPLETIME_4TRANSITIONS
+#define LPTIM_TRIGSAMPLETIME_8TRANSISTIONS LPTIM_TRIGSAMPLETIME_8TRANSITIONS
+
+/* The following 3 definition have also been present in a temporary version of lptim.h */
+/* They need to be renamed also to the right name, just in case */
+#define LPTIM_TRIGSAMPLETIME_2TRANSITION LPTIM_TRIGSAMPLETIME_2TRANSITIONS
+#define LPTIM_TRIGSAMPLETIME_4TRANSITION LPTIM_TRIGSAMPLETIME_4TRANSITIONS
+#define LPTIM_TRIGSAMPLETIME_8TRANSITION LPTIM_TRIGSAMPLETIME_8TRANSITIONS
+
+#if defined(STM32U5)
+#define LPTIM_ISR_CC1 LPTIM_ISR_CC1IF
+#define LPTIM_ISR_CC2 LPTIM_ISR_CC2IF
+#endif /* STM32U5 */
+/**
+ * @}
+ */
+
+/** @defgroup HAL_NAND_Aliased_Defines HAL NAND Aliased Defines maintained for legacy purpose
+ * @{
+ */
+#define HAL_NAND_Read_Page HAL_NAND_Read_Page_8b
+#define HAL_NAND_Write_Page HAL_NAND_Write_Page_8b
+#define HAL_NAND_Read_SpareArea HAL_NAND_Read_SpareArea_8b
+#define HAL_NAND_Write_SpareArea HAL_NAND_Write_SpareArea_8b
+
+#define NAND_AddressTypedef NAND_AddressTypeDef
+
+#define __ARRAY_ADDRESS ARRAY_ADDRESS
+#define __ADDR_1st_CYCLE ADDR_1ST_CYCLE
+#define __ADDR_2nd_CYCLE ADDR_2ND_CYCLE
+#define __ADDR_3rd_CYCLE ADDR_3RD_CYCLE
+#define __ADDR_4th_CYCLE ADDR_4TH_CYCLE
+/**
+ * @}
+ */
+
+/** @defgroup HAL_NOR_Aliased_Defines HAL NOR Aliased Defines maintained for legacy purpose
+ * @{
+ */
+#define NOR_StatusTypedef HAL_NOR_StatusTypeDef
+#define NOR_SUCCESS HAL_NOR_STATUS_SUCCESS
+#define NOR_ONGOING HAL_NOR_STATUS_ONGOING
+#define NOR_ERROR HAL_NOR_STATUS_ERROR
+#define NOR_TIMEOUT HAL_NOR_STATUS_TIMEOUT
+
+#define __NOR_WRITE NOR_WRITE
+#define __NOR_ADDR_SHIFT NOR_ADDR_SHIFT
+/**
+ * @}
+ */
+
+/** @defgroup HAL_OPAMP_Aliased_Defines HAL OPAMP Aliased Defines maintained for legacy purpose
+ * @{
+ */
+
+#define OPAMP_NONINVERTINGINPUT_VP0 OPAMP_NONINVERTINGINPUT_IO0
+#define OPAMP_NONINVERTINGINPUT_VP1 OPAMP_NONINVERTINGINPUT_IO1
+#define OPAMP_NONINVERTINGINPUT_VP2 OPAMP_NONINVERTINGINPUT_IO2
+#define OPAMP_NONINVERTINGINPUT_VP3 OPAMP_NONINVERTINGINPUT_IO3
+
+#define OPAMP_SEC_NONINVERTINGINPUT_VP0 OPAMP_SEC_NONINVERTINGINPUT_IO0
+#define OPAMP_SEC_NONINVERTINGINPUT_VP1 OPAMP_SEC_NONINVERTINGINPUT_IO1
+#define OPAMP_SEC_NONINVERTINGINPUT_VP2 OPAMP_SEC_NONINVERTINGINPUT_IO2
+#define OPAMP_SEC_NONINVERTINGINPUT_VP3 OPAMP_SEC_NONINVERTINGINPUT_IO3
+
+#define OPAMP_INVERTINGINPUT_VM0 OPAMP_INVERTINGINPUT_IO0
+#define OPAMP_INVERTINGINPUT_VM1 OPAMP_INVERTINGINPUT_IO1
+
+#define IOPAMP_INVERTINGINPUT_VM0 OPAMP_INVERTINGINPUT_IO0
+#define IOPAMP_INVERTINGINPUT_VM1 OPAMP_INVERTINGINPUT_IO1
+
+#define OPAMP_SEC_INVERTINGINPUT_VM0 OPAMP_SEC_INVERTINGINPUT_IO0
+#define OPAMP_SEC_INVERTINGINPUT_VM1 OPAMP_SEC_INVERTINGINPUT_IO1
+
+#define OPAMP_INVERTINGINPUT_VINM OPAMP_SEC_INVERTINGINPUT_IO1
+
+#define OPAMP_PGACONNECT_NO OPAMP_PGA_CONNECT_INVERTINGINPUT_NO
+#define OPAMP_PGACONNECT_VM0 OPAMP_PGA_CONNECT_INVERTINGINPUT_IO0
+#define OPAMP_PGACONNECT_VM1 OPAMP_PGA_CONNECT_INVERTINGINPUT_IO1
+
+#if defined(STM32L1) || defined(STM32L4) || defined(STM32L5) || defined(STM32H7) || defined(STM32G4)
+#define HAL_OPAMP_MSP_INIT_CB_ID HAL_OPAMP_MSPINIT_CB_ID
+#define HAL_OPAMP_MSP_DEINIT_CB_ID HAL_OPAMP_MSPDEINIT_CB_ID
+#endif
+
+#if defined(STM32L4) || defined(STM32L5)
+#define OPAMP_POWERMODE_NORMAL OPAMP_POWERMODE_NORMALPOWER
+#elif defined(STM32G4)
+#define OPAMP_POWERMODE_NORMAL OPAMP_POWERMODE_NORMALSPEED
+#endif
+
+/**
+ * @}
+ */
+
+/** @defgroup HAL_I2S_Aliased_Defines HAL I2S Aliased Defines maintained for legacy purpose
+ * @{
+ */
+#define I2S_STANDARD_PHILLIPS I2S_STANDARD_PHILIPS
+
+#if defined(STM32H7)
+#define I2S_IT_TXE I2S_IT_TXP
+#define I2S_IT_RXNE I2S_IT_RXP
+
+#define I2S_FLAG_TXE I2S_FLAG_TXP
+#define I2S_FLAG_RXNE I2S_FLAG_RXP
+#endif
+
+#if defined(STM32F7)
+#define I2S_CLOCK_SYSCLK I2S_CLOCK_PLL
+#endif
+/**
+ * @}
+ */
+
+/** @defgroup HAL_PCCARD_Aliased_Defines HAL PCCARD Aliased Defines maintained for legacy purpose
+ * @{
+ */
+
+/* Compact Flash-ATA registers description */
+#define CF_DATA ATA_DATA
+#define CF_SECTOR_COUNT ATA_SECTOR_COUNT
+#define CF_SECTOR_NUMBER ATA_SECTOR_NUMBER
+#define CF_CYLINDER_LOW ATA_CYLINDER_LOW
+#define CF_CYLINDER_HIGH ATA_CYLINDER_HIGH
+#define CF_CARD_HEAD ATA_CARD_HEAD
+#define CF_STATUS_CMD ATA_STATUS_CMD
+#define CF_STATUS_CMD_ALTERNATE ATA_STATUS_CMD_ALTERNATE
+#define CF_COMMON_DATA_AREA ATA_COMMON_DATA_AREA
+
+/* Compact Flash-ATA commands */
+#define CF_READ_SECTOR_CMD ATA_READ_SECTOR_CMD
+#define CF_WRITE_SECTOR_CMD ATA_WRITE_SECTOR_CMD
+#define CF_ERASE_SECTOR_CMD ATA_ERASE_SECTOR_CMD
+#define CF_IDENTIFY_CMD ATA_IDENTIFY_CMD
+
+#define PCCARD_StatusTypedef HAL_PCCARD_StatusTypeDef
+#define PCCARD_SUCCESS HAL_PCCARD_STATUS_SUCCESS
+#define PCCARD_ONGOING HAL_PCCARD_STATUS_ONGOING
+#define PCCARD_ERROR HAL_PCCARD_STATUS_ERROR
+#define PCCARD_TIMEOUT HAL_PCCARD_STATUS_TIMEOUT
+/**
+ * @}
+ */
+
+/** @defgroup HAL_RTC_Aliased_Defines HAL RTC Aliased Defines maintained for legacy purpose
+ * @{
+ */
+
+#define FORMAT_BIN RTC_FORMAT_BIN
+#define FORMAT_BCD RTC_FORMAT_BCD
+
+#define RTC_ALARMSUBSECONDMASK_None RTC_ALARMSUBSECONDMASK_NONE
+#define RTC_TAMPERERASEBACKUP_DISABLED RTC_TAMPER_ERASE_BACKUP_DISABLE
+#define RTC_TAMPERMASK_FLAG_DISABLED RTC_TAMPERMASK_FLAG_DISABLE
+#define RTC_TAMPERMASK_FLAG_ENABLED RTC_TAMPERMASK_FLAG_ENABLE
+
+#define RTC_MASKTAMPERFLAG_DISABLED RTC_TAMPERMASK_FLAG_DISABLE
+#define RTC_MASKTAMPERFLAG_ENABLED RTC_TAMPERMASK_FLAG_ENABLE
+#define RTC_TAMPERERASEBACKUP_ENABLED RTC_TAMPER_ERASE_BACKUP_ENABLE
+#define RTC_TAMPER1_2_INTERRUPT RTC_ALL_TAMPER_INTERRUPT
+#define RTC_TAMPER1_2_3_INTERRUPT RTC_ALL_TAMPER_INTERRUPT
+
+#define RTC_TIMESTAMPPIN_PC13 RTC_TIMESTAMPPIN_DEFAULT
+#define RTC_TIMESTAMPPIN_PA0 RTC_TIMESTAMPPIN_POS1
+#define RTC_TIMESTAMPPIN_PI8 RTC_TIMESTAMPPIN_POS1
+#define RTC_TIMESTAMPPIN_PC1 RTC_TIMESTAMPPIN_POS2
+
+#define RTC_OUTPUT_REMAP_PC13 RTC_OUTPUT_REMAP_NONE
+#define RTC_OUTPUT_REMAP_PB14 RTC_OUTPUT_REMAP_POS1
+#define RTC_OUTPUT_REMAP_PB2 RTC_OUTPUT_REMAP_POS1
+
+#define RTC_TAMPERPIN_PC13 RTC_TAMPERPIN_DEFAULT
+#define RTC_TAMPERPIN_PA0 RTC_TAMPERPIN_POS1
+#define RTC_TAMPERPIN_PI8 RTC_TAMPERPIN_POS1
+
+#if defined(STM32H7)
+#define RTC_TAMPCR_TAMPXE RTC_TAMPER_X
+#define RTC_TAMPCR_TAMPXIE RTC_TAMPER_X_INTERRUPT
+
+#define RTC_TAMPER1_INTERRUPT RTC_IT_TAMP1
+#define RTC_TAMPER2_INTERRUPT RTC_IT_TAMP2
+#define RTC_TAMPER3_INTERRUPT RTC_IT_TAMP3
+#define RTC_ALL_TAMPER_INTERRUPT RTC_IT_TAMPALL
+#endif /* STM32H7 */
+
+/**
+ * @}
+ */
+
+
+/** @defgroup HAL_SMARTCARD_Aliased_Defines HAL SMARTCARD Aliased Defines maintained for legacy purpose
+ * @{
+ */
+#define SMARTCARD_NACK_ENABLED SMARTCARD_NACK_ENABLE
+#define SMARTCARD_NACK_DISABLED SMARTCARD_NACK_DISABLE
+
+#define SMARTCARD_ONEBIT_SAMPLING_DISABLED SMARTCARD_ONE_BIT_SAMPLE_DISABLE
+#define SMARTCARD_ONEBIT_SAMPLING_ENABLED SMARTCARD_ONE_BIT_SAMPLE_ENABLE
+#define SMARTCARD_ONEBIT_SAMPLING_DISABLE SMARTCARD_ONE_BIT_SAMPLE_DISABLE
+#define SMARTCARD_ONEBIT_SAMPLING_ENABLE SMARTCARD_ONE_BIT_SAMPLE_ENABLE
+
+#define SMARTCARD_TIMEOUT_DISABLED SMARTCARD_TIMEOUT_DISABLE
+#define SMARTCARD_TIMEOUT_ENABLED SMARTCARD_TIMEOUT_ENABLE
+
+#define SMARTCARD_LASTBIT_DISABLED SMARTCARD_LASTBIT_DISABLE
+#define SMARTCARD_LASTBIT_ENABLED SMARTCARD_LASTBIT_ENABLE
+/**
+ * @}
+ */
+
+
+/** @defgroup HAL_SMBUS_Aliased_Defines HAL SMBUS Aliased Defines maintained for legacy purpose
+ * @{
+ */
+#define SMBUS_DUALADDRESS_DISABLED SMBUS_DUALADDRESS_DISABLE
+#define SMBUS_DUALADDRESS_ENABLED SMBUS_DUALADDRESS_ENABLE
+#define SMBUS_GENERALCALL_DISABLED SMBUS_GENERALCALL_DISABLE
+#define SMBUS_GENERALCALL_ENABLED SMBUS_GENERALCALL_ENABLE
+#define SMBUS_NOSTRETCH_DISABLED SMBUS_NOSTRETCH_DISABLE
+#define SMBUS_NOSTRETCH_ENABLED SMBUS_NOSTRETCH_ENABLE
+#define SMBUS_ANALOGFILTER_ENABLED SMBUS_ANALOGFILTER_ENABLE
+#define SMBUS_ANALOGFILTER_DISABLED SMBUS_ANALOGFILTER_DISABLE
+#define SMBUS_PEC_DISABLED SMBUS_PEC_DISABLE
+#define SMBUS_PEC_ENABLED SMBUS_PEC_ENABLE
+#define HAL_SMBUS_STATE_SLAVE_LISTEN HAL_SMBUS_STATE_LISTEN
+/**
+ * @}
+ */
+
+/** @defgroup HAL_SPI_Aliased_Defines HAL SPI Aliased Defines maintained for legacy purpose
+ * @{
+ */
+#define SPI_TIMODE_DISABLED SPI_TIMODE_DISABLE
+#define SPI_TIMODE_ENABLED SPI_TIMODE_ENABLE
+
+#define SPI_CRCCALCULATION_DISABLED SPI_CRCCALCULATION_DISABLE
+#define SPI_CRCCALCULATION_ENABLED SPI_CRCCALCULATION_ENABLE
+
+#define SPI_NSS_PULSE_DISABLED SPI_NSS_PULSE_DISABLE
+#define SPI_NSS_PULSE_ENABLED SPI_NSS_PULSE_ENABLE
+
+#if defined(STM32H7)
+
+#define SPI_FLAG_TXE SPI_FLAG_TXP
+#define SPI_FLAG_RXNE SPI_FLAG_RXP
+
+#define SPI_IT_TXE SPI_IT_TXP
+#define SPI_IT_RXNE SPI_IT_RXP
+
+#define SPI_FRLVL_EMPTY SPI_RX_FIFO_0PACKET
+#define SPI_FRLVL_QUARTER_FULL SPI_RX_FIFO_1PACKET
+#define SPI_FRLVL_HALF_FULL SPI_RX_FIFO_2PACKET
+#define SPI_FRLVL_FULL SPI_RX_FIFO_3PACKET
+
+#endif /* STM32H7 */
+
+/**
+ * @}
+ */
+
+/** @defgroup HAL_TIM_Aliased_Defines HAL TIM Aliased Defines maintained for legacy purpose
+ * @{
+ */
+#define CCER_CCxE_MASK TIM_CCER_CCxE_MASK
+#define CCER_CCxNE_MASK TIM_CCER_CCxNE_MASK
+
+#define TIM_DMABase_CR1 TIM_DMABASE_CR1
+#define TIM_DMABase_CR2 TIM_DMABASE_CR2
+#define TIM_DMABase_SMCR TIM_DMABASE_SMCR
+#define TIM_DMABase_DIER TIM_DMABASE_DIER
+#define TIM_DMABase_SR TIM_DMABASE_SR
+#define TIM_DMABase_EGR TIM_DMABASE_EGR
+#define TIM_DMABase_CCMR1 TIM_DMABASE_CCMR1
+#define TIM_DMABase_CCMR2 TIM_DMABASE_CCMR2
+#define TIM_DMABase_CCER TIM_DMABASE_CCER
+#define TIM_DMABase_CNT TIM_DMABASE_CNT
+#define TIM_DMABase_PSC TIM_DMABASE_PSC
+#define TIM_DMABase_ARR TIM_DMABASE_ARR
+#define TIM_DMABase_RCR TIM_DMABASE_RCR
+#define TIM_DMABase_CCR1 TIM_DMABASE_CCR1
+#define TIM_DMABase_CCR2 TIM_DMABASE_CCR2
+#define TIM_DMABase_CCR3 TIM_DMABASE_CCR3
+#define TIM_DMABase_CCR4 TIM_DMABASE_CCR4
+#define TIM_DMABase_BDTR TIM_DMABASE_BDTR
+#define TIM_DMABase_DCR TIM_DMABASE_DCR
+#define TIM_DMABase_DMAR TIM_DMABASE_DMAR
+#define TIM_DMABase_OR1 TIM_DMABASE_OR1
+#define TIM_DMABase_CCMR3 TIM_DMABASE_CCMR3
+#define TIM_DMABase_CCR5 TIM_DMABASE_CCR5
+#define TIM_DMABase_CCR6 TIM_DMABASE_CCR6
+#define TIM_DMABase_OR2 TIM_DMABASE_OR2
+#define TIM_DMABase_OR3 TIM_DMABASE_OR3
+#define TIM_DMABase_OR TIM_DMABASE_OR
+
+#define TIM_EventSource_Update TIM_EVENTSOURCE_UPDATE
+#define TIM_EventSource_CC1 TIM_EVENTSOURCE_CC1
+#define TIM_EventSource_CC2 TIM_EVENTSOURCE_CC2
+#define TIM_EventSource_CC3 TIM_EVENTSOURCE_CC3
+#define TIM_EventSource_CC4 TIM_EVENTSOURCE_CC4
+#define TIM_EventSource_COM TIM_EVENTSOURCE_COM
+#define TIM_EventSource_Trigger TIM_EVENTSOURCE_TRIGGER
+#define TIM_EventSource_Break TIM_EVENTSOURCE_BREAK
+#define TIM_EventSource_Break2 TIM_EVENTSOURCE_BREAK2
+
+#define TIM_DMABurstLength_1Transfer TIM_DMABURSTLENGTH_1TRANSFER
+#define TIM_DMABurstLength_2Transfers TIM_DMABURSTLENGTH_2TRANSFERS
+#define TIM_DMABurstLength_3Transfers TIM_DMABURSTLENGTH_3TRANSFERS
+#define TIM_DMABurstLength_4Transfers TIM_DMABURSTLENGTH_4TRANSFERS
+#define TIM_DMABurstLength_5Transfers TIM_DMABURSTLENGTH_5TRANSFERS
+#define TIM_DMABurstLength_6Transfers TIM_DMABURSTLENGTH_6TRANSFERS
+#define TIM_DMABurstLength_7Transfers TIM_DMABURSTLENGTH_7TRANSFERS
+#define TIM_DMABurstLength_8Transfers TIM_DMABURSTLENGTH_8TRANSFERS
+#define TIM_DMABurstLength_9Transfers TIM_DMABURSTLENGTH_9TRANSFERS
+#define TIM_DMABurstLength_10Transfers TIM_DMABURSTLENGTH_10TRANSFERS
+#define TIM_DMABurstLength_11Transfers TIM_DMABURSTLENGTH_11TRANSFERS
+#define TIM_DMABurstLength_12Transfers TIM_DMABURSTLENGTH_12TRANSFERS
+#define TIM_DMABurstLength_13Transfers TIM_DMABURSTLENGTH_13TRANSFERS
+#define TIM_DMABurstLength_14Transfers TIM_DMABURSTLENGTH_14TRANSFERS
+#define TIM_DMABurstLength_15Transfers TIM_DMABURSTLENGTH_15TRANSFERS
+#define TIM_DMABurstLength_16Transfers TIM_DMABURSTLENGTH_16TRANSFERS
+#define TIM_DMABurstLength_17Transfers TIM_DMABURSTLENGTH_17TRANSFERS
+#define TIM_DMABurstLength_18Transfers TIM_DMABURSTLENGTH_18TRANSFERS
+
+#if defined(STM32L0)
+#define TIM22_TI1_GPIO1 TIM22_TI1_GPIO
+#define TIM22_TI1_GPIO2 TIM22_TI1_GPIO
+#endif
+
+#if defined(STM32F3)
+#define IS_TIM_HALL_INTERFACE_INSTANCE IS_TIM_HALL_SENSOR_INTERFACE_INSTANCE
+#endif
+
+#if defined(STM32H7)
+#define TIM_TIM1_ETR_COMP1_OUT TIM_TIM1_ETR_COMP1
+#define TIM_TIM1_ETR_COMP2_OUT TIM_TIM1_ETR_COMP2
+#define TIM_TIM8_ETR_COMP1_OUT TIM_TIM8_ETR_COMP1
+#define TIM_TIM8_ETR_COMP2_OUT TIM_TIM8_ETR_COMP2
+#define TIM_TIM2_ETR_COMP1_OUT TIM_TIM2_ETR_COMP1
+#define TIM_TIM2_ETR_COMP2_OUT TIM_TIM2_ETR_COMP2
+#define TIM_TIM3_ETR_COMP1_OUT TIM_TIM3_ETR_COMP1
+#define TIM_TIM1_TI1_COMP1_OUT TIM_TIM1_TI1_COMP1
+#define TIM_TIM8_TI1_COMP2_OUT TIM_TIM8_TI1_COMP2
+#define TIM_TIM2_TI4_COMP1_OUT TIM_TIM2_TI4_COMP1
+#define TIM_TIM2_TI4_COMP2_OUT TIM_TIM2_TI4_COMP2
+#define TIM_TIM2_TI4_COMP1COMP2_OUT TIM_TIM2_TI4_COMP1_COMP2
+#define TIM_TIM3_TI1_COMP1_OUT TIM_TIM3_TI1_COMP1
+#define TIM_TIM3_TI1_COMP2_OUT TIM_TIM3_TI1_COMP2
+#define TIM_TIM3_TI1_COMP1COMP2_OUT TIM_TIM3_TI1_COMP1_COMP2
+#endif
+
+/**
+ * @}
+ */
+
+/** @defgroup HAL_TSC_Aliased_Defines HAL TSC Aliased Defines maintained for legacy purpose
+ * @{
+ */
+#define TSC_SYNC_POL_FALL TSC_SYNC_POLARITY_FALLING
+#define TSC_SYNC_POL_RISE_HIGH TSC_SYNC_POLARITY_RISING
+/**
+ * @}
+ */
+
+/** @defgroup HAL_UART_Aliased_Defines HAL UART Aliased Defines maintained for legacy purpose
+ * @{
+ */
+#define UART_ONEBIT_SAMPLING_DISABLED UART_ONE_BIT_SAMPLE_DISABLE
+#define UART_ONEBIT_SAMPLING_ENABLED UART_ONE_BIT_SAMPLE_ENABLE
+#define UART_ONE_BIT_SAMPLE_DISABLED UART_ONE_BIT_SAMPLE_DISABLE
+#define UART_ONE_BIT_SAMPLE_ENABLED UART_ONE_BIT_SAMPLE_ENABLE
+
+#define __HAL_UART_ONEBIT_ENABLE __HAL_UART_ONE_BIT_SAMPLE_ENABLE
+#define __HAL_UART_ONEBIT_DISABLE __HAL_UART_ONE_BIT_SAMPLE_DISABLE
+
+#define __DIV_SAMPLING16 UART_DIV_SAMPLING16
+#define __DIVMANT_SAMPLING16 UART_DIVMANT_SAMPLING16
+#define __DIVFRAQ_SAMPLING16 UART_DIVFRAQ_SAMPLING16
+#define __UART_BRR_SAMPLING16 UART_BRR_SAMPLING16
+
+#define __DIV_SAMPLING8 UART_DIV_SAMPLING8
+#define __DIVMANT_SAMPLING8 UART_DIVMANT_SAMPLING8
+#define __DIVFRAQ_SAMPLING8 UART_DIVFRAQ_SAMPLING8
+#define __UART_BRR_SAMPLING8 UART_BRR_SAMPLING8
+
+#define __DIV_LPUART UART_DIV_LPUART
+
+#define UART_WAKEUPMETHODE_IDLELINE UART_WAKEUPMETHOD_IDLELINE
+#define UART_WAKEUPMETHODE_ADDRESSMARK UART_WAKEUPMETHOD_ADDRESSMARK
+
+/**
+ * @}
+ */
+
+
+/** @defgroup HAL_USART_Aliased_Defines HAL USART Aliased Defines maintained for legacy purpose
+ * @{
+ */
+
+#define USART_CLOCK_DISABLED USART_CLOCK_DISABLE
+#define USART_CLOCK_ENABLED USART_CLOCK_ENABLE
+
+#define USARTNACK_ENABLED USART_NACK_ENABLE
+#define USARTNACK_DISABLED USART_NACK_DISABLE
+/**
+ * @}
+ */
+
+/** @defgroup HAL_WWDG_Aliased_Defines HAL WWDG Aliased Defines maintained for legacy purpose
+ * @{
+ */
+#define CFR_BASE WWDG_CFR_BASE
+
+/**
+ * @}
+ */
+
+/** @defgroup HAL_CAN_Aliased_Defines HAL CAN Aliased Defines maintained for legacy purpose
+ * @{
+ */
+#define CAN_FilterFIFO0 CAN_FILTER_FIFO0
+#define CAN_FilterFIFO1 CAN_FILTER_FIFO1
+#define CAN_IT_RQCP0 CAN_IT_TME
+#define CAN_IT_RQCP1 CAN_IT_TME
+#define CAN_IT_RQCP2 CAN_IT_TME
+#define INAK_TIMEOUT CAN_TIMEOUT_VALUE
+#define SLAK_TIMEOUT CAN_TIMEOUT_VALUE
+#define CAN_TXSTATUS_FAILED ((uint8_t)0x00U)
+#define CAN_TXSTATUS_OK ((uint8_t)0x01U)
+#define CAN_TXSTATUS_PENDING ((uint8_t)0x02U)
+
+/**
+ * @}
+ */
+
+/** @defgroup HAL_ETH_Aliased_Defines HAL ETH Aliased Defines maintained for legacy purpose
+ * @{
+ */
+
+#define VLAN_TAG ETH_VLAN_TAG
+#define MIN_ETH_PAYLOAD ETH_MIN_ETH_PAYLOAD
+#define MAX_ETH_PAYLOAD ETH_MAX_ETH_PAYLOAD
+#define JUMBO_FRAME_PAYLOAD ETH_JUMBO_FRAME_PAYLOAD
+#define MACMIIAR_CR_MASK ETH_MACMIIAR_CR_MASK
+#define MACCR_CLEAR_MASK ETH_MACCR_CLEAR_MASK
+#define MACFCR_CLEAR_MASK ETH_MACFCR_CLEAR_MASK
+#define DMAOMR_CLEAR_MASK ETH_DMAOMR_CLEAR_MASK
+
+#define ETH_MMCCR 0x00000100U
+#define ETH_MMCRIR 0x00000104U
+#define ETH_MMCTIR 0x00000108U
+#define ETH_MMCRIMR 0x0000010CU
+#define ETH_MMCTIMR 0x00000110U
+#define ETH_MMCTGFSCCR 0x0000014CU
+#define ETH_MMCTGFMSCCR 0x00000150U
+#define ETH_MMCTGFCR 0x00000168U
+#define ETH_MMCRFCECR 0x00000194U
+#define ETH_MMCRFAECR 0x00000198U
+#define ETH_MMCRGUFCR 0x000001C4U
+
+#define ETH_MAC_TXFIFO_FULL 0x02000000U /* Tx FIFO full */
+#define ETH_MAC_TXFIFONOT_EMPTY 0x01000000U /* Tx FIFO not empty */
+#define ETH_MAC_TXFIFO_WRITE_ACTIVE 0x00400000U /* Tx FIFO write active */
+#define ETH_MAC_TXFIFO_IDLE 0x00000000U /* Tx FIFO read status: Idle */
+#define ETH_MAC_TXFIFO_READ 0x00100000U /* Tx FIFO read status: Read (transferring data to the MAC transmitter) */
+#define ETH_MAC_TXFIFO_WAITING 0x00200000U /* Tx FIFO read status: Waiting for TxStatus from MAC transmitter */
+#define ETH_MAC_TXFIFO_WRITING 0x00300000U /* Tx FIFO read status: Writing the received TxStatus or flushing the TxFIFO */
+#define ETH_MAC_TRANSMISSION_PAUSE 0x00080000U /* MAC transmitter in pause */
+#define ETH_MAC_TRANSMITFRAMECONTROLLER_IDLE 0x00000000U /* MAC transmit frame controller: Idle */
+#define ETH_MAC_TRANSMITFRAMECONTROLLER_WAITING 0x00020000U /* MAC transmit frame controller: Waiting for Status of previous frame or IFG/backoff period to be over */
+#define ETH_MAC_TRANSMITFRAMECONTROLLER_GENRATING_PCF 0x00040000U /* MAC transmit frame controller: Generating and transmitting a Pause control frame (in full duplex mode) */
+#define ETH_MAC_TRANSMITFRAMECONTROLLER_TRANSFERRING 0x00060000U /* MAC transmit frame controller: Transferring input frame for transmission */
+#define ETH_MAC_MII_TRANSMIT_ACTIVE 0x00010000U /* MAC MII transmit engine active */
+#define ETH_MAC_RXFIFO_EMPTY 0x00000000U /* Rx FIFO fill level: empty */
+#define ETH_MAC_RXFIFO_BELOW_THRESHOLD 0x00000100U /* Rx FIFO fill level: fill-level below flow-control de-activate threshold */
+#define ETH_MAC_RXFIFO_ABOVE_THRESHOLD 0x00000200U /* Rx FIFO fill level: fill-level above flow-control activate threshold */
+#define ETH_MAC_RXFIFO_FULL 0x00000300U /* Rx FIFO fill level: full */
+#if defined(STM32F1)
+#else
+#define ETH_MAC_READCONTROLLER_IDLE 0x00000000U /* Rx FIFO read controller IDLE state */
+#define ETH_MAC_READCONTROLLER_READING_DATA 0x00000020U /* Rx FIFO read controller Reading frame data */
+#define ETH_MAC_READCONTROLLER_READING_STATUS 0x00000040U /* Rx FIFO read controller Reading frame status (or time-stamp) */
+#endif
+#define ETH_MAC_READCONTROLLER_FLUSHING 0x00000060U /* Rx FIFO read controller Flushing the frame data and status */
+#define ETH_MAC_RXFIFO_WRITE_ACTIVE 0x00000010U /* Rx FIFO write controller active */
+#define ETH_MAC_SMALL_FIFO_NOTACTIVE 0x00000000U /* MAC small FIFO read / write controllers not active */
+#define ETH_MAC_SMALL_FIFO_READ_ACTIVE 0x00000002U /* MAC small FIFO read controller active */
+#define ETH_MAC_SMALL_FIFO_WRITE_ACTIVE 0x00000004U /* MAC small FIFO write controller active */
+#define ETH_MAC_SMALL_FIFO_RW_ACTIVE 0x00000006U /* MAC small FIFO read / write controllers active */
+#define ETH_MAC_MII_RECEIVE_PROTOCOL_ACTIVE 0x00000001U /* MAC MII receive protocol engine active */
+
+/**
+ * @}
+ */
+
+/** @defgroup HAL_DCMI_Aliased_Defines HAL DCMI Aliased Defines maintained for legacy purpose
+ * @{
+ */
+#define HAL_DCMI_ERROR_OVF HAL_DCMI_ERROR_OVR
+#define DCMI_IT_OVF DCMI_IT_OVR
+#define DCMI_FLAG_OVFRI DCMI_FLAG_OVRRI
+#define DCMI_FLAG_OVFMI DCMI_FLAG_OVRMI
+
+#define HAL_DCMI_ConfigCROP HAL_DCMI_ConfigCrop
+#define HAL_DCMI_EnableCROP HAL_DCMI_EnableCrop
+#define HAL_DCMI_DisableCROP HAL_DCMI_DisableCrop
+
+/**
+ * @}
+ */
+
+#if defined(STM32L4) || defined(STM32F7) || defined(STM32F427xx) || defined(STM32F437xx) \
+ || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) \
+ || defined(STM32H7)
+/** @defgroup HAL_DMA2D_Aliased_Defines HAL DMA2D Aliased Defines maintained for legacy purpose
+ * @{
+ */
+#define DMA2D_ARGB8888 DMA2D_OUTPUT_ARGB8888
+#define DMA2D_RGB888 DMA2D_OUTPUT_RGB888
+#define DMA2D_RGB565 DMA2D_OUTPUT_RGB565
+#define DMA2D_ARGB1555 DMA2D_OUTPUT_ARGB1555
+#define DMA2D_ARGB4444 DMA2D_OUTPUT_ARGB4444
+
+#define CM_ARGB8888 DMA2D_INPUT_ARGB8888
+#define CM_RGB888 DMA2D_INPUT_RGB888
+#define CM_RGB565 DMA2D_INPUT_RGB565
+#define CM_ARGB1555 DMA2D_INPUT_ARGB1555
+#define CM_ARGB4444 DMA2D_INPUT_ARGB4444
+#define CM_L8 DMA2D_INPUT_L8
+#define CM_AL44 DMA2D_INPUT_AL44
+#define CM_AL88 DMA2D_INPUT_AL88
+#define CM_L4 DMA2D_INPUT_L4
+#define CM_A8 DMA2D_INPUT_A8
+#define CM_A4 DMA2D_INPUT_A4
+/**
+ * @}
+ */
+#endif /* STM32L4 || STM32F7 || STM32F4 || STM32H7 */
+
+#if defined(STM32L4) || defined(STM32F7) || defined(STM32F427xx) || defined(STM32F437xx) \
+ || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) \
+ || defined(STM32H7) || defined(STM32U5)
+/** @defgroup DMA2D_Aliases DMA2D API Aliases
+ * @{
+ */
+#define HAL_DMA2D_DisableCLUT HAL_DMA2D_CLUTLoading_Abort /*!< Aliased to HAL_DMA2D_CLUTLoading_Abort
+ for compatibility with legacy code */
+/**
+ * @}
+ */
+
+#endif /* STM32L4 || STM32F7 || STM32F4 || STM32H7 || STM32U5 */
+
+/** @defgroup HAL_PPP_Aliased_Defines HAL PPP Aliased Defines maintained for legacy purpose
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/* Exported functions --------------------------------------------------------*/
+
+/** @defgroup HAL_CRYP_Aliased_Functions HAL CRYP Aliased Functions maintained for legacy purpose
+ * @{
+ */
+#define HAL_CRYP_ComputationCpltCallback HAL_CRYPEx_ComputationCpltCallback
+/**
+ * @}
+ */
+
+/** @defgroup HAL_DCACHE_Aliased_Functions HAL DCACHE Aliased Functions maintained for legacy purpose
+ * @{
+ */
+
+#if defined(STM32U5)
+#define HAL_DCACHE_CleanInvalidateByAddr HAL_DCACHE_CleanInvalidByAddr
+#define HAL_DCACHE_CleanInvalidateByAddr_IT HAL_DCACHE_CleanInvalidByAddr_IT
+#endif /* STM32U5 */
+
+/**
+ * @}
+ */
+
+#if !defined(STM32F2)
+/** @defgroup HASH_alias HASH API alias
+ * @{
+ */
+#define HAL_HASHEx_IRQHandler HAL_HASH_IRQHandler /*!< Redirection for compatibility with legacy code */
+/**
+ *
+ * @}
+ */
+#endif /* STM32F2 */
+/** @defgroup HAL_HASH_Aliased_Functions HAL HASH Aliased Functions maintained for legacy purpose
+ * @{
+ */
+#define HAL_HASH_STATETypeDef HAL_HASH_StateTypeDef
+#define HAL_HASHPhaseTypeDef HAL_HASH_PhaseTypeDef
+#define HAL_HMAC_MD5_Finish HAL_HASH_MD5_Finish
+#define HAL_HMAC_SHA1_Finish HAL_HASH_SHA1_Finish
+#define HAL_HMAC_SHA224_Finish HAL_HASH_SHA224_Finish
+#define HAL_HMAC_SHA256_Finish HAL_HASH_SHA256_Finish
+
+/*HASH Algorithm Selection*/
+
+#define HASH_AlgoSelection_SHA1 HASH_ALGOSELECTION_SHA1
+#define HASH_AlgoSelection_SHA224 HASH_ALGOSELECTION_SHA224
+#define HASH_AlgoSelection_SHA256 HASH_ALGOSELECTION_SHA256
+#define HASH_AlgoSelection_MD5 HASH_ALGOSELECTION_MD5
+
+#define HASH_AlgoMode_HASH HASH_ALGOMODE_HASH
+#define HASH_AlgoMode_HMAC HASH_ALGOMODE_HMAC
+
+#define HASH_HMACKeyType_ShortKey HASH_HMAC_KEYTYPE_SHORTKEY
+#define HASH_HMACKeyType_LongKey HASH_HMAC_KEYTYPE_LONGKEY
+
+#if defined(STM32L4) || defined(STM32L5) || defined(STM32F2) || defined(STM32F4) || defined(STM32F7) || defined(STM32H7)
+
+#define HAL_HASH_MD5_Accumulate HAL_HASH_MD5_Accmlt
+#define HAL_HASH_MD5_Accumulate_End HAL_HASH_MD5_Accmlt_End
+#define HAL_HASH_MD5_Accumulate_IT HAL_HASH_MD5_Accmlt_IT
+#define HAL_HASH_MD5_Accumulate_End_IT HAL_HASH_MD5_Accmlt_End_IT
+
+#define HAL_HASH_SHA1_Accumulate HAL_HASH_SHA1_Accmlt
+#define HAL_HASH_SHA1_Accumulate_End HAL_HASH_SHA1_Accmlt_End
+#define HAL_HASH_SHA1_Accumulate_IT HAL_HASH_SHA1_Accmlt_IT
+#define HAL_HASH_SHA1_Accumulate_End_IT HAL_HASH_SHA1_Accmlt_End_IT
+
+#define HAL_HASHEx_SHA224_Accumulate HAL_HASHEx_SHA224_Accmlt
+#define HAL_HASHEx_SHA224_Accumulate_End HAL_HASHEx_SHA224_Accmlt_End
+#define HAL_HASHEx_SHA224_Accumulate_IT HAL_HASHEx_SHA224_Accmlt_IT
+#define HAL_HASHEx_SHA224_Accumulate_End_IT HAL_HASHEx_SHA224_Accmlt_End_IT
+
+#define HAL_HASHEx_SHA256_Accumulate HAL_HASHEx_SHA256_Accmlt
+#define HAL_HASHEx_SHA256_Accumulate_End HAL_HASHEx_SHA256_Accmlt_End
+#define HAL_HASHEx_SHA256_Accumulate_IT HAL_HASHEx_SHA256_Accmlt_IT
+#define HAL_HASHEx_SHA256_Accumulate_End_IT HAL_HASHEx_SHA256_Accmlt_End_IT
+
+#endif /* STM32L4 || STM32L5 || STM32F2 || STM32F4 || STM32F7 || STM32H7 */
+/**
+ * @}
+ */
+
+/** @defgroup HAL_Aliased_Functions HAL Generic Aliased Functions maintained for legacy purpose
+ * @{
+ */
+#define HAL_EnableDBGSleepMode HAL_DBGMCU_EnableDBGSleepMode
+#define HAL_DisableDBGSleepMode HAL_DBGMCU_DisableDBGSleepMode
+#define HAL_EnableDBGStopMode HAL_DBGMCU_EnableDBGStopMode
+#define HAL_DisableDBGStopMode HAL_DBGMCU_DisableDBGStopMode
+#define HAL_EnableDBGStandbyMode HAL_DBGMCU_EnableDBGStandbyMode
+#define HAL_DisableDBGStandbyMode HAL_DBGMCU_DisableDBGStandbyMode
+#define HAL_DBG_LowPowerConfig(Periph, cmd) (((cmd\
+ )==ENABLE)? HAL_DBGMCU_DBG_EnableLowPowerConfig(Periph) : HAL_DBGMCU_DBG_DisableLowPowerConfig(Periph))
+#define HAL_VREFINT_OutputSelect HAL_SYSCFG_VREFINT_OutputSelect
+#define HAL_Lock_Cmd(cmd) (((cmd)==ENABLE) ? HAL_SYSCFG_Enable_Lock_VREFINT() : HAL_SYSCFG_Disable_Lock_VREFINT())
+#if defined(STM32L0)
+#else
+#define HAL_VREFINT_Cmd(cmd) (((cmd)==ENABLE)? HAL_SYSCFG_EnableVREFINT() : HAL_SYSCFG_DisableVREFINT())
+#endif
+#define HAL_ADC_EnableBuffer_Cmd(cmd) (((cmd)==ENABLE) ? HAL_ADCEx_EnableVREFINT() : HAL_ADCEx_DisableVREFINT())
+#define HAL_ADC_EnableBufferSensor_Cmd(cmd) (((cmd\
+ )==ENABLE) ? HAL_ADCEx_EnableVREFINTTempSensor() : HAL_ADCEx_DisableVREFINTTempSensor())
+#if defined(STM32H7A3xx) || defined(STM32H7B3xx) || defined(STM32H7B0xx) || defined(STM32H7A3xxQ) || defined(STM32H7B3xxQ) || defined(STM32H7B0xxQ)
+#define HAL_EnableSRDomainDBGStopMode HAL_EnableDomain3DBGStopMode
+#define HAL_DisableSRDomainDBGStopMode HAL_DisableDomain3DBGStopMode
+#define HAL_EnableSRDomainDBGStandbyMode HAL_EnableDomain3DBGStandbyMode
+#define HAL_DisableSRDomainDBGStandbyMode HAL_DisableDomain3DBGStandbyMode
+#endif /* STM32H7A3xx || STM32H7B3xx || STM32H7B0xx || STM32H7A3xxQ || STM32H7B3xxQ || STM32H7B0xxQ */
+
+/**
+ * @}
+ */
+
+/** @defgroup HAL_FLASH_Aliased_Functions HAL FLASH Aliased Functions maintained for legacy purpose
+ * @{
+ */
+#define FLASH_HalfPageProgram HAL_FLASHEx_HalfPageProgram
+#define FLASH_EnableRunPowerDown HAL_FLASHEx_EnableRunPowerDown
+#define FLASH_DisableRunPowerDown HAL_FLASHEx_DisableRunPowerDown
+#define HAL_DATA_EEPROMEx_Unlock HAL_FLASHEx_DATAEEPROM_Unlock
+#define HAL_DATA_EEPROMEx_Lock HAL_FLASHEx_DATAEEPROM_Lock
+#define HAL_DATA_EEPROMEx_Erase HAL_FLASHEx_DATAEEPROM_Erase
+#define HAL_DATA_EEPROMEx_Program HAL_FLASHEx_DATAEEPROM_Program
+
+/**
+ * @}
+ */
+
+/** @defgroup HAL_I2C_Aliased_Functions HAL I2C Aliased Functions maintained for legacy purpose
+ * @{
+ */
+#define HAL_I2CEx_AnalogFilter_Config HAL_I2CEx_ConfigAnalogFilter
+#define HAL_I2CEx_DigitalFilter_Config HAL_I2CEx_ConfigDigitalFilter
+#define HAL_FMPI2CEx_AnalogFilter_Config HAL_FMPI2CEx_ConfigAnalogFilter
+#define HAL_FMPI2CEx_DigitalFilter_Config HAL_FMPI2CEx_ConfigDigitalFilter
+
+#define HAL_I2CFastModePlusConfig(SYSCFG_I2CFastModePlus, cmd) (((cmd\
+ )==ENABLE)? HAL_I2CEx_EnableFastModePlus(SYSCFG_I2CFastModePlus): HAL_I2CEx_DisableFastModePlus(SYSCFG_I2CFastModePlus))
+
+#if defined(STM32H7) || defined(STM32WB) || defined(STM32G0) || defined(STM32F0) || defined(STM32F1) || defined(STM32F2) || defined(STM32F3) || defined(STM32F4) || defined(STM32F7) || defined(STM32L0) || defined(STM32L4) || defined(STM32L5) || defined(STM32G4) || defined(STM32L1)
+#define HAL_I2C_Master_Sequential_Transmit_IT HAL_I2C_Master_Seq_Transmit_IT
+#define HAL_I2C_Master_Sequential_Receive_IT HAL_I2C_Master_Seq_Receive_IT
+#define HAL_I2C_Slave_Sequential_Transmit_IT HAL_I2C_Slave_Seq_Transmit_IT
+#define HAL_I2C_Slave_Sequential_Receive_IT HAL_I2C_Slave_Seq_Receive_IT
+#endif /* STM32H7 || STM32WB || STM32G0 || STM32F0 || STM32F1 || STM32F2 || STM32F3 || STM32F4 || STM32F7 || STM32L0 || STM32L4 || STM32L5 || STM32G4 || STM32L1 */
+#if defined(STM32H7) || defined(STM32WB) || defined(STM32G0) || defined(STM32F4) || defined(STM32F7) || defined(STM32L0) || defined(STM32L4) || defined(STM32L5) || defined(STM32G4)|| defined(STM32L1)
+#define HAL_I2C_Master_Sequential_Transmit_DMA HAL_I2C_Master_Seq_Transmit_DMA
+#define HAL_I2C_Master_Sequential_Receive_DMA HAL_I2C_Master_Seq_Receive_DMA
+#define HAL_I2C_Slave_Sequential_Transmit_DMA HAL_I2C_Slave_Seq_Transmit_DMA
+#define HAL_I2C_Slave_Sequential_Receive_DMA HAL_I2C_Slave_Seq_Receive_DMA
+#endif /* STM32H7 || STM32WB || STM32G0 || STM32F4 || STM32F7 || STM32L0 || STM32L4 || STM32L5 || STM32G4 || STM32L1 */
+
+#if defined(STM32F4)
+#define HAL_FMPI2C_Master_Sequential_Transmit_IT HAL_FMPI2C_Master_Seq_Transmit_IT
+#define HAL_FMPI2C_Master_Sequential_Receive_IT HAL_FMPI2C_Master_Seq_Receive_IT
+#define HAL_FMPI2C_Slave_Sequential_Transmit_IT HAL_FMPI2C_Slave_Seq_Transmit_IT
+#define HAL_FMPI2C_Slave_Sequential_Receive_IT HAL_FMPI2C_Slave_Seq_Receive_IT
+#define HAL_FMPI2C_Master_Sequential_Transmit_DMA HAL_FMPI2C_Master_Seq_Transmit_DMA
+#define HAL_FMPI2C_Master_Sequential_Receive_DMA HAL_FMPI2C_Master_Seq_Receive_DMA
+#define HAL_FMPI2C_Slave_Sequential_Transmit_DMA HAL_FMPI2C_Slave_Seq_Transmit_DMA
+#define HAL_FMPI2C_Slave_Sequential_Receive_DMA HAL_FMPI2C_Slave_Seq_Receive_DMA
+#endif /* STM32F4 */
+/**
+ * @}
+ */
+
+/** @defgroup HAL_PWR_Aliased HAL PWR Aliased maintained for legacy purpose
+ * @{
+ */
+
+#if defined(STM32G0)
+#define HAL_PWR_ConfigPVD HAL_PWREx_ConfigPVD
+#define HAL_PWR_EnablePVD HAL_PWREx_EnablePVD
+#define HAL_PWR_DisablePVD HAL_PWREx_DisablePVD
+#define HAL_PWR_PVD_IRQHandler HAL_PWREx_PVD_IRQHandler
+#endif
+#define HAL_PWR_PVDConfig HAL_PWR_ConfigPVD
+#define HAL_PWR_DisableBkUpReg HAL_PWREx_DisableBkUpReg
+#define HAL_PWR_DisableFlashPowerDown HAL_PWREx_DisableFlashPowerDown
+#define HAL_PWR_DisableVddio2Monitor HAL_PWREx_DisableVddio2Monitor
+#define HAL_PWR_EnableBkUpReg HAL_PWREx_EnableBkUpReg
+#define HAL_PWR_EnableFlashPowerDown HAL_PWREx_EnableFlashPowerDown
+#define HAL_PWR_EnableVddio2Monitor HAL_PWREx_EnableVddio2Monitor
+#define HAL_PWR_PVD_PVM_IRQHandler HAL_PWREx_PVD_PVM_IRQHandler
+#define HAL_PWR_PVDLevelConfig HAL_PWR_ConfigPVD
+#define HAL_PWR_Vddio2Monitor_IRQHandler HAL_PWREx_Vddio2Monitor_IRQHandler
+#define HAL_PWR_Vddio2MonitorCallback HAL_PWREx_Vddio2MonitorCallback
+#define HAL_PWREx_ActivateOverDrive HAL_PWREx_EnableOverDrive
+#define HAL_PWREx_DeactivateOverDrive HAL_PWREx_DisableOverDrive
+#define HAL_PWREx_DisableSDADCAnalog HAL_PWREx_DisableSDADC
+#define HAL_PWREx_EnableSDADCAnalog HAL_PWREx_EnableSDADC
+#define HAL_PWREx_PVMConfig HAL_PWREx_ConfigPVM
+
+#define PWR_MODE_NORMAL PWR_PVD_MODE_NORMAL
+#define PWR_MODE_IT_RISING PWR_PVD_MODE_IT_RISING
+#define PWR_MODE_IT_FALLING PWR_PVD_MODE_IT_FALLING
+#define PWR_MODE_IT_RISING_FALLING PWR_PVD_MODE_IT_RISING_FALLING
+#define PWR_MODE_EVENT_RISING PWR_PVD_MODE_EVENT_RISING
+#define PWR_MODE_EVENT_FALLING PWR_PVD_MODE_EVENT_FALLING
+#define PWR_MODE_EVENT_RISING_FALLING PWR_PVD_MODE_EVENT_RISING_FALLING
+
+#define CR_OFFSET_BB PWR_CR_OFFSET_BB
+#define CSR_OFFSET_BB PWR_CSR_OFFSET_BB
+#define PMODE_BIT_NUMBER VOS_BIT_NUMBER
+#define CR_PMODE_BB CR_VOS_BB
+
+#define DBP_BitNumber DBP_BIT_NUMBER
+#define PVDE_BitNumber PVDE_BIT_NUMBER
+#define PMODE_BitNumber PMODE_BIT_NUMBER
+#define EWUP_BitNumber EWUP_BIT_NUMBER
+#define FPDS_BitNumber FPDS_BIT_NUMBER
+#define ODEN_BitNumber ODEN_BIT_NUMBER
+#define ODSWEN_BitNumber ODSWEN_BIT_NUMBER
+#define MRLVDS_BitNumber MRLVDS_BIT_NUMBER
+#define LPLVDS_BitNumber LPLVDS_BIT_NUMBER
+#define BRE_BitNumber BRE_BIT_NUMBER
+
+#define PWR_MODE_EVT PWR_PVD_MODE_NORMAL
+
+/**
+ * @}
+ */
+
+/** @defgroup HAL_SMBUS_Aliased_Functions HAL SMBUS Aliased Functions maintained for legacy purpose
+ * @{
+ */
+#define HAL_SMBUS_Slave_Listen_IT HAL_SMBUS_EnableListen_IT
+#define HAL_SMBUS_SlaveAddrCallback HAL_SMBUS_AddrCallback
+#define HAL_SMBUS_SlaveListenCpltCallback HAL_SMBUS_ListenCpltCallback
+/**
+ * @}
+ */
+
+/** @defgroup HAL_SPI_Aliased_Functions HAL SPI Aliased Functions maintained for legacy purpose
+ * @{
+ */
+#define HAL_SPI_FlushRxFifo HAL_SPIEx_FlushRxFifo
+/**
+ * @}
+ */
+
+/** @defgroup HAL_TIM_Aliased_Functions HAL TIM Aliased Functions maintained for legacy purpose
+ * @{
+ */
+#define HAL_TIM_DMADelayPulseCplt TIM_DMADelayPulseCplt
+#define HAL_TIM_DMAError TIM_DMAError
+#define HAL_TIM_DMACaptureCplt TIM_DMACaptureCplt
+#define HAL_TIMEx_DMACommutationCplt TIMEx_DMACommutationCplt
+#if defined(STM32H7) || defined(STM32G0) || defined(STM32F0) || defined(STM32F1) || defined(STM32F2) || defined(STM32F3) || defined(STM32F4) || defined(STM32F7) || defined(STM32L0) || defined(STM32L4)
+#define HAL_TIM_SlaveConfigSynchronization HAL_TIM_SlaveConfigSynchro
+#define HAL_TIM_SlaveConfigSynchronization_IT HAL_TIM_SlaveConfigSynchro_IT
+#define HAL_TIMEx_CommutationCallback HAL_TIMEx_CommutCallback
+#define HAL_TIMEx_ConfigCommutationEvent HAL_TIMEx_ConfigCommutEvent
+#define HAL_TIMEx_ConfigCommutationEvent_IT HAL_TIMEx_ConfigCommutEvent_IT
+#define HAL_TIMEx_ConfigCommutationEvent_DMA HAL_TIMEx_ConfigCommutEvent_DMA
+#endif /* STM32H7 || STM32G0 || STM32F0 || STM32F1 || STM32F2 || STM32F3 || STM32F4 || STM32F7 || STM32L0 */
+/**
+ * @}
+ */
+
+/** @defgroup HAL_UART_Aliased_Functions HAL UART Aliased Functions maintained for legacy purpose
+ * @{
+ */
+#define HAL_UART_WakeupCallback HAL_UARTEx_WakeupCallback
+/**
+ * @}
+ */
+
+/** @defgroup HAL_LTDC_Aliased_Functions HAL LTDC Aliased Functions maintained for legacy purpose
+ * @{
+ */
+#define HAL_LTDC_LineEvenCallback HAL_LTDC_LineEventCallback
+#define HAL_LTDC_Relaod HAL_LTDC_Reload
+#define HAL_LTDC_StructInitFromVideoConfig HAL_LTDCEx_StructInitFromVideoConfig
+#define HAL_LTDC_StructInitFromAdaptedCommandConfig HAL_LTDCEx_StructInitFromAdaptedCommandConfig
+/**
+ * @}
+ */
+
+
+/** @defgroup HAL_PPP_Aliased_Functions HAL PPP Aliased Functions maintained for legacy purpose
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/* Exported macros ------------------------------------------------------------*/
+
+/** @defgroup HAL_AES_Aliased_Macros HAL CRYP Aliased Macros maintained for legacy purpose
+ * @{
+ */
+#define AES_IT_CC CRYP_IT_CC
+#define AES_IT_ERR CRYP_IT_ERR
+#define AES_FLAG_CCF CRYP_FLAG_CCF
+/**
+ * @}
+ */
+
+/** @defgroup HAL_Aliased_Macros HAL Generic Aliased Macros maintained for legacy purpose
+ * @{
+ */
+#define __HAL_GET_BOOT_MODE __HAL_SYSCFG_GET_BOOT_MODE
+#define __HAL_REMAPMEMORY_FLASH __HAL_SYSCFG_REMAPMEMORY_FLASH
+#define __HAL_REMAPMEMORY_SYSTEMFLASH __HAL_SYSCFG_REMAPMEMORY_SYSTEMFLASH
+#define __HAL_REMAPMEMORY_SRAM __HAL_SYSCFG_REMAPMEMORY_SRAM
+#define __HAL_REMAPMEMORY_FMC __HAL_SYSCFG_REMAPMEMORY_FMC
+#define __HAL_REMAPMEMORY_FMC_SDRAM __HAL_SYSCFG_REMAPMEMORY_FMC_SDRAM
+#define __HAL_REMAPMEMORY_FSMC __HAL_SYSCFG_REMAPMEMORY_FSMC
+#define __HAL_REMAPMEMORY_QUADSPI __HAL_SYSCFG_REMAPMEMORY_QUADSPI
+#define __HAL_FMC_BANK __HAL_SYSCFG_FMC_BANK
+#define __HAL_GET_FLAG __HAL_SYSCFG_GET_FLAG
+#define __HAL_CLEAR_FLAG __HAL_SYSCFG_CLEAR_FLAG
+#define __HAL_VREFINT_OUT_ENABLE __HAL_SYSCFG_VREFINT_OUT_ENABLE
+#define __HAL_VREFINT_OUT_DISABLE __HAL_SYSCFG_VREFINT_OUT_DISABLE
+#define __HAL_SYSCFG_SRAM2_WRP_ENABLE __HAL_SYSCFG_SRAM2_WRP_0_31_ENABLE
+
+#define SYSCFG_FLAG_VREF_READY SYSCFG_FLAG_VREFINT_READY
+#define SYSCFG_FLAG_RC48 RCC_FLAG_HSI48
+#define IS_SYSCFG_FASTMODEPLUS_CONFIG IS_I2C_FASTMODEPLUS
+#define UFB_MODE_BitNumber UFB_MODE_BIT_NUMBER
+#define CMP_PD_BitNumber CMP_PD_BIT_NUMBER
+
+/**
+ * @}
+ */
+
+
+/** @defgroup HAL_ADC_Aliased_Macros HAL ADC Aliased Macros maintained for legacy purpose
+ * @{
+ */
+#define __ADC_ENABLE __HAL_ADC_ENABLE
+#define __ADC_DISABLE __HAL_ADC_DISABLE
+#define __HAL_ADC_ENABLING_CONDITIONS ADC_ENABLING_CONDITIONS
+#define __HAL_ADC_DISABLING_CONDITIONS ADC_DISABLING_CONDITIONS
+#define __HAL_ADC_IS_ENABLED ADC_IS_ENABLE
+#define __ADC_IS_ENABLED ADC_IS_ENABLE
+#define __HAL_ADC_IS_SOFTWARE_START_REGULAR ADC_IS_SOFTWARE_START_REGULAR
+#define __HAL_ADC_IS_SOFTWARE_START_INJECTED ADC_IS_SOFTWARE_START_INJECTED
+#define __HAL_ADC_IS_CONVERSION_ONGOING_REGULAR_INJECTED ADC_IS_CONVERSION_ONGOING_REGULAR_INJECTED
+#define __HAL_ADC_IS_CONVERSION_ONGOING_REGULAR ADC_IS_CONVERSION_ONGOING_REGULAR
+#define __HAL_ADC_IS_CONVERSION_ONGOING_INJECTED ADC_IS_CONVERSION_ONGOING_INJECTED
+#define __HAL_ADC_IS_CONVERSION_ONGOING ADC_IS_CONVERSION_ONGOING
+#define __HAL_ADC_CLEAR_ERRORCODE ADC_CLEAR_ERRORCODE
+
+#define __HAL_ADC_GET_RESOLUTION ADC_GET_RESOLUTION
+#define __HAL_ADC_JSQR_RK ADC_JSQR_RK
+#define __HAL_ADC_CFGR_AWD1CH ADC_CFGR_AWD1CH_SHIFT
+#define __HAL_ADC_CFGR_AWD23CR ADC_CFGR_AWD23CR
+#define __HAL_ADC_CFGR_INJECT_AUTO_CONVERSION ADC_CFGR_INJECT_AUTO_CONVERSION
+#define __HAL_ADC_CFGR_INJECT_CONTEXT_QUEUE ADC_CFGR_INJECT_CONTEXT_QUEUE
+#define __HAL_ADC_CFGR_INJECT_DISCCONTINUOUS ADC_CFGR_INJECT_DISCCONTINUOUS
+#define __HAL_ADC_CFGR_REG_DISCCONTINUOUS ADC_CFGR_REG_DISCCONTINUOUS
+#define __HAL_ADC_CFGR_DISCONTINUOUS_NUM ADC_CFGR_DISCONTINUOUS_NUM
+#define __HAL_ADC_CFGR_AUTOWAIT ADC_CFGR_AUTOWAIT
+#define __HAL_ADC_CFGR_CONTINUOUS ADC_CFGR_CONTINUOUS
+#define __HAL_ADC_CFGR_OVERRUN ADC_CFGR_OVERRUN
+#define __HAL_ADC_CFGR_DMACONTREQ ADC_CFGR_DMACONTREQ
+#define __HAL_ADC_CFGR_EXTSEL ADC_CFGR_EXTSEL_SET
+#define __HAL_ADC_JSQR_JEXTSEL ADC_JSQR_JEXTSEL_SET
+#define __HAL_ADC_OFR_CHANNEL ADC_OFR_CHANNEL
+#define __HAL_ADC_DIFSEL_CHANNEL ADC_DIFSEL_CHANNEL
+#define __HAL_ADC_CALFACT_DIFF_SET ADC_CALFACT_DIFF_SET
+#define __HAL_ADC_CALFACT_DIFF_GET ADC_CALFACT_DIFF_GET
+#define __HAL_ADC_TRX_HIGHTHRESHOLD ADC_TRX_HIGHTHRESHOLD
+
+#define __HAL_ADC_OFFSET_SHIFT_RESOLUTION ADC_OFFSET_SHIFT_RESOLUTION
+#define __HAL_ADC_AWD1THRESHOLD_SHIFT_RESOLUTION ADC_AWD1THRESHOLD_SHIFT_RESOLUTION
+#define __HAL_ADC_AWD23THRESHOLD_SHIFT_RESOLUTION ADC_AWD23THRESHOLD_SHIFT_RESOLUTION
+#define __HAL_ADC_COMMON_REGISTER ADC_COMMON_REGISTER
+#define __HAL_ADC_COMMON_CCR_MULTI ADC_COMMON_CCR_MULTI
+#define __HAL_ADC_MULTIMODE_IS_ENABLED ADC_MULTIMODE_IS_ENABLE
+#define __ADC_MULTIMODE_IS_ENABLED ADC_MULTIMODE_IS_ENABLE
+#define __HAL_ADC_NONMULTIMODE_OR_MULTIMODEMASTER ADC_NONMULTIMODE_OR_MULTIMODEMASTER
+#define __HAL_ADC_COMMON_ADC_OTHER ADC_COMMON_ADC_OTHER
+#define __HAL_ADC_MULTI_SLAVE ADC_MULTI_SLAVE
+
+#define __HAL_ADC_SQR1_L ADC_SQR1_L_SHIFT
+#define __HAL_ADC_JSQR_JL ADC_JSQR_JL_SHIFT
+#define __HAL_ADC_JSQR_RK_JL ADC_JSQR_RK_JL
+#define __HAL_ADC_CR1_DISCONTINUOUS_NUM ADC_CR1_DISCONTINUOUS_NUM
+#define __HAL_ADC_CR1_SCAN ADC_CR1_SCAN_SET
+#define __HAL_ADC_CONVCYCLES_MAX_RANGE ADC_CONVCYCLES_MAX_RANGE
+#define __HAL_ADC_CLOCK_PRESCALER_RANGE ADC_CLOCK_PRESCALER_RANGE
+#define __HAL_ADC_GET_CLOCK_PRESCALER ADC_GET_CLOCK_PRESCALER
+
+#define __HAL_ADC_SQR1 ADC_SQR1
+#define __HAL_ADC_SMPR1 ADC_SMPR1
+#define __HAL_ADC_SMPR2 ADC_SMPR2
+#define __HAL_ADC_SQR3_RK ADC_SQR3_RK
+#define __HAL_ADC_SQR2_RK ADC_SQR2_RK
+#define __HAL_ADC_SQR1_RK ADC_SQR1_RK
+#define __HAL_ADC_CR2_CONTINUOUS ADC_CR2_CONTINUOUS
+#define __HAL_ADC_CR1_DISCONTINUOUS ADC_CR1_DISCONTINUOUS
+#define __HAL_ADC_CR1_SCANCONV ADC_CR1_SCANCONV
+#define __HAL_ADC_CR2_EOCSelection ADC_CR2_EOCSelection
+#define __HAL_ADC_CR2_DMAContReq ADC_CR2_DMAContReq
+#define __HAL_ADC_JSQR ADC_JSQR
+
+#define __HAL_ADC_CHSELR_CHANNEL ADC_CHSELR_CHANNEL
+#define __HAL_ADC_CFGR1_REG_DISCCONTINUOUS ADC_CFGR1_REG_DISCCONTINUOUS
+#define __HAL_ADC_CFGR1_AUTOOFF ADC_CFGR1_AUTOOFF
+#define __HAL_ADC_CFGR1_AUTOWAIT ADC_CFGR1_AUTOWAIT
+#define __HAL_ADC_CFGR1_CONTINUOUS ADC_CFGR1_CONTINUOUS
+#define __HAL_ADC_CFGR1_OVERRUN ADC_CFGR1_OVERRUN
+#define __HAL_ADC_CFGR1_SCANDIR ADC_CFGR1_SCANDIR
+#define __HAL_ADC_CFGR1_DMACONTREQ ADC_CFGR1_DMACONTREQ
+
+/**
+ * @}
+ */
+
+/** @defgroup HAL_DAC_Aliased_Macros HAL DAC Aliased Macros maintained for legacy purpose
+ * @{
+ */
+#define __HAL_DHR12R1_ALIGNEMENT DAC_DHR12R1_ALIGNMENT
+#define __HAL_DHR12R2_ALIGNEMENT DAC_DHR12R2_ALIGNMENT
+#define __HAL_DHR12RD_ALIGNEMENT DAC_DHR12RD_ALIGNMENT
+#define IS_DAC_GENERATE_WAVE IS_DAC_WAVE
+
+/**
+ * @}
+ */
+
+/** @defgroup HAL_DBGMCU_Aliased_Macros HAL DBGMCU Aliased Macros maintained for legacy purpose
+ * @{
+ */
+#define __HAL_FREEZE_TIM1_DBGMCU __HAL_DBGMCU_FREEZE_TIM1
+#define __HAL_UNFREEZE_TIM1_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM1
+#define __HAL_FREEZE_TIM2_DBGMCU __HAL_DBGMCU_FREEZE_TIM2
+#define __HAL_UNFREEZE_TIM2_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM2
+#define __HAL_FREEZE_TIM3_DBGMCU __HAL_DBGMCU_FREEZE_TIM3
+#define __HAL_UNFREEZE_TIM3_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM3
+#define __HAL_FREEZE_TIM4_DBGMCU __HAL_DBGMCU_FREEZE_TIM4
+#define __HAL_UNFREEZE_TIM4_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM4
+#define __HAL_FREEZE_TIM5_DBGMCU __HAL_DBGMCU_FREEZE_TIM5
+#define __HAL_UNFREEZE_TIM5_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM5
+#define __HAL_FREEZE_TIM6_DBGMCU __HAL_DBGMCU_FREEZE_TIM6
+#define __HAL_UNFREEZE_TIM6_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM6
+#define __HAL_FREEZE_TIM7_DBGMCU __HAL_DBGMCU_FREEZE_TIM7
+#define __HAL_UNFREEZE_TIM7_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM7
+#define __HAL_FREEZE_TIM8_DBGMCU __HAL_DBGMCU_FREEZE_TIM8
+#define __HAL_UNFREEZE_TIM8_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM8
+
+#define __HAL_FREEZE_TIM9_DBGMCU __HAL_DBGMCU_FREEZE_TIM9
+#define __HAL_UNFREEZE_TIM9_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM9
+#define __HAL_FREEZE_TIM10_DBGMCU __HAL_DBGMCU_FREEZE_TIM10
+#define __HAL_UNFREEZE_TIM10_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM10
+#define __HAL_FREEZE_TIM11_DBGMCU __HAL_DBGMCU_FREEZE_TIM11
+#define __HAL_UNFREEZE_TIM11_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM11
+#define __HAL_FREEZE_TIM12_DBGMCU __HAL_DBGMCU_FREEZE_TIM12
+#define __HAL_UNFREEZE_TIM12_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM12
+#define __HAL_FREEZE_TIM13_DBGMCU __HAL_DBGMCU_FREEZE_TIM13
+#define __HAL_UNFREEZE_TIM13_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM13
+#define __HAL_FREEZE_TIM14_DBGMCU __HAL_DBGMCU_FREEZE_TIM14
+#define __HAL_UNFREEZE_TIM14_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM14
+#define __HAL_FREEZE_CAN2_DBGMCU __HAL_DBGMCU_FREEZE_CAN2
+#define __HAL_UNFREEZE_CAN2_DBGMCU __HAL_DBGMCU_UNFREEZE_CAN2
+
+
+#define __HAL_FREEZE_TIM15_DBGMCU __HAL_DBGMCU_FREEZE_TIM15
+#define __HAL_UNFREEZE_TIM15_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM15
+#define __HAL_FREEZE_TIM16_DBGMCU __HAL_DBGMCU_FREEZE_TIM16
+#define __HAL_UNFREEZE_TIM16_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM16
+#define __HAL_FREEZE_TIM17_DBGMCU __HAL_DBGMCU_FREEZE_TIM17
+#define __HAL_UNFREEZE_TIM17_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM17
+#define __HAL_FREEZE_RTC_DBGMCU __HAL_DBGMCU_FREEZE_RTC
+#define __HAL_UNFREEZE_RTC_DBGMCU __HAL_DBGMCU_UNFREEZE_RTC
+#if defined(STM32H7)
+#define __HAL_FREEZE_WWDG_DBGMCU __HAL_DBGMCU_FREEZE_WWDG1
+#define __HAL_UNFREEZE_WWDG_DBGMCU __HAL_DBGMCU_UnFreeze_WWDG1
+#define __HAL_FREEZE_IWDG_DBGMCU __HAL_DBGMCU_FREEZE_IWDG1
+#define __HAL_UNFREEZE_IWDG_DBGMCU __HAL_DBGMCU_UnFreeze_IWDG1
+#else
+#define __HAL_FREEZE_WWDG_DBGMCU __HAL_DBGMCU_FREEZE_WWDG
+#define __HAL_UNFREEZE_WWDG_DBGMCU __HAL_DBGMCU_UNFREEZE_WWDG
+#define __HAL_FREEZE_IWDG_DBGMCU __HAL_DBGMCU_FREEZE_IWDG
+#define __HAL_UNFREEZE_IWDG_DBGMCU __HAL_DBGMCU_UNFREEZE_IWDG
+#endif /* STM32H7 */
+#define __HAL_FREEZE_I2C1_TIMEOUT_DBGMCU __HAL_DBGMCU_FREEZE_I2C1_TIMEOUT
+#define __HAL_UNFREEZE_I2C1_TIMEOUT_DBGMCU __HAL_DBGMCU_UNFREEZE_I2C1_TIMEOUT
+#define __HAL_FREEZE_I2C2_TIMEOUT_DBGMCU __HAL_DBGMCU_FREEZE_I2C2_TIMEOUT
+#define __HAL_UNFREEZE_I2C2_TIMEOUT_DBGMCU __HAL_DBGMCU_UNFREEZE_I2C2_TIMEOUT
+#define __HAL_FREEZE_I2C3_TIMEOUT_DBGMCU __HAL_DBGMCU_FREEZE_I2C3_TIMEOUT
+#define __HAL_UNFREEZE_I2C3_TIMEOUT_DBGMCU __HAL_DBGMCU_UNFREEZE_I2C3_TIMEOUT
+#define __HAL_FREEZE_CAN1_DBGMCU __HAL_DBGMCU_FREEZE_CAN1
+#define __HAL_UNFREEZE_CAN1_DBGMCU __HAL_DBGMCU_UNFREEZE_CAN1
+#define __HAL_FREEZE_LPTIM1_DBGMCU __HAL_DBGMCU_FREEZE_LPTIM1
+#define __HAL_UNFREEZE_LPTIM1_DBGMCU __HAL_DBGMCU_UNFREEZE_LPTIM1
+#define __HAL_FREEZE_LPTIM2_DBGMCU __HAL_DBGMCU_FREEZE_LPTIM2
+#define __HAL_UNFREEZE_LPTIM2_DBGMCU __HAL_DBGMCU_UNFREEZE_LPTIM2
+
+/**
+ * @}
+ */
+
+/** @defgroup HAL_COMP_Aliased_Macros HAL COMP Aliased Macros maintained for legacy purpose
+ * @{
+ */
+#if defined(STM32F3)
+#define COMP_START __HAL_COMP_ENABLE
+#define COMP_STOP __HAL_COMP_DISABLE
+#define COMP_LOCK __HAL_COMP_LOCK
+
+#if defined(STM32F301x8) || defined(STM32F302x8) || defined(STM32F318xx) || defined(STM32F303x8) || defined(STM32F334x8) || defined(STM32F328xx)
+#define __HAL_COMP_EXTI_RISING_IT_ENABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_ENABLE_RISING_EDGE() : \
+ ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_ENABLE_RISING_EDGE() : \
+ __HAL_COMP_COMP6_EXTI_ENABLE_RISING_EDGE())
+#define __HAL_COMP_EXTI_RISING_IT_DISABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_DISABLE_RISING_EDGE() : \
+ ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_DISABLE_RISING_EDGE() : \
+ __HAL_COMP_COMP6_EXTI_DISABLE_RISING_EDGE())
+#define __HAL_COMP_EXTI_FALLING_IT_ENABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_ENABLE_FALLING_EDGE() : \
+ ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_ENABLE_FALLING_EDGE() : \
+ __HAL_COMP_COMP6_EXTI_ENABLE_FALLING_EDGE())
+#define __HAL_COMP_EXTI_FALLING_IT_DISABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_DISABLE_FALLING_EDGE() : \
+ ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_DISABLE_FALLING_EDGE() : \
+ __HAL_COMP_COMP6_EXTI_DISABLE_FALLING_EDGE())
+#define __HAL_COMP_EXTI_ENABLE_IT(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_ENABLE_IT() : \
+ ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_ENABLE_IT() : \
+ __HAL_COMP_COMP6_EXTI_ENABLE_IT())
+#define __HAL_COMP_EXTI_DISABLE_IT(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_DISABLE_IT() : \
+ ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_DISABLE_IT() : \
+ __HAL_COMP_COMP6_EXTI_DISABLE_IT())
+#define __HAL_COMP_EXTI_GET_FLAG(__FLAG__) (((__FLAG__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_GET_FLAG() : \
+ ((__FLAG__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_GET_FLAG() : \
+ __HAL_COMP_COMP6_EXTI_GET_FLAG())
+#define __HAL_COMP_EXTI_CLEAR_FLAG(__FLAG__) (((__FLAG__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_CLEAR_FLAG() : \
+ ((__FLAG__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_CLEAR_FLAG() : \
+ __HAL_COMP_COMP6_EXTI_CLEAR_FLAG())
+# endif
+# if defined(STM32F302xE) || defined(STM32F302xC)
+#define __HAL_COMP_EXTI_RISING_IT_ENABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_RISING_EDGE() : \
+ ((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_ENABLE_RISING_EDGE() : \
+ ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_ENABLE_RISING_EDGE() : \
+ __HAL_COMP_COMP6_EXTI_ENABLE_RISING_EDGE())
+#define __HAL_COMP_EXTI_RISING_IT_DISABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_DISABLE_RISING_EDGE() : \
+ ((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_DISABLE_RISING_EDGE() : \
+ ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_DISABLE_RISING_EDGE() : \
+ __HAL_COMP_COMP6_EXTI_DISABLE_RISING_EDGE())
+#define __HAL_COMP_EXTI_FALLING_IT_ENABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_FALLING_EDGE() : \
+ ((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_ENABLE_FALLING_EDGE() : \
+ ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_ENABLE_FALLING_EDGE() : \
+ __HAL_COMP_COMP6_EXTI_ENABLE_FALLING_EDGE())
+#define __HAL_COMP_EXTI_FALLING_IT_DISABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_DISABLE_FALLING_EDGE() : \
+ ((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_DISABLE_FALLING_EDGE() : \
+ ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_DISABLE_FALLING_EDGE() : \
+ __HAL_COMP_COMP6_EXTI_DISABLE_FALLING_EDGE())
+#define __HAL_COMP_EXTI_ENABLE_IT(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_IT() : \
+ ((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_ENABLE_IT() : \
+ ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_ENABLE_IT() : \
+ __HAL_COMP_COMP6_EXTI_ENABLE_IT())
+#define __HAL_COMP_EXTI_DISABLE_IT(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_DISABLE_IT() : \
+ ((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_DISABLE_IT() : \
+ ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_DISABLE_IT() : \
+ __HAL_COMP_COMP6_EXTI_DISABLE_IT())
+#define __HAL_COMP_EXTI_GET_FLAG(__FLAG__) (((__FLAG__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_GET_FLAG() : \
+ ((__FLAG__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_GET_FLAG() : \
+ ((__FLAG__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_GET_FLAG() : \
+ __HAL_COMP_COMP6_EXTI_GET_FLAG())
+#define __HAL_COMP_EXTI_CLEAR_FLAG(__FLAG__) (((__FLAG__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_CLEAR_FLAG() : \
+ ((__FLAG__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_CLEAR_FLAG() : \
+ ((__FLAG__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_CLEAR_FLAG() : \
+ __HAL_COMP_COMP6_EXTI_CLEAR_FLAG())
+# endif
+# if defined(STM32F303xE) || defined(STM32F398xx) || defined(STM32F303xC) || defined(STM32F358xx)
+#define __HAL_COMP_EXTI_RISING_IT_ENABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_RISING_EDGE() : \
+ ((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_ENABLE_RISING_EDGE() : \
+ ((__EXTILINE__) == COMP_EXTI_LINE_COMP3) ? __HAL_COMP_COMP3_EXTI_ENABLE_RISING_EDGE() : \
+ ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_ENABLE_RISING_EDGE() : \
+ ((__EXTILINE__) == COMP_EXTI_LINE_COMP5) ? __HAL_COMP_COMP5_EXTI_ENABLE_RISING_EDGE() : \
+ ((__EXTILINE__) == COMP_EXTI_LINE_COMP6) ? __HAL_COMP_COMP6_EXTI_ENABLE_RISING_EDGE() : \
+ __HAL_COMP_COMP7_EXTI_ENABLE_RISING_EDGE())
+#define __HAL_COMP_EXTI_RISING_IT_DISABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_DISABLE_RISING_EDGE() : \
+ ((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_DISABLE_RISING_EDGE() : \
+ ((__EXTILINE__) == COMP_EXTI_LINE_COMP3) ? __HAL_COMP_COMP3_EXTI_DISABLE_RISING_EDGE() : \
+ ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_DISABLE_RISING_EDGE() : \
+ ((__EXTILINE__) == COMP_EXTI_LINE_COMP5) ? __HAL_COMP_COMP5_EXTI_DISABLE_RISING_EDGE() : \
+ ((__EXTILINE__) == COMP_EXTI_LINE_COMP6) ? __HAL_COMP_COMP6_EXTI_DISABLE_RISING_EDGE() : \
+ __HAL_COMP_COMP7_EXTI_DISABLE_RISING_EDGE())
+#define __HAL_COMP_EXTI_FALLING_IT_ENABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_FALLING_EDGE() : \
+ ((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_ENABLE_FALLING_EDGE() : \
+ ((__EXTILINE__) == COMP_EXTI_LINE_COMP3) ? __HAL_COMP_COMP3_EXTI_ENABLE_FALLING_EDGE() : \
+ ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_ENABLE_FALLING_EDGE() : \
+ ((__EXTILINE__) == COMP_EXTI_LINE_COMP5) ? __HAL_COMP_COMP5_EXTI_ENABLE_FALLING_EDGE() : \
+ ((__EXTILINE__) == COMP_EXTI_LINE_COMP6) ? __HAL_COMP_COMP6_EXTI_ENABLE_FALLING_EDGE() : \
+ __HAL_COMP_COMP7_EXTI_ENABLE_FALLING_EDGE())
+#define __HAL_COMP_EXTI_FALLING_IT_DISABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_DISABLE_FALLING_EDGE() : \
+ ((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_DISABLE_FALLING_EDGE() : \
+ ((__EXTILINE__) == COMP_EXTI_LINE_COMP3) ? __HAL_COMP_COMP3_EXTI_DISABLE_FALLING_EDGE() : \
+ ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_DISABLE_FALLING_EDGE() : \
+ ((__EXTILINE__) == COMP_EXTI_LINE_COMP5) ? __HAL_COMP_COMP5_EXTI_DISABLE_FALLING_EDGE() : \
+ ((__EXTILINE__) == COMP_EXTI_LINE_COMP6) ? __HAL_COMP_COMP6_EXTI_DISABLE_FALLING_EDGE() : \
+ __HAL_COMP_COMP7_EXTI_DISABLE_FALLING_EDGE())
+#define __HAL_COMP_EXTI_ENABLE_IT(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_IT() : \
+ ((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_ENABLE_IT() : \
+ ((__EXTILINE__) == COMP_EXTI_LINE_COMP3) ? __HAL_COMP_COMP3_EXTI_ENABLE_IT() : \
+ ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_ENABLE_IT() : \
+ ((__EXTILINE__) == COMP_EXTI_LINE_COMP5) ? __HAL_COMP_COMP5_EXTI_ENABLE_IT() : \
+ ((__EXTILINE__) == COMP_EXTI_LINE_COMP6) ? __HAL_COMP_COMP6_EXTI_ENABLE_IT() : \
+ __HAL_COMP_COMP7_EXTI_ENABLE_IT())
+#define __HAL_COMP_EXTI_DISABLE_IT(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_DISABLE_IT() : \
+ ((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_DISABLE_IT() : \
+ ((__EXTILINE__) == COMP_EXTI_LINE_COMP3) ? __HAL_COMP_COMP3_EXTI_DISABLE_IT() : \
+ ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_DISABLE_IT() : \
+ ((__EXTILINE__) == COMP_EXTI_LINE_COMP5) ? __HAL_COMP_COMP5_EXTI_DISABLE_IT() : \
+ ((__EXTILINE__) == COMP_EXTI_LINE_COMP6) ? __HAL_COMP_COMP6_EXTI_DISABLE_IT() : \
+ __HAL_COMP_COMP7_EXTI_DISABLE_IT())
+#define __HAL_COMP_EXTI_GET_FLAG(__FLAG__) (((__FLAG__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_GET_FLAG() : \
+ ((__FLAG__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_GET_FLAG() : \
+ ((__FLAG__) == COMP_EXTI_LINE_COMP3) ? __HAL_COMP_COMP3_EXTI_GET_FLAG() : \
+ ((__FLAG__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_GET_FLAG() : \
+ ((__FLAG__) == COMP_EXTI_LINE_COMP5) ? __HAL_COMP_COMP5_EXTI_GET_FLAG() : \
+ ((__FLAG__) == COMP_EXTI_LINE_COMP6) ? __HAL_COMP_COMP6_EXTI_GET_FLAG() : \
+ __HAL_COMP_COMP7_EXTI_GET_FLAG())
+#define __HAL_COMP_EXTI_CLEAR_FLAG(__FLAG__) (((__FLAG__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_CLEAR_FLAG() : \
+ ((__FLAG__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_CLEAR_FLAG() : \
+ ((__FLAG__) == COMP_EXTI_LINE_COMP3) ? __HAL_COMP_COMP3_EXTI_CLEAR_FLAG() : \
+ ((__FLAG__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_CLEAR_FLAG() : \
+ ((__FLAG__) == COMP_EXTI_LINE_COMP5) ? __HAL_COMP_COMP5_EXTI_CLEAR_FLAG() : \
+ ((__FLAG__) == COMP_EXTI_LINE_COMP6) ? __HAL_COMP_COMP6_EXTI_CLEAR_FLAG() : \
+ __HAL_COMP_COMP7_EXTI_CLEAR_FLAG())
+# endif
+# if defined(STM32F373xC) ||defined(STM32F378xx)
+#define __HAL_COMP_EXTI_RISING_IT_ENABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_RISING_EDGE() : \
+ __HAL_COMP_COMP2_EXTI_ENABLE_RISING_EDGE())
+#define __HAL_COMP_EXTI_RISING_IT_DISABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_DISABLE_RISING_EDGE() : \
+ __HAL_COMP_COMP2_EXTI_DISABLE_RISING_EDGE())
+#define __HAL_COMP_EXTI_FALLING_IT_ENABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_FALLING_EDGE() : \
+ __HAL_COMP_COMP2_EXTI_ENABLE_FALLING_EDGE())
+#define __HAL_COMP_EXTI_FALLING_IT_DISABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_DISABLE_FALLING_EDGE() : \
+ __HAL_COMP_COMP2_EXTI_DISABLE_FALLING_EDGE())
+#define __HAL_COMP_EXTI_ENABLE_IT(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_IT() : \
+ __HAL_COMP_COMP2_EXTI_ENABLE_IT())
+#define __HAL_COMP_EXTI_DISABLE_IT(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_DISABLE_IT() : \
+ __HAL_COMP_COMP2_EXTI_DISABLE_IT())
+#define __HAL_COMP_EXTI_GET_FLAG(__FLAG__) (((__FLAG__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_GET_FLAG() : \
+ __HAL_COMP_COMP2_EXTI_GET_FLAG())
+#define __HAL_COMP_EXTI_CLEAR_FLAG(__FLAG__) (((__FLAG__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_CLEAR_FLAG() : \
+ __HAL_COMP_COMP2_EXTI_CLEAR_FLAG())
+# endif
+#else
+#define __HAL_COMP_EXTI_RISING_IT_ENABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_RISING_EDGE() : \
+ __HAL_COMP_COMP2_EXTI_ENABLE_RISING_EDGE())
+#define __HAL_COMP_EXTI_RISING_IT_DISABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_DISABLE_RISING_EDGE() : \
+ __HAL_COMP_COMP2_EXTI_DISABLE_RISING_EDGE())
+#define __HAL_COMP_EXTI_FALLING_IT_ENABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_FALLING_EDGE() : \
+ __HAL_COMP_COMP2_EXTI_ENABLE_FALLING_EDGE())
+#define __HAL_COMP_EXTI_FALLING_IT_DISABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_DISABLE_FALLING_EDGE() : \
+ __HAL_COMP_COMP2_EXTI_DISABLE_FALLING_EDGE())
+#define __HAL_COMP_EXTI_ENABLE_IT(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_IT() : \
+ __HAL_COMP_COMP2_EXTI_ENABLE_IT())
+#define __HAL_COMP_EXTI_DISABLE_IT(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_DISABLE_IT() : \
+ __HAL_COMP_COMP2_EXTI_DISABLE_IT())
+#define __HAL_COMP_EXTI_GET_FLAG(__FLAG__) (((__FLAG__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_GET_FLAG() : \
+ __HAL_COMP_COMP2_EXTI_GET_FLAG())
+#define __HAL_COMP_EXTI_CLEAR_FLAG(__FLAG__) (((__FLAG__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_CLEAR_FLAG() : \
+ __HAL_COMP_COMP2_EXTI_CLEAR_FLAG())
+#endif
+
+#define __HAL_COMP_GET_EXTI_LINE COMP_GET_EXTI_LINE
+
+#if defined(STM32L0) || defined(STM32L4)
+/* Note: On these STM32 families, the only argument of this macro */
+/* is COMP_FLAG_LOCK. */
+/* This macro is replaced by __HAL_COMP_IS_LOCKED with only HAL handle */
+/* argument. */
+#define __HAL_COMP_GET_FLAG(__HANDLE__, __FLAG__) (__HAL_COMP_IS_LOCKED(__HANDLE__))
+#endif
+/**
+ * @}
+ */
+
+#if defined(STM32L0) || defined(STM32L4)
+/** @defgroup HAL_COMP_Aliased_Functions HAL COMP Aliased Functions maintained for legacy purpose
+ * @{
+ */
+#define HAL_COMP_Start_IT HAL_COMP_Start /* Function considered as legacy as EXTI event or IT configuration is done into HAL_COMP_Init() */
+#define HAL_COMP_Stop_IT HAL_COMP_Stop /* Function considered as legacy as EXTI event or IT configuration is done into HAL_COMP_Init() */
+/**
+ * @}
+ */
+#endif
+
+/** @defgroup HAL_DAC_Aliased_Macros HAL DAC Aliased Macros maintained for legacy purpose
+ * @{
+ */
+
+#define IS_DAC_WAVE(WAVE) (((WAVE) == DAC_WAVE_NONE) || \
+ ((WAVE) == DAC_WAVE_NOISE)|| \
+ ((WAVE) == DAC_WAVE_TRIANGLE))
+
+/**
+ * @}
+ */
+
+/** @defgroup HAL_FLASH_Aliased_Macros HAL FLASH Aliased Macros maintained for legacy purpose
+ * @{
+ */
+
+#define IS_WRPAREA IS_OB_WRPAREA
+#define IS_TYPEPROGRAM IS_FLASH_TYPEPROGRAM
+#define IS_TYPEPROGRAMFLASH IS_FLASH_TYPEPROGRAM
+#define IS_TYPEERASE IS_FLASH_TYPEERASE
+#define IS_NBSECTORS IS_FLASH_NBSECTORS
+#define IS_OB_WDG_SOURCE IS_OB_IWDG_SOURCE
+
+/**
+ * @}
+ */
+
+/** @defgroup HAL_I2C_Aliased_Macros HAL I2C Aliased Macros maintained for legacy purpose
+ * @{
+ */
+
+#define __HAL_I2C_RESET_CR2 I2C_RESET_CR2
+#define __HAL_I2C_GENERATE_START I2C_GENERATE_START
+#if defined(STM32F1)
+#define __HAL_I2C_FREQ_RANGE I2C_FREQRANGE
+#else
+#define __HAL_I2C_FREQ_RANGE I2C_FREQ_RANGE
+#endif /* STM32F1 */
+#define __HAL_I2C_RISE_TIME I2C_RISE_TIME
+#define __HAL_I2C_SPEED_STANDARD I2C_SPEED_STANDARD
+#define __HAL_I2C_SPEED_FAST I2C_SPEED_FAST
+#define __HAL_I2C_SPEED I2C_SPEED
+#define __HAL_I2C_7BIT_ADD_WRITE I2C_7BIT_ADD_WRITE
+#define __HAL_I2C_7BIT_ADD_READ I2C_7BIT_ADD_READ
+#define __HAL_I2C_10BIT_ADDRESS I2C_10BIT_ADDRESS
+#define __HAL_I2C_10BIT_HEADER_WRITE I2C_10BIT_HEADER_WRITE
+#define __HAL_I2C_10BIT_HEADER_READ I2C_10BIT_HEADER_READ
+#define __HAL_I2C_MEM_ADD_MSB I2C_MEM_ADD_MSB
+#define __HAL_I2C_MEM_ADD_LSB I2C_MEM_ADD_LSB
+#define __HAL_I2C_FREQRANGE I2C_FREQRANGE
+/**
+ * @}
+ */
+
+/** @defgroup HAL_I2S_Aliased_Macros HAL I2S Aliased Macros maintained for legacy purpose
+ * @{
+ */
+
+#define IS_I2S_INSTANCE IS_I2S_ALL_INSTANCE
+#define IS_I2S_INSTANCE_EXT IS_I2S_ALL_INSTANCE_EXT
+
+#if defined(STM32H7)
+#define __HAL_I2S_CLEAR_FREFLAG __HAL_I2S_CLEAR_TIFREFLAG
+#endif
+
+/**
+ * @}
+ */
+
+/** @defgroup HAL_IRDA_Aliased_Macros HAL IRDA Aliased Macros maintained for legacy purpose
+ * @{
+ */
+
+#define __IRDA_DISABLE __HAL_IRDA_DISABLE
+#define __IRDA_ENABLE __HAL_IRDA_ENABLE
+
+#define __HAL_IRDA_GETCLOCKSOURCE IRDA_GETCLOCKSOURCE
+#define __HAL_IRDA_MASK_COMPUTATION IRDA_MASK_COMPUTATION
+#define __IRDA_GETCLOCKSOURCE IRDA_GETCLOCKSOURCE
+#define __IRDA_MASK_COMPUTATION IRDA_MASK_COMPUTATION
+
+#define IS_IRDA_ONEBIT_SAMPLE IS_IRDA_ONE_BIT_SAMPLE
+
+
+/**
+ * @}
+ */
+
+
+/** @defgroup HAL_IWDG_Aliased_Macros HAL IWDG Aliased Macros maintained for legacy purpose
+ * @{
+ */
+#define __HAL_IWDG_ENABLE_WRITE_ACCESS IWDG_ENABLE_WRITE_ACCESS
+#define __HAL_IWDG_DISABLE_WRITE_ACCESS IWDG_DISABLE_WRITE_ACCESS
+/**
+ * @}
+ */
+
+
+/** @defgroup HAL_LPTIM_Aliased_Macros HAL LPTIM Aliased Macros maintained for legacy purpose
+ * @{
+ */
+
+#define __HAL_LPTIM_ENABLE_INTERRUPT __HAL_LPTIM_ENABLE_IT
+#define __HAL_LPTIM_DISABLE_INTERRUPT __HAL_LPTIM_DISABLE_IT
+#define __HAL_LPTIM_GET_ITSTATUS __HAL_LPTIM_GET_IT_SOURCE
+
+/**
+ * @}
+ */
+
+
+/** @defgroup HAL_OPAMP_Aliased_Macros HAL OPAMP Aliased Macros maintained for legacy purpose
+ * @{
+ */
+#define __OPAMP_CSR_OPAXPD OPAMP_CSR_OPAXPD
+#define __OPAMP_CSR_S3SELX OPAMP_CSR_S3SELX
+#define __OPAMP_CSR_S4SELX OPAMP_CSR_S4SELX
+#define __OPAMP_CSR_S5SELX OPAMP_CSR_S5SELX
+#define __OPAMP_CSR_S6SELX OPAMP_CSR_S6SELX
+#define __OPAMP_CSR_OPAXCAL_L OPAMP_CSR_OPAXCAL_L
+#define __OPAMP_CSR_OPAXCAL_H OPAMP_CSR_OPAXCAL_H
+#define __OPAMP_CSR_OPAXLPM OPAMP_CSR_OPAXLPM
+#define __OPAMP_CSR_ALL_SWITCHES OPAMP_CSR_ALL_SWITCHES
+#define __OPAMP_CSR_ANAWSELX OPAMP_CSR_ANAWSELX
+#define __OPAMP_CSR_OPAXCALOUT OPAMP_CSR_OPAXCALOUT
+#define __OPAMP_OFFSET_TRIM_BITSPOSITION OPAMP_OFFSET_TRIM_BITSPOSITION
+#define __OPAMP_OFFSET_TRIM_SET OPAMP_OFFSET_TRIM_SET
+
+/**
+ * @}
+ */
+
+
+/** @defgroup HAL_PWR_Aliased_Macros HAL PWR Aliased Macros maintained for legacy purpose
+ * @{
+ */
+#define __HAL_PVD_EVENT_DISABLE __HAL_PWR_PVD_EXTI_DISABLE_EVENT
+#define __HAL_PVD_EVENT_ENABLE __HAL_PWR_PVD_EXTI_ENABLE_EVENT
+#define __HAL_PVD_EXTI_FALLINGTRIGGER_DISABLE __HAL_PWR_PVD_EXTI_DISABLE_FALLING_EDGE
+#define __HAL_PVD_EXTI_FALLINGTRIGGER_ENABLE __HAL_PWR_PVD_EXTI_ENABLE_FALLING_EDGE
+#define __HAL_PVD_EXTI_RISINGTRIGGER_DISABLE __HAL_PWR_PVD_EXTI_DISABLE_RISING_EDGE
+#define __HAL_PVD_EXTI_RISINGTRIGGER_ENABLE __HAL_PWR_PVD_EXTI_ENABLE_RISING_EDGE
+#define __HAL_PVM_EVENT_DISABLE __HAL_PWR_PVM_EVENT_DISABLE
+#define __HAL_PVM_EVENT_ENABLE __HAL_PWR_PVM_EVENT_ENABLE
+#define __HAL_PVM_EXTI_FALLINGTRIGGER_DISABLE __HAL_PWR_PVM_EXTI_FALLINGTRIGGER_DISABLE
+#define __HAL_PVM_EXTI_FALLINGTRIGGER_ENABLE __HAL_PWR_PVM_EXTI_FALLINGTRIGGER_ENABLE
+#define __HAL_PVM_EXTI_RISINGTRIGGER_DISABLE __HAL_PWR_PVM_EXTI_RISINGTRIGGER_DISABLE
+#define __HAL_PVM_EXTI_RISINGTRIGGER_ENABLE __HAL_PWR_PVM_EXTI_RISINGTRIGGER_ENABLE
+#define __HAL_PWR_INTERNALWAKEUP_DISABLE HAL_PWREx_DisableInternalWakeUpLine
+#define __HAL_PWR_INTERNALWAKEUP_ENABLE HAL_PWREx_EnableInternalWakeUpLine
+#define __HAL_PWR_PULL_UP_DOWN_CONFIG_DISABLE HAL_PWREx_DisablePullUpPullDownConfig
+#define __HAL_PWR_PULL_UP_DOWN_CONFIG_ENABLE HAL_PWREx_EnablePullUpPullDownConfig
+#define __HAL_PWR_PVD_EXTI_CLEAR_EGDE_TRIGGER() do { __HAL_PWR_PVD_EXTI_DISABLE_RISING_EDGE();__HAL_PWR_PVD_EXTI_DISABLE_FALLING_EDGE(); } while(0)
+#define __HAL_PWR_PVD_EXTI_EVENT_DISABLE __HAL_PWR_PVD_EXTI_DISABLE_EVENT
+#define __HAL_PWR_PVD_EXTI_EVENT_ENABLE __HAL_PWR_PVD_EXTI_ENABLE_EVENT
+#define __HAL_PWR_PVD_EXTI_FALLINGTRIGGER_DISABLE __HAL_PWR_PVD_EXTI_DISABLE_FALLING_EDGE
+#define __HAL_PWR_PVD_EXTI_FALLINGTRIGGER_ENABLE __HAL_PWR_PVD_EXTI_ENABLE_FALLING_EDGE
+#define __HAL_PWR_PVD_EXTI_RISINGTRIGGER_DISABLE __HAL_PWR_PVD_EXTI_DISABLE_RISING_EDGE
+#define __HAL_PWR_PVD_EXTI_RISINGTRIGGER_ENABLE __HAL_PWR_PVD_EXTI_ENABLE_RISING_EDGE
+#define __HAL_PWR_PVD_EXTI_SET_FALLING_EGDE_TRIGGER __HAL_PWR_PVD_EXTI_ENABLE_FALLING_EDGE
+#define __HAL_PWR_PVD_EXTI_SET_RISING_EDGE_TRIGGER __HAL_PWR_PVD_EXTI_ENABLE_RISING_EDGE
+#define __HAL_PWR_PVM_DISABLE() do { HAL_PWREx_DisablePVM1();HAL_PWREx_DisablePVM2();HAL_PWREx_DisablePVM3();HAL_PWREx_DisablePVM4(); } while(0)
+#define __HAL_PWR_PVM_ENABLE() do { HAL_PWREx_EnablePVM1();HAL_PWREx_EnablePVM2();HAL_PWREx_EnablePVM3();HAL_PWREx_EnablePVM4(); } while(0)
+#define __HAL_PWR_SRAM2CONTENT_PRESERVE_DISABLE HAL_PWREx_DisableSRAM2ContentRetention
+#define __HAL_PWR_SRAM2CONTENT_PRESERVE_ENABLE HAL_PWREx_EnableSRAM2ContentRetention
+#define __HAL_PWR_VDDIO2_DISABLE HAL_PWREx_DisableVddIO2
+#define __HAL_PWR_VDDIO2_ENABLE HAL_PWREx_EnableVddIO2
+#define __HAL_PWR_VDDIO2_EXTI_CLEAR_EGDE_TRIGGER __HAL_PWR_VDDIO2_EXTI_DISABLE_FALLING_EDGE
+#define __HAL_PWR_VDDIO2_EXTI_SET_FALLING_EGDE_TRIGGER __HAL_PWR_VDDIO2_EXTI_ENABLE_FALLING_EDGE
+#define __HAL_PWR_VDDUSB_DISABLE HAL_PWREx_DisableVddUSB
+#define __HAL_PWR_VDDUSB_ENABLE HAL_PWREx_EnableVddUSB
+
+#if defined (STM32F4)
+#define __HAL_PVD_EXTI_ENABLE_IT(PWR_EXTI_LINE_PVD) __HAL_PWR_PVD_EXTI_ENABLE_IT()
+#define __HAL_PVD_EXTI_DISABLE_IT(PWR_EXTI_LINE_PVD) __HAL_PWR_PVD_EXTI_DISABLE_IT()
+#define __HAL_PVD_EXTI_GET_FLAG(PWR_EXTI_LINE_PVD) __HAL_PWR_PVD_EXTI_GET_FLAG()
+#define __HAL_PVD_EXTI_CLEAR_FLAG(PWR_EXTI_LINE_PVD) __HAL_PWR_PVD_EXTI_CLEAR_FLAG()
+#define __HAL_PVD_EXTI_GENERATE_SWIT(PWR_EXTI_LINE_PVD) __HAL_PWR_PVD_EXTI_GENERATE_SWIT()
+#else
+#define __HAL_PVD_EXTI_CLEAR_FLAG __HAL_PWR_PVD_EXTI_CLEAR_FLAG
+#define __HAL_PVD_EXTI_DISABLE_IT __HAL_PWR_PVD_EXTI_DISABLE_IT
+#define __HAL_PVD_EXTI_ENABLE_IT __HAL_PWR_PVD_EXTI_ENABLE_IT
+#define __HAL_PVD_EXTI_GENERATE_SWIT __HAL_PWR_PVD_EXTI_GENERATE_SWIT
+#define __HAL_PVD_EXTI_GET_FLAG __HAL_PWR_PVD_EXTI_GET_FLAG
+#endif /* STM32F4 */
+/**
+ * @}
+ */
+
+
+/** @defgroup HAL_RCC_Aliased HAL RCC Aliased maintained for legacy purpose
+ * @{
+ */
+
+#define RCC_StopWakeUpClock_MSI RCC_STOP_WAKEUPCLOCK_MSI
+#define RCC_StopWakeUpClock_HSI RCC_STOP_WAKEUPCLOCK_HSI
+
+#define HAL_RCC_CCSCallback HAL_RCC_CSSCallback
+#define HAL_RC48_EnableBuffer_Cmd(cmd) (((cmd\
+ )==ENABLE) ? HAL_RCCEx_EnableHSI48_VREFINT() : HAL_RCCEx_DisableHSI48_VREFINT())
+
+#define __ADC_CLK_DISABLE __HAL_RCC_ADC_CLK_DISABLE
+#define __ADC_CLK_ENABLE __HAL_RCC_ADC_CLK_ENABLE
+#define __ADC_CLK_SLEEP_DISABLE __HAL_RCC_ADC_CLK_SLEEP_DISABLE
+#define __ADC_CLK_SLEEP_ENABLE __HAL_RCC_ADC_CLK_SLEEP_ENABLE
+#define __ADC_FORCE_RESET __HAL_RCC_ADC_FORCE_RESET
+#define __ADC_RELEASE_RESET __HAL_RCC_ADC_RELEASE_RESET
+#define __ADC1_CLK_DISABLE __HAL_RCC_ADC1_CLK_DISABLE
+#define __ADC1_CLK_ENABLE __HAL_RCC_ADC1_CLK_ENABLE
+#define __ADC1_FORCE_RESET __HAL_RCC_ADC1_FORCE_RESET
+#define __ADC1_RELEASE_RESET __HAL_RCC_ADC1_RELEASE_RESET
+#define __ADC1_CLK_SLEEP_ENABLE __HAL_RCC_ADC1_CLK_SLEEP_ENABLE
+#define __ADC1_CLK_SLEEP_DISABLE __HAL_RCC_ADC1_CLK_SLEEP_DISABLE
+#define __ADC2_CLK_DISABLE __HAL_RCC_ADC2_CLK_DISABLE
+#define __ADC2_CLK_ENABLE __HAL_RCC_ADC2_CLK_ENABLE
+#define __ADC2_FORCE_RESET __HAL_RCC_ADC2_FORCE_RESET
+#define __ADC2_RELEASE_RESET __HAL_RCC_ADC2_RELEASE_RESET
+#define __ADC3_CLK_DISABLE __HAL_RCC_ADC3_CLK_DISABLE
+#define __ADC3_CLK_ENABLE __HAL_RCC_ADC3_CLK_ENABLE
+#define __ADC3_FORCE_RESET __HAL_RCC_ADC3_FORCE_RESET
+#define __ADC3_RELEASE_RESET __HAL_RCC_ADC3_RELEASE_RESET
+#define __AES_CLK_DISABLE __HAL_RCC_AES_CLK_DISABLE
+#define __AES_CLK_ENABLE __HAL_RCC_AES_CLK_ENABLE
+#define __AES_CLK_SLEEP_DISABLE __HAL_RCC_AES_CLK_SLEEP_DISABLE
+#define __AES_CLK_SLEEP_ENABLE __HAL_RCC_AES_CLK_SLEEP_ENABLE
+#define __AES_FORCE_RESET __HAL_RCC_AES_FORCE_RESET
+#define __AES_RELEASE_RESET __HAL_RCC_AES_RELEASE_RESET
+#define __CRYP_CLK_SLEEP_ENABLE __HAL_RCC_CRYP_CLK_SLEEP_ENABLE
+#define __CRYP_CLK_SLEEP_DISABLE __HAL_RCC_CRYP_CLK_SLEEP_DISABLE
+#define __CRYP_CLK_ENABLE __HAL_RCC_CRYP_CLK_ENABLE
+#define __CRYP_CLK_DISABLE __HAL_RCC_CRYP_CLK_DISABLE
+#define __CRYP_FORCE_RESET __HAL_RCC_CRYP_FORCE_RESET
+#define __CRYP_RELEASE_RESET __HAL_RCC_CRYP_RELEASE_RESET
+#define __AFIO_CLK_DISABLE __HAL_RCC_AFIO_CLK_DISABLE
+#define __AFIO_CLK_ENABLE __HAL_RCC_AFIO_CLK_ENABLE
+#define __AFIO_FORCE_RESET __HAL_RCC_AFIO_FORCE_RESET
+#define __AFIO_RELEASE_RESET __HAL_RCC_AFIO_RELEASE_RESET
+#define __AHB_FORCE_RESET __HAL_RCC_AHB_FORCE_RESET
+#define __AHB_RELEASE_RESET __HAL_RCC_AHB_RELEASE_RESET
+#define __AHB1_FORCE_RESET __HAL_RCC_AHB1_FORCE_RESET
+#define __AHB1_RELEASE_RESET __HAL_RCC_AHB1_RELEASE_RESET
+#define __AHB2_FORCE_RESET __HAL_RCC_AHB2_FORCE_RESET
+#define __AHB2_RELEASE_RESET __HAL_RCC_AHB2_RELEASE_RESET
+#define __AHB3_FORCE_RESET __HAL_RCC_AHB3_FORCE_RESET
+#define __AHB3_RELEASE_RESET __HAL_RCC_AHB3_RELEASE_RESET
+#define __APB1_FORCE_RESET __HAL_RCC_APB1_FORCE_RESET
+#define __APB1_RELEASE_RESET __HAL_RCC_APB1_RELEASE_RESET
+#define __APB2_FORCE_RESET __HAL_RCC_APB2_FORCE_RESET
+#define __APB2_RELEASE_RESET __HAL_RCC_APB2_RELEASE_RESET
+#define __BKP_CLK_DISABLE __HAL_RCC_BKP_CLK_DISABLE
+#define __BKP_CLK_ENABLE __HAL_RCC_BKP_CLK_ENABLE
+#define __BKP_FORCE_RESET __HAL_RCC_BKP_FORCE_RESET
+#define __BKP_RELEASE_RESET __HAL_RCC_BKP_RELEASE_RESET
+#define __CAN1_CLK_DISABLE __HAL_RCC_CAN1_CLK_DISABLE
+#define __CAN1_CLK_ENABLE __HAL_RCC_CAN1_CLK_ENABLE
+#define __CAN1_CLK_SLEEP_DISABLE __HAL_RCC_CAN1_CLK_SLEEP_DISABLE
+#define __CAN1_CLK_SLEEP_ENABLE __HAL_RCC_CAN1_CLK_SLEEP_ENABLE
+#define __CAN1_FORCE_RESET __HAL_RCC_CAN1_FORCE_RESET
+#define __CAN1_RELEASE_RESET __HAL_RCC_CAN1_RELEASE_RESET
+#define __CAN_CLK_DISABLE __HAL_RCC_CAN1_CLK_DISABLE
+#define __CAN_CLK_ENABLE __HAL_RCC_CAN1_CLK_ENABLE
+#define __CAN_FORCE_RESET __HAL_RCC_CAN1_FORCE_RESET
+#define __CAN_RELEASE_RESET __HAL_RCC_CAN1_RELEASE_RESET
+#define __CAN2_CLK_DISABLE __HAL_RCC_CAN2_CLK_DISABLE
+#define __CAN2_CLK_ENABLE __HAL_RCC_CAN2_CLK_ENABLE
+#define __CAN2_FORCE_RESET __HAL_RCC_CAN2_FORCE_RESET
+#define __CAN2_RELEASE_RESET __HAL_RCC_CAN2_RELEASE_RESET
+#define __CEC_CLK_DISABLE __HAL_RCC_CEC_CLK_DISABLE
+#define __CEC_CLK_ENABLE __HAL_RCC_CEC_CLK_ENABLE
+#define __COMP_CLK_DISABLE __HAL_RCC_COMP_CLK_DISABLE
+#define __COMP_CLK_ENABLE __HAL_RCC_COMP_CLK_ENABLE
+#define __COMP_FORCE_RESET __HAL_RCC_COMP_FORCE_RESET
+#define __COMP_RELEASE_RESET __HAL_RCC_COMP_RELEASE_RESET
+#define __COMP_CLK_SLEEP_ENABLE __HAL_RCC_COMP_CLK_SLEEP_ENABLE
+#define __COMP_CLK_SLEEP_DISABLE __HAL_RCC_COMP_CLK_SLEEP_DISABLE
+#define __CEC_FORCE_RESET __HAL_RCC_CEC_FORCE_RESET
+#define __CEC_RELEASE_RESET __HAL_RCC_CEC_RELEASE_RESET
+#define __CRC_CLK_DISABLE __HAL_RCC_CRC_CLK_DISABLE
+#define __CRC_CLK_ENABLE __HAL_RCC_CRC_CLK_ENABLE
+#define __CRC_CLK_SLEEP_DISABLE __HAL_RCC_CRC_CLK_SLEEP_DISABLE
+#define __CRC_CLK_SLEEP_ENABLE __HAL_RCC_CRC_CLK_SLEEP_ENABLE
+#define __CRC_FORCE_RESET __HAL_RCC_CRC_FORCE_RESET
+#define __CRC_RELEASE_RESET __HAL_RCC_CRC_RELEASE_RESET
+#define __DAC_CLK_DISABLE __HAL_RCC_DAC_CLK_DISABLE
+#define __DAC_CLK_ENABLE __HAL_RCC_DAC_CLK_ENABLE
+#define __DAC_FORCE_RESET __HAL_RCC_DAC_FORCE_RESET
+#define __DAC_RELEASE_RESET __HAL_RCC_DAC_RELEASE_RESET
+#define __DAC1_CLK_DISABLE __HAL_RCC_DAC1_CLK_DISABLE
+#define __DAC1_CLK_ENABLE __HAL_RCC_DAC1_CLK_ENABLE
+#define __DAC1_CLK_SLEEP_DISABLE __HAL_RCC_DAC1_CLK_SLEEP_DISABLE
+#define __DAC1_CLK_SLEEP_ENABLE __HAL_RCC_DAC1_CLK_SLEEP_ENABLE
+#define __DAC1_FORCE_RESET __HAL_RCC_DAC1_FORCE_RESET
+#define __DAC1_RELEASE_RESET __HAL_RCC_DAC1_RELEASE_RESET
+#define __DBGMCU_CLK_ENABLE __HAL_RCC_DBGMCU_CLK_ENABLE
+#define __DBGMCU_CLK_DISABLE __HAL_RCC_DBGMCU_CLK_DISABLE
+#define __DBGMCU_FORCE_RESET __HAL_RCC_DBGMCU_FORCE_RESET
+#define __DBGMCU_RELEASE_RESET __HAL_RCC_DBGMCU_RELEASE_RESET
+#define __DFSDM_CLK_DISABLE __HAL_RCC_DFSDM_CLK_DISABLE
+#define __DFSDM_CLK_ENABLE __HAL_RCC_DFSDM_CLK_ENABLE
+#define __DFSDM_CLK_SLEEP_DISABLE __HAL_RCC_DFSDM_CLK_SLEEP_DISABLE
+#define __DFSDM_CLK_SLEEP_ENABLE __HAL_RCC_DFSDM_CLK_SLEEP_ENABLE
+#define __DFSDM_FORCE_RESET __HAL_RCC_DFSDM_FORCE_RESET
+#define __DFSDM_RELEASE_RESET __HAL_RCC_DFSDM_RELEASE_RESET
+#define __DMA1_CLK_DISABLE __HAL_RCC_DMA1_CLK_DISABLE
+#define __DMA1_CLK_ENABLE __HAL_RCC_DMA1_CLK_ENABLE
+#define __DMA1_CLK_SLEEP_DISABLE __HAL_RCC_DMA1_CLK_SLEEP_DISABLE
+#define __DMA1_CLK_SLEEP_ENABLE __HAL_RCC_DMA1_CLK_SLEEP_ENABLE
+#define __DMA1_FORCE_RESET __HAL_RCC_DMA1_FORCE_RESET
+#define __DMA1_RELEASE_RESET __HAL_RCC_DMA1_RELEASE_RESET
+#define __DMA2_CLK_DISABLE __HAL_RCC_DMA2_CLK_DISABLE
+#define __DMA2_CLK_ENABLE __HAL_RCC_DMA2_CLK_ENABLE
+#define __DMA2_CLK_SLEEP_DISABLE __HAL_RCC_DMA2_CLK_SLEEP_DISABLE
+#define __DMA2_CLK_SLEEP_ENABLE __HAL_RCC_DMA2_CLK_SLEEP_ENABLE
+#define __DMA2_FORCE_RESET __HAL_RCC_DMA2_FORCE_RESET
+#define __DMA2_RELEASE_RESET __HAL_RCC_DMA2_RELEASE_RESET
+#define __ETHMAC_CLK_DISABLE __HAL_RCC_ETHMAC_CLK_DISABLE
+#define __ETHMAC_CLK_ENABLE __HAL_RCC_ETHMAC_CLK_ENABLE
+#define __ETHMAC_FORCE_RESET __HAL_RCC_ETHMAC_FORCE_RESET
+#define __ETHMAC_RELEASE_RESET __HAL_RCC_ETHMAC_RELEASE_RESET
+#define __ETHMACRX_CLK_DISABLE __HAL_RCC_ETHMACRX_CLK_DISABLE
+#define __ETHMACRX_CLK_ENABLE __HAL_RCC_ETHMACRX_CLK_ENABLE
+#define __ETHMACTX_CLK_DISABLE __HAL_RCC_ETHMACTX_CLK_DISABLE
+#define __ETHMACTX_CLK_ENABLE __HAL_RCC_ETHMACTX_CLK_ENABLE
+#define __FIREWALL_CLK_DISABLE __HAL_RCC_FIREWALL_CLK_DISABLE
+#define __FIREWALL_CLK_ENABLE __HAL_RCC_FIREWALL_CLK_ENABLE
+#define __FLASH_CLK_DISABLE __HAL_RCC_FLASH_CLK_DISABLE
+#define __FLASH_CLK_ENABLE __HAL_RCC_FLASH_CLK_ENABLE
+#define __FLASH_CLK_SLEEP_DISABLE __HAL_RCC_FLASH_CLK_SLEEP_DISABLE
+#define __FLASH_CLK_SLEEP_ENABLE __HAL_RCC_FLASH_CLK_SLEEP_ENABLE
+#define __FLASH_FORCE_RESET __HAL_RCC_FLASH_FORCE_RESET
+#define __FLASH_RELEASE_RESET __HAL_RCC_FLASH_RELEASE_RESET
+#define __FLITF_CLK_DISABLE __HAL_RCC_FLITF_CLK_DISABLE
+#define __FLITF_CLK_ENABLE __HAL_RCC_FLITF_CLK_ENABLE
+#define __FLITF_FORCE_RESET __HAL_RCC_FLITF_FORCE_RESET
+#define __FLITF_RELEASE_RESET __HAL_RCC_FLITF_RELEASE_RESET
+#define __FLITF_CLK_SLEEP_ENABLE __HAL_RCC_FLITF_CLK_SLEEP_ENABLE
+#define __FLITF_CLK_SLEEP_DISABLE __HAL_RCC_FLITF_CLK_SLEEP_DISABLE
+#define __FMC_CLK_DISABLE __HAL_RCC_FMC_CLK_DISABLE
+#define __FMC_CLK_ENABLE __HAL_RCC_FMC_CLK_ENABLE
+#define __FMC_CLK_SLEEP_DISABLE __HAL_RCC_FMC_CLK_SLEEP_DISABLE
+#define __FMC_CLK_SLEEP_ENABLE __HAL_RCC_FMC_CLK_SLEEP_ENABLE
+#define __FMC_FORCE_RESET __HAL_RCC_FMC_FORCE_RESET
+#define __FMC_RELEASE_RESET __HAL_RCC_FMC_RELEASE_RESET
+#define __FSMC_CLK_DISABLE __HAL_RCC_FSMC_CLK_DISABLE
+#define __FSMC_CLK_ENABLE __HAL_RCC_FSMC_CLK_ENABLE
+#define __GPIOA_CLK_DISABLE __HAL_RCC_GPIOA_CLK_DISABLE
+#define __GPIOA_CLK_ENABLE __HAL_RCC_GPIOA_CLK_ENABLE
+#define __GPIOA_CLK_SLEEP_DISABLE __HAL_RCC_GPIOA_CLK_SLEEP_DISABLE
+#define __GPIOA_CLK_SLEEP_ENABLE __HAL_RCC_GPIOA_CLK_SLEEP_ENABLE
+#define __GPIOA_FORCE_RESET __HAL_RCC_GPIOA_FORCE_RESET
+#define __GPIOA_RELEASE_RESET __HAL_RCC_GPIOA_RELEASE_RESET
+#define __GPIOB_CLK_DISABLE __HAL_RCC_GPIOB_CLK_DISABLE
+#define __GPIOB_CLK_ENABLE __HAL_RCC_GPIOB_CLK_ENABLE
+#define __GPIOB_CLK_SLEEP_DISABLE __HAL_RCC_GPIOB_CLK_SLEEP_DISABLE
+#define __GPIOB_CLK_SLEEP_ENABLE __HAL_RCC_GPIOB_CLK_SLEEP_ENABLE
+#define __GPIOB_FORCE_RESET __HAL_RCC_GPIOB_FORCE_RESET
+#define __GPIOB_RELEASE_RESET __HAL_RCC_GPIOB_RELEASE_RESET
+#define __GPIOC_CLK_DISABLE __HAL_RCC_GPIOC_CLK_DISABLE
+#define __GPIOC_CLK_ENABLE __HAL_RCC_GPIOC_CLK_ENABLE
+#define __GPIOC_CLK_SLEEP_DISABLE __HAL_RCC_GPIOC_CLK_SLEEP_DISABLE
+#define __GPIOC_CLK_SLEEP_ENABLE __HAL_RCC_GPIOC_CLK_SLEEP_ENABLE
+#define __GPIOC_FORCE_RESET __HAL_RCC_GPIOC_FORCE_RESET
+#define __GPIOC_RELEASE_RESET __HAL_RCC_GPIOC_RELEASE_RESET
+#define __GPIOD_CLK_DISABLE __HAL_RCC_GPIOD_CLK_DISABLE
+#define __GPIOD_CLK_ENABLE __HAL_RCC_GPIOD_CLK_ENABLE
+#define __GPIOD_CLK_SLEEP_DISABLE __HAL_RCC_GPIOD_CLK_SLEEP_DISABLE
+#define __GPIOD_CLK_SLEEP_ENABLE __HAL_RCC_GPIOD_CLK_SLEEP_ENABLE
+#define __GPIOD_FORCE_RESET __HAL_RCC_GPIOD_FORCE_RESET
+#define __GPIOD_RELEASE_RESET __HAL_RCC_GPIOD_RELEASE_RESET
+#define __GPIOE_CLK_DISABLE __HAL_RCC_GPIOE_CLK_DISABLE
+#define __GPIOE_CLK_ENABLE __HAL_RCC_GPIOE_CLK_ENABLE
+#define __GPIOE_CLK_SLEEP_DISABLE __HAL_RCC_GPIOE_CLK_SLEEP_DISABLE
+#define __GPIOE_CLK_SLEEP_ENABLE __HAL_RCC_GPIOE_CLK_SLEEP_ENABLE
+#define __GPIOE_FORCE_RESET __HAL_RCC_GPIOE_FORCE_RESET
+#define __GPIOE_RELEASE_RESET __HAL_RCC_GPIOE_RELEASE_RESET
+#define __GPIOF_CLK_DISABLE __HAL_RCC_GPIOF_CLK_DISABLE
+#define __GPIOF_CLK_ENABLE __HAL_RCC_GPIOF_CLK_ENABLE
+#define __GPIOF_CLK_SLEEP_DISABLE __HAL_RCC_GPIOF_CLK_SLEEP_DISABLE
+#define __GPIOF_CLK_SLEEP_ENABLE __HAL_RCC_GPIOF_CLK_SLEEP_ENABLE
+#define __GPIOF_FORCE_RESET __HAL_RCC_GPIOF_FORCE_RESET
+#define __GPIOF_RELEASE_RESET __HAL_RCC_GPIOF_RELEASE_RESET
+#define __GPIOG_CLK_DISABLE __HAL_RCC_GPIOG_CLK_DISABLE
+#define __GPIOG_CLK_ENABLE __HAL_RCC_GPIOG_CLK_ENABLE
+#define __GPIOG_CLK_SLEEP_DISABLE __HAL_RCC_GPIOG_CLK_SLEEP_DISABLE
+#define __GPIOG_CLK_SLEEP_ENABLE __HAL_RCC_GPIOG_CLK_SLEEP_ENABLE
+#define __GPIOG_FORCE_RESET __HAL_RCC_GPIOG_FORCE_RESET
+#define __GPIOG_RELEASE_RESET __HAL_RCC_GPIOG_RELEASE_RESET
+#define __GPIOH_CLK_DISABLE __HAL_RCC_GPIOH_CLK_DISABLE
+#define __GPIOH_CLK_ENABLE __HAL_RCC_GPIOH_CLK_ENABLE
+#define __GPIOH_CLK_SLEEP_DISABLE __HAL_RCC_GPIOH_CLK_SLEEP_DISABLE
+#define __GPIOH_CLK_SLEEP_ENABLE __HAL_RCC_GPIOH_CLK_SLEEP_ENABLE
+#define __GPIOH_FORCE_RESET __HAL_RCC_GPIOH_FORCE_RESET
+#define __GPIOH_RELEASE_RESET __HAL_RCC_GPIOH_RELEASE_RESET
+#define __I2C1_CLK_DISABLE __HAL_RCC_I2C1_CLK_DISABLE
+#define __I2C1_CLK_ENABLE __HAL_RCC_I2C1_CLK_ENABLE
+#define __I2C1_CLK_SLEEP_DISABLE __HAL_RCC_I2C1_CLK_SLEEP_DISABLE
+#define __I2C1_CLK_SLEEP_ENABLE __HAL_RCC_I2C1_CLK_SLEEP_ENABLE
+#define __I2C1_FORCE_RESET __HAL_RCC_I2C1_FORCE_RESET
+#define __I2C1_RELEASE_RESET __HAL_RCC_I2C1_RELEASE_RESET
+#define __I2C2_CLK_DISABLE __HAL_RCC_I2C2_CLK_DISABLE
+#define __I2C2_CLK_ENABLE __HAL_RCC_I2C2_CLK_ENABLE
+#define __I2C2_CLK_SLEEP_DISABLE __HAL_RCC_I2C2_CLK_SLEEP_DISABLE
+#define __I2C2_CLK_SLEEP_ENABLE __HAL_RCC_I2C2_CLK_SLEEP_ENABLE
+#define __I2C2_FORCE_RESET __HAL_RCC_I2C2_FORCE_RESET
+#define __I2C2_RELEASE_RESET __HAL_RCC_I2C2_RELEASE_RESET
+#define __I2C3_CLK_DISABLE __HAL_RCC_I2C3_CLK_DISABLE
+#define __I2C3_CLK_ENABLE __HAL_RCC_I2C3_CLK_ENABLE
+#define __I2C3_CLK_SLEEP_DISABLE __HAL_RCC_I2C3_CLK_SLEEP_DISABLE
+#define __I2C3_CLK_SLEEP_ENABLE __HAL_RCC_I2C3_CLK_SLEEP_ENABLE
+#define __I2C3_FORCE_RESET __HAL_RCC_I2C3_FORCE_RESET
+#define __I2C3_RELEASE_RESET __HAL_RCC_I2C3_RELEASE_RESET
+#define __LCD_CLK_DISABLE __HAL_RCC_LCD_CLK_DISABLE
+#define __LCD_CLK_ENABLE __HAL_RCC_LCD_CLK_ENABLE
+#define __LCD_CLK_SLEEP_DISABLE __HAL_RCC_LCD_CLK_SLEEP_DISABLE
+#define __LCD_CLK_SLEEP_ENABLE __HAL_RCC_LCD_CLK_SLEEP_ENABLE
+#define __LCD_FORCE_RESET __HAL_RCC_LCD_FORCE_RESET
+#define __LCD_RELEASE_RESET __HAL_RCC_LCD_RELEASE_RESET
+#define __LPTIM1_CLK_DISABLE __HAL_RCC_LPTIM1_CLK_DISABLE
+#define __LPTIM1_CLK_ENABLE __HAL_RCC_LPTIM1_CLK_ENABLE
+#define __LPTIM1_CLK_SLEEP_DISABLE __HAL_RCC_LPTIM1_CLK_SLEEP_DISABLE
+#define __LPTIM1_CLK_SLEEP_ENABLE __HAL_RCC_LPTIM1_CLK_SLEEP_ENABLE
+#define __LPTIM1_FORCE_RESET __HAL_RCC_LPTIM1_FORCE_RESET
+#define __LPTIM1_RELEASE_RESET __HAL_RCC_LPTIM1_RELEASE_RESET
+#define __LPTIM2_CLK_DISABLE __HAL_RCC_LPTIM2_CLK_DISABLE
+#define __LPTIM2_CLK_ENABLE __HAL_RCC_LPTIM2_CLK_ENABLE
+#define __LPTIM2_CLK_SLEEP_DISABLE __HAL_RCC_LPTIM2_CLK_SLEEP_DISABLE
+#define __LPTIM2_CLK_SLEEP_ENABLE __HAL_RCC_LPTIM2_CLK_SLEEP_ENABLE
+#define __LPTIM2_FORCE_RESET __HAL_RCC_LPTIM2_FORCE_RESET
+#define __LPTIM2_RELEASE_RESET __HAL_RCC_LPTIM2_RELEASE_RESET
+#define __LPUART1_CLK_DISABLE __HAL_RCC_LPUART1_CLK_DISABLE
+#define __LPUART1_CLK_ENABLE __HAL_RCC_LPUART1_CLK_ENABLE
+#define __LPUART1_CLK_SLEEP_DISABLE __HAL_RCC_LPUART1_CLK_SLEEP_DISABLE
+#define __LPUART1_CLK_SLEEP_ENABLE __HAL_RCC_LPUART1_CLK_SLEEP_ENABLE
+#define __LPUART1_FORCE_RESET __HAL_RCC_LPUART1_FORCE_RESET
+#define __LPUART1_RELEASE_RESET __HAL_RCC_LPUART1_RELEASE_RESET
+#define __OPAMP_CLK_DISABLE __HAL_RCC_OPAMP_CLK_DISABLE
+#define __OPAMP_CLK_ENABLE __HAL_RCC_OPAMP_CLK_ENABLE
+#define __OPAMP_CLK_SLEEP_DISABLE __HAL_RCC_OPAMP_CLK_SLEEP_DISABLE
+#define __OPAMP_CLK_SLEEP_ENABLE __HAL_RCC_OPAMP_CLK_SLEEP_ENABLE
+#define __OPAMP_FORCE_RESET __HAL_RCC_OPAMP_FORCE_RESET
+#define __OPAMP_RELEASE_RESET __HAL_RCC_OPAMP_RELEASE_RESET
+#define __OTGFS_CLK_DISABLE __HAL_RCC_OTGFS_CLK_DISABLE
+#define __OTGFS_CLK_ENABLE __HAL_RCC_OTGFS_CLK_ENABLE
+#define __OTGFS_CLK_SLEEP_DISABLE __HAL_RCC_OTGFS_CLK_SLEEP_DISABLE
+#define __OTGFS_CLK_SLEEP_ENABLE __HAL_RCC_OTGFS_CLK_SLEEP_ENABLE
+#define __OTGFS_FORCE_RESET __HAL_RCC_OTGFS_FORCE_RESET
+#define __OTGFS_RELEASE_RESET __HAL_RCC_OTGFS_RELEASE_RESET
+#define __PWR_CLK_DISABLE __HAL_RCC_PWR_CLK_DISABLE
+#define __PWR_CLK_ENABLE __HAL_RCC_PWR_CLK_ENABLE
+#define __PWR_CLK_SLEEP_DISABLE __HAL_RCC_PWR_CLK_SLEEP_DISABLE
+#define __PWR_CLK_SLEEP_ENABLE __HAL_RCC_PWR_CLK_SLEEP_ENABLE
+#define __PWR_FORCE_RESET __HAL_RCC_PWR_FORCE_RESET
+#define __PWR_RELEASE_RESET __HAL_RCC_PWR_RELEASE_RESET
+#define __QSPI_CLK_DISABLE __HAL_RCC_QSPI_CLK_DISABLE
+#define __QSPI_CLK_ENABLE __HAL_RCC_QSPI_CLK_ENABLE
+#define __QSPI_CLK_SLEEP_DISABLE __HAL_RCC_QSPI_CLK_SLEEP_DISABLE
+#define __QSPI_CLK_SLEEP_ENABLE __HAL_RCC_QSPI_CLK_SLEEP_ENABLE
+#define __QSPI_FORCE_RESET __HAL_RCC_QSPI_FORCE_RESET
+#define __QSPI_RELEASE_RESET __HAL_RCC_QSPI_RELEASE_RESET
+
+#if defined(STM32WB)
+#define __HAL_RCC_QSPI_CLK_DISABLE __HAL_RCC_QUADSPI_CLK_DISABLE
+#define __HAL_RCC_QSPI_CLK_ENABLE __HAL_RCC_QUADSPI_CLK_ENABLE
+#define __HAL_RCC_QSPI_CLK_SLEEP_DISABLE __HAL_RCC_QUADSPI_CLK_SLEEP_DISABLE
+#define __HAL_RCC_QSPI_CLK_SLEEP_ENABLE __HAL_RCC_QUADSPI_CLK_SLEEP_ENABLE
+#define __HAL_RCC_QSPI_FORCE_RESET __HAL_RCC_QUADSPI_FORCE_RESET
+#define __HAL_RCC_QSPI_RELEASE_RESET __HAL_RCC_QUADSPI_RELEASE_RESET
+#define __HAL_RCC_QSPI_IS_CLK_ENABLED __HAL_RCC_QUADSPI_IS_CLK_ENABLED
+#define __HAL_RCC_QSPI_IS_CLK_DISABLED __HAL_RCC_QUADSPI_IS_CLK_DISABLED
+#define __HAL_RCC_QSPI_IS_CLK_SLEEP_ENABLED __HAL_RCC_QUADSPI_IS_CLK_SLEEP_ENABLED
+#define __HAL_RCC_QSPI_IS_CLK_SLEEP_DISABLED __HAL_RCC_QUADSPI_IS_CLK_SLEEP_DISABLED
+#define QSPI_IRQHandler QUADSPI_IRQHandler
+#endif /* __HAL_RCC_QUADSPI_CLK_ENABLE */
+
+#define __RNG_CLK_DISABLE __HAL_RCC_RNG_CLK_DISABLE
+#define __RNG_CLK_ENABLE __HAL_RCC_RNG_CLK_ENABLE
+#define __RNG_CLK_SLEEP_DISABLE __HAL_RCC_RNG_CLK_SLEEP_DISABLE
+#define __RNG_CLK_SLEEP_ENABLE __HAL_RCC_RNG_CLK_SLEEP_ENABLE
+#define __RNG_FORCE_RESET __HAL_RCC_RNG_FORCE_RESET
+#define __RNG_RELEASE_RESET __HAL_RCC_RNG_RELEASE_RESET
+#define __SAI1_CLK_DISABLE __HAL_RCC_SAI1_CLK_DISABLE
+#define __SAI1_CLK_ENABLE __HAL_RCC_SAI1_CLK_ENABLE
+#define __SAI1_CLK_SLEEP_DISABLE __HAL_RCC_SAI1_CLK_SLEEP_DISABLE
+#define __SAI1_CLK_SLEEP_ENABLE __HAL_RCC_SAI1_CLK_SLEEP_ENABLE
+#define __SAI1_FORCE_RESET __HAL_RCC_SAI1_FORCE_RESET
+#define __SAI1_RELEASE_RESET __HAL_RCC_SAI1_RELEASE_RESET
+#define __SAI2_CLK_DISABLE __HAL_RCC_SAI2_CLK_DISABLE
+#define __SAI2_CLK_ENABLE __HAL_RCC_SAI2_CLK_ENABLE
+#define __SAI2_CLK_SLEEP_DISABLE __HAL_RCC_SAI2_CLK_SLEEP_DISABLE
+#define __SAI2_CLK_SLEEP_ENABLE __HAL_RCC_SAI2_CLK_SLEEP_ENABLE
+#define __SAI2_FORCE_RESET __HAL_RCC_SAI2_FORCE_RESET
+#define __SAI2_RELEASE_RESET __HAL_RCC_SAI2_RELEASE_RESET
+#define __SDIO_CLK_DISABLE __HAL_RCC_SDIO_CLK_DISABLE
+#define __SDIO_CLK_ENABLE __HAL_RCC_SDIO_CLK_ENABLE
+#define __SDMMC_CLK_DISABLE __HAL_RCC_SDMMC_CLK_DISABLE
+#define __SDMMC_CLK_ENABLE __HAL_RCC_SDMMC_CLK_ENABLE
+#define __SDMMC_CLK_SLEEP_DISABLE __HAL_RCC_SDMMC_CLK_SLEEP_DISABLE
+#define __SDMMC_CLK_SLEEP_ENABLE __HAL_RCC_SDMMC_CLK_SLEEP_ENABLE
+#define __SDMMC_FORCE_RESET __HAL_RCC_SDMMC_FORCE_RESET
+#define __SDMMC_RELEASE_RESET __HAL_RCC_SDMMC_RELEASE_RESET
+#define __SPI1_CLK_DISABLE __HAL_RCC_SPI1_CLK_DISABLE
+#define __SPI1_CLK_ENABLE __HAL_RCC_SPI1_CLK_ENABLE
+#define __SPI1_CLK_SLEEP_DISABLE __HAL_RCC_SPI1_CLK_SLEEP_DISABLE
+#define __SPI1_CLK_SLEEP_ENABLE __HAL_RCC_SPI1_CLK_SLEEP_ENABLE
+#define __SPI1_FORCE_RESET __HAL_RCC_SPI1_FORCE_RESET
+#define __SPI1_RELEASE_RESET __HAL_RCC_SPI1_RELEASE_RESET
+#define __SPI2_CLK_DISABLE __HAL_RCC_SPI2_CLK_DISABLE
+#define __SPI2_CLK_ENABLE __HAL_RCC_SPI2_CLK_ENABLE
+#define __SPI2_CLK_SLEEP_DISABLE __HAL_RCC_SPI2_CLK_SLEEP_DISABLE
+#define __SPI2_CLK_SLEEP_ENABLE __HAL_RCC_SPI2_CLK_SLEEP_ENABLE
+#define __SPI2_FORCE_RESET __HAL_RCC_SPI2_FORCE_RESET
+#define __SPI2_RELEASE_RESET __HAL_RCC_SPI2_RELEASE_RESET
+#define __SPI3_CLK_DISABLE __HAL_RCC_SPI3_CLK_DISABLE
+#define __SPI3_CLK_ENABLE __HAL_RCC_SPI3_CLK_ENABLE
+#define __SPI3_CLK_SLEEP_DISABLE __HAL_RCC_SPI3_CLK_SLEEP_DISABLE
+#define __SPI3_CLK_SLEEP_ENABLE __HAL_RCC_SPI3_CLK_SLEEP_ENABLE
+#define __SPI3_FORCE_RESET __HAL_RCC_SPI3_FORCE_RESET
+#define __SPI3_RELEASE_RESET __HAL_RCC_SPI3_RELEASE_RESET
+#define __SRAM_CLK_DISABLE __HAL_RCC_SRAM_CLK_DISABLE
+#define __SRAM_CLK_ENABLE __HAL_RCC_SRAM_CLK_ENABLE
+#define __SRAM1_CLK_SLEEP_DISABLE __HAL_RCC_SRAM1_CLK_SLEEP_DISABLE
+#define __SRAM1_CLK_SLEEP_ENABLE __HAL_RCC_SRAM1_CLK_SLEEP_ENABLE
+#define __SRAM2_CLK_SLEEP_DISABLE __HAL_RCC_SRAM2_CLK_SLEEP_DISABLE
+#define __SRAM2_CLK_SLEEP_ENABLE __HAL_RCC_SRAM2_CLK_SLEEP_ENABLE
+#define __SWPMI1_CLK_DISABLE __HAL_RCC_SWPMI1_CLK_DISABLE
+#define __SWPMI1_CLK_ENABLE __HAL_RCC_SWPMI1_CLK_ENABLE
+#define __SWPMI1_CLK_SLEEP_DISABLE __HAL_RCC_SWPMI1_CLK_SLEEP_DISABLE
+#define __SWPMI1_CLK_SLEEP_ENABLE __HAL_RCC_SWPMI1_CLK_SLEEP_ENABLE
+#define __SWPMI1_FORCE_RESET __HAL_RCC_SWPMI1_FORCE_RESET
+#define __SWPMI1_RELEASE_RESET __HAL_RCC_SWPMI1_RELEASE_RESET
+#define __SYSCFG_CLK_DISABLE __HAL_RCC_SYSCFG_CLK_DISABLE
+#define __SYSCFG_CLK_ENABLE __HAL_RCC_SYSCFG_CLK_ENABLE
+#define __SYSCFG_CLK_SLEEP_DISABLE __HAL_RCC_SYSCFG_CLK_SLEEP_DISABLE
+#define __SYSCFG_CLK_SLEEP_ENABLE __HAL_RCC_SYSCFG_CLK_SLEEP_ENABLE
+#define __SYSCFG_FORCE_RESET __HAL_RCC_SYSCFG_FORCE_RESET
+#define __SYSCFG_RELEASE_RESET __HAL_RCC_SYSCFG_RELEASE_RESET
+#define __TIM1_CLK_DISABLE __HAL_RCC_TIM1_CLK_DISABLE
+#define __TIM1_CLK_ENABLE __HAL_RCC_TIM1_CLK_ENABLE
+#define __TIM1_CLK_SLEEP_DISABLE __HAL_RCC_TIM1_CLK_SLEEP_DISABLE
+#define __TIM1_CLK_SLEEP_ENABLE __HAL_RCC_TIM1_CLK_SLEEP_ENABLE
+#define __TIM1_FORCE_RESET __HAL_RCC_TIM1_FORCE_RESET
+#define __TIM1_RELEASE_RESET __HAL_RCC_TIM1_RELEASE_RESET
+#define __TIM10_CLK_DISABLE __HAL_RCC_TIM10_CLK_DISABLE
+#define __TIM10_CLK_ENABLE __HAL_RCC_TIM10_CLK_ENABLE
+#define __TIM10_FORCE_RESET __HAL_RCC_TIM10_FORCE_RESET
+#define __TIM10_RELEASE_RESET __HAL_RCC_TIM10_RELEASE_RESET
+#define __TIM11_CLK_DISABLE __HAL_RCC_TIM11_CLK_DISABLE
+#define __TIM11_CLK_ENABLE __HAL_RCC_TIM11_CLK_ENABLE
+#define __TIM11_FORCE_RESET __HAL_RCC_TIM11_FORCE_RESET
+#define __TIM11_RELEASE_RESET __HAL_RCC_TIM11_RELEASE_RESET
+#define __TIM12_CLK_DISABLE __HAL_RCC_TIM12_CLK_DISABLE
+#define __TIM12_CLK_ENABLE __HAL_RCC_TIM12_CLK_ENABLE
+#define __TIM12_FORCE_RESET __HAL_RCC_TIM12_FORCE_RESET
+#define __TIM12_RELEASE_RESET __HAL_RCC_TIM12_RELEASE_RESET
+#define __TIM13_CLK_DISABLE __HAL_RCC_TIM13_CLK_DISABLE
+#define __TIM13_CLK_ENABLE __HAL_RCC_TIM13_CLK_ENABLE
+#define __TIM13_FORCE_RESET __HAL_RCC_TIM13_FORCE_RESET
+#define __TIM13_RELEASE_RESET __HAL_RCC_TIM13_RELEASE_RESET
+#define __TIM14_CLK_DISABLE __HAL_RCC_TIM14_CLK_DISABLE
+#define __TIM14_CLK_ENABLE __HAL_RCC_TIM14_CLK_ENABLE
+#define __TIM14_FORCE_RESET __HAL_RCC_TIM14_FORCE_RESET
+#define __TIM14_RELEASE_RESET __HAL_RCC_TIM14_RELEASE_RESET
+#define __TIM15_CLK_DISABLE __HAL_RCC_TIM15_CLK_DISABLE
+#define __TIM15_CLK_ENABLE __HAL_RCC_TIM15_CLK_ENABLE
+#define __TIM15_CLK_SLEEP_DISABLE __HAL_RCC_TIM15_CLK_SLEEP_DISABLE
+#define __TIM15_CLK_SLEEP_ENABLE __HAL_RCC_TIM15_CLK_SLEEP_ENABLE
+#define __TIM15_FORCE_RESET __HAL_RCC_TIM15_FORCE_RESET
+#define __TIM15_RELEASE_RESET __HAL_RCC_TIM15_RELEASE_RESET
+#define __TIM16_CLK_DISABLE __HAL_RCC_TIM16_CLK_DISABLE
+#define __TIM16_CLK_ENABLE __HAL_RCC_TIM16_CLK_ENABLE
+#define __TIM16_CLK_SLEEP_DISABLE __HAL_RCC_TIM16_CLK_SLEEP_DISABLE
+#define __TIM16_CLK_SLEEP_ENABLE __HAL_RCC_TIM16_CLK_SLEEP_ENABLE
+#define __TIM16_FORCE_RESET __HAL_RCC_TIM16_FORCE_RESET
+#define __TIM16_RELEASE_RESET __HAL_RCC_TIM16_RELEASE_RESET
+#define __TIM17_CLK_DISABLE __HAL_RCC_TIM17_CLK_DISABLE
+#define __TIM17_CLK_ENABLE __HAL_RCC_TIM17_CLK_ENABLE
+#define __TIM17_CLK_SLEEP_DISABLE __HAL_RCC_TIM17_CLK_SLEEP_DISABLE
+#define __TIM17_CLK_SLEEP_ENABLE __HAL_RCC_TIM17_CLK_SLEEP_ENABLE
+#define __TIM17_FORCE_RESET __HAL_RCC_TIM17_FORCE_RESET
+#define __TIM17_RELEASE_RESET __HAL_RCC_TIM17_RELEASE_RESET
+#define __TIM2_CLK_DISABLE __HAL_RCC_TIM2_CLK_DISABLE
+#define __TIM2_CLK_ENABLE __HAL_RCC_TIM2_CLK_ENABLE
+#define __TIM2_CLK_SLEEP_DISABLE __HAL_RCC_TIM2_CLK_SLEEP_DISABLE
+#define __TIM2_CLK_SLEEP_ENABLE __HAL_RCC_TIM2_CLK_SLEEP_ENABLE
+#define __TIM2_FORCE_RESET __HAL_RCC_TIM2_FORCE_RESET
+#define __TIM2_RELEASE_RESET __HAL_RCC_TIM2_RELEASE_RESET
+#define __TIM3_CLK_DISABLE __HAL_RCC_TIM3_CLK_DISABLE
+#define __TIM3_CLK_ENABLE __HAL_RCC_TIM3_CLK_ENABLE
+#define __TIM3_CLK_SLEEP_DISABLE __HAL_RCC_TIM3_CLK_SLEEP_DISABLE
+#define __TIM3_CLK_SLEEP_ENABLE __HAL_RCC_TIM3_CLK_SLEEP_ENABLE
+#define __TIM3_FORCE_RESET __HAL_RCC_TIM3_FORCE_RESET
+#define __TIM3_RELEASE_RESET __HAL_RCC_TIM3_RELEASE_RESET
+#define __TIM4_CLK_DISABLE __HAL_RCC_TIM4_CLK_DISABLE
+#define __TIM4_CLK_ENABLE __HAL_RCC_TIM4_CLK_ENABLE
+#define __TIM4_CLK_SLEEP_DISABLE __HAL_RCC_TIM4_CLK_SLEEP_DISABLE
+#define __TIM4_CLK_SLEEP_ENABLE __HAL_RCC_TIM4_CLK_SLEEP_ENABLE
+#define __TIM4_FORCE_RESET __HAL_RCC_TIM4_FORCE_RESET
+#define __TIM4_RELEASE_RESET __HAL_RCC_TIM4_RELEASE_RESET
+#define __TIM5_CLK_DISABLE __HAL_RCC_TIM5_CLK_DISABLE
+#define __TIM5_CLK_ENABLE __HAL_RCC_TIM5_CLK_ENABLE
+#define __TIM5_CLK_SLEEP_DISABLE __HAL_RCC_TIM5_CLK_SLEEP_DISABLE
+#define __TIM5_CLK_SLEEP_ENABLE __HAL_RCC_TIM5_CLK_SLEEP_ENABLE
+#define __TIM5_FORCE_RESET __HAL_RCC_TIM5_FORCE_RESET
+#define __TIM5_RELEASE_RESET __HAL_RCC_TIM5_RELEASE_RESET
+#define __TIM6_CLK_DISABLE __HAL_RCC_TIM6_CLK_DISABLE
+#define __TIM6_CLK_ENABLE __HAL_RCC_TIM6_CLK_ENABLE
+#define __TIM6_CLK_SLEEP_DISABLE __HAL_RCC_TIM6_CLK_SLEEP_DISABLE
+#define __TIM6_CLK_SLEEP_ENABLE __HAL_RCC_TIM6_CLK_SLEEP_ENABLE
+#define __TIM6_FORCE_RESET __HAL_RCC_TIM6_FORCE_RESET
+#define __TIM6_RELEASE_RESET __HAL_RCC_TIM6_RELEASE_RESET
+#define __TIM7_CLK_DISABLE __HAL_RCC_TIM7_CLK_DISABLE
+#define __TIM7_CLK_ENABLE __HAL_RCC_TIM7_CLK_ENABLE
+#define __TIM7_CLK_SLEEP_DISABLE __HAL_RCC_TIM7_CLK_SLEEP_DISABLE
+#define __TIM7_CLK_SLEEP_ENABLE __HAL_RCC_TIM7_CLK_SLEEP_ENABLE
+#define __TIM7_FORCE_RESET __HAL_RCC_TIM7_FORCE_RESET
+#define __TIM7_RELEASE_RESET __HAL_RCC_TIM7_RELEASE_RESET
+#define __TIM8_CLK_DISABLE __HAL_RCC_TIM8_CLK_DISABLE
+#define __TIM8_CLK_ENABLE __HAL_RCC_TIM8_CLK_ENABLE
+#define __TIM8_CLK_SLEEP_DISABLE __HAL_RCC_TIM8_CLK_SLEEP_DISABLE
+#define __TIM8_CLK_SLEEP_ENABLE __HAL_RCC_TIM8_CLK_SLEEP_ENABLE
+#define __TIM8_FORCE_RESET __HAL_RCC_TIM8_FORCE_RESET
+#define __TIM8_RELEASE_RESET __HAL_RCC_TIM8_RELEASE_RESET
+#define __TIM9_CLK_DISABLE __HAL_RCC_TIM9_CLK_DISABLE
+#define __TIM9_CLK_ENABLE __HAL_RCC_TIM9_CLK_ENABLE
+#define __TIM9_FORCE_RESET __HAL_RCC_TIM9_FORCE_RESET
+#define __TIM9_RELEASE_RESET __HAL_RCC_TIM9_RELEASE_RESET
+#define __TSC_CLK_DISABLE __HAL_RCC_TSC_CLK_DISABLE
+#define __TSC_CLK_ENABLE __HAL_RCC_TSC_CLK_ENABLE
+#define __TSC_CLK_SLEEP_DISABLE __HAL_RCC_TSC_CLK_SLEEP_DISABLE
+#define __TSC_CLK_SLEEP_ENABLE __HAL_RCC_TSC_CLK_SLEEP_ENABLE
+#define __TSC_FORCE_RESET __HAL_RCC_TSC_FORCE_RESET
+#define __TSC_RELEASE_RESET __HAL_RCC_TSC_RELEASE_RESET
+#define __UART4_CLK_DISABLE __HAL_RCC_UART4_CLK_DISABLE
+#define __UART4_CLK_ENABLE __HAL_RCC_UART4_CLK_ENABLE
+#define __UART4_CLK_SLEEP_DISABLE __HAL_RCC_UART4_CLK_SLEEP_DISABLE
+#define __UART4_CLK_SLEEP_ENABLE __HAL_RCC_UART4_CLK_SLEEP_ENABLE
+#define __UART4_FORCE_RESET __HAL_RCC_UART4_FORCE_RESET
+#define __UART4_RELEASE_RESET __HAL_RCC_UART4_RELEASE_RESET
+#define __UART5_CLK_DISABLE __HAL_RCC_UART5_CLK_DISABLE
+#define __UART5_CLK_ENABLE __HAL_RCC_UART5_CLK_ENABLE
+#define __UART5_CLK_SLEEP_DISABLE __HAL_RCC_UART5_CLK_SLEEP_DISABLE
+#define __UART5_CLK_SLEEP_ENABLE __HAL_RCC_UART5_CLK_SLEEP_ENABLE
+#define __UART5_FORCE_RESET __HAL_RCC_UART5_FORCE_RESET
+#define __UART5_RELEASE_RESET __HAL_RCC_UART5_RELEASE_RESET
+#define __USART1_CLK_DISABLE __HAL_RCC_USART1_CLK_DISABLE
+#define __USART1_CLK_ENABLE __HAL_RCC_USART1_CLK_ENABLE
+#define __USART1_CLK_SLEEP_DISABLE __HAL_RCC_USART1_CLK_SLEEP_DISABLE
+#define __USART1_CLK_SLEEP_ENABLE __HAL_RCC_USART1_CLK_SLEEP_ENABLE
+#define __USART1_FORCE_RESET __HAL_RCC_USART1_FORCE_RESET
+#define __USART1_RELEASE_RESET __HAL_RCC_USART1_RELEASE_RESET
+#define __USART2_CLK_DISABLE __HAL_RCC_USART2_CLK_DISABLE
+#define __USART2_CLK_ENABLE __HAL_RCC_USART2_CLK_ENABLE
+#define __USART2_CLK_SLEEP_DISABLE __HAL_RCC_USART2_CLK_SLEEP_DISABLE
+#define __USART2_CLK_SLEEP_ENABLE __HAL_RCC_USART2_CLK_SLEEP_ENABLE
+#define __USART2_FORCE_RESET __HAL_RCC_USART2_FORCE_RESET
+#define __USART2_RELEASE_RESET __HAL_RCC_USART2_RELEASE_RESET
+#define __USART3_CLK_DISABLE __HAL_RCC_USART3_CLK_DISABLE
+#define __USART3_CLK_ENABLE __HAL_RCC_USART3_CLK_ENABLE
+#define __USART3_CLK_SLEEP_DISABLE __HAL_RCC_USART3_CLK_SLEEP_DISABLE
+#define __USART3_CLK_SLEEP_ENABLE __HAL_RCC_USART3_CLK_SLEEP_ENABLE
+#define __USART3_FORCE_RESET __HAL_RCC_USART3_FORCE_RESET
+#define __USART3_RELEASE_RESET __HAL_RCC_USART3_RELEASE_RESET
+#define __USART4_CLK_DISABLE __HAL_RCC_UART4_CLK_DISABLE
+#define __USART4_CLK_ENABLE __HAL_RCC_UART4_CLK_ENABLE
+#define __USART4_CLK_SLEEP_ENABLE __HAL_RCC_UART4_CLK_SLEEP_ENABLE
+#define __USART4_CLK_SLEEP_DISABLE __HAL_RCC_UART4_CLK_SLEEP_DISABLE
+#define __USART4_FORCE_RESET __HAL_RCC_UART4_FORCE_RESET
+#define __USART4_RELEASE_RESET __HAL_RCC_UART4_RELEASE_RESET
+#define __USART5_CLK_DISABLE __HAL_RCC_UART5_CLK_DISABLE
+#define __USART5_CLK_ENABLE __HAL_RCC_UART5_CLK_ENABLE
+#define __USART5_CLK_SLEEP_ENABLE __HAL_RCC_UART5_CLK_SLEEP_ENABLE
+#define __USART5_CLK_SLEEP_DISABLE __HAL_RCC_UART5_CLK_SLEEP_DISABLE
+#define __USART5_FORCE_RESET __HAL_RCC_UART5_FORCE_RESET
+#define __USART5_RELEASE_RESET __HAL_RCC_UART5_RELEASE_RESET
+#define __USART7_CLK_DISABLE __HAL_RCC_UART7_CLK_DISABLE
+#define __USART7_CLK_ENABLE __HAL_RCC_UART7_CLK_ENABLE
+#define __USART7_FORCE_RESET __HAL_RCC_UART7_FORCE_RESET
+#define __USART7_RELEASE_RESET __HAL_RCC_UART7_RELEASE_RESET
+#define __USART8_CLK_DISABLE __HAL_RCC_UART8_CLK_DISABLE
+#define __USART8_CLK_ENABLE __HAL_RCC_UART8_CLK_ENABLE
+#define __USART8_FORCE_RESET __HAL_RCC_UART8_FORCE_RESET
+#define __USART8_RELEASE_RESET __HAL_RCC_UART8_RELEASE_RESET
+#define __USB_CLK_DISABLE __HAL_RCC_USB_CLK_DISABLE
+#define __USB_CLK_ENABLE __HAL_RCC_USB_CLK_ENABLE
+#define __USB_FORCE_RESET __HAL_RCC_USB_FORCE_RESET
+#define __USB_CLK_SLEEP_ENABLE __HAL_RCC_USB_CLK_SLEEP_ENABLE
+#define __USB_CLK_SLEEP_DISABLE __HAL_RCC_USB_CLK_SLEEP_DISABLE
+#define __USB_OTG_FS_CLK_DISABLE __HAL_RCC_USB_OTG_FS_CLK_DISABLE
+#define __USB_OTG_FS_CLK_ENABLE __HAL_RCC_USB_OTG_FS_CLK_ENABLE
+#define __USB_RELEASE_RESET __HAL_RCC_USB_RELEASE_RESET
+
+#if defined(STM32H7)
+#define __HAL_RCC_WWDG_CLK_DISABLE __HAL_RCC_WWDG1_CLK_DISABLE
+#define __HAL_RCC_WWDG_CLK_ENABLE __HAL_RCC_WWDG1_CLK_ENABLE
+#define __HAL_RCC_WWDG_CLK_SLEEP_DISABLE __HAL_RCC_WWDG1_CLK_SLEEP_DISABLE
+#define __HAL_RCC_WWDG_CLK_SLEEP_ENABLE __HAL_RCC_WWDG1_CLK_SLEEP_ENABLE
+
+#define __HAL_RCC_WWDG_FORCE_RESET ((void)0U) /* Not available on the STM32H7*/
+#define __HAL_RCC_WWDG_RELEASE_RESET ((void)0U) /* Not available on the STM32H7*/
+
+
+#define __HAL_RCC_WWDG_IS_CLK_ENABLED __HAL_RCC_WWDG1_IS_CLK_ENABLED
+#define __HAL_RCC_WWDG_IS_CLK_DISABLED __HAL_RCC_WWDG1_IS_CLK_DISABLED
+#endif
+
+#define __WWDG_CLK_DISABLE __HAL_RCC_WWDG_CLK_DISABLE
+#define __WWDG_CLK_ENABLE __HAL_RCC_WWDG_CLK_ENABLE
+#define __WWDG_CLK_SLEEP_DISABLE __HAL_RCC_WWDG_CLK_SLEEP_DISABLE
+#define __WWDG_CLK_SLEEP_ENABLE __HAL_RCC_WWDG_CLK_SLEEP_ENABLE
+#define __WWDG_FORCE_RESET __HAL_RCC_WWDG_FORCE_RESET
+#define __WWDG_RELEASE_RESET __HAL_RCC_WWDG_RELEASE_RESET
+
+#define __TIM21_CLK_ENABLE __HAL_RCC_TIM21_CLK_ENABLE
+#define __TIM21_CLK_DISABLE __HAL_RCC_TIM21_CLK_DISABLE
+#define __TIM21_FORCE_RESET __HAL_RCC_TIM21_FORCE_RESET
+#define __TIM21_RELEASE_RESET __HAL_RCC_TIM21_RELEASE_RESET
+#define __TIM21_CLK_SLEEP_ENABLE __HAL_RCC_TIM21_CLK_SLEEP_ENABLE
+#define __TIM21_CLK_SLEEP_DISABLE __HAL_RCC_TIM21_CLK_SLEEP_DISABLE
+#define __TIM22_CLK_ENABLE __HAL_RCC_TIM22_CLK_ENABLE
+#define __TIM22_CLK_DISABLE __HAL_RCC_TIM22_CLK_DISABLE
+#define __TIM22_FORCE_RESET __HAL_RCC_TIM22_FORCE_RESET
+#define __TIM22_RELEASE_RESET __HAL_RCC_TIM22_RELEASE_RESET
+#define __TIM22_CLK_SLEEP_ENABLE __HAL_RCC_TIM22_CLK_SLEEP_ENABLE
+#define __TIM22_CLK_SLEEP_DISABLE __HAL_RCC_TIM22_CLK_SLEEP_DISABLE
+#define __CRS_CLK_DISABLE __HAL_RCC_CRS_CLK_DISABLE
+#define __CRS_CLK_ENABLE __HAL_RCC_CRS_CLK_ENABLE
+#define __CRS_CLK_SLEEP_DISABLE __HAL_RCC_CRS_CLK_SLEEP_DISABLE
+#define __CRS_CLK_SLEEP_ENABLE __HAL_RCC_CRS_CLK_SLEEP_ENABLE
+#define __CRS_FORCE_RESET __HAL_RCC_CRS_FORCE_RESET
+#define __CRS_RELEASE_RESET __HAL_RCC_CRS_RELEASE_RESET
+#define __RCC_BACKUPRESET_FORCE __HAL_RCC_BACKUPRESET_FORCE
+#define __RCC_BACKUPRESET_RELEASE __HAL_RCC_BACKUPRESET_RELEASE
+
+#define __USB_OTG_FS_FORCE_RESET __HAL_RCC_USB_OTG_FS_FORCE_RESET
+#define __USB_OTG_FS_RELEASE_RESET __HAL_RCC_USB_OTG_FS_RELEASE_RESET
+#define __USB_OTG_FS_CLK_SLEEP_ENABLE __HAL_RCC_USB_OTG_FS_CLK_SLEEP_ENABLE
+#define __USB_OTG_FS_CLK_SLEEP_DISABLE __HAL_RCC_USB_OTG_FS_CLK_SLEEP_DISABLE
+#define __USB_OTG_HS_CLK_DISABLE __HAL_RCC_USB_OTG_HS_CLK_DISABLE
+#define __USB_OTG_HS_CLK_ENABLE __HAL_RCC_USB_OTG_HS_CLK_ENABLE
+#define __USB_OTG_HS_ULPI_CLK_ENABLE __HAL_RCC_USB_OTG_HS_ULPI_CLK_ENABLE
+#define __USB_OTG_HS_ULPI_CLK_DISABLE __HAL_RCC_USB_OTG_HS_ULPI_CLK_DISABLE
+#define __TIM9_CLK_SLEEP_ENABLE __HAL_RCC_TIM9_CLK_SLEEP_ENABLE
+#define __TIM9_CLK_SLEEP_DISABLE __HAL_RCC_TIM9_CLK_SLEEP_DISABLE
+#define __TIM10_CLK_SLEEP_ENABLE __HAL_RCC_TIM10_CLK_SLEEP_ENABLE
+#define __TIM10_CLK_SLEEP_DISABLE __HAL_RCC_TIM10_CLK_SLEEP_DISABLE
+#define __TIM11_CLK_SLEEP_ENABLE __HAL_RCC_TIM11_CLK_SLEEP_ENABLE
+#define __TIM11_CLK_SLEEP_DISABLE __HAL_RCC_TIM11_CLK_SLEEP_DISABLE
+#define __ETHMACPTP_CLK_SLEEP_ENABLE __HAL_RCC_ETHMACPTP_CLK_SLEEP_ENABLE
+#define __ETHMACPTP_CLK_SLEEP_DISABLE __HAL_RCC_ETHMACPTP_CLK_SLEEP_DISABLE
+#define __ETHMACPTP_CLK_ENABLE __HAL_RCC_ETHMACPTP_CLK_ENABLE
+#define __ETHMACPTP_CLK_DISABLE __HAL_RCC_ETHMACPTP_CLK_DISABLE
+#define __HASH_CLK_ENABLE __HAL_RCC_HASH_CLK_ENABLE
+#define __HASH_FORCE_RESET __HAL_RCC_HASH_FORCE_RESET
+#define __HASH_RELEASE_RESET __HAL_RCC_HASH_RELEASE_RESET
+#define __HASH_CLK_SLEEP_ENABLE __HAL_RCC_HASH_CLK_SLEEP_ENABLE
+#define __HASH_CLK_SLEEP_DISABLE __HAL_RCC_HASH_CLK_SLEEP_DISABLE
+#define __HASH_CLK_DISABLE __HAL_RCC_HASH_CLK_DISABLE
+#define __SPI5_CLK_ENABLE __HAL_RCC_SPI5_CLK_ENABLE
+#define __SPI5_CLK_DISABLE __HAL_RCC_SPI5_CLK_DISABLE
+#define __SPI5_FORCE_RESET __HAL_RCC_SPI5_FORCE_RESET
+#define __SPI5_RELEASE_RESET __HAL_RCC_SPI5_RELEASE_RESET
+#define __SPI5_CLK_SLEEP_ENABLE __HAL_RCC_SPI5_CLK_SLEEP_ENABLE
+#define __SPI5_CLK_SLEEP_DISABLE __HAL_RCC_SPI5_CLK_SLEEP_DISABLE
+#define __SPI6_CLK_ENABLE __HAL_RCC_SPI6_CLK_ENABLE
+#define __SPI6_CLK_DISABLE __HAL_RCC_SPI6_CLK_DISABLE
+#define __SPI6_FORCE_RESET __HAL_RCC_SPI6_FORCE_RESET
+#define __SPI6_RELEASE_RESET __HAL_RCC_SPI6_RELEASE_RESET
+#define __SPI6_CLK_SLEEP_ENABLE __HAL_RCC_SPI6_CLK_SLEEP_ENABLE
+#define __SPI6_CLK_SLEEP_DISABLE __HAL_RCC_SPI6_CLK_SLEEP_DISABLE
+#define __LTDC_CLK_ENABLE __HAL_RCC_LTDC_CLK_ENABLE
+#define __LTDC_CLK_DISABLE __HAL_RCC_LTDC_CLK_DISABLE
+#define __LTDC_FORCE_RESET __HAL_RCC_LTDC_FORCE_RESET
+#define __LTDC_RELEASE_RESET __HAL_RCC_LTDC_RELEASE_RESET
+#define __LTDC_CLK_SLEEP_ENABLE __HAL_RCC_LTDC_CLK_SLEEP_ENABLE
+#define __ETHMAC_CLK_SLEEP_ENABLE __HAL_RCC_ETHMAC_CLK_SLEEP_ENABLE
+#define __ETHMAC_CLK_SLEEP_DISABLE __HAL_RCC_ETHMAC_CLK_SLEEP_DISABLE
+#define __ETHMACTX_CLK_SLEEP_ENABLE __HAL_RCC_ETHMACTX_CLK_SLEEP_ENABLE
+#define __ETHMACTX_CLK_SLEEP_DISABLE __HAL_RCC_ETHMACTX_CLK_SLEEP_DISABLE
+#define __ETHMACRX_CLK_SLEEP_ENABLE __HAL_RCC_ETHMACRX_CLK_SLEEP_ENABLE
+#define __ETHMACRX_CLK_SLEEP_DISABLE __HAL_RCC_ETHMACRX_CLK_SLEEP_DISABLE
+#define __TIM12_CLK_SLEEP_ENABLE __HAL_RCC_TIM12_CLK_SLEEP_ENABLE
+#define __TIM12_CLK_SLEEP_DISABLE __HAL_RCC_TIM12_CLK_SLEEP_DISABLE
+#define __TIM13_CLK_SLEEP_ENABLE __HAL_RCC_TIM13_CLK_SLEEP_ENABLE
+#define __TIM13_CLK_SLEEP_DISABLE __HAL_RCC_TIM13_CLK_SLEEP_DISABLE
+#define __TIM14_CLK_SLEEP_ENABLE __HAL_RCC_TIM14_CLK_SLEEP_ENABLE
+#define __TIM14_CLK_SLEEP_DISABLE __HAL_RCC_TIM14_CLK_SLEEP_DISABLE
+#define __BKPSRAM_CLK_ENABLE __HAL_RCC_BKPSRAM_CLK_ENABLE
+#define __BKPSRAM_CLK_DISABLE __HAL_RCC_BKPSRAM_CLK_DISABLE
+#define __BKPSRAM_CLK_SLEEP_ENABLE __HAL_RCC_BKPSRAM_CLK_SLEEP_ENABLE
+#define __BKPSRAM_CLK_SLEEP_DISABLE __HAL_RCC_BKPSRAM_CLK_SLEEP_DISABLE
+#define __CCMDATARAMEN_CLK_ENABLE __HAL_RCC_CCMDATARAMEN_CLK_ENABLE
+#define __CCMDATARAMEN_CLK_DISABLE __HAL_RCC_CCMDATARAMEN_CLK_DISABLE
+#define __USART6_CLK_ENABLE __HAL_RCC_USART6_CLK_ENABLE
+#define __USART6_CLK_DISABLE __HAL_RCC_USART6_CLK_DISABLE
+#define __USART6_FORCE_RESET __HAL_RCC_USART6_FORCE_RESET
+#define __USART6_RELEASE_RESET __HAL_RCC_USART6_RELEASE_RESET
+#define __USART6_CLK_SLEEP_ENABLE __HAL_RCC_USART6_CLK_SLEEP_ENABLE
+#define __USART6_CLK_SLEEP_DISABLE __HAL_RCC_USART6_CLK_SLEEP_DISABLE
+#define __SPI4_CLK_ENABLE __HAL_RCC_SPI4_CLK_ENABLE
+#define __SPI4_CLK_DISABLE __HAL_RCC_SPI4_CLK_DISABLE
+#define __SPI4_FORCE_RESET __HAL_RCC_SPI4_FORCE_RESET
+#define __SPI4_RELEASE_RESET __HAL_RCC_SPI4_RELEASE_RESET
+#define __SPI4_CLK_SLEEP_ENABLE __HAL_RCC_SPI4_CLK_SLEEP_ENABLE
+#define __SPI4_CLK_SLEEP_DISABLE __HAL_RCC_SPI4_CLK_SLEEP_DISABLE
+#define __GPIOI_CLK_ENABLE __HAL_RCC_GPIOI_CLK_ENABLE
+#define __GPIOI_CLK_DISABLE __HAL_RCC_GPIOI_CLK_DISABLE
+#define __GPIOI_FORCE_RESET __HAL_RCC_GPIOI_FORCE_RESET
+#define __GPIOI_RELEASE_RESET __HAL_RCC_GPIOI_RELEASE_RESET
+#define __GPIOI_CLK_SLEEP_ENABLE __HAL_RCC_GPIOI_CLK_SLEEP_ENABLE
+#define __GPIOI_CLK_SLEEP_DISABLE __HAL_RCC_GPIOI_CLK_SLEEP_DISABLE
+#define __GPIOJ_CLK_ENABLE __HAL_RCC_GPIOJ_CLK_ENABLE
+#define __GPIOJ_CLK_DISABLE __HAL_RCC_GPIOJ_CLK_DISABLE
+#define __GPIOJ_FORCE_RESET __HAL_RCC_GPIOJ_FORCE_RESET
+#define __GPIOJ_RELEASE_RESET __HAL_RCC_GPIOJ_RELEASE_RESET
+#define __GPIOJ_CLK_SLEEP_ENABLE __HAL_RCC_GPIOJ_CLK_SLEEP_ENABLE
+#define __GPIOJ_CLK_SLEEP_DISABLE __HAL_RCC_GPIOJ_CLK_SLEEP_DISABLE
+#define __GPIOK_CLK_ENABLE __HAL_RCC_GPIOK_CLK_ENABLE
+#define __GPIOK_CLK_DISABLE __HAL_RCC_GPIOK_CLK_DISABLE
+#define __GPIOK_RELEASE_RESET __HAL_RCC_GPIOK_RELEASE_RESET
+#define __GPIOK_CLK_SLEEP_ENABLE __HAL_RCC_GPIOK_CLK_SLEEP_ENABLE
+#define __GPIOK_CLK_SLEEP_DISABLE __HAL_RCC_GPIOK_CLK_SLEEP_DISABLE
+#define __ETH_CLK_ENABLE __HAL_RCC_ETH_CLK_ENABLE
+#define __ETH_CLK_DISABLE __HAL_RCC_ETH_CLK_DISABLE
+#define __DCMI_CLK_ENABLE __HAL_RCC_DCMI_CLK_ENABLE
+#define __DCMI_CLK_DISABLE __HAL_RCC_DCMI_CLK_DISABLE
+#define __DCMI_FORCE_RESET __HAL_RCC_DCMI_FORCE_RESET
+#define __DCMI_RELEASE_RESET __HAL_RCC_DCMI_RELEASE_RESET
+#define __DCMI_CLK_SLEEP_ENABLE __HAL_RCC_DCMI_CLK_SLEEP_ENABLE
+#define __DCMI_CLK_SLEEP_DISABLE __HAL_RCC_DCMI_CLK_SLEEP_DISABLE
+#define __UART7_CLK_ENABLE __HAL_RCC_UART7_CLK_ENABLE
+#define __UART7_CLK_DISABLE __HAL_RCC_UART7_CLK_DISABLE
+#define __UART7_RELEASE_RESET __HAL_RCC_UART7_RELEASE_RESET
+#define __UART7_FORCE_RESET __HAL_RCC_UART7_FORCE_RESET
+#define __UART7_CLK_SLEEP_ENABLE __HAL_RCC_UART7_CLK_SLEEP_ENABLE
+#define __UART7_CLK_SLEEP_DISABLE __HAL_RCC_UART7_CLK_SLEEP_DISABLE
+#define __UART8_CLK_ENABLE __HAL_RCC_UART8_CLK_ENABLE
+#define __UART8_CLK_DISABLE __HAL_RCC_UART8_CLK_DISABLE
+#define __UART8_FORCE_RESET __HAL_RCC_UART8_FORCE_RESET
+#define __UART8_RELEASE_RESET __HAL_RCC_UART8_RELEASE_RESET
+#define __UART8_CLK_SLEEP_ENABLE __HAL_RCC_UART8_CLK_SLEEP_ENABLE
+#define __UART8_CLK_SLEEP_DISABLE __HAL_RCC_UART8_CLK_SLEEP_DISABLE
+#define __OTGHS_CLK_SLEEP_ENABLE __HAL_RCC_USB_OTG_HS_CLK_SLEEP_ENABLE
+#define __OTGHS_CLK_SLEEP_DISABLE __HAL_RCC_USB_OTG_HS_CLK_SLEEP_DISABLE
+#define __OTGHS_FORCE_RESET __HAL_RCC_USB_OTG_HS_FORCE_RESET
+#define __OTGHS_RELEASE_RESET __HAL_RCC_USB_OTG_HS_RELEASE_RESET
+#define __OTGHSULPI_CLK_SLEEP_ENABLE __HAL_RCC_USB_OTG_HS_ULPI_CLK_SLEEP_ENABLE
+#define __OTGHSULPI_CLK_SLEEP_DISABLE __HAL_RCC_USB_OTG_HS_ULPI_CLK_SLEEP_DISABLE
+#define __HAL_RCC_OTGHS_CLK_SLEEP_ENABLE __HAL_RCC_USB_OTG_HS_CLK_SLEEP_ENABLE
+#define __HAL_RCC_OTGHS_CLK_SLEEP_DISABLE __HAL_RCC_USB_OTG_HS_CLK_SLEEP_DISABLE
+#define __HAL_RCC_OTGHS_IS_CLK_SLEEP_ENABLED __HAL_RCC_USB_OTG_HS_IS_CLK_SLEEP_ENABLED
+#define __HAL_RCC_OTGHS_IS_CLK_SLEEP_DISABLED __HAL_RCC_USB_OTG_HS_IS_CLK_SLEEP_DISABLED
+#define __HAL_RCC_OTGHS_FORCE_RESET __HAL_RCC_USB_OTG_HS_FORCE_RESET
+#define __HAL_RCC_OTGHS_RELEASE_RESET __HAL_RCC_USB_OTG_HS_RELEASE_RESET
+#define __HAL_RCC_OTGHSULPI_CLK_SLEEP_ENABLE __HAL_RCC_USB_OTG_HS_ULPI_CLK_SLEEP_ENABLE
+#define __HAL_RCC_OTGHSULPI_CLK_SLEEP_DISABLE __HAL_RCC_USB_OTG_HS_ULPI_CLK_SLEEP_DISABLE
+#define __HAL_RCC_OTGHSULPI_IS_CLK_SLEEP_ENABLED __HAL_RCC_USB_OTG_HS_ULPI_IS_CLK_SLEEP_ENABLED
+#define __HAL_RCC_OTGHSULPI_IS_CLK_SLEEP_DISABLED __HAL_RCC_USB_OTG_HS_ULPI_IS_CLK_SLEEP_DISABLED
+#define __SRAM3_CLK_SLEEP_ENABLE __HAL_RCC_SRAM3_CLK_SLEEP_ENABLE
+#define __CAN2_CLK_SLEEP_ENABLE __HAL_RCC_CAN2_CLK_SLEEP_ENABLE
+#define __CAN2_CLK_SLEEP_DISABLE __HAL_RCC_CAN2_CLK_SLEEP_DISABLE
+#define __DAC_CLK_SLEEP_ENABLE __HAL_RCC_DAC_CLK_SLEEP_ENABLE
+#define __DAC_CLK_SLEEP_DISABLE __HAL_RCC_DAC_CLK_SLEEP_DISABLE
+#define __ADC2_CLK_SLEEP_ENABLE __HAL_RCC_ADC2_CLK_SLEEP_ENABLE
+#define __ADC2_CLK_SLEEP_DISABLE __HAL_RCC_ADC2_CLK_SLEEP_DISABLE
+#define __ADC3_CLK_SLEEP_ENABLE __HAL_RCC_ADC3_CLK_SLEEP_ENABLE
+#define __ADC3_CLK_SLEEP_DISABLE __HAL_RCC_ADC3_CLK_SLEEP_DISABLE
+#define __FSMC_FORCE_RESET __HAL_RCC_FSMC_FORCE_RESET
+#define __FSMC_RELEASE_RESET __HAL_RCC_FSMC_RELEASE_RESET
+#define __FSMC_CLK_SLEEP_ENABLE __HAL_RCC_FSMC_CLK_SLEEP_ENABLE
+#define __FSMC_CLK_SLEEP_DISABLE __HAL_RCC_FSMC_CLK_SLEEP_DISABLE
+#define __SDIO_FORCE_RESET __HAL_RCC_SDIO_FORCE_RESET
+#define __SDIO_RELEASE_RESET __HAL_RCC_SDIO_RELEASE_RESET
+#define __SDIO_CLK_SLEEP_DISABLE __HAL_RCC_SDIO_CLK_SLEEP_DISABLE
+#define __SDIO_CLK_SLEEP_ENABLE __HAL_RCC_SDIO_CLK_SLEEP_ENABLE
+#define __DMA2D_CLK_ENABLE __HAL_RCC_DMA2D_CLK_ENABLE
+#define __DMA2D_CLK_DISABLE __HAL_RCC_DMA2D_CLK_DISABLE
+#define __DMA2D_FORCE_RESET __HAL_RCC_DMA2D_FORCE_RESET
+#define __DMA2D_RELEASE_RESET __HAL_RCC_DMA2D_RELEASE_RESET
+#define __DMA2D_CLK_SLEEP_ENABLE __HAL_RCC_DMA2D_CLK_SLEEP_ENABLE
+#define __DMA2D_CLK_SLEEP_DISABLE __HAL_RCC_DMA2D_CLK_SLEEP_DISABLE
+
+/* alias define maintained for legacy */
+#define __HAL_RCC_OTGFS_FORCE_RESET __HAL_RCC_USB_OTG_FS_FORCE_RESET
+#define __HAL_RCC_OTGFS_RELEASE_RESET __HAL_RCC_USB_OTG_FS_RELEASE_RESET
+
+#define __ADC12_CLK_ENABLE __HAL_RCC_ADC12_CLK_ENABLE
+#define __ADC12_CLK_DISABLE __HAL_RCC_ADC12_CLK_DISABLE
+#define __ADC34_CLK_ENABLE __HAL_RCC_ADC34_CLK_ENABLE
+#define __ADC34_CLK_DISABLE __HAL_RCC_ADC34_CLK_DISABLE
+#define __DAC2_CLK_ENABLE __HAL_RCC_DAC2_CLK_ENABLE
+#define __DAC2_CLK_DISABLE __HAL_RCC_DAC2_CLK_DISABLE
+#define __TIM18_CLK_ENABLE __HAL_RCC_TIM18_CLK_ENABLE
+#define __TIM18_CLK_DISABLE __HAL_RCC_TIM18_CLK_DISABLE
+#define __TIM19_CLK_ENABLE __HAL_RCC_TIM19_CLK_ENABLE
+#define __TIM19_CLK_DISABLE __HAL_RCC_TIM19_CLK_DISABLE
+#define __TIM20_CLK_ENABLE __HAL_RCC_TIM20_CLK_ENABLE
+#define __TIM20_CLK_DISABLE __HAL_RCC_TIM20_CLK_DISABLE
+#define __HRTIM1_CLK_ENABLE __HAL_RCC_HRTIM1_CLK_ENABLE
+#define __HRTIM1_CLK_DISABLE __HAL_RCC_HRTIM1_CLK_DISABLE
+#define __SDADC1_CLK_ENABLE __HAL_RCC_SDADC1_CLK_ENABLE
+#define __SDADC2_CLK_ENABLE __HAL_RCC_SDADC2_CLK_ENABLE
+#define __SDADC3_CLK_ENABLE __HAL_RCC_SDADC3_CLK_ENABLE
+#define __SDADC1_CLK_DISABLE __HAL_RCC_SDADC1_CLK_DISABLE
+#define __SDADC2_CLK_DISABLE __HAL_RCC_SDADC2_CLK_DISABLE
+#define __SDADC3_CLK_DISABLE __HAL_RCC_SDADC3_CLK_DISABLE
+
+#define __ADC12_FORCE_RESET __HAL_RCC_ADC12_FORCE_RESET
+#define __ADC12_RELEASE_RESET __HAL_RCC_ADC12_RELEASE_RESET
+#define __ADC34_FORCE_RESET __HAL_RCC_ADC34_FORCE_RESET
+#define __ADC34_RELEASE_RESET __HAL_RCC_ADC34_RELEASE_RESET
+#define __DAC2_FORCE_RESET __HAL_RCC_DAC2_FORCE_RESET
+#define __DAC2_RELEASE_RESET __HAL_RCC_DAC2_RELEASE_RESET
+#define __TIM18_FORCE_RESET __HAL_RCC_TIM18_FORCE_RESET
+#define __TIM18_RELEASE_RESET __HAL_RCC_TIM18_RELEASE_RESET
+#define __TIM19_FORCE_RESET __HAL_RCC_TIM19_FORCE_RESET
+#define __TIM19_RELEASE_RESET __HAL_RCC_TIM19_RELEASE_RESET
+#define __TIM20_FORCE_RESET __HAL_RCC_TIM20_FORCE_RESET
+#define __TIM20_RELEASE_RESET __HAL_RCC_TIM20_RELEASE_RESET
+#define __HRTIM1_FORCE_RESET __HAL_RCC_HRTIM1_FORCE_RESET
+#define __HRTIM1_RELEASE_RESET __HAL_RCC_HRTIM1_RELEASE_RESET
+#define __SDADC1_FORCE_RESET __HAL_RCC_SDADC1_FORCE_RESET
+#define __SDADC2_FORCE_RESET __HAL_RCC_SDADC2_FORCE_RESET
+#define __SDADC3_FORCE_RESET __HAL_RCC_SDADC3_FORCE_RESET
+#define __SDADC1_RELEASE_RESET __HAL_RCC_SDADC1_RELEASE_RESET
+#define __SDADC2_RELEASE_RESET __HAL_RCC_SDADC2_RELEASE_RESET
+#define __SDADC3_RELEASE_RESET __HAL_RCC_SDADC3_RELEASE_RESET
+
+#define __ADC1_IS_CLK_ENABLED __HAL_RCC_ADC1_IS_CLK_ENABLED
+#define __ADC1_IS_CLK_DISABLED __HAL_RCC_ADC1_IS_CLK_DISABLED
+#define __ADC12_IS_CLK_ENABLED __HAL_RCC_ADC12_IS_CLK_ENABLED
+#define __ADC12_IS_CLK_DISABLED __HAL_RCC_ADC12_IS_CLK_DISABLED
+#define __ADC34_IS_CLK_ENABLED __HAL_RCC_ADC34_IS_CLK_ENABLED
+#define __ADC34_IS_CLK_DISABLED __HAL_RCC_ADC34_IS_CLK_DISABLED
+#define __CEC_IS_CLK_ENABLED __HAL_RCC_CEC_IS_CLK_ENABLED
+#define __CEC_IS_CLK_DISABLED __HAL_RCC_CEC_IS_CLK_DISABLED
+#define __CRC_IS_CLK_ENABLED __HAL_RCC_CRC_IS_CLK_ENABLED
+#define __CRC_IS_CLK_DISABLED __HAL_RCC_CRC_IS_CLK_DISABLED
+#define __DAC1_IS_CLK_ENABLED __HAL_RCC_DAC1_IS_CLK_ENABLED
+#define __DAC1_IS_CLK_DISABLED __HAL_RCC_DAC1_IS_CLK_DISABLED
+#define __DAC2_IS_CLK_ENABLED __HAL_RCC_DAC2_IS_CLK_ENABLED
+#define __DAC2_IS_CLK_DISABLED __HAL_RCC_DAC2_IS_CLK_DISABLED
+#define __DMA1_IS_CLK_ENABLED __HAL_RCC_DMA1_IS_CLK_ENABLED
+#define __DMA1_IS_CLK_DISABLED __HAL_RCC_DMA1_IS_CLK_DISABLED
+#define __DMA2_IS_CLK_ENABLED __HAL_RCC_DMA2_IS_CLK_ENABLED
+#define __DMA2_IS_CLK_DISABLED __HAL_RCC_DMA2_IS_CLK_DISABLED
+#define __FLITF_IS_CLK_ENABLED __HAL_RCC_FLITF_IS_CLK_ENABLED
+#define __FLITF_IS_CLK_DISABLED __HAL_RCC_FLITF_IS_CLK_DISABLED
+#define __FMC_IS_CLK_ENABLED __HAL_RCC_FMC_IS_CLK_ENABLED
+#define __FMC_IS_CLK_DISABLED __HAL_RCC_FMC_IS_CLK_DISABLED
+#define __GPIOA_IS_CLK_ENABLED __HAL_RCC_GPIOA_IS_CLK_ENABLED
+#define __GPIOA_IS_CLK_DISABLED __HAL_RCC_GPIOA_IS_CLK_DISABLED
+#define __GPIOB_IS_CLK_ENABLED __HAL_RCC_GPIOB_IS_CLK_ENABLED
+#define __GPIOB_IS_CLK_DISABLED __HAL_RCC_GPIOB_IS_CLK_DISABLED
+#define __GPIOC_IS_CLK_ENABLED __HAL_RCC_GPIOC_IS_CLK_ENABLED
+#define __GPIOC_IS_CLK_DISABLED __HAL_RCC_GPIOC_IS_CLK_DISABLED
+#define __GPIOD_IS_CLK_ENABLED __HAL_RCC_GPIOD_IS_CLK_ENABLED
+#define __GPIOD_IS_CLK_DISABLED __HAL_RCC_GPIOD_IS_CLK_DISABLED
+#define __GPIOE_IS_CLK_ENABLED __HAL_RCC_GPIOE_IS_CLK_ENABLED
+#define __GPIOE_IS_CLK_DISABLED __HAL_RCC_GPIOE_IS_CLK_DISABLED
+#define __GPIOF_IS_CLK_ENABLED __HAL_RCC_GPIOF_IS_CLK_ENABLED
+#define __GPIOF_IS_CLK_DISABLED __HAL_RCC_GPIOF_IS_CLK_DISABLED
+#define __GPIOG_IS_CLK_ENABLED __HAL_RCC_GPIOG_IS_CLK_ENABLED
+#define __GPIOG_IS_CLK_DISABLED __HAL_RCC_GPIOG_IS_CLK_DISABLED
+#define __GPIOH_IS_CLK_ENABLED __HAL_RCC_GPIOH_IS_CLK_ENABLED
+#define __GPIOH_IS_CLK_DISABLED __HAL_RCC_GPIOH_IS_CLK_DISABLED
+#define __HRTIM1_IS_CLK_ENABLED __HAL_RCC_HRTIM1_IS_CLK_ENABLED
+#define __HRTIM1_IS_CLK_DISABLED __HAL_RCC_HRTIM1_IS_CLK_DISABLED
+#define __I2C1_IS_CLK_ENABLED __HAL_RCC_I2C1_IS_CLK_ENABLED
+#define __I2C1_IS_CLK_DISABLED __HAL_RCC_I2C1_IS_CLK_DISABLED
+#define __I2C2_IS_CLK_ENABLED __HAL_RCC_I2C2_IS_CLK_ENABLED
+#define __I2C2_IS_CLK_DISABLED __HAL_RCC_I2C2_IS_CLK_DISABLED
+#define __I2C3_IS_CLK_ENABLED __HAL_RCC_I2C3_IS_CLK_ENABLED
+#define __I2C3_IS_CLK_DISABLED __HAL_RCC_I2C3_IS_CLK_DISABLED
+#define __PWR_IS_CLK_ENABLED __HAL_RCC_PWR_IS_CLK_ENABLED
+#define __PWR_IS_CLK_DISABLED __HAL_RCC_PWR_IS_CLK_DISABLED
+#define __SYSCFG_IS_CLK_ENABLED __HAL_RCC_SYSCFG_IS_CLK_ENABLED
+#define __SYSCFG_IS_CLK_DISABLED __HAL_RCC_SYSCFG_IS_CLK_DISABLED
+#define __SPI1_IS_CLK_ENABLED __HAL_RCC_SPI1_IS_CLK_ENABLED
+#define __SPI1_IS_CLK_DISABLED __HAL_RCC_SPI1_IS_CLK_DISABLED
+#define __SPI2_IS_CLK_ENABLED __HAL_RCC_SPI2_IS_CLK_ENABLED
+#define __SPI2_IS_CLK_DISABLED __HAL_RCC_SPI2_IS_CLK_DISABLED
+#define __SPI3_IS_CLK_ENABLED __HAL_RCC_SPI3_IS_CLK_ENABLED
+#define __SPI3_IS_CLK_DISABLED __HAL_RCC_SPI3_IS_CLK_DISABLED
+#define __SPI4_IS_CLK_ENABLED __HAL_RCC_SPI4_IS_CLK_ENABLED
+#define __SPI4_IS_CLK_DISABLED __HAL_RCC_SPI4_IS_CLK_DISABLED
+#define __SDADC1_IS_CLK_ENABLED __HAL_RCC_SDADC1_IS_CLK_ENABLED
+#define __SDADC1_IS_CLK_DISABLED __HAL_RCC_SDADC1_IS_CLK_DISABLED
+#define __SDADC2_IS_CLK_ENABLED __HAL_RCC_SDADC2_IS_CLK_ENABLED
+#define __SDADC2_IS_CLK_DISABLED __HAL_RCC_SDADC2_IS_CLK_DISABLED
+#define __SDADC3_IS_CLK_ENABLED __HAL_RCC_SDADC3_IS_CLK_ENABLED
+#define __SDADC3_IS_CLK_DISABLED __HAL_RCC_SDADC3_IS_CLK_DISABLED
+#define __SRAM_IS_CLK_ENABLED __HAL_RCC_SRAM_IS_CLK_ENABLED
+#define __SRAM_IS_CLK_DISABLED __HAL_RCC_SRAM_IS_CLK_DISABLED
+#define __TIM1_IS_CLK_ENABLED __HAL_RCC_TIM1_IS_CLK_ENABLED
+#define __TIM1_IS_CLK_DISABLED __HAL_RCC_TIM1_IS_CLK_DISABLED
+#define __TIM2_IS_CLK_ENABLED __HAL_RCC_TIM2_IS_CLK_ENABLED
+#define __TIM2_IS_CLK_DISABLED __HAL_RCC_TIM2_IS_CLK_DISABLED
+#define __TIM3_IS_CLK_ENABLED __HAL_RCC_TIM3_IS_CLK_ENABLED
+#define __TIM3_IS_CLK_DISABLED __HAL_RCC_TIM3_IS_CLK_DISABLED
+#define __TIM4_IS_CLK_ENABLED __HAL_RCC_TIM4_IS_CLK_ENABLED
+#define __TIM4_IS_CLK_DISABLED __HAL_RCC_TIM4_IS_CLK_DISABLED
+#define __TIM5_IS_CLK_ENABLED __HAL_RCC_TIM5_IS_CLK_ENABLED
+#define __TIM5_IS_CLK_DISABLED __HAL_RCC_TIM5_IS_CLK_DISABLED
+#define __TIM6_IS_CLK_ENABLED __HAL_RCC_TIM6_IS_CLK_ENABLED
+#define __TIM6_IS_CLK_DISABLED __HAL_RCC_TIM6_IS_CLK_DISABLED
+#define __TIM7_IS_CLK_ENABLED __HAL_RCC_TIM7_IS_CLK_ENABLED
+#define __TIM7_IS_CLK_DISABLED __HAL_RCC_TIM7_IS_CLK_DISABLED
+#define __TIM8_IS_CLK_ENABLED __HAL_RCC_TIM8_IS_CLK_ENABLED
+#define __TIM8_IS_CLK_DISABLED __HAL_RCC_TIM8_IS_CLK_DISABLED
+#define __TIM12_IS_CLK_ENABLED __HAL_RCC_TIM12_IS_CLK_ENABLED
+#define __TIM12_IS_CLK_DISABLED __HAL_RCC_TIM12_IS_CLK_DISABLED
+#define __TIM13_IS_CLK_ENABLED __HAL_RCC_TIM13_IS_CLK_ENABLED
+#define __TIM13_IS_CLK_DISABLED __HAL_RCC_TIM13_IS_CLK_DISABLED
+#define __TIM14_IS_CLK_ENABLED __HAL_RCC_TIM14_IS_CLK_ENABLED
+#define __TIM14_IS_CLK_DISABLED __HAL_RCC_TIM14_IS_CLK_DISABLED
+#define __TIM15_IS_CLK_ENABLED __HAL_RCC_TIM15_IS_CLK_ENABLED
+#define __TIM15_IS_CLK_DISABLED __HAL_RCC_TIM15_IS_CLK_DISABLED
+#define __TIM16_IS_CLK_ENABLED __HAL_RCC_TIM16_IS_CLK_ENABLED
+#define __TIM16_IS_CLK_DISABLED __HAL_RCC_TIM16_IS_CLK_DISABLED
+#define __TIM17_IS_CLK_ENABLED __HAL_RCC_TIM17_IS_CLK_ENABLED
+#define __TIM17_IS_CLK_DISABLED __HAL_RCC_TIM17_IS_CLK_DISABLED
+#define __TIM18_IS_CLK_ENABLED __HAL_RCC_TIM18_IS_CLK_ENABLED
+#define __TIM18_IS_CLK_DISABLED __HAL_RCC_TIM18_IS_CLK_DISABLED
+#define __TIM19_IS_CLK_ENABLED __HAL_RCC_TIM19_IS_CLK_ENABLED
+#define __TIM19_IS_CLK_DISABLED __HAL_RCC_TIM19_IS_CLK_DISABLED
+#define __TIM20_IS_CLK_ENABLED __HAL_RCC_TIM20_IS_CLK_ENABLED
+#define __TIM20_IS_CLK_DISABLED __HAL_RCC_TIM20_IS_CLK_DISABLED
+#define __TSC_IS_CLK_ENABLED __HAL_RCC_TSC_IS_CLK_ENABLED
+#define __TSC_IS_CLK_DISABLED __HAL_RCC_TSC_IS_CLK_DISABLED
+#define __UART4_IS_CLK_ENABLED __HAL_RCC_UART4_IS_CLK_ENABLED
+#define __UART4_IS_CLK_DISABLED __HAL_RCC_UART4_IS_CLK_DISABLED
+#define __UART5_IS_CLK_ENABLED __HAL_RCC_UART5_IS_CLK_ENABLED
+#define __UART5_IS_CLK_DISABLED __HAL_RCC_UART5_IS_CLK_DISABLED
+#define __USART1_IS_CLK_ENABLED __HAL_RCC_USART1_IS_CLK_ENABLED
+#define __USART1_IS_CLK_DISABLED __HAL_RCC_USART1_IS_CLK_DISABLED
+#define __USART2_IS_CLK_ENABLED __HAL_RCC_USART2_IS_CLK_ENABLED
+#define __USART2_IS_CLK_DISABLED __HAL_RCC_USART2_IS_CLK_DISABLED
+#define __USART3_IS_CLK_ENABLED __HAL_RCC_USART3_IS_CLK_ENABLED
+#define __USART3_IS_CLK_DISABLED __HAL_RCC_USART3_IS_CLK_DISABLED
+#define __USB_IS_CLK_ENABLED __HAL_RCC_USB_IS_CLK_ENABLED
+#define __USB_IS_CLK_DISABLED __HAL_RCC_USB_IS_CLK_DISABLED
+#define __WWDG_IS_CLK_ENABLED __HAL_RCC_WWDG_IS_CLK_ENABLED
+#define __WWDG_IS_CLK_DISABLED __HAL_RCC_WWDG_IS_CLK_DISABLED
+
+#if defined(STM32L1)
+#define __HAL_RCC_CRYP_CLK_DISABLE __HAL_RCC_AES_CLK_DISABLE
+#define __HAL_RCC_CRYP_CLK_ENABLE __HAL_RCC_AES_CLK_ENABLE
+#define __HAL_RCC_CRYP_CLK_SLEEP_DISABLE __HAL_RCC_AES_CLK_SLEEP_DISABLE
+#define __HAL_RCC_CRYP_CLK_SLEEP_ENABLE __HAL_RCC_AES_CLK_SLEEP_ENABLE
+#define __HAL_RCC_CRYP_FORCE_RESET __HAL_RCC_AES_FORCE_RESET
+#define __HAL_RCC_CRYP_RELEASE_RESET __HAL_RCC_AES_RELEASE_RESET
+#endif /* STM32L1 */
+
+#if defined(STM32F4)
+#define __HAL_RCC_SDMMC1_FORCE_RESET __HAL_RCC_SDIO_FORCE_RESET
+#define __HAL_RCC_SDMMC1_RELEASE_RESET __HAL_RCC_SDIO_RELEASE_RESET
+#define __HAL_RCC_SDMMC1_CLK_SLEEP_ENABLE __HAL_RCC_SDIO_CLK_SLEEP_ENABLE
+#define __HAL_RCC_SDMMC1_CLK_SLEEP_DISABLE __HAL_RCC_SDIO_CLK_SLEEP_DISABLE
+#define __HAL_RCC_SDMMC1_CLK_ENABLE __HAL_RCC_SDIO_CLK_ENABLE
+#define __HAL_RCC_SDMMC1_CLK_DISABLE __HAL_RCC_SDIO_CLK_DISABLE
+#define __HAL_RCC_SDMMC1_IS_CLK_ENABLED __HAL_RCC_SDIO_IS_CLK_ENABLED
+#define __HAL_RCC_SDMMC1_IS_CLK_DISABLED __HAL_RCC_SDIO_IS_CLK_DISABLED
+#define Sdmmc1ClockSelection SdioClockSelection
+#define RCC_PERIPHCLK_SDMMC1 RCC_PERIPHCLK_SDIO
+#define RCC_SDMMC1CLKSOURCE_CLK48 RCC_SDIOCLKSOURCE_CK48
+#define RCC_SDMMC1CLKSOURCE_SYSCLK RCC_SDIOCLKSOURCE_SYSCLK
+#define __HAL_RCC_SDMMC1_CONFIG __HAL_RCC_SDIO_CONFIG
+#define __HAL_RCC_GET_SDMMC1_SOURCE __HAL_RCC_GET_SDIO_SOURCE
+#endif
+
+#if defined(STM32F7) || defined(STM32L4)
+#define __HAL_RCC_SDIO_FORCE_RESET __HAL_RCC_SDMMC1_FORCE_RESET
+#define __HAL_RCC_SDIO_RELEASE_RESET __HAL_RCC_SDMMC1_RELEASE_RESET
+#define __HAL_RCC_SDIO_CLK_SLEEP_ENABLE __HAL_RCC_SDMMC1_CLK_SLEEP_ENABLE
+#define __HAL_RCC_SDIO_CLK_SLEEP_DISABLE __HAL_RCC_SDMMC1_CLK_SLEEP_DISABLE
+#define __HAL_RCC_SDIO_CLK_ENABLE __HAL_RCC_SDMMC1_CLK_ENABLE
+#define __HAL_RCC_SDIO_CLK_DISABLE __HAL_RCC_SDMMC1_CLK_DISABLE
+#define __HAL_RCC_SDIO_IS_CLK_ENABLED __HAL_RCC_SDMMC1_IS_CLK_ENABLED
+#define __HAL_RCC_SDIO_IS_CLK_DISABLED __HAL_RCC_SDMMC1_IS_CLK_DISABLED
+#define SdioClockSelection Sdmmc1ClockSelection
+#define RCC_PERIPHCLK_SDIO RCC_PERIPHCLK_SDMMC1
+#define __HAL_RCC_SDIO_CONFIG __HAL_RCC_SDMMC1_CONFIG
+#define __HAL_RCC_GET_SDIO_SOURCE __HAL_RCC_GET_SDMMC1_SOURCE
+#endif
+
+#if defined(STM32F7)
+#define RCC_SDIOCLKSOURCE_CLK48 RCC_SDMMC1CLKSOURCE_CLK48
+#define RCC_SDIOCLKSOURCE_SYSCLK RCC_SDMMC1CLKSOURCE_SYSCLK
+#endif
+
+#if defined(STM32H7)
+#define __HAL_RCC_USB_OTG_HS_CLK_ENABLE() __HAL_RCC_USB1_OTG_HS_CLK_ENABLE()
+#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_ENABLE() __HAL_RCC_USB1_OTG_HS_ULPI_CLK_ENABLE()
+#define __HAL_RCC_USB_OTG_HS_CLK_DISABLE() __HAL_RCC_USB1_OTG_HS_CLK_DISABLE()
+#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_DISABLE() __HAL_RCC_USB1_OTG_HS_ULPI_CLK_DISABLE()
+#define __HAL_RCC_USB_OTG_HS_FORCE_RESET() __HAL_RCC_USB1_OTG_HS_FORCE_RESET()
+#define __HAL_RCC_USB_OTG_HS_RELEASE_RESET() __HAL_RCC_USB1_OTG_HS_RELEASE_RESET()
+#define __HAL_RCC_USB_OTG_HS_CLK_SLEEP_ENABLE() __HAL_RCC_USB1_OTG_HS_CLK_SLEEP_ENABLE()
+#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_SLEEP_ENABLE() __HAL_RCC_USB1_OTG_HS_ULPI_CLK_SLEEP_ENABLE()
+#define __HAL_RCC_USB_OTG_HS_CLK_SLEEP_DISABLE() __HAL_RCC_USB1_OTG_HS_CLK_SLEEP_DISABLE()
+#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_SLEEP_DISABLE() __HAL_RCC_USB1_OTG_HS_ULPI_CLK_SLEEP_DISABLE()
+
+#define __HAL_RCC_USB_OTG_FS_CLK_ENABLE() __HAL_RCC_USB2_OTG_FS_CLK_ENABLE()
+#define __HAL_RCC_USB_OTG_FS_ULPI_CLK_ENABLE() __HAL_RCC_USB2_OTG_FS_ULPI_CLK_ENABLE()
+#define __HAL_RCC_USB_OTG_FS_CLK_DISABLE() __HAL_RCC_USB2_OTG_FS_CLK_DISABLE()
+#define __HAL_RCC_USB_OTG_FS_ULPI_CLK_DISABLE() __HAL_RCC_USB2_OTG_FS_ULPI_CLK_DISABLE()
+#define __HAL_RCC_USB_OTG_FS_FORCE_RESET() __HAL_RCC_USB2_OTG_FS_FORCE_RESET()
+#define __HAL_RCC_USB_OTG_FS_RELEASE_RESET() __HAL_RCC_USB2_OTG_FS_RELEASE_RESET()
+#define __HAL_RCC_USB_OTG_FS_CLK_SLEEP_ENABLE() __HAL_RCC_USB2_OTG_FS_CLK_SLEEP_ENABLE()
+#define __HAL_RCC_USB_OTG_FS_ULPI_CLK_SLEEP_ENABLE() __HAL_RCC_USB2_OTG_FS_ULPI_CLK_SLEEP_ENABLE()
+#define __HAL_RCC_USB_OTG_FS_CLK_SLEEP_DISABLE() __HAL_RCC_USB2_OTG_FS_CLK_SLEEP_DISABLE()
+#define __HAL_RCC_USB_OTG_FS_ULPI_CLK_SLEEP_DISABLE() __HAL_RCC_USB2_OTG_FS_ULPI_CLK_SLEEP_DISABLE()
+#endif
+
+#define __HAL_RCC_I2SCLK __HAL_RCC_I2S_CONFIG
+#define __HAL_RCC_I2SCLK_CONFIG __HAL_RCC_I2S_CONFIG
+
+#define __RCC_PLLSRC RCC_GET_PLL_OSCSOURCE
+
+#define IS_RCC_MSIRANGE IS_RCC_MSI_CLOCK_RANGE
+#define IS_RCC_RTCCLK_SOURCE IS_RCC_RTCCLKSOURCE
+#define IS_RCC_SYSCLK_DIV IS_RCC_HCLK
+#define IS_RCC_HCLK_DIV IS_RCC_PCLK
+#define IS_RCC_PERIPHCLK IS_RCC_PERIPHCLOCK
+
+#define RCC_IT_HSI14 RCC_IT_HSI14RDY
+
+#define RCC_IT_CSSLSE RCC_IT_LSECSS
+#define RCC_IT_CSSHSE RCC_IT_CSS
+
+#define RCC_PLLMUL_3 RCC_PLL_MUL3
+#define RCC_PLLMUL_4 RCC_PLL_MUL4
+#define RCC_PLLMUL_6 RCC_PLL_MUL6
+#define RCC_PLLMUL_8 RCC_PLL_MUL8
+#define RCC_PLLMUL_12 RCC_PLL_MUL12
+#define RCC_PLLMUL_16 RCC_PLL_MUL16
+#define RCC_PLLMUL_24 RCC_PLL_MUL24
+#define RCC_PLLMUL_32 RCC_PLL_MUL32
+#define RCC_PLLMUL_48 RCC_PLL_MUL48
+
+#define RCC_PLLDIV_2 RCC_PLL_DIV2
+#define RCC_PLLDIV_3 RCC_PLL_DIV3
+#define RCC_PLLDIV_4 RCC_PLL_DIV4
+
+#define IS_RCC_MCOSOURCE IS_RCC_MCO1SOURCE
+#define __HAL_RCC_MCO_CONFIG __HAL_RCC_MCO1_CONFIG
+#define RCC_MCO_NODIV RCC_MCODIV_1
+#define RCC_MCO_DIV1 RCC_MCODIV_1
+#define RCC_MCO_DIV2 RCC_MCODIV_2
+#define RCC_MCO_DIV4 RCC_MCODIV_4
+#define RCC_MCO_DIV8 RCC_MCODIV_8
+#define RCC_MCO_DIV16 RCC_MCODIV_16
+#define RCC_MCO_DIV32 RCC_MCODIV_32
+#define RCC_MCO_DIV64 RCC_MCODIV_64
+#define RCC_MCO_DIV128 RCC_MCODIV_128
+#define RCC_MCOSOURCE_NONE RCC_MCO1SOURCE_NOCLOCK
+#define RCC_MCOSOURCE_LSI RCC_MCO1SOURCE_LSI
+#define RCC_MCOSOURCE_LSE RCC_MCO1SOURCE_LSE
+#define RCC_MCOSOURCE_SYSCLK RCC_MCO1SOURCE_SYSCLK
+#define RCC_MCOSOURCE_HSI RCC_MCO1SOURCE_HSI
+#define RCC_MCOSOURCE_HSI14 RCC_MCO1SOURCE_HSI14
+#define RCC_MCOSOURCE_HSI48 RCC_MCO1SOURCE_HSI48
+#define RCC_MCOSOURCE_HSE RCC_MCO1SOURCE_HSE
+#define RCC_MCOSOURCE_PLLCLK_DIV1 RCC_MCO1SOURCE_PLLCLK
+#define RCC_MCOSOURCE_PLLCLK_NODIV RCC_MCO1SOURCE_PLLCLK
+#define RCC_MCOSOURCE_PLLCLK_DIV2 RCC_MCO1SOURCE_PLLCLK_DIV2
+
+#if defined(STM32L4) || defined(STM32WB) || defined(STM32G0) || defined(STM32G4) || defined(STM32L5) || defined(STM32WL)
+#define RCC_RTCCLKSOURCE_NO_CLK RCC_RTCCLKSOURCE_NONE
+#else
+#define RCC_RTCCLKSOURCE_NONE RCC_RTCCLKSOURCE_NO_CLK
+#endif
+
+#define RCC_USBCLK_PLLSAI1 RCC_USBCLKSOURCE_PLLSAI1
+#define RCC_USBCLK_PLL RCC_USBCLKSOURCE_PLL
+#define RCC_USBCLK_MSI RCC_USBCLKSOURCE_MSI
+#define RCC_USBCLKSOURCE_PLLCLK RCC_USBCLKSOURCE_PLL
+#define RCC_USBPLLCLK_DIV1 RCC_USBCLKSOURCE_PLL
+#define RCC_USBPLLCLK_DIV1_5 RCC_USBCLKSOURCE_PLL_DIV1_5
+#define RCC_USBPLLCLK_DIV2 RCC_USBCLKSOURCE_PLL_DIV2
+#define RCC_USBPLLCLK_DIV3 RCC_USBCLKSOURCE_PLL_DIV3
+
+#define HSION_BitNumber RCC_HSION_BIT_NUMBER
+#define HSION_BITNUMBER RCC_HSION_BIT_NUMBER
+#define HSEON_BitNumber RCC_HSEON_BIT_NUMBER
+#define HSEON_BITNUMBER RCC_HSEON_BIT_NUMBER
+#define MSION_BITNUMBER RCC_MSION_BIT_NUMBER
+#define CSSON_BitNumber RCC_CSSON_BIT_NUMBER
+#define CSSON_BITNUMBER RCC_CSSON_BIT_NUMBER
+#define PLLON_BitNumber RCC_PLLON_BIT_NUMBER
+#define PLLON_BITNUMBER RCC_PLLON_BIT_NUMBER
+#define PLLI2SON_BitNumber RCC_PLLI2SON_BIT_NUMBER
+#define I2SSRC_BitNumber RCC_I2SSRC_BIT_NUMBER
+#define RTCEN_BitNumber RCC_RTCEN_BIT_NUMBER
+#define RTCEN_BITNUMBER RCC_RTCEN_BIT_NUMBER
+#define BDRST_BitNumber RCC_BDRST_BIT_NUMBER
+#define BDRST_BITNUMBER RCC_BDRST_BIT_NUMBER
+#define RTCRST_BITNUMBER RCC_RTCRST_BIT_NUMBER
+#define LSION_BitNumber RCC_LSION_BIT_NUMBER
+#define LSION_BITNUMBER RCC_LSION_BIT_NUMBER
+#define LSEON_BitNumber RCC_LSEON_BIT_NUMBER
+#define LSEON_BITNUMBER RCC_LSEON_BIT_NUMBER
+#define LSEBYP_BITNUMBER RCC_LSEBYP_BIT_NUMBER
+#define PLLSAION_BitNumber RCC_PLLSAION_BIT_NUMBER
+#define TIMPRE_BitNumber RCC_TIMPRE_BIT_NUMBER
+#define RMVF_BitNumber RCC_RMVF_BIT_NUMBER
+#define RMVF_BITNUMBER RCC_RMVF_BIT_NUMBER
+#define RCC_CR2_HSI14TRIM_BitNumber RCC_HSI14TRIM_BIT_NUMBER
+#define CR_BYTE2_ADDRESS RCC_CR_BYTE2_ADDRESS
+#define CIR_BYTE1_ADDRESS RCC_CIR_BYTE1_ADDRESS
+#define CIR_BYTE2_ADDRESS RCC_CIR_BYTE2_ADDRESS
+#define BDCR_BYTE0_ADDRESS RCC_BDCR_BYTE0_ADDRESS
+#define DBP_TIMEOUT_VALUE RCC_DBP_TIMEOUT_VALUE
+#define LSE_TIMEOUT_VALUE RCC_LSE_TIMEOUT_VALUE
+
+#define CR_HSION_BB RCC_CR_HSION_BB
+#define CR_CSSON_BB RCC_CR_CSSON_BB
+#define CR_PLLON_BB RCC_CR_PLLON_BB
+#define CR_PLLI2SON_BB RCC_CR_PLLI2SON_BB
+#define CR_MSION_BB RCC_CR_MSION_BB
+#define CSR_LSION_BB RCC_CSR_LSION_BB
+#define CSR_LSEON_BB RCC_CSR_LSEON_BB
+#define CSR_LSEBYP_BB RCC_CSR_LSEBYP_BB
+#define CSR_RTCEN_BB RCC_CSR_RTCEN_BB
+#define CSR_RTCRST_BB RCC_CSR_RTCRST_BB
+#define CFGR_I2SSRC_BB RCC_CFGR_I2SSRC_BB
+#define BDCR_RTCEN_BB RCC_BDCR_RTCEN_BB
+#define BDCR_BDRST_BB RCC_BDCR_BDRST_BB
+#define CR_HSEON_BB RCC_CR_HSEON_BB
+#define CSR_RMVF_BB RCC_CSR_RMVF_BB
+#define CR_PLLSAION_BB RCC_CR_PLLSAION_BB
+#define DCKCFGR_TIMPRE_BB RCC_DCKCFGR_TIMPRE_BB
+
+#define __HAL_RCC_CRS_ENABLE_FREQ_ERROR_COUNTER __HAL_RCC_CRS_FREQ_ERROR_COUNTER_ENABLE
+#define __HAL_RCC_CRS_DISABLE_FREQ_ERROR_COUNTER __HAL_RCC_CRS_FREQ_ERROR_COUNTER_DISABLE
+#define __HAL_RCC_CRS_ENABLE_AUTOMATIC_CALIB __HAL_RCC_CRS_AUTOMATIC_CALIB_ENABLE
+#define __HAL_RCC_CRS_DISABLE_AUTOMATIC_CALIB __HAL_RCC_CRS_AUTOMATIC_CALIB_DISABLE
+#define __HAL_RCC_CRS_CALCULATE_RELOADVALUE __HAL_RCC_CRS_RELOADVALUE_CALCULATE
+
+#define __HAL_RCC_GET_IT_SOURCE __HAL_RCC_GET_IT
+
+#define RCC_CRS_SYNCWARM RCC_CRS_SYNCWARN
+#define RCC_CRS_TRIMOV RCC_CRS_TRIMOVF
+
+#define RCC_PERIPHCLK_CK48 RCC_PERIPHCLK_CLK48
+#define RCC_CK48CLKSOURCE_PLLQ RCC_CLK48CLKSOURCE_PLLQ
+#define RCC_CK48CLKSOURCE_PLLSAIP RCC_CLK48CLKSOURCE_PLLSAIP
+#define RCC_CK48CLKSOURCE_PLLI2SQ RCC_CLK48CLKSOURCE_PLLI2SQ
+#define IS_RCC_CK48CLKSOURCE IS_RCC_CLK48CLKSOURCE
+#define RCC_SDIOCLKSOURCE_CK48 RCC_SDIOCLKSOURCE_CLK48
+
+#define __HAL_RCC_DFSDM_CLK_ENABLE __HAL_RCC_DFSDM1_CLK_ENABLE
+#define __HAL_RCC_DFSDM_CLK_DISABLE __HAL_RCC_DFSDM1_CLK_DISABLE
+#define __HAL_RCC_DFSDM_IS_CLK_ENABLED __HAL_RCC_DFSDM1_IS_CLK_ENABLED
+#define __HAL_RCC_DFSDM_IS_CLK_DISABLED __HAL_RCC_DFSDM1_IS_CLK_DISABLED
+#define __HAL_RCC_DFSDM_FORCE_RESET __HAL_RCC_DFSDM1_FORCE_RESET
+#define __HAL_RCC_DFSDM_RELEASE_RESET __HAL_RCC_DFSDM1_RELEASE_RESET
+#define __HAL_RCC_DFSDM_CLK_SLEEP_ENABLE __HAL_RCC_DFSDM1_CLK_SLEEP_ENABLE
+#define __HAL_RCC_DFSDM_CLK_SLEEP_DISABLE __HAL_RCC_DFSDM1_CLK_SLEEP_DISABLE
+#define __HAL_RCC_DFSDM_IS_CLK_SLEEP_ENABLED __HAL_RCC_DFSDM1_IS_CLK_SLEEP_ENABLED
+#define __HAL_RCC_DFSDM_IS_CLK_SLEEP_DISABLED __HAL_RCC_DFSDM1_IS_CLK_SLEEP_DISABLED
+#define DfsdmClockSelection Dfsdm1ClockSelection
+#define RCC_PERIPHCLK_DFSDM RCC_PERIPHCLK_DFSDM1
+#define RCC_DFSDMCLKSOURCE_PCLK RCC_DFSDM1CLKSOURCE_PCLK2
+#define RCC_DFSDMCLKSOURCE_SYSCLK RCC_DFSDM1CLKSOURCE_SYSCLK
+#define __HAL_RCC_DFSDM_CONFIG __HAL_RCC_DFSDM1_CONFIG
+#define __HAL_RCC_GET_DFSDM_SOURCE __HAL_RCC_GET_DFSDM1_SOURCE
+#define RCC_DFSDM1CLKSOURCE_PCLK RCC_DFSDM1CLKSOURCE_PCLK2
+#define RCC_SWPMI1CLKSOURCE_PCLK RCC_SWPMI1CLKSOURCE_PCLK1
+#define RCC_LPTIM1CLKSOURCE_PCLK RCC_LPTIM1CLKSOURCE_PCLK1
+#define RCC_LPTIM2CLKSOURCE_PCLK RCC_LPTIM2CLKSOURCE_PCLK1
+
+#define RCC_DFSDM1AUDIOCLKSOURCE_I2SAPB1 RCC_DFSDM1AUDIOCLKSOURCE_I2S1
+#define RCC_DFSDM1AUDIOCLKSOURCE_I2SAPB2 RCC_DFSDM1AUDIOCLKSOURCE_I2S2
+#define RCC_DFSDM2AUDIOCLKSOURCE_I2SAPB1 RCC_DFSDM2AUDIOCLKSOURCE_I2S1
+#define RCC_DFSDM2AUDIOCLKSOURCE_I2SAPB2 RCC_DFSDM2AUDIOCLKSOURCE_I2S2
+#define RCC_DFSDM1CLKSOURCE_APB2 RCC_DFSDM1CLKSOURCE_PCLK2
+#define RCC_DFSDM2CLKSOURCE_APB2 RCC_DFSDM2CLKSOURCE_PCLK2
+#define RCC_FMPI2C1CLKSOURCE_APB RCC_FMPI2C1CLKSOURCE_PCLK1
+#if defined(STM32U5)
+#define MSIKPLLModeSEL RCC_MSIKPLL_MODE_SEL
+#define MSISPLLModeSEL RCC_MSISPLL_MODE_SEL
+#define __HAL_RCC_AHB21_CLK_DISABLE __HAL_RCC_AHB2_1_CLK_DISABLE
+#define __HAL_RCC_AHB22_CLK_DISABLE __HAL_RCC_AHB2_2_CLK_DISABLE
+#define __HAL_RCC_AHB1_CLK_Disable_Clear __HAL_RCC_AHB1_CLK_ENABLE
+#define __HAL_RCC_AHB21_CLK_Disable_Clear __HAL_RCC_AHB2_1_CLK_ENABLE
+#define __HAL_RCC_AHB22_CLK_Disable_Clear __HAL_RCC_AHB2_2_CLK_ENABLE
+#define __HAL_RCC_AHB3_CLK_Disable_Clear __HAL_RCC_AHB3_CLK_ENABLE
+#define __HAL_RCC_APB1_CLK_Disable_Clear __HAL_RCC_APB1_CLK_ENABLE
+#define __HAL_RCC_APB2_CLK_Disable_Clear __HAL_RCC_APB2_CLK_ENABLE
+#define __HAL_RCC_APB3_CLK_Disable_Clear __HAL_RCC_APB3_CLK_ENABLE
+#define IS_RCC_MSIPLLModeSelection IS_RCC_MSIPLLMODE_SELECT
+#endif
+/**
+ * @}
+ */
+
+/** @defgroup HAL_RNG_Aliased_Macros HAL RNG Aliased Macros maintained for legacy purpose
+ * @{
+ */
+#define HAL_RNG_ReadyCallback(__HANDLE__) HAL_RNG_ReadyDataCallback((__HANDLE__), uint32_t random32bit)
+
+/**
+ * @}
+ */
+
+/** @defgroup HAL_RTC_Aliased_Macros HAL RTC Aliased Macros maintained for legacy purpose
+ * @{
+ */
+#if defined (STM32G0) || defined (STM32L5) || defined (STM32L412xx) || defined (STM32L422xx) || defined (STM32L4P5xx) || defined (STM32L4Q5xx) || defined (STM32G4) || defined (STM32WL) || defined (STM32U5)
+#else
+#define __HAL_RTC_CLEAR_FLAG __HAL_RTC_EXTI_CLEAR_FLAG
+#endif
+#define __HAL_RTC_DISABLE_IT __HAL_RTC_EXTI_DISABLE_IT
+#define __HAL_RTC_ENABLE_IT __HAL_RTC_EXTI_ENABLE_IT
+
+#if defined (STM32F1)
+#define __HAL_RTC_EXTI_CLEAR_FLAG(RTC_EXTI_LINE_ALARM_EVENT) __HAL_RTC_ALARM_EXTI_CLEAR_FLAG()
+
+#define __HAL_RTC_EXTI_ENABLE_IT(RTC_EXTI_LINE_ALARM_EVENT) __HAL_RTC_ALARM_EXTI_ENABLE_IT()
+
+#define __HAL_RTC_EXTI_DISABLE_IT(RTC_EXTI_LINE_ALARM_EVENT) __HAL_RTC_ALARM_EXTI_DISABLE_IT()
+
+#define __HAL_RTC_EXTI_GET_FLAG(RTC_EXTI_LINE_ALARM_EVENT) __HAL_RTC_ALARM_EXTI_GET_FLAG()
+
+#define __HAL_RTC_EXTI_GENERATE_SWIT(RTC_EXTI_LINE_ALARM_EVENT) __HAL_RTC_ALARM_EXTI_GENERATE_SWIT()
+#else
+#define __HAL_RTC_EXTI_CLEAR_FLAG(__EXTI_LINE__) (((__EXTI_LINE__) == RTC_EXTI_LINE_ALARM_EVENT) ? __HAL_RTC_ALARM_EXTI_CLEAR_FLAG() : \
+ (((__EXTI_LINE__) == RTC_EXTI_LINE_WAKEUPTIMER_EVENT) ? __HAL_RTC_WAKEUPTIMER_EXTI_CLEAR_FLAG() : \
+ __HAL_RTC_TAMPER_TIMESTAMP_EXTI_CLEAR_FLAG()))
+#define __HAL_RTC_EXTI_ENABLE_IT(__EXTI_LINE__) (((__EXTI_LINE__) == RTC_EXTI_LINE_ALARM_EVENT) ? __HAL_RTC_ALARM_EXTI_ENABLE_IT() : \
+ (((__EXTI_LINE__) == RTC_EXTI_LINE_WAKEUPTIMER_EVENT) ? __HAL_RTC_WAKEUPTIMER_EXTI_ENABLE_IT() : \
+ __HAL_RTC_TAMPER_TIMESTAMP_EXTI_ENABLE_IT()))
+#define __HAL_RTC_EXTI_DISABLE_IT(__EXTI_LINE__) (((__EXTI_LINE__) == RTC_EXTI_LINE_ALARM_EVENT) ? __HAL_RTC_ALARM_EXTI_DISABLE_IT() : \
+ (((__EXTI_LINE__) == RTC_EXTI_LINE_WAKEUPTIMER_EVENT) ? __HAL_RTC_WAKEUPTIMER_EXTI_DISABLE_IT() : \
+ __HAL_RTC_TAMPER_TIMESTAMP_EXTI_DISABLE_IT()))
+#define __HAL_RTC_EXTI_GET_FLAG(__EXTI_LINE__) (((__EXTI_LINE__) == RTC_EXTI_LINE_ALARM_EVENT) ? __HAL_RTC_ALARM_EXTI_GET_FLAG() : \
+ (((__EXTI_LINE__) == RTC_EXTI_LINE_WAKEUPTIMER_EVENT) ? __HAL_RTC_WAKEUPTIMER_EXTI_GET_FLAG() : \
+ __HAL_RTC_TAMPER_TIMESTAMP_EXTI_GET_FLAG()))
+#define __HAL_RTC_EXTI_GENERATE_SWIT(__EXTI_LINE__) (((__EXTI_LINE__) == RTC_EXTI_LINE_ALARM_EVENT) ? __HAL_RTC_ALARM_EXTI_GENERATE_SWIT() : \
+ (((__EXTI_LINE__) == RTC_EXTI_LINE_WAKEUPTIMER_EVENT) ? __HAL_RTC_WAKEUPTIMER_EXTI_GENERATE_SWIT() : \
+ __HAL_RTC_TAMPER_TIMESTAMP_EXTI_GENERATE_SWIT()))
+#endif /* STM32F1 */
+
+#define IS_ALARM IS_RTC_ALARM
+#define IS_ALARM_MASK IS_RTC_ALARM_MASK
+#define IS_TAMPER IS_RTC_TAMPER
+#define IS_TAMPER_ERASE_MODE IS_RTC_TAMPER_ERASE_MODE
+#define IS_TAMPER_FILTER IS_RTC_TAMPER_FILTER
+#define IS_TAMPER_INTERRUPT IS_RTC_TAMPER_INTERRUPT
+#define IS_TAMPER_MASKFLAG_STATE IS_RTC_TAMPER_MASKFLAG_STATE
+#define IS_TAMPER_PRECHARGE_DURATION IS_RTC_TAMPER_PRECHARGE_DURATION
+#define IS_TAMPER_PULLUP_STATE IS_RTC_TAMPER_PULLUP_STATE
+#define IS_TAMPER_SAMPLING_FREQ IS_RTC_TAMPER_SAMPLING_FREQ
+#define IS_TAMPER_TIMESTAMPONTAMPER_DETECTION IS_RTC_TAMPER_TIMESTAMPONTAMPER_DETECTION
+#define IS_TAMPER_TRIGGER IS_RTC_TAMPER_TRIGGER
+#define IS_WAKEUP_CLOCK IS_RTC_WAKEUP_CLOCK
+#define IS_WAKEUP_COUNTER IS_RTC_WAKEUP_COUNTER
+
+#define __RTC_WRITEPROTECTION_ENABLE __HAL_RTC_WRITEPROTECTION_ENABLE
+#define __RTC_WRITEPROTECTION_DISABLE __HAL_RTC_WRITEPROTECTION_DISABLE
+
+/**
+ * @}
+ */
+
+/** @defgroup HAL_SD_Aliased_Macros HAL SD/MMC Aliased Macros maintained for legacy purpose
+ * @{
+ */
+
+#define SD_OCR_CID_CSD_OVERWRIETE SD_OCR_CID_CSD_OVERWRITE
+#define SD_CMD_SD_APP_STAUS SD_CMD_SD_APP_STATUS
+
+#if !defined(STM32F1) && !defined(STM32F2) && !defined(STM32F4) && !defined(STM32F7) && !defined(STM32L1)
+#define eMMC_HIGH_VOLTAGE_RANGE EMMC_HIGH_VOLTAGE_RANGE
+#define eMMC_DUAL_VOLTAGE_RANGE EMMC_DUAL_VOLTAGE_RANGE
+#define eMMC_LOW_VOLTAGE_RANGE EMMC_LOW_VOLTAGE_RANGE
+
+#define SDMMC_NSpeed_CLK_DIV SDMMC_NSPEED_CLK_DIV
+#define SDMMC_HSpeed_CLK_DIV SDMMC_HSPEED_CLK_DIV
+#endif
+
+#if defined(STM32F4) || defined(STM32F2)
+#define SD_SDMMC_DISABLED SD_SDIO_DISABLED
+#define SD_SDMMC_FUNCTION_BUSY SD_SDIO_FUNCTION_BUSY
+#define SD_SDMMC_FUNCTION_FAILED SD_SDIO_FUNCTION_FAILED
+#define SD_SDMMC_UNKNOWN_FUNCTION SD_SDIO_UNKNOWN_FUNCTION
+#define SD_CMD_SDMMC_SEN_OP_COND SD_CMD_SDIO_SEN_OP_COND
+#define SD_CMD_SDMMC_RW_DIRECT SD_CMD_SDIO_RW_DIRECT
+#define SD_CMD_SDMMC_RW_EXTENDED SD_CMD_SDIO_RW_EXTENDED
+#define __HAL_SD_SDMMC_ENABLE __HAL_SD_SDIO_ENABLE
+#define __HAL_SD_SDMMC_DISABLE __HAL_SD_SDIO_DISABLE
+#define __HAL_SD_SDMMC_DMA_ENABLE __HAL_SD_SDIO_DMA_ENABLE
+#define __HAL_SD_SDMMC_DMA_DISABLE __HAL_SD_SDIO_DMA_DISABL
+#define __HAL_SD_SDMMC_ENABLE_IT __HAL_SD_SDIO_ENABLE_IT
+#define __HAL_SD_SDMMC_DISABLE_IT __HAL_SD_SDIO_DISABLE_IT
+#define __HAL_SD_SDMMC_GET_FLAG __HAL_SD_SDIO_GET_FLAG
+#define __HAL_SD_SDMMC_CLEAR_FLAG __HAL_SD_SDIO_CLEAR_FLAG
+#define __HAL_SD_SDMMC_GET_IT __HAL_SD_SDIO_GET_IT
+#define __HAL_SD_SDMMC_CLEAR_IT __HAL_SD_SDIO_CLEAR_IT
+#define SDMMC_STATIC_FLAGS SDIO_STATIC_FLAGS
+#define SDMMC_CMD0TIMEOUT SDIO_CMD0TIMEOUT
+#define SD_SDMMC_SEND_IF_COND SD_SDIO_SEND_IF_COND
+/* alias CMSIS */
+#define SDMMC1_IRQn SDIO_IRQn
+#define SDMMC1_IRQHandler SDIO_IRQHandler
+#endif
+
+#if defined(STM32F7) || defined(STM32L4)
+#define SD_SDIO_DISABLED SD_SDMMC_DISABLED
+#define SD_SDIO_FUNCTION_BUSY SD_SDMMC_FUNCTION_BUSY
+#define SD_SDIO_FUNCTION_FAILED SD_SDMMC_FUNCTION_FAILED
+#define SD_SDIO_UNKNOWN_FUNCTION SD_SDMMC_UNKNOWN_FUNCTION
+#define SD_CMD_SDIO_SEN_OP_COND SD_CMD_SDMMC_SEN_OP_COND
+#define SD_CMD_SDIO_RW_DIRECT SD_CMD_SDMMC_RW_DIRECT
+#define SD_CMD_SDIO_RW_EXTENDED SD_CMD_SDMMC_RW_EXTENDED
+#define __HAL_SD_SDIO_ENABLE __HAL_SD_SDMMC_ENABLE
+#define __HAL_SD_SDIO_DISABLE __HAL_SD_SDMMC_DISABLE
+#define __HAL_SD_SDIO_DMA_ENABLE __HAL_SD_SDMMC_DMA_ENABLE
+#define __HAL_SD_SDIO_DMA_DISABL __HAL_SD_SDMMC_DMA_DISABLE
+#define __HAL_SD_SDIO_ENABLE_IT __HAL_SD_SDMMC_ENABLE_IT
+#define __HAL_SD_SDIO_DISABLE_IT __HAL_SD_SDMMC_DISABLE_IT
+#define __HAL_SD_SDIO_GET_FLAG __HAL_SD_SDMMC_GET_FLAG
+#define __HAL_SD_SDIO_CLEAR_FLAG __HAL_SD_SDMMC_CLEAR_FLAG
+#define __HAL_SD_SDIO_GET_IT __HAL_SD_SDMMC_GET_IT
+#define __HAL_SD_SDIO_CLEAR_IT __HAL_SD_SDMMC_CLEAR_IT
+#define SDIO_STATIC_FLAGS SDMMC_STATIC_FLAGS
+#define SDIO_CMD0TIMEOUT SDMMC_CMD0TIMEOUT
+#define SD_SDIO_SEND_IF_COND SD_SDMMC_SEND_IF_COND
+/* alias CMSIS for compatibilities */
+#define SDIO_IRQn SDMMC1_IRQn
+#define SDIO_IRQHandler SDMMC1_IRQHandler
+#endif
+
+#if defined(STM32F7) || defined(STM32F4) || defined(STM32F2) || defined(STM32L4) || defined(STM32H7)
+#define HAL_SD_CardCIDTypedef HAL_SD_CardCIDTypeDef
+#define HAL_SD_CardCSDTypedef HAL_SD_CardCSDTypeDef
+#define HAL_SD_CardStatusTypedef HAL_SD_CardStatusTypeDef
+#define HAL_SD_CardStateTypedef HAL_SD_CardStateTypeDef
+#endif
+
+#if defined(STM32H7) || defined(STM32L5)
+#define HAL_MMCEx_Read_DMADoubleBuffer0CpltCallback HAL_MMCEx_Read_DMADoubleBuf0CpltCallback
+#define HAL_MMCEx_Read_DMADoubleBuffer1CpltCallback HAL_MMCEx_Read_DMADoubleBuf1CpltCallback
+#define HAL_MMCEx_Write_DMADoubleBuffer0CpltCallback HAL_MMCEx_Write_DMADoubleBuf0CpltCallback
+#define HAL_MMCEx_Write_DMADoubleBuffer1CpltCallback HAL_MMCEx_Write_DMADoubleBuf1CpltCallback
+#define HAL_SDEx_Read_DMADoubleBuffer0CpltCallback HAL_SDEx_Read_DMADoubleBuf0CpltCallback
+#define HAL_SDEx_Read_DMADoubleBuffer1CpltCallback HAL_SDEx_Read_DMADoubleBuf1CpltCallback
+#define HAL_SDEx_Write_DMADoubleBuffer0CpltCallback HAL_SDEx_Write_DMADoubleBuf0CpltCallback
+#define HAL_SDEx_Write_DMADoubleBuffer1CpltCallback HAL_SDEx_Write_DMADoubleBuf1CpltCallback
+#define HAL_SD_DriveTransciver_1_8V_Callback HAL_SD_DriveTransceiver_1_8V_Callback
+#endif
+/**
+ * @}
+ */
+
+/** @defgroup HAL_SMARTCARD_Aliased_Macros HAL SMARTCARD Aliased Macros maintained for legacy purpose
+ * @{
+ */
+
+#define __SMARTCARD_ENABLE_IT __HAL_SMARTCARD_ENABLE_IT
+#define __SMARTCARD_DISABLE_IT __HAL_SMARTCARD_DISABLE_IT
+#define __SMARTCARD_ENABLE __HAL_SMARTCARD_ENABLE
+#define __SMARTCARD_DISABLE __HAL_SMARTCARD_DISABLE
+#define __SMARTCARD_DMA_REQUEST_ENABLE __HAL_SMARTCARD_DMA_REQUEST_ENABLE
+#define __SMARTCARD_DMA_REQUEST_DISABLE __HAL_SMARTCARD_DMA_REQUEST_DISABLE
+
+#define __HAL_SMARTCARD_GETCLOCKSOURCE SMARTCARD_GETCLOCKSOURCE
+#define __SMARTCARD_GETCLOCKSOURCE SMARTCARD_GETCLOCKSOURCE
+
+#define IS_SMARTCARD_ONEBIT_SAMPLING IS_SMARTCARD_ONE_BIT_SAMPLE
+
+/**
+ * @}
+ */
+
+/** @defgroup HAL_SMBUS_Aliased_Macros HAL SMBUS Aliased Macros maintained for legacy purpose
+ * @{
+ */
+#define __HAL_SMBUS_RESET_CR1 SMBUS_RESET_CR1
+#define __HAL_SMBUS_RESET_CR2 SMBUS_RESET_CR2
+#define __HAL_SMBUS_GENERATE_START SMBUS_GENERATE_START
+#define __HAL_SMBUS_GET_ADDR_MATCH SMBUS_GET_ADDR_MATCH
+#define __HAL_SMBUS_GET_DIR SMBUS_GET_DIR
+#define __HAL_SMBUS_GET_STOP_MODE SMBUS_GET_STOP_MODE
+#define __HAL_SMBUS_GET_PEC_MODE SMBUS_GET_PEC_MODE
+#define __HAL_SMBUS_GET_ALERT_ENABLED SMBUS_GET_ALERT_ENABLED
+/**
+ * @}
+ */
+
+/** @defgroup HAL_SPI_Aliased_Macros HAL SPI Aliased Macros maintained for legacy purpose
+ * @{
+ */
+
+#define __HAL_SPI_1LINE_TX SPI_1LINE_TX
+#define __HAL_SPI_1LINE_RX SPI_1LINE_RX
+#define __HAL_SPI_RESET_CRC SPI_RESET_CRC
+
+/**
+ * @}
+ */
+
+/** @defgroup HAL_UART_Aliased_Macros HAL UART Aliased Macros maintained for legacy purpose
+ * @{
+ */
+
+#define __HAL_UART_GETCLOCKSOURCE UART_GETCLOCKSOURCE
+#define __HAL_UART_MASK_COMPUTATION UART_MASK_COMPUTATION
+#define __UART_GETCLOCKSOURCE UART_GETCLOCKSOURCE
+#define __UART_MASK_COMPUTATION UART_MASK_COMPUTATION
+
+#define IS_UART_WAKEUPMETHODE IS_UART_WAKEUPMETHOD
+
+#define IS_UART_ONEBIT_SAMPLE IS_UART_ONE_BIT_SAMPLE
+#define IS_UART_ONEBIT_SAMPLING IS_UART_ONE_BIT_SAMPLE
+
+/**
+ * @}
+ */
+
+
+/** @defgroup HAL_USART_Aliased_Macros HAL USART Aliased Macros maintained for legacy purpose
+ * @{
+ */
+
+#define __USART_ENABLE_IT __HAL_USART_ENABLE_IT
+#define __USART_DISABLE_IT __HAL_USART_DISABLE_IT
+#define __USART_ENABLE __HAL_USART_ENABLE
+#define __USART_DISABLE __HAL_USART_DISABLE
+
+#define __HAL_USART_GETCLOCKSOURCE USART_GETCLOCKSOURCE
+#define __USART_GETCLOCKSOURCE USART_GETCLOCKSOURCE
+
+#if defined(STM32F0) || defined(STM32F3) || defined(STM32F7)
+#define USART_OVERSAMPLING_16 0x00000000U
+#define USART_OVERSAMPLING_8 USART_CR1_OVER8
+
+#define IS_USART_OVERSAMPLING(__SAMPLING__) (((__SAMPLING__) == USART_OVERSAMPLING_16) || \
+ ((__SAMPLING__) == USART_OVERSAMPLING_8))
+#endif /* STM32F0 || STM32F3 || STM32F7 */
+/**
+ * @}
+ */
+
+/** @defgroup HAL_USB_Aliased_Macros HAL USB Aliased Macros maintained for legacy purpose
+ * @{
+ */
+#define USB_EXTI_LINE_WAKEUP USB_WAKEUP_EXTI_LINE
+
+#define USB_FS_EXTI_TRIGGER_RISING_EDGE USB_OTG_FS_WAKEUP_EXTI_RISING_EDGE
+#define USB_FS_EXTI_TRIGGER_FALLING_EDGE USB_OTG_FS_WAKEUP_EXTI_FALLING_EDGE
+#define USB_FS_EXTI_TRIGGER_BOTH_EDGE USB_OTG_FS_WAKEUP_EXTI_RISING_FALLING_EDGE
+#define USB_FS_EXTI_LINE_WAKEUP USB_OTG_FS_WAKEUP_EXTI_LINE
+
+#define USB_HS_EXTI_TRIGGER_RISING_EDGE USB_OTG_HS_WAKEUP_EXTI_RISING_EDGE
+#define USB_HS_EXTI_TRIGGER_FALLING_EDGE USB_OTG_HS_WAKEUP_EXTI_FALLING_EDGE
+#define USB_HS_EXTI_TRIGGER_BOTH_EDGE USB_OTG_HS_WAKEUP_EXTI_RISING_FALLING_EDGE
+#define USB_HS_EXTI_LINE_WAKEUP USB_OTG_HS_WAKEUP_EXTI_LINE
+
+#define __HAL_USB_EXTI_ENABLE_IT __HAL_USB_WAKEUP_EXTI_ENABLE_IT
+#define __HAL_USB_EXTI_DISABLE_IT __HAL_USB_WAKEUP_EXTI_DISABLE_IT
+#define __HAL_USB_EXTI_GET_FLAG __HAL_USB_WAKEUP_EXTI_GET_FLAG
+#define __HAL_USB_EXTI_CLEAR_FLAG __HAL_USB_WAKEUP_EXTI_CLEAR_FLAG
+#define __HAL_USB_EXTI_SET_RISING_EDGE_TRIGGER __HAL_USB_WAKEUP_EXTI_ENABLE_RISING_EDGE
+#define __HAL_USB_EXTI_SET_FALLING_EDGE_TRIGGER __HAL_USB_WAKEUP_EXTI_ENABLE_FALLING_EDGE
+#define __HAL_USB_EXTI_SET_FALLINGRISING_TRIGGER __HAL_USB_WAKEUP_EXTI_ENABLE_RISING_FALLING_EDGE
+
+#define __HAL_USB_FS_EXTI_ENABLE_IT __HAL_USB_OTG_FS_WAKEUP_EXTI_ENABLE_IT
+#define __HAL_USB_FS_EXTI_DISABLE_IT __HAL_USB_OTG_FS_WAKEUP_EXTI_DISABLE_IT
+#define __HAL_USB_FS_EXTI_GET_FLAG __HAL_USB_OTG_FS_WAKEUP_EXTI_GET_FLAG
+#define __HAL_USB_FS_EXTI_CLEAR_FLAG __HAL_USB_OTG_FS_WAKEUP_EXTI_CLEAR_FLAG
+#define __HAL_USB_FS_EXTI_SET_RISING_EGDE_TRIGGER __HAL_USB_OTG_FS_WAKEUP_EXTI_ENABLE_RISING_EDGE
+#define __HAL_USB_FS_EXTI_SET_FALLING_EGDE_TRIGGER __HAL_USB_OTG_FS_WAKEUP_EXTI_ENABLE_FALLING_EDGE
+#define __HAL_USB_FS_EXTI_SET_FALLINGRISING_TRIGGER __HAL_USB_OTG_FS_WAKEUP_EXTI_ENABLE_RISING_FALLING_EDGE
+#define __HAL_USB_FS_EXTI_GENERATE_SWIT __HAL_USB_OTG_FS_WAKEUP_EXTI_GENERATE_SWIT
+
+#define __HAL_USB_HS_EXTI_ENABLE_IT __HAL_USB_OTG_HS_WAKEUP_EXTI_ENABLE_IT
+#define __HAL_USB_HS_EXTI_DISABLE_IT __HAL_USB_OTG_HS_WAKEUP_EXTI_DISABLE_IT
+#define __HAL_USB_HS_EXTI_GET_FLAG __HAL_USB_OTG_HS_WAKEUP_EXTI_GET_FLAG
+#define __HAL_USB_HS_EXTI_CLEAR_FLAG __HAL_USB_OTG_HS_WAKEUP_EXTI_CLEAR_FLAG
+#define __HAL_USB_HS_EXTI_SET_RISING_EGDE_TRIGGER __HAL_USB_OTG_HS_WAKEUP_EXTI_ENABLE_RISING_EDGE
+#define __HAL_USB_HS_EXTI_SET_FALLING_EGDE_TRIGGER __HAL_USB_OTG_HS_WAKEUP_EXTI_ENABLE_FALLING_EDGE
+#define __HAL_USB_HS_EXTI_SET_FALLINGRISING_TRIGGER __HAL_USB_OTG_HS_WAKEUP_EXTI_ENABLE_RISING_FALLING_EDGE
+#define __HAL_USB_HS_EXTI_GENERATE_SWIT __HAL_USB_OTG_HS_WAKEUP_EXTI_GENERATE_SWIT
+
+#define HAL_PCD_ActiveRemoteWakeup HAL_PCD_ActivateRemoteWakeup
+#define HAL_PCD_DeActiveRemoteWakeup HAL_PCD_DeActivateRemoteWakeup
+
+#define HAL_PCD_SetTxFiFo HAL_PCDEx_SetTxFiFo
+#define HAL_PCD_SetRxFiFo HAL_PCDEx_SetRxFiFo
+/**
+ * @}
+ */
+
+/** @defgroup HAL_TIM_Aliased_Macros HAL TIM Aliased Macros maintained for legacy purpose
+ * @{
+ */
+#define __HAL_TIM_SetICPrescalerValue TIM_SET_ICPRESCALERVALUE
+#define __HAL_TIM_ResetICPrescalerValue TIM_RESET_ICPRESCALERVALUE
+
+#define TIM_GET_ITSTATUS __HAL_TIM_GET_IT_SOURCE
+#define TIM_GET_CLEAR_IT __HAL_TIM_CLEAR_IT
+
+#define __HAL_TIM_GET_ITSTATUS __HAL_TIM_GET_IT_SOURCE
+
+#define __HAL_TIM_DIRECTION_STATUS __HAL_TIM_IS_TIM_COUNTING_DOWN
+#define __HAL_TIM_PRESCALER __HAL_TIM_SET_PRESCALER
+#define __HAL_TIM_SetCounter __HAL_TIM_SET_COUNTER
+#define __HAL_TIM_GetCounter __HAL_TIM_GET_COUNTER
+#define __HAL_TIM_SetAutoreload __HAL_TIM_SET_AUTORELOAD
+#define __HAL_TIM_GetAutoreload __HAL_TIM_GET_AUTORELOAD
+#define __HAL_TIM_SetClockDivision __HAL_TIM_SET_CLOCKDIVISION
+#define __HAL_TIM_GetClockDivision __HAL_TIM_GET_CLOCKDIVISION
+#define __HAL_TIM_SetICPrescaler __HAL_TIM_SET_ICPRESCALER
+#define __HAL_TIM_GetICPrescaler __HAL_TIM_GET_ICPRESCALER
+#define __HAL_TIM_SetCompare __HAL_TIM_SET_COMPARE
+#define __HAL_TIM_GetCompare __HAL_TIM_GET_COMPARE
+
+#define TIM_BREAKINPUTSOURCE_DFSDM TIM_BREAKINPUTSOURCE_DFSDM1
+/**
+ * @}
+ */
+
+/** @defgroup HAL_ETH_Aliased_Macros HAL ETH Aliased Macros maintained for legacy purpose
+ * @{
+ */
+
+#define __HAL_ETH_EXTI_ENABLE_IT __HAL_ETH_WAKEUP_EXTI_ENABLE_IT
+#define __HAL_ETH_EXTI_DISABLE_IT __HAL_ETH_WAKEUP_EXTI_DISABLE_IT
+#define __HAL_ETH_EXTI_GET_FLAG __HAL_ETH_WAKEUP_EXTI_GET_FLAG
+#define __HAL_ETH_EXTI_CLEAR_FLAG __HAL_ETH_WAKEUP_EXTI_CLEAR_FLAG
+#define __HAL_ETH_EXTI_SET_RISING_EGDE_TRIGGER __HAL_ETH_WAKEUP_EXTI_ENABLE_RISING_EDGE_TRIGGER
+#define __HAL_ETH_EXTI_SET_FALLING_EGDE_TRIGGER __HAL_ETH_WAKEUP_EXTI_ENABLE_FALLING_EDGE_TRIGGER
+#define __HAL_ETH_EXTI_SET_FALLINGRISING_TRIGGER __HAL_ETH_WAKEUP_EXTI_ENABLE_FALLINGRISING_TRIGGER
+
+#define ETH_PROMISCIOUSMODE_ENABLE ETH_PROMISCUOUS_MODE_ENABLE
+#define ETH_PROMISCIOUSMODE_DISABLE ETH_PROMISCUOUS_MODE_DISABLE
+#define IS_ETH_PROMISCIOUS_MODE IS_ETH_PROMISCUOUS_MODE
+/**
+ * @}
+ */
+
+/** @defgroup HAL_LTDC_Aliased_Macros HAL LTDC Aliased Macros maintained for legacy purpose
+ * @{
+ */
+#define __HAL_LTDC_LAYER LTDC_LAYER
+#define __HAL_LTDC_RELOAD_CONFIG __HAL_LTDC_RELOAD_IMMEDIATE_CONFIG
+/**
+ * @}
+ */
+
+/** @defgroup HAL_SAI_Aliased_Macros HAL SAI Aliased Macros maintained for legacy purpose
+ * @{
+ */
+#define SAI_OUTPUTDRIVE_DISABLED SAI_OUTPUTDRIVE_DISABLE
+#define SAI_OUTPUTDRIVE_ENABLED SAI_OUTPUTDRIVE_ENABLE
+#define SAI_MASTERDIVIDER_ENABLED SAI_MASTERDIVIDER_ENABLE
+#define SAI_MASTERDIVIDER_DISABLED SAI_MASTERDIVIDER_DISABLE
+#define SAI_STREOMODE SAI_STEREOMODE
+#define SAI_FIFOStatus_Empty SAI_FIFOSTATUS_EMPTY
+#define SAI_FIFOStatus_Less1QuarterFull SAI_FIFOSTATUS_LESS1QUARTERFULL
+#define SAI_FIFOStatus_1QuarterFull SAI_FIFOSTATUS_1QUARTERFULL
+#define SAI_FIFOStatus_HalfFull SAI_FIFOSTATUS_HALFFULL
+#define SAI_FIFOStatus_3QuartersFull SAI_FIFOSTATUS_3QUARTERFULL
+#define SAI_FIFOStatus_Full SAI_FIFOSTATUS_FULL
+#define IS_SAI_BLOCK_MONO_STREO_MODE IS_SAI_BLOCK_MONO_STEREO_MODE
+#define SAI_SYNCHRONOUS_EXT SAI_SYNCHRONOUS_EXT_SAI1
+#define SAI_SYNCEXT_IN_ENABLE SAI_SYNCEXT_OUTBLOCKA_ENABLE
+/**
+ * @}
+ */
+
+/** @defgroup HAL_SPDIFRX_Aliased_Macros HAL SPDIFRX Aliased Macros maintained for legacy purpose
+ * @{
+ */
+#if defined(STM32H7)
+#define HAL_SPDIFRX_ReceiveControlFlow HAL_SPDIFRX_ReceiveCtrlFlow
+#define HAL_SPDIFRX_ReceiveControlFlow_IT HAL_SPDIFRX_ReceiveCtrlFlow_IT
+#define HAL_SPDIFRX_ReceiveControlFlow_DMA HAL_SPDIFRX_ReceiveCtrlFlow_DMA
+#endif
+/**
+ * @}
+ */
+
+/** @defgroup HAL_HRTIM_Aliased_Functions HAL HRTIM Aliased Functions maintained for legacy purpose
+ * @{
+ */
+#if defined (STM32H7) || defined (STM32G4) || defined (STM32F3)
+#define HAL_HRTIM_WaveformCounterStart_IT HAL_HRTIM_WaveformCountStart_IT
+#define HAL_HRTIM_WaveformCounterStart_DMA HAL_HRTIM_WaveformCountStart_DMA
+#define HAL_HRTIM_WaveformCounterStart HAL_HRTIM_WaveformCountStart
+#define HAL_HRTIM_WaveformCounterStop_IT HAL_HRTIM_WaveformCountStop_IT
+#define HAL_HRTIM_WaveformCounterStop_DMA HAL_HRTIM_WaveformCountStop_DMA
+#define HAL_HRTIM_WaveformCounterStop HAL_HRTIM_WaveformCountStop
+#endif
+/**
+ * @}
+ */
+
+/** @defgroup HAL_QSPI_Aliased_Macros HAL QSPI Aliased Macros maintained for legacy purpose
+ * @{
+ */
+#if defined (STM32L4) || defined (STM32F4) || defined (STM32F7) || defined(STM32H7)
+#define HAL_QPSI_TIMEOUT_DEFAULT_VALUE HAL_QSPI_TIMEOUT_DEFAULT_VALUE
+#endif /* STM32L4 || STM32F4 || STM32F7 */
+/**
+ * @}
+ */
+
+/** @defgroup HAL_Generic_Aliased_Macros HAL Generic Aliased Macros maintained for legacy purpose
+ * @{
+ */
+#if defined (STM32F7)
+#define ART_ACCLERATOR_ENABLE ART_ACCELERATOR_ENABLE
+#endif /* STM32F7 */
+/**
+ * @}
+ */
+
+/** @defgroup HAL_PPP_Aliased_Macros HAL PPP Aliased Macros maintained for legacy purpose
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* STM32_HAL_LEGACY */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
+
diff --git a/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal.h b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal.h
new file mode 100644
index 0000000..6fe6c64
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal.h
@@ -0,0 +1,585 @@
+/**
+ ******************************************************************************
+ * @file stm32f0xx_hal.h
+ * @author MCD Application Team
+ * @brief This file contains all the functions prototypes for the HAL
+ * module driver.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2016 STMicroelectronics.
+ * All rights reserved.
+ *
+ * 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 __STM32F0xx_HAL_H
+#define __STM32F0xx_HAL_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f0xx_hal_conf.h"
+
+/** @addtogroup STM32F0xx_HAL_Driver
+ * @{
+ */
+
+/** @addtogroup HAL
+ * @{
+ */
+
+/* Private macros ------------------------------------------------------------*/
+/** @addtogroup HAL_Private_Macros
+ * @{
+ */
+#if defined(STM32F091xC) || defined(STM32F098xx) || defined(STM32F042x6) || defined(STM32F048xx) || \
+ defined(STM32F030x6) || defined(STM32F031x6) || defined(STM32F038xx) || defined(STM32F070x6) || \
+ defined(STM32F070xB) || defined(STM32F030x6)
+#define IS_SYSCFG_FASTMODEPLUS(__PIN__) ((((__PIN__) & SYSCFG_FASTMODEPLUS_PA9) == SYSCFG_FASTMODEPLUS_PA9) || \
+ (((__PIN__) & SYSCFG_FASTMODEPLUS_PA10) == SYSCFG_FASTMODEPLUS_PA10) || \
+ (((__PIN__) & SYSCFG_FASTMODEPLUS_PB6) == SYSCFG_FASTMODEPLUS_PB6) || \
+ (((__PIN__) & SYSCFG_FASTMODEPLUS_PB7) == SYSCFG_FASTMODEPLUS_PB7) || \
+ (((__PIN__) & SYSCFG_FASTMODEPLUS_PB8) == SYSCFG_FASTMODEPLUS_PB8) || \
+ (((__PIN__) & SYSCFG_FASTMODEPLUS_PB9) == SYSCFG_FASTMODEPLUS_PB9))
+#else
+#define IS_SYSCFG_FASTMODEPLUS(__PIN__) ((((__PIN__) & SYSCFG_FASTMODEPLUS_PB6) == SYSCFG_FASTMODEPLUS_PB6) || \
+ (((__PIN__) & SYSCFG_FASTMODEPLUS_PB7) == SYSCFG_FASTMODEPLUS_PB7) || \
+ (((__PIN__) & SYSCFG_FASTMODEPLUS_PB8) == SYSCFG_FASTMODEPLUS_PB8) || \
+ (((__PIN__) & SYSCFG_FASTMODEPLUS_PB9) == SYSCFG_FASTMODEPLUS_PB9))
+#endif
+#if defined(SYSCFG_CFGR1_PA11_PA12_RMP)
+#define IS_HAL_REMAP_PIN(RMP) ((RMP) == HAL_REMAP_PA11_PA12)
+#endif /* SYSCFG_CFGR1_PA11_PA12_RMP */
+#if defined(STM32F091xC) || defined(STM32F098xx)
+#define IS_HAL_SYSCFG_IRDA_ENV_SEL(SEL) (((SEL) == HAL_SYSCFG_IRDA_ENV_SEL_TIM16) || \
+ ((SEL) == HAL_SYSCFG_IRDA_ENV_SEL_USART1) || \
+ ((SEL) == HAL_SYSCFG_IRDA_ENV_SEL_USART4))
+#endif /* STM32F091xC || STM32F098xx */
+/**
+ * @}
+ */
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/** @defgroup HAL_Exported_Constants HAL Exported Constants
+ * @{
+ */
+
+/** @defgroup HAL_TICK_FREQ Tick Frequency
+ * @{
+ */
+typedef enum
+{
+ HAL_TICK_FREQ_10HZ = 100U,
+ HAL_TICK_FREQ_100HZ = 10U,
+ HAL_TICK_FREQ_1KHZ = 1U,
+ HAL_TICK_FREQ_DEFAULT = HAL_TICK_FREQ_1KHZ
+} HAL_TickFreqTypeDef;
+
+/**
+ * @}
+ */
+
+#if defined(SYSCFG_CFGR1_PA11_PA12_RMP)
+/** @defgroup HAL_Pin_remapping HAL Pin remapping
+ * @{
+ */
+#define HAL_REMAP_PA11_PA12 (SYSCFG_CFGR1_PA11_PA12_RMP) /*!< PA11 and PA12 remapping bit for small packages (28 and 20 pins).
+ 0: No remap (pin pair PA9/10 mapped on the pins)
+ 1: Remap (pin pair PA11/12 mapped instead of PA9/10) */
+
+/**
+ * @}
+ */
+#endif /* SYSCFG_CFGR1_PA11_PA12_RMP */
+
+#if defined(STM32F091xC) || defined(STM32F098xx)
+/** @defgroup HAL_IRDA_ENV_SEL HAL IRDA Enveloppe Selection
+ * @note Applicable on STM32F09x
+ * @{
+ */
+#define HAL_SYSCFG_IRDA_ENV_SEL_TIM16 (SYSCFG_CFGR1_IRDA_ENV_SEL_0 & SYSCFG_CFGR1_IRDA_ENV_SEL_1) /* 00: Timer16 is selected as IRDA Modulation enveloppe source */
+#define HAL_SYSCFG_IRDA_ENV_SEL_USART1 (SYSCFG_CFGR1_IRDA_ENV_SEL_0) /* 01: USART1 is selected as IRDA Modulation enveloppe source */
+#define HAL_SYSCFG_IRDA_ENV_SEL_USART4 (SYSCFG_CFGR1_IRDA_ENV_SEL_1) /* 10: USART4 is selected as IRDA Modulation enveloppe source */
+
+/**
+ * @}
+ */
+#endif /* STM32F091xC || STM32F098xx */
+
+
+/** @defgroup SYSCFG_FastModePlus_GPIO Fast-mode Plus on GPIO
+ * @{
+ */
+
+/** @brief Fast-mode Plus driving capability on a specific GPIO
+ */
+#if defined(STM32F091xC) || defined(STM32F098xx) || defined(STM32F042x6) || defined(STM32F048xx) || \
+ defined(STM32F030x6) || defined(STM32F031x6) || defined(STM32F038xx) || defined(STM32F070x6) || \
+ defined(STM32F070xB) || defined(STM32F030x6)
+#define SYSCFG_FASTMODEPLUS_PA9 SYSCFG_CFGR1_I2C_FMP_PA9 /*!< Enable Fast-mode Plus on PA9 */
+#define SYSCFG_FASTMODEPLUS_PA10 SYSCFG_CFGR1_I2C_FMP_PA10 /*!< Enable Fast-mode Plus on PA10 */
+#endif
+#define SYSCFG_FASTMODEPLUS_PB6 SYSCFG_CFGR1_I2C_FMP_PB6 /*!< Enable Fast-mode Plus on PB6 */
+#define SYSCFG_FASTMODEPLUS_PB7 SYSCFG_CFGR1_I2C_FMP_PB7 /*!< Enable Fast-mode Plus on PB7 */
+#define SYSCFG_FASTMODEPLUS_PB8 SYSCFG_CFGR1_I2C_FMP_PB8 /*!< Enable Fast-mode Plus on PB8 */
+#define SYSCFG_FASTMODEPLUS_PB9 SYSCFG_CFGR1_I2C_FMP_PB9 /*!< Enable Fast-mode Plus on PB9 */
+
+/**
+ * @}
+ */
+
+
+#if defined(STM32F091xC) || defined (STM32F098xx)
+/** @defgroup HAL_ISR_Wrapper HAL ISR Wrapper
+ * @brief ISR Wrapper
+ * @note applicable on STM32F09x
+ * @{
+ */
+#define HAL_SYSCFG_ITLINE0 ( 0x00000000U) /*!< Internal define for macro handling */
+#define HAL_SYSCFG_ITLINE1 ( 0x00000001U) /*!< Internal define for macro handling */
+#define HAL_SYSCFG_ITLINE2 ( 0x00000002U) /*!< Internal define for macro handling */
+#define HAL_SYSCFG_ITLINE3 ( 0x00000003U) /*!< Internal define for macro handling */
+#define HAL_SYSCFG_ITLINE4 ( 0x00000004U) /*!< Internal define for macro handling */
+#define HAL_SYSCFG_ITLINE5 ( 0x00000005U) /*!< Internal define for macro handling */
+#define HAL_SYSCFG_ITLINE6 ( 0x00000006U) /*!< Internal define for macro handling */
+#define HAL_SYSCFG_ITLINE7 ( 0x00000007U) /*!< Internal define for macro handling */
+#define HAL_SYSCFG_ITLINE8 ( 0x00000008U) /*!< Internal define for macro handling */
+#define HAL_SYSCFG_ITLINE9 ( 0x00000009U) /*!< Internal define for macro handling */
+#define HAL_SYSCFG_ITLINE10 ( 0x0000000AU) /*!< Internal define for macro handling */
+#define HAL_SYSCFG_ITLINE11 ( 0x0000000BU) /*!< Internal define for macro handling */
+#define HAL_SYSCFG_ITLINE12 ( 0x0000000CU) /*!< Internal define for macro handling */
+#define HAL_SYSCFG_ITLINE13 ( 0x0000000DU) /*!< Internal define for macro handling */
+#define HAL_SYSCFG_ITLINE14 ( 0x0000000EU) /*!< Internal define for macro handling */
+#define HAL_SYSCFG_ITLINE15 ( 0x0000000FU) /*!< Internal define for macro handling */
+#define HAL_SYSCFG_ITLINE16 ( 0x00000010U) /*!< Internal define for macro handling */
+#define HAL_SYSCFG_ITLINE17 ( 0x00000011U) /*!< Internal define for macro handling */
+#define HAL_SYSCFG_ITLINE18 ( 0x00000012U) /*!< Internal define for macro handling */
+#define HAL_SYSCFG_ITLINE19 ( 0x00000013U) /*!< Internal define for macro handling */
+#define HAL_SYSCFG_ITLINE20 ( 0x00000014U) /*!< Internal define for macro handling */
+#define HAL_SYSCFG_ITLINE21 ( 0x00000015U) /*!< Internal define for macro handling */
+#define HAL_SYSCFG_ITLINE22 ( 0x00000016U) /*!< Internal define for macro handling */
+#define HAL_SYSCFG_ITLINE23 ( 0x00000017U) /*!< Internal define for macro handling */
+#define HAL_SYSCFG_ITLINE24 ( 0x00000018U) /*!< Internal define for macro handling */
+#define HAL_SYSCFG_ITLINE25 ( 0x00000019U) /*!< Internal define for macro handling */
+#define HAL_SYSCFG_ITLINE26 ( 0x0000001AU) /*!< Internal define for macro handling */
+#define HAL_SYSCFG_ITLINE27 ( 0x0000001BU) /*!< Internal define for macro handling */
+#define HAL_SYSCFG_ITLINE28 ( 0x0000001CU) /*!< Internal define for macro handling */
+#define HAL_SYSCFG_ITLINE29 ( 0x0000001DU) /*!< Internal define for macro handling */
+#define HAL_SYSCFG_ITLINE30 ( 0x0000001EU) /*!< Internal define for macro handling */
+#define HAL_SYSCFG_ITLINE31 ( 0x0000001FU) /*!< Internal define for macro handling */
+
+#define HAL_ITLINE_EWDG ((uint32_t) ((HAL_SYSCFG_ITLINE0 << 0x18U) | SYSCFG_ITLINE0_SR_EWDG)) /*!< EWDG has expired .... */
+#if defined(STM32F091xC)
+#define HAL_ITLINE_PVDOUT ((uint32_t) ((HAL_SYSCFG_ITLINE1 << 0x18U) | SYSCFG_ITLINE1_SR_PVDOUT)) /*!< Power voltage detection Interrupt .... */
+#endif
+#define HAL_ITLINE_VDDIO2 ((uint32_t) ((HAL_SYSCFG_ITLINE1 << 0x18U) | SYSCFG_ITLINE1_SR_VDDIO2)) /*!< VDDIO2 Interrupt .... */
+#define HAL_ITLINE_RTC_WAKEUP ((uint32_t) ((HAL_SYSCFG_ITLINE2 << 0x18U) | SYSCFG_ITLINE2_SR_RTC_WAKEUP)) /*!< RTC WAKEUP -> exti[20] Interrupt */
+#define HAL_ITLINE_RTC_TSTAMP ((uint32_t) ((HAL_SYSCFG_ITLINE2 << 0x18U) | SYSCFG_ITLINE2_SR_RTC_TSTAMP)) /*!< RTC Time Stamp -> exti[19] interrupt */
+#define HAL_ITLINE_RTC_ALRA ((uint32_t) ((HAL_SYSCFG_ITLINE2 << 0x18U) | SYSCFG_ITLINE2_SR_RTC_ALRA)) /*!< RTC Alarm -> exti[17] interrupt .... */
+#define HAL_ITLINE_FLASH_ITF ((uint32_t) ((HAL_SYSCFG_ITLINE3 << 0x18U) | SYSCFG_ITLINE3_SR_FLASH_ITF)) /*!< Flash ITF Interrupt */
+#define HAL_ITLINE_CRS ((uint32_t) ((HAL_SYSCFG_ITLINE4 << 0x18U) | SYSCFG_ITLINE4_SR_CRS)) /*!< CRS Interrupt */
+#define HAL_ITLINE_CLK_CTRL ((uint32_t) ((HAL_SYSCFG_ITLINE4 << 0x18U) | SYSCFG_ITLINE4_SR_CLK_CTRL)) /*!< CLK Control Interrupt */
+#define HAL_ITLINE_EXTI0 ((uint32_t) ((HAL_SYSCFG_ITLINE5 << 0x18U) | SYSCFG_ITLINE5_SR_EXTI0)) /*!< External Interrupt 0 */
+#define HAL_ITLINE_EXTI1 ((uint32_t) ((HAL_SYSCFG_ITLINE5 << 0x18U) | SYSCFG_ITLINE5_SR_EXTI1)) /*!< External Interrupt 1 */
+#define HAL_ITLINE_EXTI2 ((uint32_t) ((HAL_SYSCFG_ITLINE6 << 0x18U) | SYSCFG_ITLINE6_SR_EXTI2)) /*!< External Interrupt 2 */
+#define HAL_ITLINE_EXTI3 ((uint32_t) ((HAL_SYSCFG_ITLINE6 << 0x18U) | SYSCFG_ITLINE6_SR_EXTI3)) /*!< External Interrupt 3 */
+#define HAL_ITLINE_EXTI4 ((uint32_t) ((HAL_SYSCFG_ITLINE7 << 0x18U) | SYSCFG_ITLINE7_SR_EXTI4)) /*!< EXTI4 Interrupt */
+#define HAL_ITLINE_EXTI5 ((uint32_t) ((HAL_SYSCFG_ITLINE7 << 0x18U) | SYSCFG_ITLINE7_SR_EXTI5)) /*!< EXTI5 Interrupt */
+#define HAL_ITLINE_EXTI6 ((uint32_t) ((HAL_SYSCFG_ITLINE7 << 0x18U) | SYSCFG_ITLINE7_SR_EXTI6)) /*!< EXTI6 Interrupt */
+#define HAL_ITLINE_EXTI7 ((uint32_t) ((HAL_SYSCFG_ITLINE7 << 0x18U) | SYSCFG_ITLINE7_SR_EXTI7)) /*!< EXTI7 Interrupt */
+#define HAL_ITLINE_EXTI8 ((uint32_t) ((HAL_SYSCFG_ITLINE7 << 0x18U) | SYSCFG_ITLINE7_SR_EXTI8)) /*!< EXTI8 Interrupt */
+#define HAL_ITLINE_EXTI9 ((uint32_t) ((HAL_SYSCFG_ITLINE7 << 0x18U) | SYSCFG_ITLINE7_SR_EXTI9)) /*!< EXTI9 Interrupt */
+#define HAL_ITLINE_EXTI10 ((uint32_t) ((HAL_SYSCFG_ITLINE7 << 0x18U) | SYSCFG_ITLINE7_SR_EXTI10)) /*!< EXTI10 Interrupt */
+#define HAL_ITLINE_EXTI11 ((uint32_t) ((HAL_SYSCFG_ITLINE7 << 0x18U) | SYSCFG_ITLINE7_SR_EXTI11)) /*!< EXTI11 Interrupt */
+#define HAL_ITLINE_EXTI12 ((uint32_t) ((HAL_SYSCFG_ITLINE7 << 0x18U) | SYSCFG_ITLINE7_SR_EXTI12)) /*!< EXTI12 Interrupt */
+#define HAL_ITLINE_EXTI13 ((uint32_t) ((HAL_SYSCFG_ITLINE7 << 0x18U) | SYSCFG_ITLINE7_SR_EXTI13)) /*!< EXTI13 Interrupt */
+#define HAL_ITLINE_EXTI14 ((uint32_t) ((HAL_SYSCFG_ITLINE7 << 0x18U) | SYSCFG_ITLINE7_SR_EXTI14)) /*!< EXTI14 Interrupt */
+#define HAL_ITLINE_EXTI15 ((uint32_t) ((HAL_SYSCFG_ITLINE7 << 0x18U) | SYSCFG_ITLINE7_SR_EXTI15)) /*!< EXTI15 Interrupt */
+#define HAL_ITLINE_TSC_EOA ((uint32_t) ((HAL_SYSCFG_ITLINE8 << 0x18U) | SYSCFG_ITLINE8_SR_TSC_EOA)) /*!< Touch control EOA Interrupt */
+#define HAL_ITLINE_TSC_MCE ((uint32_t) ((HAL_SYSCFG_ITLINE8 << 0x18U) | SYSCFG_ITLINE8_SR_TSC_MCE)) /*!< Touch control MCE Interrupt */
+#define HAL_ITLINE_DMA1_CH1 ((uint32_t) ((HAL_SYSCFG_ITLINE9 << 0x18U) | SYSCFG_ITLINE9_SR_DMA1_CH1)) /*!< DMA1 Channel 1 Interrupt */
+#define HAL_ITLINE_DMA1_CH2 ((uint32_t) ((HAL_SYSCFG_ITLINE10 << 0x18U) | SYSCFG_ITLINE10_SR_DMA1_CH2)) /*!< DMA1 Channel 2 Interrupt */
+#define HAL_ITLINE_DMA1_CH3 ((uint32_t) ((HAL_SYSCFG_ITLINE10 << 0x18U) | SYSCFG_ITLINE10_SR_DMA1_CH3)) /*!< DMA1 Channel 3 Interrupt */
+#define HAL_ITLINE_DMA2_CH1 ((uint32_t) ((HAL_SYSCFG_ITLINE10 << 0x18U) | SYSCFG_ITLINE10_SR_DMA2_CH1)) /*!< DMA2 Channel 1 Interrupt */
+#define HAL_ITLINE_DMA2_CH2 ((uint32_t) ((HAL_SYSCFG_ITLINE10 << 0x18U) | SYSCFG_ITLINE10_SR_DMA2_CH2)) /*!< DMA2 Channel 2 Interrupt */
+#define HAL_ITLINE_DMA1_CH4 ((uint32_t) ((HAL_SYSCFG_ITLINE11 << 0x18U) | SYSCFG_ITLINE11_SR_DMA1_CH4)) /*!< DMA1 Channel 4 Interrupt */
+#define HAL_ITLINE_DMA1_CH5 ((uint32_t) ((HAL_SYSCFG_ITLINE11 << 0x18U) | SYSCFG_ITLINE11_SR_DMA1_CH5)) /*!< DMA1 Channel 5 Interrupt */
+#define HAL_ITLINE_DMA1_CH6 ((uint32_t) ((HAL_SYSCFG_ITLINE11 << 0x18U) | SYSCFG_ITLINE11_SR_DMA1_CH6)) /*!< DMA1 Channel 6 Interrupt */
+#define HAL_ITLINE_DMA1_CH7 ((uint32_t) ((HAL_SYSCFG_ITLINE11 << 0x18U) | SYSCFG_ITLINE11_SR_DMA1_CH7)) /*!< DMA1 Channel 7 Interrupt */
+#define HAL_ITLINE_DMA2_CH3 ((uint32_t) ((HAL_SYSCFG_ITLINE11 << 0x18U) | SYSCFG_ITLINE11_SR_DMA2_CH3)) /*!< DMA2 Channel 3 Interrupt */
+#define HAL_ITLINE_DMA2_CH4 ((uint32_t) ((HAL_SYSCFG_ITLINE11 << 0x18U) | SYSCFG_ITLINE11_SR_DMA2_CH4)) /*!< DMA2 Channel 4 Interrupt */
+#define HAL_ITLINE_DMA2_CH5 ((uint32_t) ((HAL_SYSCFG_ITLINE11 << 0x18U) | SYSCFG_ITLINE11_SR_DMA2_CH5)) /*!< DMA2 Channel 5 Interrupt */
+#define HAL_ITLINE_ADC ((uint32_t) ((HAL_SYSCFG_ITLINE12 << 0x18U) | SYSCFG_ITLINE12_SR_ADC)) /*!< ADC Interrupt */
+#define HAL_ITLINE_COMP1 ((uint32_t) ((HAL_SYSCFG_ITLINE12 << 0x18U) | SYSCFG_ITLINE12_SR_COMP1)) /*!< COMP1 Interrupt -> exti[21] */
+#define HAL_ITLINE_COMP2 ((uint32_t) ((HAL_SYSCFG_ITLINE12 << 0x18U) | SYSCFG_ITLINE12_SR_COMP2)) /*!< COMP2 Interrupt -> exti[21] */
+#define HAL_ITLINE_TIM1_BRK ((uint32_t) ((HAL_SYSCFG_ITLINE13 << 0x18U) | SYSCFG_ITLINE13_SR_TIM1_BRK)) /*!< TIM1 BRK Interrupt */
+#define HAL_ITLINE_TIM1_UPD ((uint32_t) ((HAL_SYSCFG_ITLINE13 << 0x18U) | SYSCFG_ITLINE13_SR_TIM1_UPD)) /*!< TIM1 UPD Interrupt */
+#define HAL_ITLINE_TIM1_TRG ((uint32_t) ((HAL_SYSCFG_ITLINE13 << 0x18U) | SYSCFG_ITLINE13_SR_TIM1_TRG)) /*!< TIM1 TRG Interrupt */
+#define HAL_ITLINE_TIM1_CCU ((uint32_t) ((HAL_SYSCFG_ITLINE13 << 0x18U) | SYSCFG_ITLINE13_SR_TIM1_CCU)) /*!< TIM1 CCU Interrupt */
+#define HAL_ITLINE_TIM1_CC ((uint32_t) ((HAL_SYSCFG_ITLINE14 << 0x18U) | SYSCFG_ITLINE14_SR_TIM1_CC)) /*!< TIM1 CC Interrupt */
+#define HAL_ITLINE_TIM2 ((uint32_t) ((HAL_SYSCFG_ITLINE15 << 0x18U) | SYSCFG_ITLINE15_SR_TIM2_GLB)) /*!< TIM2 Interrupt */
+#define HAL_ITLINE_TIM3 ((uint32_t) ((HAL_SYSCFG_ITLINE16 << 0x18U) | SYSCFG_ITLINE16_SR_TIM3_GLB)) /*!< TIM3 Interrupt */
+#define HAL_ITLINE_DAC ((uint32_t) ((HAL_SYSCFG_ITLINE17 << 0x18U) | SYSCFG_ITLINE17_SR_DAC)) /*!< DAC Interrupt */
+#define HAL_ITLINE_TIM6 ((uint32_t) ((HAL_SYSCFG_ITLINE17 << 0x18U) | SYSCFG_ITLINE17_SR_TIM6_GLB)) /*!< TIM6 Interrupt */
+#define HAL_ITLINE_TIM7 ((uint32_t) ((HAL_SYSCFG_ITLINE18 << 0x18U) | SYSCFG_ITLINE18_SR_TIM7_GLB)) /*!< TIM7 Interrupt */
+#define HAL_ITLINE_TIM14 ((uint32_t) ((HAL_SYSCFG_ITLINE19 << 0x18U) | SYSCFG_ITLINE19_SR_TIM14_GLB)) /*!< TIM14 Interrupt */
+#define HAL_ITLINE_TIM15 ((uint32_t) ((HAL_SYSCFG_ITLINE20 << 0x18U) | SYSCFG_ITLINE20_SR_TIM15_GLB)) /*!< TIM15 Interrupt */
+#define HAL_ITLINE_TIM16 ((uint32_t) ((HAL_SYSCFG_ITLINE21 << 0x18U) | SYSCFG_ITLINE21_SR_TIM16_GLB)) /*!< TIM16 Interrupt */
+#define HAL_ITLINE_TIM17 ((uint32_t) ((HAL_SYSCFG_ITLINE22 << 0x18U) | SYSCFG_ITLINE22_SR_TIM17_GLB)) /*!< TIM17 Interrupt */
+#define HAL_ITLINE_I2C1 ((uint32_t) ((HAL_SYSCFG_ITLINE23 << 0x18U) | SYSCFG_ITLINE23_SR_I2C1_GLB)) /*!< I2C1 Interrupt -> exti[23] */
+#define HAL_ITLINE_I2C2 ((uint32_t) ((HAL_SYSCFG_ITLINE24 << 0x18U) | SYSCFG_ITLINE24_SR_I2C2_GLB)) /*!< I2C2 Interrupt */
+#define HAL_ITLINE_SPI1 ((uint32_t) ((HAL_SYSCFG_ITLINE25 << 0x18U) | SYSCFG_ITLINE25_SR_SPI1)) /*!< I2C1 Interrupt -> exti[23] */
+#define HAL_ITLINE_SPI2 ((uint32_t) ((HAL_SYSCFG_ITLINE26 << 0x18U) | SYSCFG_ITLINE26_SR_SPI2)) /*!< SPI1 Interrupt */
+#define HAL_ITLINE_USART1 ((uint32_t) ((HAL_SYSCFG_ITLINE27 << 0x18U) | SYSCFG_ITLINE27_SR_USART1_GLB)) /*!< USART1 GLB Interrupt -> exti[25] */
+#define HAL_ITLINE_USART2 ((uint32_t) ((HAL_SYSCFG_ITLINE28 << 0x18U) | SYSCFG_ITLINE28_SR_USART2_GLB)) /*!< USART2 GLB Interrupt -> exti[26] */
+#define HAL_ITLINE_USART3 ((uint32_t) ((HAL_SYSCFG_ITLINE29 << 0x18U) | SYSCFG_ITLINE29_SR_USART3_GLB)) /*!< USART3 Interrupt .... */
+#define HAL_ITLINE_USART4 ((uint32_t) ((HAL_SYSCFG_ITLINE29 << 0x18U) | SYSCFG_ITLINE29_SR_USART4_GLB)) /*!< USART4 Interrupt .... */
+#define HAL_ITLINE_USART5 ((uint32_t) ((HAL_SYSCFG_ITLINE29 << 0x18U) | SYSCFG_ITLINE29_SR_USART5_GLB)) /*!< USART5 Interrupt .... */
+#define HAL_ITLINE_USART6 ((uint32_t) ((HAL_SYSCFG_ITLINE29 << 0x18U) | SYSCFG_ITLINE29_SR_USART6_GLB)) /*!< USART6 Interrupt .... */
+#define HAL_ITLINE_USART7 ((uint32_t) ((HAL_SYSCFG_ITLINE29 << 0x18U) | SYSCFG_ITLINE29_SR_USART7_GLB)) /*!< USART7 Interrupt .... */
+#define HAL_ITLINE_USART8 ((uint32_t) ((HAL_SYSCFG_ITLINE29 << 0x18U) | SYSCFG_ITLINE29_SR_USART8_GLB)) /*!< USART8 Interrupt .... */
+#define HAL_ITLINE_CAN ((uint32_t) ((HAL_SYSCFG_ITLINE30 << 0x18U) | SYSCFG_ITLINE30_SR_CAN)) /*!< CAN Interrupt */
+#define HAL_ITLINE_CEC ((uint32_t) ((HAL_SYSCFG_ITLINE30 << 0x18U) | SYSCFG_ITLINE30_SR_CEC)) /*!< CEC Interrupt -> exti[27] */
+/**
+ * @}
+ */
+#endif /* STM32F091xC || STM32F098xx */
+
+/**
+ * @}
+ */
+
+/* Exported macros -----------------------------------------------------------*/
+/** @defgroup HAL_Exported_Macros HAL Exported Macros
+ * @{
+ */
+
+/** @defgroup HAL_Freeze_Unfreeze_Peripherals HAL Freeze Unfreeze Peripherals
+ * @brief Freeze/Unfreeze Peripherals in Debug mode
+ * @{
+ */
+
+#if defined(DBGMCU_APB1_FZ_DBG_CAN_STOP)
+#define __HAL_FREEZE_CAN_DBGMCU() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_CAN_STOP))
+#define __HAL_UNFREEZE_CAN_DBGMCU() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_CAN_STOP))
+#endif /* DBGMCU_APB1_FZ_DBG_CAN_STOP */
+
+#if defined(DBGMCU_APB1_FZ_DBG_RTC_STOP)
+#define __HAL_DBGMCU_FREEZE_RTC() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_RTC_STOP))
+#define __HAL_DBGMCU_UNFREEZE_RTC() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_RTC_STOP))
+#endif /* DBGMCU_APB1_FZ_DBG_RTC_STOP */
+
+#if defined(DBGMCU_APB1_FZ_DBG_I2C1_SMBUS_TIMEOUT)
+#define __HAL_DBGMCU_FREEZE_I2C1_TIMEOUT() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_I2C1_SMBUS_TIMEOUT))
+#define __HAL_DBGMCU_UNFREEZE_I2C1_TIMEOUT() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_I2C1_SMBUS_TIMEOUT))
+#endif /* DBGMCU_APB1_FZ_DBG_I2C1_SMBUS_TIMEOUT */
+
+#if defined(DBGMCU_APB1_FZ_DBG_IWDG_STOP)
+#define __HAL_DBGMCU_FREEZE_IWDG() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_IWDG_STOP))
+#define __HAL_DBGMCU_UNFREEZE_IWDG() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_IWDG_STOP))
+#endif /* DBGMCU_APB1_FZ_DBG_IWDG_STOP */
+
+#if defined(DBGMCU_APB1_FZ_DBG_WWDG_STOP)
+#define __HAL_DBGMCU_FREEZE_WWDG() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_WWDG_STOP))
+#define __HAL_DBGMCU_UNFREEZE_WWDG() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_WWDG_STOP))
+#endif /* DBGMCU_APB1_FZ_DBG_WWDG_STOP */
+
+#if defined(DBGMCU_APB1_FZ_DBG_TIM2_STOP)
+#define __HAL_DBGMCU_FREEZE_TIM2() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_TIM2_STOP))
+#define __HAL_DBGMCU_UNFREEZE_TIM2() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_TIM2_STOP))
+#endif /* DBGMCU_APB1_FZ_DBG_TIM2_STOP */
+
+#if defined(DBGMCU_APB1_FZ_DBG_TIM3_STOP)
+#define __HAL_DBGMCU_FREEZE_TIM3() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_TIM3_STOP))
+#define __HAL_DBGMCU_UNFREEZE_TIM3() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_TIM3_STOP))
+#endif /* DBGMCU_APB1_FZ_DBG_TIM3_STOP */
+
+#if defined(DBGMCU_APB1_FZ_DBG_TIM6_STOP)
+#define __HAL_DBGMCU_FREEZE_TIM6() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_TIM6_STOP))
+#define __HAL_DBGMCU_UNFREEZE_TIM6() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_TIM6_STOP))
+#endif /* DBGMCU_APB1_FZ_DBG_TIM6_STOP */
+
+#if defined(DBGMCU_APB1_FZ_DBG_TIM7_STOP)
+#define __HAL_DBGMCU_FREEZE_TIM7() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_TIM7_STOP))
+#define __HAL_DBGMCU_UNFREEZE_TIM7() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_TIM7_STOP))
+#endif /* DBGMCU_APB1_FZ_DBG_TIM7_STOP */
+
+#if defined(DBGMCU_APB1_FZ_DBG_TIM14_STOP)
+#define __HAL_DBGMCU_FREEZE_TIM14() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_TIM14_STOP))
+#define __HAL_DBGMCU_UNFREEZE_TIM14() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_TIM14_STOP))
+#endif /* DBGMCU_APB1_FZ_DBG_TIM14_STOP */
+
+#if defined(DBGMCU_APB2_FZ_DBG_TIM1_STOP)
+#define __HAL_DBGMCU_FREEZE_TIM1() (DBGMCU->APB2FZ |= (DBGMCU_APB2_FZ_DBG_TIM1_STOP))
+#define __HAL_DBGMCU_UNFREEZE_TIM1() (DBGMCU->APB2FZ &= ~(DBGMCU_APB2_FZ_DBG_TIM1_STOP))
+#endif /* DBGMCU_APB2_FZ_DBG_TIM1_STOP */
+
+#if defined(DBGMCU_APB2_FZ_DBG_TIM15_STOP)
+#define __HAL_DBGMCU_FREEZE_TIM15() (DBGMCU->APB2FZ |= (DBGMCU_APB2_FZ_DBG_TIM15_STOP))
+#define __HAL_DBGMCU_UNFREEZE_TIM15() (DBGMCU->APB2FZ &= ~(DBGMCU_APB2_FZ_DBG_TIM15_STOP))
+#endif /* DBGMCU_APB2_FZ_DBG_TIM15_STOP */
+
+#if defined(DBGMCU_APB2_FZ_DBG_TIM16_STOP)
+#define __HAL_DBGMCU_FREEZE_TIM16() (DBGMCU->APB2FZ |= (DBGMCU_APB2_FZ_DBG_TIM16_STOP))
+#define __HAL_DBGMCU_UNFREEZE_TIM16() (DBGMCU->APB2FZ &= ~(DBGMCU_APB2_FZ_DBG_TIM16_STOP))
+#endif /* DBGMCU_APB2_FZ_DBG_TIM16_STOP */
+
+#if defined(DBGMCU_APB2_FZ_DBG_TIM17_STOP)
+#define __HAL_DBGMCU_FREEZE_TIM17() (DBGMCU->APB2FZ |= (DBGMCU_APB2_FZ_DBG_TIM17_STOP))
+#define __HAL_DBGMCU_UNFREEZE_TIM17() (DBGMCU->APB2FZ &= ~(DBGMCU_APB2_FZ_DBG_TIM17_STOP))
+#endif /* DBGMCU_APB2_FZ_DBG_TIM17_STOP */
+
+/**
+ * @}
+ */
+
+/** @defgroup Memory_Mapping_Selection Memory Mapping Selection
+ * @{
+ */
+#if defined(SYSCFG_CFGR1_MEM_MODE)
+/** @brief Main Flash memory mapped at 0x00000000
+ */
+#define __HAL_SYSCFG_REMAPMEMORY_FLASH() (SYSCFG->CFGR1 &= ~(SYSCFG_CFGR1_MEM_MODE))
+#endif /* SYSCFG_CFGR1_MEM_MODE */
+
+#if defined(SYSCFG_CFGR1_MEM_MODE_0)
+/** @brief System Flash memory mapped at 0x00000000
+ */
+#define __HAL_SYSCFG_REMAPMEMORY_SYSTEMFLASH() do {SYSCFG->CFGR1 &= ~(SYSCFG_CFGR1_MEM_MODE); \
+ SYSCFG->CFGR1 |= SYSCFG_CFGR1_MEM_MODE_0; \
+ }while(0)
+#endif /* SYSCFG_CFGR1_MEM_MODE_0 */
+
+#if defined(SYSCFG_CFGR1_MEM_MODE_0) && defined(SYSCFG_CFGR1_MEM_MODE_1)
+/** @brief Embedded SRAM mapped at 0x00000000
+ */
+#define __HAL_SYSCFG_REMAPMEMORY_SRAM() do {SYSCFG->CFGR1 &= ~(SYSCFG_CFGR1_MEM_MODE); \
+ SYSCFG->CFGR1 |= (SYSCFG_CFGR1_MEM_MODE_0 | SYSCFG_CFGR1_MEM_MODE_1); \
+ }while(0)
+#endif /* SYSCFG_CFGR1_MEM_MODE_0 && SYSCFG_CFGR1_MEM_MODE_1 */
+/**
+ * @}
+ */
+
+
+#if defined(SYSCFG_CFGR1_PA11_PA12_RMP)
+/** @defgroup HAL_Pin_remap HAL Pin remap
+ * @brief Pin remapping enable/disable macros
+ * @param __PIN_REMAP__ This parameter can be a value of @ref HAL_Pin_remapping
+ * @{
+ */
+#define __HAL_REMAP_PIN_ENABLE(__PIN_REMAP__) do {assert_param(IS_HAL_REMAP_PIN((__PIN_REMAP__))); \
+ SYSCFG->CFGR1 |= (__PIN_REMAP__); \
+ }while(0)
+#define __HAL_REMAP_PIN_DISABLE(__PIN_REMAP__) do {assert_param(IS_HAL_REMAP_PIN((__PIN_REMAP__))); \
+ SYSCFG->CFGR1 &= ~(__PIN_REMAP__); \
+ }while(0)
+/**
+ * @}
+ */
+#endif /* SYSCFG_CFGR1_PA11_PA12_RMP */
+
+/** @brief Fast-mode Plus driving capability enable/disable macros
+ * @param __FASTMODEPLUS__ This parameter can be a value of @ref SYSCFG_FastModePlus_GPIO values.
+ * That you can find above these macros.
+ */
+#define __HAL_SYSCFG_FASTMODEPLUS_ENABLE(__FASTMODEPLUS__) do {assert_param(IS_SYSCFG_FASTMODEPLUS((__FASTMODEPLUS__)));\
+ SET_BIT(SYSCFG->CFGR1, (__FASTMODEPLUS__));\
+ }while(0)
+
+#define __HAL_SYSCFG_FASTMODEPLUS_DISABLE(__FASTMODEPLUS__) do {assert_param(IS_SYSCFG_FASTMODEPLUS((__FASTMODEPLUS__)));\
+ CLEAR_BIT(SYSCFG->CFGR1, (__FASTMODEPLUS__));\
+ }while(0)
+#if defined(SYSCFG_CFGR2_LOCKUP_LOCK)
+/** @defgroup Cortex_Lockup_Enable Cortex Lockup Enable
+ * @{
+ */
+/** @brief SYSCFG Break Lockup lock
+ * Enables and locks the connection of Cortex-M0 LOCKUP (Hardfault) output to TIM1/15/16/17 Break input
+ * @note The selected configuration is locked and can be unlocked by system reset
+ */
+#define __HAL_SYSCFG_BREAK_LOCKUP_LOCK() do {SYSCFG->CFGR2 &= ~(SYSCFG_CFGR2_LOCKUP_LOCK); \
+ SYSCFG->CFGR2 |= SYSCFG_CFGR2_LOCKUP_LOCK; \
+ }while(0)
+/**
+ * @}
+ */
+#endif /* SYSCFG_CFGR2_LOCKUP_LOCK */
+
+#if defined(SYSCFG_CFGR2_PVD_LOCK)
+/** @defgroup PVD_Lock_Enable PVD Lock
+ * @{
+ */
+/** @brief SYSCFG Break PVD lock
+ * Enables and locks the PVD connection with Timer1/8/15/16/17 Break Input, , as well as the PVDE and PLS[2:0] in the PWR_CR register
+ * @note The selected configuration is locked and can be unlocked by system reset
+ */
+#define __HAL_SYSCFG_BREAK_PVD_LOCK() do {SYSCFG->CFGR2 &= ~(SYSCFG_CFGR2_PVD_LOCK); \
+ SYSCFG->CFGR2 |= SYSCFG_CFGR2_PVD_LOCK; \
+ }while(0)
+/**
+ * @}
+ */
+#endif /* SYSCFG_CFGR2_PVD_LOCK */
+
+#if defined(SYSCFG_CFGR2_SRAM_PARITY_LOCK)
+/** @defgroup SRAM_Parity_Lock SRAM Parity Lock
+ * @{
+ */
+/** @brief SYSCFG Break SRAM PARITY lock
+ * Enables and locks the SRAM_PARITY error signal with Break Input of TIMER1/8/15/16/17
+ * @note The selected configuration is locked and can be unlocked by system reset
+ */
+#define __HAL_SYSCFG_BREAK_SRAMPARITY_LOCK() do {SYSCFG->CFGR2 &= ~(SYSCFG_CFGR2_SRAM_PARITY_LOCK); \
+ SYSCFG->CFGR2 |= SYSCFG_CFGR2_SRAM_PARITY_LOCK; \
+ }while(0)
+/**
+ * @}
+ */
+#endif /* SYSCFG_CFGR2_SRAM_PARITY_LOCK */
+
+#if defined(SYSCFG_CFGR2_SRAM_PEF)
+/** @defgroup HAL_SYSCFG_Parity_check_on_RAM HAL SYSCFG Parity check on RAM
+ * @brief Parity check on RAM disable macro
+ * @note Disabling the parity check on RAM locks the configuration bit.
+ * To re-enable the parity check on RAM perform a system reset.
+ * @{
+ */
+#define __HAL_SYSCFG_RAM_PARITYCHECK_DISABLE() (SYSCFG->CFGR2 |= SYSCFG_CFGR2_SRAM_PEF)
+/**
+ * @}
+ */
+#endif /* SYSCFG_CFGR2_SRAM_PEF */
+
+
+#if defined(STM32F091xC) || defined (STM32F098xx)
+/** @defgroup HAL_ISR_wrapper_check HAL ISR wrapper check
+ * @brief ISR wrapper check
+ * @note This feature is applicable on STM32F09x
+ * @note Allow to determine interrupt source per line.
+ * @{
+ */
+#define __HAL_GET_PENDING_IT(__SOURCE__) (SYSCFG->IT_LINE_SR[((__SOURCE__) >> 0x18U)] & ((__SOURCE__) & 0x00FFFFFF))
+/**
+ * @}
+ */
+#endif /* (STM32F091xC) || defined (STM32F098xx)*/
+
+#if defined(STM32F091xC) || defined (STM32F098xx)
+/** @defgroup HAL_SYSCFG_IRDA_modulation_envelope_selection HAL SYSCFG IRDA modulation envelope selection
+ * @brief selection of the modulation envelope signal macro, using bits [7:6] of SYS_CTRL(CFGR1) register
+ * @note This feature is applicable on STM32F09x
+ * @param __SOURCE__ This parameter can be a value of @ref HAL_IRDA_ENV_SEL
+ * @{
+ */
+#define __HAL_SYSCFG_IRDA_ENV_SELECTION(__SOURCE__) do {assert_param(IS_HAL_SYSCFG_IRDA_ENV_SEL((__SOURCE__))); \
+ SYSCFG->CFGR1 &= ~(SYSCFG_CFGR1_IRDA_ENV_SEL); \
+ SYSCFG->CFGR1 |= (__SOURCE__); \
+ }while(0)
+
+#define __HAL_SYSCFG_GET_IRDA_ENV_SELECTION() ((SYSCFG->CFGR1) & 0x000000C0)
+/**
+ * @}
+ */
+#endif /* (STM32F091xC) || defined (STM32F098xx)*/
+
+/**
+ * @}
+ */
+
+/** @defgroup HAL_Private_Macros HAL Private Macros
+ * @{
+ */
+#define IS_TICKFREQ(FREQ) (((FREQ) == HAL_TICK_FREQ_10HZ) || \
+ ((FREQ) == HAL_TICK_FREQ_100HZ) || \
+ ((FREQ) == HAL_TICK_FREQ_1KHZ))
+/**
+ * @}
+ */
+
+/* Exported functions --------------------------------------------------------*/
+
+/** @addtogroup HAL_Exported_Functions
+ * @{
+ */
+
+/** @addtogroup HAL_Exported_Functions_Group1
+ * @{
+ */
+/* Initialization and de-initialization functions ******************************/
+HAL_StatusTypeDef HAL_Init(void);
+HAL_StatusTypeDef HAL_DeInit(void);
+void HAL_MspInit(void);
+void HAL_MspDeInit(void);
+HAL_StatusTypeDef HAL_InitTick (uint32_t TickPriority);
+/**
+ * @}
+ */
+
+/* Exported variables ---------------------------------------------------------*/
+/** @addtogroup HAL_Exported_Variables
+ * @{
+ */
+extern __IO uint32_t uwTick;
+extern uint32_t uwTickPrio;
+extern HAL_TickFreqTypeDef uwTickFreq;
+/**
+ * @}
+ */
+
+/** @addtogroup HAL_Exported_Functions_Group2
+ * @{
+ */
+
+/* Peripheral Control functions ************************************************/
+void HAL_IncTick(void);
+void HAL_Delay(uint32_t Delay);
+uint32_t HAL_GetTick(void);
+uint32_t HAL_GetTickPrio(void);
+HAL_StatusTypeDef HAL_SetTickFreq(HAL_TickFreqTypeDef Freq);
+HAL_TickFreqTypeDef HAL_GetTickFreq(void);
+void HAL_SuspendTick(void);
+void HAL_ResumeTick(void);
+uint32_t HAL_GetHalVersion(void);
+uint32_t HAL_GetREVID(void);
+uint32_t HAL_GetDEVID(void);
+uint32_t HAL_GetUIDw0(void);
+uint32_t HAL_GetUIDw1(void);
+uint32_t HAL_GetUIDw2(void);
+void HAL_DBGMCU_EnableDBGStopMode(void);
+void HAL_DBGMCU_DisableDBGStopMode(void);
+void HAL_DBGMCU_EnableDBGStandbyMode(void);
+void HAL_DBGMCU_DisableDBGStandbyMode(void);
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __STM32F0xx_HAL_H */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal_cortex.h b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal_cortex.h
new file mode 100644
index 0000000..d8a4251
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal_cortex.h
@@ -0,0 +1,133 @@
+/**
+ ******************************************************************************
+ * @file stm32f0xx_hal_cortex.h
+ * @author MCD Application Team
+ * @brief Header file of CORTEX HAL module.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2016 STMicroelectronics.
+ * All rights reserved.
+ *
+ * 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 __STM32F0xx_HAL_CORTEX_H
+#define __STM32F0xx_HAL_CORTEX_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f0xx_hal_def.h"
+
+/** @addtogroup STM32F0xx_HAL_Driver
+ * @{
+ */
+
+/** @addtogroup CORTEX CORTEX
+ * @{
+ */
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+
+/** @defgroup CORTEX_Exported_Constants CORTEX Exported Constants
+ * @{
+ */
+
+/** @defgroup CORTEX_SysTick_clock_source CORTEX SysTick clock source
+ * @{
+ */
+#define SYSTICK_CLKSOURCE_HCLK_DIV8 (0x00000000U)
+#define SYSTICK_CLKSOURCE_HCLK (0x00000004U)
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/* Exported Macros -----------------------------------------------------------*/
+
+/* Exported functions --------------------------------------------------------*/
+/** @addtogroup CORTEX_Exported_Functions CORTEX Exported Functions
+ * @{
+ */
+/** @addtogroup CORTEX_Exported_Functions_Group1 Initialization and de-initialization functions
+ * @brief Initialization and Configuration functions
+ * @{
+ */
+/* Initialization and de-initialization functions *******************************/
+void HAL_NVIC_SetPriority(IRQn_Type IRQn,uint32_t PreemptPriority, uint32_t SubPriority);
+void HAL_NVIC_EnableIRQ(IRQn_Type IRQn);
+void HAL_NVIC_DisableIRQ(IRQn_Type IRQn);
+void HAL_NVIC_SystemReset(void);
+uint32_t HAL_SYSTICK_Config(uint32_t TicksNumb);
+/**
+ * @}
+ */
+
+/** @addtogroup CORTEX_Exported_Functions_Group2 Peripheral Control functions
+ * @brief Cortex control functions
+ * @{
+ */
+
+/* Peripheral Control functions *************************************************/
+uint32_t HAL_NVIC_GetPriority(IRQn_Type IRQn);
+uint32_t HAL_NVIC_GetPendingIRQ(IRQn_Type IRQn);
+void HAL_NVIC_SetPendingIRQ(IRQn_Type IRQn);
+void HAL_NVIC_ClearPendingIRQ(IRQn_Type IRQn);
+void HAL_SYSTICK_CLKSourceConfig(uint32_t CLKSource);
+void HAL_SYSTICK_IRQHandler(void);
+void HAL_SYSTICK_Callback(void);
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/* Private types -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private constants ---------------------------------------------------------*/
+/* Private macros ------------------------------------------------------------*/
+/** @defgroup CORTEX_Private_Macros CORTEX Private Macros
+ * @{
+ */
+#define IS_NVIC_PREEMPTION_PRIORITY(PRIORITY) ((PRIORITY) < 0x4)
+
+#define IS_NVIC_DEVICE_IRQ(IRQ) ((IRQ) >= 0x00)
+
+#define IS_SYSTICK_CLK_SOURCE(SOURCE) (((SOURCE) == SYSTICK_CLKSOURCE_HCLK) || \
+ ((SOURCE) == SYSTICK_CLKSOURCE_HCLK_DIV8))
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __STM32F0xx_HAL_CORTEX_H */
+
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
+
diff --git a/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal_crc.h b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal_crc.h
new file mode 100644
index 0000000..39cb29a
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal_crc.h
@@ -0,0 +1,359 @@
+/**
+ ******************************************************************************
+ * @file stm32f0xx_hal_crc.h
+ * @author MCD Application Team
+ * @brief Header file of CRC HAL module.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2016 STMicroelectronics.
+ * All rights reserved.
+ *
+ * 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 STM32F0xx_HAL_CRC_H
+#define STM32F0xx_HAL_CRC_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f0xx_hal_def.h"
+
+/** @addtogroup STM32F0xx_HAL_Driver
+ * @{
+ */
+
+/** @addtogroup CRC
+ * @{
+ */
+
+/* Exported types ------------------------------------------------------------*/
+/** @defgroup CRC_Exported_Types CRC Exported Types
+ * @{
+ */
+
+/**
+ * @brief CRC HAL State Structure definition
+ */
+typedef enum
+{
+ HAL_CRC_STATE_RESET = 0x00U, /*!< CRC not yet initialized or disabled */
+ HAL_CRC_STATE_READY = 0x01U, /*!< CRC initialized and ready for use */
+ HAL_CRC_STATE_BUSY = 0x02U, /*!< CRC internal process is ongoing */
+ HAL_CRC_STATE_TIMEOUT = 0x03U, /*!< CRC timeout state */
+ HAL_CRC_STATE_ERROR = 0x04U /*!< CRC error state */
+} HAL_CRC_StateTypeDef;
+
+/**
+ * @brief CRC Init Structure definition
+ */
+typedef struct
+{
+#if defined(CRC_POL_POL)
+ uint8_t DefaultPolynomialUse; /*!< This parameter is a value of @ref CRC_Default_Polynomial and indicates if default polynomial is used.
+ If set to DEFAULT_POLYNOMIAL_ENABLE, resort to default
+ X^32 + X^26 + X^23 + X^22 + X^16 + X^12 + X^11 + X^10 +X^8 + X^7 + X^5 +
+ X^4 + X^2+ X +1.
+ In that case, there is no need to set GeneratingPolynomial field.
+ If otherwise set to DEFAULT_POLYNOMIAL_DISABLE, GeneratingPolynomial and
+ CRCLength fields must be set. */
+#endif /* CRC_POL_POL */
+
+ uint8_t DefaultInitValueUse; /*!< This parameter is a value of @ref CRC_Default_InitValue_Use and indicates if default init value is used.
+ If set to DEFAULT_INIT_VALUE_ENABLE, resort to default
+ 0xFFFFFFFF value. In that case, there is no need to set InitValue field. If
+ otherwise set to DEFAULT_INIT_VALUE_DISABLE, InitValue field must be set. */
+
+#if defined(CRC_POL_POL)
+ uint32_t GeneratingPolynomial; /*!< Set CRC generating polynomial as a 7, 8, 16 or 32-bit long value for a polynomial degree
+ respectively equal to 7, 8, 16 or 32. This field is written in normal,
+ representation e.g., for a polynomial of degree 7, X^7 + X^6 + X^5 + X^2 + 1
+ is written 0x65. No need to specify it if DefaultPolynomialUse is set to
+ DEFAULT_POLYNOMIAL_ENABLE. */
+
+ uint32_t CRCLength; /*!< This parameter is a value of @ref CRC_Polynomial_Sizes and indicates CRC length.
+ Value can be either one of
+ @arg @ref CRC_POLYLENGTH_32B (32-bit CRC),
+ @arg @ref CRC_POLYLENGTH_16B (16-bit CRC),
+ @arg @ref CRC_POLYLENGTH_8B (8-bit CRC),
+ @arg @ref CRC_POLYLENGTH_7B (7-bit CRC). */
+#endif /* CRC_POL_POL */
+
+ uint32_t InitValue; /*!< Init value to initiate CRC computation. No need to specify it if DefaultInitValueUse
+ is set to DEFAULT_INIT_VALUE_ENABLE. */
+
+ uint32_t InputDataInversionMode; /*!< This parameter is a value of @ref CRCEx_Input_Data_Inversion and specifies input data inversion mode.
+ Can be either one of the following values
+ @arg @ref CRC_INPUTDATA_INVERSION_NONE no input data inversion
+ @arg @ref CRC_INPUTDATA_INVERSION_BYTE byte-wise inversion, 0x1A2B3C4D
+ becomes 0x58D43CB2
+ @arg @ref CRC_INPUTDATA_INVERSION_HALFWORD halfword-wise inversion,
+ 0x1A2B3C4D becomes 0xD458B23C
+ @arg @ref CRC_INPUTDATA_INVERSION_WORD word-wise inversion, 0x1A2B3C4D
+ becomes 0xB23CD458 */
+
+ uint32_t OutputDataInversionMode; /*!< This parameter is a value of @ref CRCEx_Output_Data_Inversion and specifies output data (i.e. CRC) inversion mode.
+ Can be either
+ @arg @ref CRC_OUTPUTDATA_INVERSION_DISABLE no CRC inversion,
+ @arg @ref CRC_OUTPUTDATA_INVERSION_ENABLE CRC 0x11223344 is converted
+ into 0x22CC4488 */
+} CRC_InitTypeDef;
+
+/**
+ * @brief CRC Handle Structure definition
+ */
+typedef struct
+{
+ CRC_TypeDef *Instance; /*!< Register base address */
+
+ CRC_InitTypeDef Init; /*!< CRC configuration parameters */
+
+ HAL_LockTypeDef Lock; /*!< CRC Locking object */
+
+ __IO HAL_CRC_StateTypeDef State; /*!< CRC communication state */
+
+ uint32_t InputDataFormat; /*!< This parameter is a value of @ref CRC_Input_Buffer_Format and specifies input data format.
+ Can be either
+ @arg @ref CRC_INPUTDATA_FORMAT_BYTES input data is a stream of bytes
+ (8-bit data)
+ @arg @ref CRC_INPUTDATA_FORMAT_HALFWORDS input data is a stream of
+ half-words (16-bit data)
+ @arg @ref CRC_INPUTDATA_FORMAT_WORDS input data is a stream of words
+ (32-bit data)
+
+ Note that constant CRC_INPUT_FORMAT_UNDEFINED is defined but an initialization
+ error must occur if InputBufferFormat is not one of the three values listed
+ above */
+} CRC_HandleTypeDef;
+/**
+ * @}
+ */
+
+/* Exported constants --------------------------------------------------------*/
+/** @defgroup CRC_Exported_Constants CRC Exported Constants
+ * @{
+ */
+
+#if defined(CRC_POL_POL)
+/** @defgroup CRC_Default_Polynomial_Value Default CRC generating polynomial
+ * @{
+ */
+#define DEFAULT_CRC32_POLY 0x04C11DB7U /*!< X^32 + X^26 + X^23 + X^22 + X^16 + X^12 + X^11 + X^10 +X^8 + X^7 + X^5 + X^4 + X^2+ X +1 */
+/**
+ * @}
+ */
+#endif /* CRC_POL_POL */
+
+/** @defgroup CRC_Default_InitValue Default CRC computation initialization value
+ * @{
+ */
+#define DEFAULT_CRC_INITVALUE 0xFFFFFFFFU /*!< Initial CRC default value */
+/**
+ * @}
+ */
+
+#if defined(CRC_POL_POL)
+/** @defgroup CRC_Default_Polynomial Indicates whether or not default polynomial is used
+ * @{
+ */
+#define DEFAULT_POLYNOMIAL_ENABLE ((uint8_t)0x00U) /*!< Enable default generating polynomial 0x04C11DB7 */
+#define DEFAULT_POLYNOMIAL_DISABLE ((uint8_t)0x01U) /*!< Disable default generating polynomial 0x04C11DB7 */
+/**
+ * @}
+ */
+#endif /* CRC_POL_POL */
+
+/** @defgroup CRC_Default_InitValue_Use Indicates whether or not default init value is used
+ * @{
+ */
+#define DEFAULT_INIT_VALUE_ENABLE ((uint8_t)0x00U) /*!< Enable initial CRC default value */
+#define DEFAULT_INIT_VALUE_DISABLE ((uint8_t)0x01U) /*!< Disable initial CRC default value */
+/**
+ * @}
+ */
+
+#if defined(CRC_POL_POL)
+/** @defgroup CRC_Polynomial_Sizes Polynomial sizes to configure the peripheral
+ * @{
+ */
+#define CRC_POLYLENGTH_32B 0x00000000U /*!< Resort to a 32-bit long generating polynomial */
+#define CRC_POLYLENGTH_16B CRC_CR_POLYSIZE_0 /*!< Resort to a 16-bit long generating polynomial */
+#define CRC_POLYLENGTH_8B CRC_CR_POLYSIZE_1 /*!< Resort to a 8-bit long generating polynomial */
+#define CRC_POLYLENGTH_7B CRC_CR_POLYSIZE /*!< Resort to a 7-bit long generating polynomial */
+/**
+ * @}
+ */
+
+/** @defgroup CRC_Polynomial_Size_Definitions CRC polynomial possible sizes actual definitions
+ * @{
+ */
+#define HAL_CRC_LENGTH_32B 32U /*!< 32-bit long CRC */
+#define HAL_CRC_LENGTH_16B 16U /*!< 16-bit long CRC */
+#define HAL_CRC_LENGTH_8B 8U /*!< 8-bit long CRC */
+#define HAL_CRC_LENGTH_7B 7U /*!< 7-bit long CRC */
+/**
+ * @}
+ */
+#endif /* CRC_POL_POL */
+
+/** @defgroup CRC_Input_Buffer_Format Input Buffer Format
+ * @{
+ */
+/* WARNING: CRC_INPUT_FORMAT_UNDEFINED is created for reference purposes but
+ * an error is triggered in HAL_CRC_Init() if InputDataFormat field is set
+ * to CRC_INPUT_FORMAT_UNDEFINED: the format MUST be defined by the user for
+ * the CRC APIs to provide a correct result */
+#define CRC_INPUTDATA_FORMAT_UNDEFINED 0x00000000U /*!< Undefined input data format */
+#define CRC_INPUTDATA_FORMAT_BYTES 0x00000001U /*!< Input data in byte format */
+#define CRC_INPUTDATA_FORMAT_HALFWORDS 0x00000002U /*!< Input data in half-word format */
+#define CRC_INPUTDATA_FORMAT_WORDS 0x00000003U /*!< Input data in word format */
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/* Exported macros -----------------------------------------------------------*/
+/** @defgroup CRC_Exported_Macros CRC Exported Macros
+ * @{
+ */
+
+/** @brief Reset CRC handle state.
+ * @param __HANDLE__ CRC handle.
+ * @retval None
+ */
+#define __HAL_CRC_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_CRC_STATE_RESET)
+
+/**
+ * @brief Reset CRC Data Register.
+ * @param __HANDLE__ CRC handle
+ * @retval None
+ */
+#define __HAL_CRC_DR_RESET(__HANDLE__) ((__HANDLE__)->Instance->CR |= CRC_CR_RESET)
+
+/**
+ * @brief Set CRC INIT non-default value
+ * @param __HANDLE__ CRC handle
+ * @param __INIT__ 32-bit initial value
+ * @retval None
+ */
+#define __HAL_CRC_INITIALCRCVALUE_CONFIG(__HANDLE__, __INIT__) ((__HANDLE__)->Instance->INIT = (__INIT__))
+
+/**
+ * @brief Store data in the Independent Data (ID) register.
+ * @param __HANDLE__ CRC handle
+ * @param __VALUE__ Value to be stored in the ID register
+ * @note Refer to the Reference Manual to get the authorized __VALUE__ length in bits
+ * @retval None
+ */
+#define __HAL_CRC_SET_IDR(__HANDLE__, __VALUE__) (WRITE_REG((__HANDLE__)->Instance->IDR, (__VALUE__)))
+
+/**
+ * @brief Return the data stored in the Independent Data (ID) register.
+ * @param __HANDLE__ CRC handle
+ * @note Refer to the Reference Manual to get the authorized __VALUE__ length in bits
+ * @retval Value of the ID register
+ */
+#define __HAL_CRC_GET_IDR(__HANDLE__) (((__HANDLE__)->Instance->IDR) & CRC_IDR_IDR)
+/**
+ * @}
+ */
+
+
+/* Private macros --------------------------------------------------------*/
+/** @defgroup CRC_Private_Macros CRC Private Macros
+ * @{
+ */
+
+#if defined(CRC_POL_POL)
+#define IS_DEFAULT_POLYNOMIAL(DEFAULT) (((DEFAULT) == DEFAULT_POLYNOMIAL_ENABLE) || \
+ ((DEFAULT) == DEFAULT_POLYNOMIAL_DISABLE))
+#endif /* CRC_POL_POL */
+
+#define IS_DEFAULT_INIT_VALUE(VALUE) (((VALUE) == DEFAULT_INIT_VALUE_ENABLE) || \
+ ((VALUE) == DEFAULT_INIT_VALUE_DISABLE))
+
+#if defined(CRC_POL_POL)
+#define IS_CRC_POL_LENGTH(LENGTH) (((LENGTH) == CRC_POLYLENGTH_32B) || \
+ ((LENGTH) == CRC_POLYLENGTH_16B) || \
+ ((LENGTH) == CRC_POLYLENGTH_8B) || \
+ ((LENGTH) == CRC_POLYLENGTH_7B))
+#endif /* CRC_POL_POL */
+
+#define IS_CRC_INPUTDATA_FORMAT(FORMAT) (((FORMAT) == CRC_INPUTDATA_FORMAT_BYTES) || \
+ ((FORMAT) == CRC_INPUTDATA_FORMAT_HALFWORDS) || \
+ ((FORMAT) == CRC_INPUTDATA_FORMAT_WORDS))
+
+/**
+ * @}
+ */
+
+/* Include CRC HAL Extended module */
+#include "stm32f0xx_hal_crc_ex.h"
+
+/* Exported functions --------------------------------------------------------*/
+/** @defgroup CRC_Exported_Functions CRC Exported Functions
+ * @{
+ */
+
+/* Initialization and de-initialization functions ****************************/
+/** @defgroup CRC_Exported_Functions_Group1 Initialization and de-initialization functions
+ * @{
+ */
+HAL_StatusTypeDef HAL_CRC_Init(CRC_HandleTypeDef *hcrc);
+HAL_StatusTypeDef HAL_CRC_DeInit(CRC_HandleTypeDef *hcrc);
+void HAL_CRC_MspInit(CRC_HandleTypeDef *hcrc);
+void HAL_CRC_MspDeInit(CRC_HandleTypeDef *hcrc);
+/**
+ * @}
+ */
+
+/* Peripheral Control functions ***********************************************/
+/** @defgroup CRC_Exported_Functions_Group2 Peripheral Control functions
+ * @{
+ */
+uint32_t HAL_CRC_Accumulate(CRC_HandleTypeDef *hcrc, uint32_t pBuffer[], uint32_t BufferLength);
+uint32_t HAL_CRC_Calculate(CRC_HandleTypeDef *hcrc, uint32_t pBuffer[], uint32_t BufferLength);
+/**
+ * @}
+ */
+
+/* Peripheral State and Error functions ***************************************/
+/** @defgroup CRC_Exported_Functions_Group3 Peripheral State functions
+ * @{
+ */
+HAL_CRC_StateTypeDef HAL_CRC_GetState(CRC_HandleTypeDef *hcrc);
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* STM32F0xx_HAL_CRC_H */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal_crc_ex.h b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal_crc_ex.h
new file mode 100644
index 0000000..6678dc9
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal_crc_ex.h
@@ -0,0 +1,153 @@
+/**
+ ******************************************************************************
+ * @file stm32f0xx_hal_crc_ex.h
+ * @author MCD Application Team
+ * @brief Header file of CRC HAL extended module.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2016 STMicroelectronics.
+ * All rights reserved.
+ *
+ * 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 STM32F0xx_HAL_CRC_EX_H
+#define STM32F0xx_HAL_CRC_EX_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f0xx_hal_def.h"
+
+/** @addtogroup STM32F0xx_HAL_Driver
+ * @{
+ */
+
+/** @addtogroup CRCEx
+ * @{
+ */
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/** @defgroup CRCEx_Exported_Constants CRC Extended Exported Constants
+ * @{
+ */
+
+/** @defgroup CRCEx_Input_Data_Inversion Input Data Inversion Modes
+ * @{
+ */
+#define CRC_INPUTDATA_INVERSION_NONE 0x00000000U /*!< No input data inversion */
+#define CRC_INPUTDATA_INVERSION_BYTE CRC_CR_REV_IN_0 /*!< Byte-wise input data inversion */
+#define CRC_INPUTDATA_INVERSION_HALFWORD CRC_CR_REV_IN_1 /*!< HalfWord-wise input data inversion */
+#define CRC_INPUTDATA_INVERSION_WORD CRC_CR_REV_IN /*!< Word-wise input data inversion */
+/**
+ * @}
+ */
+
+/** @defgroup CRCEx_Output_Data_Inversion Output Data Inversion Modes
+ * @{
+ */
+#define CRC_OUTPUTDATA_INVERSION_DISABLE 0x00000000U /*!< No output data inversion */
+#define CRC_OUTPUTDATA_INVERSION_ENABLE CRC_CR_REV_OUT /*!< Bit-wise output data inversion */
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/* Exported macro ------------------------------------------------------------*/
+/** @defgroup CRCEx_Exported_Macros CRC Extended Exported Macros
+ * @{
+ */
+
+/**
+ * @brief Set CRC output reversal
+ * @param __HANDLE__ CRC handle
+ * @retval None
+ */
+#define __HAL_CRC_OUTPUTREVERSAL_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR |= CRC_CR_REV_OUT)
+
+/**
+ * @brief Unset CRC output reversal
+ * @param __HANDLE__ CRC handle
+ * @retval None
+ */
+#define __HAL_CRC_OUTPUTREVERSAL_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR &= ~(CRC_CR_REV_OUT))
+
+/**
+ * @brief Set CRC non-default polynomial
+ * @param __HANDLE__ CRC handle
+ * @param __POLYNOMIAL__ 7, 8, 16 or 32-bit polynomial
+ * @retval None
+ */
+#define __HAL_CRC_POLYNOMIAL_CONFIG(__HANDLE__, __POLYNOMIAL__) ((__HANDLE__)->Instance->POL = (__POLYNOMIAL__))
+
+/**
+ * @}
+ */
+
+/* Private macros --------------------------------------------------------*/
+/** @defgroup CRCEx_Private_Macros CRC Extended Private Macros
+ * @{
+ */
+
+#define IS_CRC_INPUTDATA_INVERSION_MODE(MODE) (((MODE) == CRC_INPUTDATA_INVERSION_NONE) || \
+ ((MODE) == CRC_INPUTDATA_INVERSION_BYTE) || \
+ ((MODE) == CRC_INPUTDATA_INVERSION_HALFWORD) || \
+ ((MODE) == CRC_INPUTDATA_INVERSION_WORD))
+
+#define IS_CRC_OUTPUTDATA_INVERSION_MODE(MODE) (((MODE) == CRC_OUTPUTDATA_INVERSION_DISABLE) || \
+ ((MODE) == CRC_OUTPUTDATA_INVERSION_ENABLE))
+
+/**
+ * @}
+ */
+
+/* Exported functions --------------------------------------------------------*/
+
+/** @addtogroup CRCEx_Exported_Functions
+ * @{
+ */
+
+/** @addtogroup CRCEx_Exported_Functions_Group1
+ * @{
+ */
+/* Initialization and de-initialization functions ****************************/
+HAL_StatusTypeDef HAL_CRCEx_Polynomial_Set(CRC_HandleTypeDef *hcrc, uint32_t Pol, uint32_t PolyLength);
+HAL_StatusTypeDef HAL_CRCEx_Input_Data_Reverse(CRC_HandleTypeDef *hcrc, uint32_t InputReverseMode);
+HAL_StatusTypeDef HAL_CRCEx_Output_Data_Reverse(CRC_HandleTypeDef *hcrc, uint32_t OutputReverseMode);
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* STM32F0xx_HAL_CRC_EX_H */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal_def.h b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal_def.h
new file mode 100644
index 0000000..6c8fe37
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal_def.h
@@ -0,0 +1,178 @@
+/**
+ ******************************************************************************
+ * @file stm32f0xx_hal_def.h
+ * @author MCD Application Team
+ * @brief This file contains HAL common defines, enumeration, macros and
+ * structures definitions.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2016 STMicroelectronics.
+ * All rights reserved.
+ *
+ * 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 __STM32F0xx_HAL_DEF
+#define __STM32F0xx_HAL_DEF
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f0xx.h"
+#include "Legacy/stm32_hal_legacy.h"
+#include
+
+/* Exported types ------------------------------------------------------------*/
+
+/**
+ * @brief HAL Status structures definition
+ */
+typedef enum
+{
+ HAL_OK = 0x00U,
+ HAL_ERROR = 0x01U,
+ HAL_BUSY = 0x02U,
+ HAL_TIMEOUT = 0x03U
+} HAL_StatusTypeDef;
+
+/**
+ * @brief HAL Lock structures definition
+ */
+typedef enum
+{
+ HAL_UNLOCKED = 0x00U,
+ HAL_LOCKED = 0x01U
+} HAL_LockTypeDef;
+
+/* Exported macro ------------------------------------------------------------*/
+
+#define UNUSED(X) (void)X /* To avoid gcc/g++ warnings */
+
+#define HAL_MAX_DELAY 0xFFFFFFFFU
+
+#define HAL_IS_BIT_SET(REG, BIT) (((REG) & (BIT)) == (BIT))
+#define HAL_IS_BIT_CLR(REG, BIT) (((REG) & (BIT)) == 0U)
+
+#define __HAL_LINKDMA(__HANDLE__, __PPP_DMA_FIELD__, __DMA_HANDLE__) \
+ do{ \
+ (__HANDLE__)->__PPP_DMA_FIELD__ = &(__DMA_HANDLE__); \
+ (__DMA_HANDLE__).Parent = (__HANDLE__); \
+ } while(0U)
+
+/** @brief Reset the Handle's State field.
+ * @param __HANDLE__ specifies the Peripheral Handle.
+ * @note This macro can be used for the following purpose:
+ * - When the Handle is declared as local variable; before passing it as parameter
+ * to HAL_PPP_Init() for the first time, it is mandatory to use this macro
+ * to set to 0 the Handle's "State" field.
+ * Otherwise, "State" field may have any random value and the first time the function
+ * HAL_PPP_Init() is called, the low level hardware initialization will be missed
+ * (i.e. HAL_PPP_MspInit() will not be executed).
+ * - When there is a need to reconfigure the low level hardware: instead of calling
+ * HAL_PPP_DeInit() then HAL_PPP_Init(), user can make a call to this macro then HAL_PPP_Init().
+ * In this later function, when the Handle's "State" field is set to 0, it will execute the function
+ * HAL_PPP_MspInit() which will reconfigure the low level hardware.
+ * @retval None
+ */
+#define __HAL_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = 0U)
+
+#if (USE_RTOS == 1U)
+ /* Reserved for future use */
+ #error " USE_RTOS should be 0 in the current HAL release "
+#else
+ #define __HAL_LOCK(__HANDLE__) \
+ do{ \
+ if((__HANDLE__)->Lock == HAL_LOCKED) \
+ { \
+ return HAL_BUSY; \
+ } \
+ else \
+ { \
+ (__HANDLE__)->Lock = HAL_LOCKED; \
+ } \
+ }while (0U)
+
+ #define __HAL_UNLOCK(__HANDLE__) \
+ do{ \
+ (__HANDLE__)->Lock = HAL_UNLOCKED; \
+ }while (0U)
+#endif /* USE_RTOS */
+
+#if defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) /* ARM Compiler V6 */
+ #ifndef __weak
+ #define __weak __attribute__((weak))
+ #endif
+ #ifndef __packed
+ #define __packed __attribute__((packed))
+ #endif
+#elif defined ( __GNUC__ ) && !defined (__CC_ARM) /* GNU Compiler */
+ #ifndef __weak
+ #define __weak __attribute__((weak))
+ #endif /* __weak */
+ #ifndef __packed
+ #define __packed __attribute__((__packed__))
+ #endif /* __packed */
+#endif /* __GNUC__ */
+
+
+/* Macro to get variable aligned on 4-bytes, for __ICCARM__ the directive "#pragma data_alignment=4" must be used instead */
+#if defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) /* ARM Compiler V6 */
+ #ifndef __ALIGN_BEGIN
+ #define __ALIGN_BEGIN
+ #endif
+ #ifndef __ALIGN_END
+ #define __ALIGN_END __attribute__ ((aligned (4)))
+ #endif
+#elif defined ( __GNUC__ ) && !defined (__CC_ARM) /* GNU Compiler */
+ #ifndef __ALIGN_END
+ #define __ALIGN_END __attribute__ ((aligned (4)))
+ #endif /* __ALIGN_END */
+ #ifndef __ALIGN_BEGIN
+ #define __ALIGN_BEGIN
+ #endif /* __ALIGN_BEGIN */
+#else
+ #ifndef __ALIGN_END
+ #define __ALIGN_END
+ #endif /* __ALIGN_END */
+ #ifndef __ALIGN_BEGIN
+ #if defined (__CC_ARM) /* ARM Compiler V5*/
+ #define __ALIGN_BEGIN __align(4)
+ #elif defined (__ICCARM__) /* IAR Compiler */
+ #define __ALIGN_BEGIN
+ #endif /* __CC_ARM */
+ #endif /* __ALIGN_BEGIN */
+#endif /* __GNUC__ */
+
+/**
+ * @brief __NOINLINE definition
+ */
+#if defined ( __CC_ARM ) || (defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)) || defined ( __GNUC__ )
+/* ARM V4/V5 and V6 & GNU Compiler
+ -------------------------------
+*/
+#define __NOINLINE __attribute__ ( (noinline) )
+
+#elif defined ( __ICCARM__ )
+/* ICCARM Compiler
+ ---------------
+*/
+#define __NOINLINE _Pragma("optimize = no_inline")
+
+#endif
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* ___STM32F0xx_HAL_DEF */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal_dma.h b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal_dma.h
new file mode 100644
index 0000000..1304d1d
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal_dma.h
@@ -0,0 +1,563 @@
+/**
+ ******************************************************************************
+ * @file stm32f0xx_hal_dma.h
+ * @author MCD Application Team
+ * @brief Header file of DMA HAL module.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2016 STMicroelectronics.
+ * All rights reserved.
+ *
+ * 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 __STM32F0xx_HAL_DMA_H
+#define __STM32F0xx_HAL_DMA_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f0xx_hal_def.h"
+
+/** @addtogroup STM32F0xx_HAL_Driver
+ * @{
+ */
+
+/** @addtogroup DMA
+ * @{
+ */
+
+/* Exported types ------------------------------------------------------------*/
+
+/** @defgroup DMA_Exported_Types DMA Exported Types
+ * @{
+ */
+
+/**
+ * @brief DMA Configuration Structure definition
+ */
+typedef struct
+{
+ uint32_t Direction; /*!< Specifies if the data will be transferred from memory to peripheral,
+ from memory to memory or from peripheral to memory.
+ This parameter can be a value of @ref DMA_Data_transfer_direction */
+
+ uint32_t PeriphInc; /*!< Specifies whether the Peripheral address register should be incremented or not.
+ This parameter can be a value of @ref DMA_Peripheral_incremented_mode */
+
+ uint32_t MemInc; /*!< Specifies whether the memory address register should be incremented or not.
+ This parameter can be a value of @ref DMA_Memory_incremented_mode */
+
+ uint32_t PeriphDataAlignment; /*!< Specifies the Peripheral data width.
+ This parameter can be a value of @ref DMA_Peripheral_data_size */
+
+ uint32_t MemDataAlignment; /*!< Specifies the Memory data width.
+ This parameter can be a value of @ref DMA_Memory_data_size */
+
+ uint32_t Mode; /*!< Specifies the operation mode of the DMAy Channelx.
+ This parameter can be a value of @ref DMA_mode
+ @note The circular buffer mode cannot be used if the memory-to-memory
+ data transfer is configured on the selected Channel */
+
+ uint32_t Priority; /*!< Specifies the software priority for the DMAy Channelx.
+ This parameter can be a value of @ref DMA_Priority_level */
+} DMA_InitTypeDef;
+
+/**
+ * @brief HAL DMA State structures definition
+ */
+typedef enum
+{
+ HAL_DMA_STATE_RESET = 0x00U, /*!< DMA not yet initialized or disabled */
+ HAL_DMA_STATE_READY = 0x01U, /*!< DMA initialized and ready for use */
+ HAL_DMA_STATE_BUSY = 0x02U, /*!< DMA process is ongoing */
+ HAL_DMA_STATE_TIMEOUT = 0x03U /*!< DMA timeout state */
+}HAL_DMA_StateTypeDef;
+
+/**
+ * @brief HAL DMA Error Code structure definition
+ */
+typedef enum
+{
+ HAL_DMA_FULL_TRANSFER = 0x00U, /*!< Full transfer */
+ HAL_DMA_HALF_TRANSFER = 0x01U /*!< Half Transfer */
+}HAL_DMA_LevelCompleteTypeDef;
+
+/**
+ * @brief HAL DMA Callback ID structure definition
+ */
+typedef enum
+{
+ HAL_DMA_XFER_CPLT_CB_ID = 0x00U, /*!< Full transfer */
+ HAL_DMA_XFER_HALFCPLT_CB_ID = 0x01U, /*!< Half transfer */
+ HAL_DMA_XFER_ERROR_CB_ID = 0x02U, /*!< Error */
+ HAL_DMA_XFER_ABORT_CB_ID = 0x03U, /*!< Abort */
+ HAL_DMA_XFER_ALL_CB_ID = 0x04U /*!< All */
+
+}HAL_DMA_CallbackIDTypeDef;
+
+/**
+ * @brief DMA handle Structure definition
+ */
+typedef struct __DMA_HandleTypeDef
+{
+ DMA_Channel_TypeDef *Instance; /*!< Register base address */
+
+ DMA_InitTypeDef Init; /*!< DMA communication parameters */
+
+ HAL_LockTypeDef Lock; /*!< DMA locking object */
+
+ __IO HAL_DMA_StateTypeDef State; /*!< DMA transfer state */
+
+ void *Parent; /*!< Parent object state */
+
+ void (* XferCpltCallback)( struct __DMA_HandleTypeDef * hdma); /*!< DMA transfer complete callback */
+
+ void (* XferHalfCpltCallback)( struct __DMA_HandleTypeDef * hdma); /*!< DMA Half transfer complete callback */
+
+ void (* XferErrorCallback)( struct __DMA_HandleTypeDef * hdma); /*!< DMA transfer error callback */
+
+ void (* XferAbortCallback)( struct __DMA_HandleTypeDef * hdma); /*!< DMA transfer abort callback */
+
+ __IO uint32_t ErrorCode; /*!< DMA Error code */
+
+ DMA_TypeDef *DmaBaseAddress; /*!< DMA Channel Base Address */
+
+ uint32_t ChannelIndex; /*!< DMA Channel Index */
+} DMA_HandleTypeDef;
+
+/**
+ * @}
+ */
+
+/* Exported constants --------------------------------------------------------*/
+
+/** @defgroup DMA_Exported_Constants DMA Exported Constants
+ * @{
+ */
+
+/** @defgroup DMA_Error_Code DMA Error Code
+ * @{
+ */
+#define HAL_DMA_ERROR_NONE (0x00000000U) /*!< No error */
+#define HAL_DMA_ERROR_TE (0x00000001U) /*!< Transfer error */
+#define HAL_DMA_ERROR_NO_XFER (0x00000004U) /*!< no ongoin transfer */
+#define HAL_DMA_ERROR_TIMEOUT (0x00000020U) /*!< Timeout error */
+#define HAL_DMA_ERROR_NOT_SUPPORTED (0x00000100U) /*!< Not supported mode */
+/**
+ * @}
+ */
+
+/** @defgroup DMA_Data_transfer_direction DMA Data transfer direction
+ * @{
+ */
+#define DMA_PERIPH_TO_MEMORY (0x00000000U) /*!< Peripheral to memory direction */
+#define DMA_MEMORY_TO_PERIPH ((uint32_t)DMA_CCR_DIR) /*!< Memory to peripheral direction */
+#define DMA_MEMORY_TO_MEMORY ((uint32_t)(DMA_CCR_MEM2MEM)) /*!< Memory to memory direction */
+
+/**
+ * @}
+ */
+
+/** @defgroup DMA_Peripheral_incremented_mode DMA Peripheral incremented mode
+ * @{
+ */
+#define DMA_PINC_ENABLE ((uint32_t)DMA_CCR_PINC) /*!< Peripheral increment mode Enable */
+#define DMA_PINC_DISABLE (0x00000000U) /*!< Peripheral increment mode Disable */
+/**
+ * @}
+ */
+
+/** @defgroup DMA_Memory_incremented_mode DMA Memory incremented mode
+ * @{
+ */
+#define DMA_MINC_ENABLE ((uint32_t)DMA_CCR_MINC) /*!< Memory increment mode Enable */
+#define DMA_MINC_DISABLE (0x00000000U) /*!< Memory increment mode Disable */
+/**
+ * @}
+ */
+
+/** @defgroup DMA_Peripheral_data_size DMA Peripheral data size
+ * @{
+ */
+#define DMA_PDATAALIGN_BYTE (0x00000000U) /*!< Peripheral data alignment : Byte */
+#define DMA_PDATAALIGN_HALFWORD ((uint32_t)DMA_CCR_PSIZE_0) /*!< Peripheral data alignment : HalfWord */
+#define DMA_PDATAALIGN_WORD ((uint32_t)DMA_CCR_PSIZE_1) /*!< Peripheral data alignment : Word */
+/**
+ * @}
+ */
+
+/** @defgroup DMA_Memory_data_size DMA Memory data size
+ * @{
+ */
+#define DMA_MDATAALIGN_BYTE (0x00000000U) /*!< Memory data alignment : Byte */
+#define DMA_MDATAALIGN_HALFWORD ((uint32_t)DMA_CCR_MSIZE_0) /*!< Memory data alignment : HalfWord */
+#define DMA_MDATAALIGN_WORD ((uint32_t)DMA_CCR_MSIZE_1) /*!< Memory data alignment : Word */
+/**
+ * @}
+ */
+
+/** @defgroup DMA_mode DMA mode
+ * @{
+ */
+#define DMA_NORMAL (0x00000000U) /*!< Normal Mode */
+#define DMA_CIRCULAR ((uint32_t)DMA_CCR_CIRC) /*!< Circular Mode */
+/**
+ * @}
+ */
+
+/** @defgroup DMA_Priority_level DMA Priority level
+ * @{
+ */
+#define DMA_PRIORITY_LOW (0x00000000U) /*!< Priority level : Low */
+#define DMA_PRIORITY_MEDIUM ((uint32_t)DMA_CCR_PL_0) /*!< Priority level : Medium */
+#define DMA_PRIORITY_HIGH ((uint32_t)DMA_CCR_PL_1) /*!< Priority level : High */
+#define DMA_PRIORITY_VERY_HIGH ((uint32_t)DMA_CCR_PL) /*!< Priority level : Very_High */
+/**
+ * @}
+ */
+
+
+/** @defgroup DMA_interrupt_enable_definitions DMA interrupt enable definitions
+ * @{
+ */
+#define DMA_IT_TC ((uint32_t)DMA_CCR_TCIE)
+#define DMA_IT_HT ((uint32_t)DMA_CCR_HTIE)
+#define DMA_IT_TE ((uint32_t)DMA_CCR_TEIE)
+/**
+ * @}
+ */
+
+/** @defgroup DMA_flag_definitions DMA flag definitions
+ * @{
+ */
+
+#define DMA_FLAG_GL1 (0x00000001U) /*!< Channel 1 global interrupt flag */
+#define DMA_FLAG_TC1 (0x00000002U) /*!< Channel 1 transfer complete flag */
+#define DMA_FLAG_HT1 (0x00000004U) /*!< Channel 1 half transfer flag */
+#define DMA_FLAG_TE1 (0x00000008U) /*!< Channel 1 transfer error flag */
+#define DMA_FLAG_GL2 (0x00000010U) /*!< Channel 2 global interrupt flag */
+#define DMA_FLAG_TC2 (0x00000020U) /*!< Channel 2 transfer complete flag */
+#define DMA_FLAG_HT2 (0x00000040U) /*!< Channel 2 half transfer flag */
+#define DMA_FLAG_TE2 (0x00000080U) /*!< Channel 2 transfer error flag */
+#define DMA_FLAG_GL3 (0x00000100U) /*!< Channel 3 global interrupt flag */
+#define DMA_FLAG_TC3 (0x00000200U) /*!< Channel 3 transfer complete flag */
+#define DMA_FLAG_HT3 (0x00000400U) /*!< Channel 3 half transfer flag */
+#define DMA_FLAG_TE3 (0x00000800U) /*!< Channel 3 transfer error flag */
+#define DMA_FLAG_GL4 (0x00001000U) /*!< Channel 4 global interrupt flag */
+#define DMA_FLAG_TC4 (0x00002000U) /*!< Channel 4 transfer complete flag */
+#define DMA_FLAG_HT4 (0x00004000U) /*!< Channel 4 half transfer flag */
+#define DMA_FLAG_TE4 (0x00008000U) /*!< Channel 4 transfer error flag */
+#define DMA_FLAG_GL5 (0x00010000U) /*!< Channel 5 global interrupt flag */
+#define DMA_FLAG_TC5 (0x00020000U) /*!< Channel 5 transfer complete flag */
+#define DMA_FLAG_HT5 (0x00040000U) /*!< Channel 5 half transfer flag */
+#define DMA_FLAG_TE5 (0x00080000U) /*!< Channel 5 transfer error flag */
+#define DMA_FLAG_GL6 (0x00100000U) /*!< Channel 6 global interrupt flag */
+#define DMA_FLAG_TC6 (0x00200000U) /*!< Channel 6 transfer complete flag */
+#define DMA_FLAG_HT6 (0x00400000U) /*!< Channel 6 half transfer flag */
+#define DMA_FLAG_TE6 (0x00800000U) /*!< Channel 6 transfer error flag */
+#define DMA_FLAG_GL7 (0x01000000U) /*!< Channel 7 global interrupt flag */
+#define DMA_FLAG_TC7 (0x02000000U) /*!< Channel 7 transfer complete flag */
+#define DMA_FLAG_HT7 (0x04000000U) /*!< Channel 7 half transfer flag */
+#define DMA_FLAG_TE7 (0x08000000U) /*!< Channel 7 transfer error flag */
+
+/**
+ * @}
+ */
+
+#if defined(SYSCFG_CFGR1_DMA_RMP)
+/** @defgroup HAL_DMA_remapping HAL DMA remapping
+ * Elements values convention: 0xYYYYYYYY
+ * - YYYYYYYY : Position in the SYSCFG register CFGR1
+ * @{
+ */
+#define DMA_REMAP_ADC_DMA_CH2 ((uint32_t)SYSCFG_CFGR1_ADC_DMA_RMP) /*!< ADC DMA remap
+ 0: No remap (ADC DMA requests mapped on DMA channel 1
+ 1: Remap (ADC DMA requests mapped on DMA channel 2 */
+#define DMA_REMAP_USART1_TX_DMA_CH4 ((uint32_t)SYSCFG_CFGR1_USART1TX_DMA_RMP) /*!< USART1 TX DMA remap
+ 0: No remap (USART1_TX DMA request mapped on DMA channel 2
+ 1: Remap (USART1_TX DMA request mapped on DMA channel 4 */
+#define DMA_REMAP_USART1_RX_DMA_CH5 ((uint32_t)SYSCFG_CFGR1_USART1RX_DMA_RMP) /*!< USART1 RX DMA remap
+ 0: No remap (USART1_RX DMA request mapped on DMA channel 3
+ 1: Remap (USART1_RX DMA request mapped on DMA channel 5 */
+#define DMA_REMAP_TIM16_DMA_CH4 ((uint32_t)SYSCFG_CFGR1_TIM16_DMA_RMP) /*!< TIM16 DMA request remap
+ 0: No remap (TIM16_CH1 and TIM16_UP DMA requests mapped on DMA channel 3)
+ 1: Remap (TIM16_CH1 and TIM16_UP DMA requests mapped on DMA channel 4) */
+#define DMA_REMAP_TIM17_DMA_CH2 ((uint32_t)SYSCFG_CFGR1_TIM17_DMA_RMP) /*!< TIM17 DMA request remap
+ 0: No remap (TIM17_CH1 and TIM17_UP DMA requests mapped on DMA channel 1
+ 1: Remap (TIM17_CH1 and TIM17_UP DMA requests mapped on DMA channel 2) */
+#if defined (STM32F070xB)
+#define DMA_REMAP_USART3_DMA_CH32 ((uint32_t)SYSCFG_CFGR1_USART3_DMA_RMP) /*!< USART3 DMA request remapping bit. Available on STM32F070xB devices only.
+ 0: Disabled, need to remap before use
+ 1: Remap (USART3_RX and USART3_TX DMA requests mapped on DMA channel 3 and 2 respectively) */
+
+#endif
+
+#if defined (STM32F071xB) || defined (STM32F072xB) || defined (STM32F078xx)
+#define DMA_REMAP_TIM16_DMA_CH6 ((uint32_t)SYSCFG_CFGR1_TIM16_DMA_RMP2) /*!< TIM16 alternate DMA request remapping bit. Available on STM32F07x devices only
+ 0: No alternate remap (TIM16 DMA requestsmapped according to TIM16_DMA_RMP bit)
+ 1: Alternate remap (TIM16_CH1 and TIM16_UP DMA requests mapped on DMA channel 6) */
+#define DMA_REMAP_TIM17_DMA_CH7 ((uint32_t)SYSCFG_CFGR1_TIM17_DMA_RMP2) /*!< TIM17 alternate DMA request remapping bit. Available on STM32F07x devices only
+ 0: No alternate remap (TIM17 DMA requestsmapped according to TIM17_DMA_RMP bit)
+ 1: Alternate remap (TIM17_CH1 and TIM17_UP DMA requests mapped on DMA channel 7) */
+#define DMA_REMAP_SPI2_DMA_CH67 ((uint32_t)SYSCFG_CFGR1_SPI2_DMA_RMP) /*!< SPI2 DMA request remapping bit. Available on STM32F07x devices only.
+ 0: No remap (SPI2_RX and SPI2_TX DMA requests mapped on DMA channel 4 and 5 respectively)
+ 1: Remap (SPI2_RX and SPI2_TX DMA requests mapped on DMA channel 6 and 7 respectively) */
+#define DMA_REMAP_USART2_DMA_CH67 ((uint32_t)SYSCFG_CFGR1_USART2_DMA_RMP) /*!< USART2 DMA request remapping bit. Available on STM32F07x devices only.
+ 0: No remap (USART2_RX and USART2_TX DMA requests mapped on DMA channel 5 and 4 respectively)
+ 1: 1: Remap (USART2_RX and USART2_TX DMA requests mapped on DMA channel 6 and 7 respectively) */
+#define DMA_REMAP_USART3_DMA_CH32 ((uint32_t)SYSCFG_CFGR1_USART3_DMA_RMP) /*!< USART3 DMA request remapping bit. Available on STM32F07x devices only.
+ 0: No remap (USART3_RX and USART3_TX DMA requests mapped on DMA channel 6 and 7 respectively)
+ 1: Remap (USART3_RX and USART3_TX DMA requests mapped on DMA channel 3 and 2 respectively) */
+#define DMA_REMAP_I2C1_DMA_CH76 ((uint32_t)SYSCFG_CFGR1_I2C1_DMA_RMP) /*!< I2C1 DMA request remapping bit. Available on STM32F07x devices only.
+ 0: No remap (I2C1_RX and I2C1_TX DMA requests mapped on DMA channel 3 and 2 respectively)
+ 1: Remap (I2C1_RX and I2C1_TX DMA requests mapped on DMA channel 7 and 6 respectively) */
+#define DMA_REMAP_TIM1_DMA_CH6 ((uint32_t)SYSCFG_CFGR1_TIM1_DMA_RMP) /*!< TIM1 DMA request remapping bit. Available on STM32F07x devices only.
+ 0: No remap (TIM1_CH1, TIM1_CH2 and TIM1_CH3 DMA requests mapped on DMA channel 2, 3 and 4 respectively)
+ 1: Remap (TIM1_CH1, TIM1_CH2 and TIM1_CH3 DMA requests mapped on DMA channel 6 */
+#define DMA_REMAP_TIM2_DMA_CH7 ((uint32_t)SYSCFG_CFGR1_TIM2_DMA_RMP) /*!< TIM2 DMA request remapping bit. Available on STM32F07x devices only.
+ 0: No remap (TIM2_CH2 and TIM2_CH4 DMA requests mapped on DMA channel 3 and 4 respectively)
+ 1: Remap (TIM2_CH2 and TIM2_CH4 DMA requests mapped on DMA channel 7 */
+#define DMA_REMAP_TIM3_DMA_CH6 ((uint32_t)SYSCFG_CFGR1_TIM3_DMA_RMP) /*!< TIM3 DMA request remapping bit. Available on STM32F07x devices only.
+ 0: No remap (TIM3_CH1 and TIM3_TRIG DMA requests mapped on DMA channel 4)
+ 1: Remap (TIM3_CH1 and TIM3_TRIG DMA requests mapped on DMA channel 6) */
+#endif
+
+/**
+ * @}
+ */
+
+#endif /* SYSCFG_CFGR1_DMA_RMP */
+/**
+ * @}
+ */
+
+/* Exported macro ------------------------------------------------------------*/
+/** @defgroup DMA_Exported_Macros DMA Exported Macros
+ * @{
+ */
+
+/** @brief Reset DMA handle state
+ * @param __HANDLE__ DMA handle.
+ * @retval None
+ */
+#define __HAL_DMA_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_DMA_STATE_RESET)
+
+/**
+ * @brief Enable the specified DMA Channel.
+ * @param __HANDLE__ DMA handle
+ * @retval None
+ */
+#define __HAL_DMA_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CCR |= DMA_CCR_EN)
+
+/**
+ * @brief Disable the specified DMA Channel.
+ * @param __HANDLE__ DMA handle
+ * @retval None
+ */
+#define __HAL_DMA_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CCR &= ~DMA_CCR_EN)
+
+
+/* Interrupt & Flag management */
+
+/**
+ * @brief Enables the specified DMA Channel interrupts.
+ * @param __HANDLE__ DMA handle
+ * @param __INTERRUPT__ specifies the DMA interrupt sources to be enabled or disabled.
+ * This parameter can be any combination of the following values:
+ * @arg DMA_IT_TC: Transfer complete interrupt mask
+ * @arg DMA_IT_HT: Half transfer complete interrupt mask
+ * @arg DMA_IT_TE: Transfer error interrupt mask
+ * @retval None
+ */
+#define __HAL_DMA_ENABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->CCR |= (__INTERRUPT__))
+
+/**
+ * @brief Disables the specified DMA Channel interrupts.
+ * @param __HANDLE__ DMA handle
+ * @param __INTERRUPT__ specifies the DMA interrupt sources to be enabled or disabled.
+ * This parameter can be any combination of the following values:
+ * @arg DMA_IT_TC: Transfer complete interrupt mask
+ * @arg DMA_IT_HT: Half transfer complete interrupt mask
+ * @arg DMA_IT_TE: Transfer error interrupt mask
+ * @retval None
+ */
+#define __HAL_DMA_DISABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->CCR &= ~(__INTERRUPT__))
+
+/**
+ * @brief Checks whether the specified DMA Channel interrupt is enabled or disabled.
+ * @param __HANDLE__ DMA handle
+ * @param __INTERRUPT__ specifies the DMA interrupt source to check.
+ * This parameter can be one of the following values:
+ * @arg DMA_IT_TC: Transfer complete interrupt mask
+ * @arg DMA_IT_HT: Half transfer complete interrupt mask
+ * @arg DMA_IT_TE: Transfer error interrupt mask
+ * @retval The state of DMA_IT (SET or RESET).
+ */
+#define __HAL_DMA_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->CCR & (__INTERRUPT__)))
+
+/**
+ * @brief Returns the number of remaining data units in the current DMAy Channelx transfer.
+ * @param __HANDLE__ DMA handle
+ *
+ * @retval The number of remaining data units in the current DMA Channel transfer.
+ */
+#define __HAL_DMA_GET_COUNTER(__HANDLE__) ((__HANDLE__)->Instance->CNDTR)
+
+#if defined(SYSCFG_CFGR1_DMA_RMP)
+/** @brief DMA remapping enable/disable macros
+ * @param __DMA_REMAP__ This parameter can be a value of @ref HAL_DMA_remapping
+ */
+#define __HAL_DMA_REMAP_CHANNEL_ENABLE(__DMA_REMAP__) do {assert_param(IS_DMA_REMAP((__DMA_REMAP__))); \
+ SYSCFG->CFGR1 |= (__DMA_REMAP__); \
+ }while(0)
+#define __HAL_DMA_REMAP_CHANNEL_DISABLE(__DMA_REMAP__) do {assert_param(IS_DMA_REMAP((__DMA_REMAP__))); \
+ SYSCFG->CFGR1 &= ~(__DMA_REMAP__); \
+ }while(0)
+#endif /* SYSCFG_CFGR1_DMA_RMP */
+
+/**
+ * @}
+ */
+
+/* Include DMA HAL Extension module */
+#include "stm32f0xx_hal_dma_ex.h"
+
+/* Exported functions --------------------------------------------------------*/
+/** @addtogroup DMA_Exported_Functions
+ * @{
+ */
+
+/** @addtogroup DMA_Exported_Functions_Group1
+ * @{
+ */
+/* Initialization and de-initialization functions *****************************/
+HAL_StatusTypeDef HAL_DMA_Init(DMA_HandleTypeDef *hdma);
+HAL_StatusTypeDef HAL_DMA_DeInit (DMA_HandleTypeDef *hdma);
+/**
+ * @}
+ */
+
+/** @addtogroup DMA_Exported_Functions_Group2
+ * @{
+ */
+/* Input and Output operation functions *****************************************************/
+HAL_StatusTypeDef HAL_DMA_Start (DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t DataLength);
+HAL_StatusTypeDef HAL_DMA_Start_IT(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t DataLength);
+HAL_StatusTypeDef HAL_DMA_Abort(DMA_HandleTypeDef *hdma);
+HAL_StatusTypeDef HAL_DMA_Abort_IT(DMA_HandleTypeDef *hdma);
+HAL_StatusTypeDef HAL_DMA_PollForTransfer(DMA_HandleTypeDef *hdma, uint32_t CompleteLevel, uint32_t Timeout);
+void HAL_DMA_IRQHandler(DMA_HandleTypeDef *hdma);
+HAL_StatusTypeDef HAL_DMA_RegisterCallback(DMA_HandleTypeDef *hdma, HAL_DMA_CallbackIDTypeDef CallbackID, void (* pCallback)( DMA_HandleTypeDef * _hdma));
+HAL_StatusTypeDef HAL_DMA_UnRegisterCallback(DMA_HandleTypeDef *hdma, HAL_DMA_CallbackIDTypeDef CallbackID);
+
+/**
+ * @}
+ */
+
+/** @addtogroup DMA_Exported_Functions_Group3
+ * @{
+ */
+/* Peripheral State and Error functions ***************************************/
+HAL_DMA_StateTypeDef HAL_DMA_GetState(DMA_HandleTypeDef *hdma);
+uint32_t HAL_DMA_GetError(DMA_HandleTypeDef *hdma);
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/** @addtogroup DMA_Private_Macros
+ * @{
+ */
+#define IS_DMA_DIRECTION(DIRECTION) (((DIRECTION) == DMA_PERIPH_TO_MEMORY ) || \
+ ((DIRECTION) == DMA_MEMORY_TO_PERIPH) || \
+ ((DIRECTION) == DMA_MEMORY_TO_MEMORY))
+#define IS_DMA_PERIPHERAL_INC_STATE(STATE) (((STATE) == DMA_PINC_ENABLE) || \
+ ((STATE) == DMA_PINC_DISABLE))
+
+#define IS_DMA_MEMORY_INC_STATE(STATE) (((STATE) == DMA_MINC_ENABLE) || \
+ ((STATE) == DMA_MINC_DISABLE))
+
+#define IS_DMA_PERIPHERAL_DATA_SIZE(SIZE) (((SIZE) == DMA_PDATAALIGN_BYTE) || \
+ ((SIZE) == DMA_PDATAALIGN_HALFWORD) || \
+ ((SIZE) == DMA_PDATAALIGN_WORD))
+
+#define IS_DMA_MEMORY_DATA_SIZE(SIZE) (((SIZE) == DMA_MDATAALIGN_BYTE) || \
+ ((SIZE) == DMA_MDATAALIGN_HALFWORD) || \
+ ((SIZE) == DMA_MDATAALIGN_WORD ))
+
+#define IS_DMA_MODE(MODE) (((MODE) == DMA_NORMAL ) || \
+ ((MODE) == DMA_CIRCULAR))
+#define IS_DMA_PRIORITY(PRIORITY) (((PRIORITY) == DMA_PRIORITY_LOW ) || \
+ ((PRIORITY) == DMA_PRIORITY_MEDIUM) || \
+ ((PRIORITY) == DMA_PRIORITY_HIGH) || \
+ ((PRIORITY) == DMA_PRIORITY_VERY_HIGH))
+#define IS_DMA_BUFFER_SIZE(SIZE) (((SIZE) >= 0x1U) && ((SIZE) < 0x10000U))
+
+#if defined(SYSCFG_CFGR1_DMA_RMP)
+
+#if defined (STM32F071xB) || defined (STM32F072xB) || defined (STM32F078xx)
+#define IS_DMA_REMAP(RMP) (((RMP) == DMA_REMAP_ADC_DMA_CH2) || \
+ ((RMP) == DMA_REMAP_USART1_TX_DMA_CH4) || \
+ ((RMP) == DMA_REMAP_USART1_RX_DMA_CH5) || \
+ ((RMP) == DMA_REMAP_TIM16_DMA_CH4) || \
+ ((RMP) == DMA_REMAP_TIM17_DMA_CH2) || \
+ ((RMP) == DMA_REMAP_TIM16_DMA_CH6) || \
+ ((RMP) == DMA_REMAP_TIM17_DMA_CH7) || \
+ ((RMP) == DMA_REMAP_SPI2_DMA_CH67) || \
+ ((RMP) == DMA_REMAP_USART2_DMA_CH67) || \
+ ((RMP) == DMA_REMAP_USART3_DMA_CH32) || \
+ ((RMP) == DMA_REMAP_I2C1_DMA_CH76) || \
+ ((RMP) == DMA_REMAP_TIM1_DMA_CH6) || \
+ ((RMP) == DMA_REMAP_TIM2_DMA_CH7) || \
+ ((RMP) == DMA_REMAP_TIM3_DMA_CH6))
+#elif defined (STM32F070xB)
+#define IS_DMA_REMAP(RMP) (((RMP) == DMA_REMAP_USART3_DMA_CH32) || \
+ ((RMP) == DMA_REMAP_ADC_DMA_CH2) || \
+ ((RMP) == DMA_REMAP_USART1_TX_DMA_CH4) || \
+ ((RMP) == DMA_REMAP_USART1_RX_DMA_CH5) || \
+ ((RMP) == DMA_REMAP_TIM16_DMA_CH4) || \
+ ((RMP) == DMA_REMAP_TIM17_DMA_CH2))
+#else
+#define IS_DMA_REMAP(RMP) (((RMP) == DMA_REMAP_ADC_DMA_CH2) || \
+ ((RMP) == DMA_REMAP_USART1_TX_DMA_CH4) || \
+ ((RMP) == DMA_REMAP_USART1_RX_DMA_CH5) || \
+ ((RMP) == DMA_REMAP_TIM16_DMA_CH4) || \
+ ((RMP) == DMA_REMAP_TIM17_DMA_CH2))
+#endif
+
+#endif /* SYSCFG_CFGR1_DMA_RMP */
+
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __STM32F0xx_HAL_DMA_H */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
+
diff --git a/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal_dma_ex.h b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal_dma_ex.h
new file mode 100644
index 0000000..1eaf396
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal_dma_ex.h
@@ -0,0 +1,811 @@
+/**
+ ******************************************************************************
+ * @file stm32f0xx_hal_dma_ex.h
+ * @author MCD Application Team
+ * @brief Header file of DMA HAL Extension module.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2016 STMicroelectronics.
+ * All rights reserved.
+ *
+ * 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 __STM32F0xx_HAL_DMA_EX_H
+#define __STM32F0xx_HAL_DMA_EX_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f0xx_hal_def.h"
+
+/** @addtogroup STM32F0xx_HAL_Driver
+ * @{
+ */
+
+/** @defgroup DMAEx DMAEx
+ * @brief DMA HAL module driver
+ * @{
+ */
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+#if defined(STM32F091xC) || defined(STM32F098xx) || defined(STM32F030xC)
+/** @defgroup DMAEx_Exported_Constants DMAEx Exported Constants
+ * @{
+ */
+#define DMA1_CHANNEL1_RMP 0x00000000 /*!< Internal define for remaping on STM32F09x/30xC */
+#define DMA1_CHANNEL2_RMP 0x10000000 /*!< Internal define for remaping on STM32F09x/30xC */
+#define DMA1_CHANNEL3_RMP 0x20000000 /*!< Internal define for remaping on STM32F09x/30xC */
+#define DMA1_CHANNEL4_RMP 0x30000000 /*!< Internal define for remaping on STM32F09x/30xC */
+#define DMA1_CHANNEL5_RMP 0x40000000 /*!< Internal define for remaping on STM32F09x/30xC */
+#if !defined(STM32F030xC)
+#define DMA1_CHANNEL6_RMP 0x50000000 /*!< Internal define for remaping on STM32F09x/30xC */
+#define DMA1_CHANNEL7_RMP 0x60000000 /*!< Internal define for remaping on STM32F09x/30xC */
+#define DMA2_CHANNEL1_RMP 0x00000000 /*!< Internal define for remaping on STM32F09x/30xC */
+#define DMA2_CHANNEL2_RMP 0x10000000 /*!< Internal define for remaping on STM32F09x/30xC */
+#define DMA2_CHANNEL3_RMP 0x20000000 /*!< Internal define for remaping on STM32F09x/30xC */
+#define DMA2_CHANNEL4_RMP 0x30000000 /*!< Internal define for remaping on STM32F09x/30xC */
+#define DMA2_CHANNEL5_RMP 0x40000000 /*!< Internal define for remaping on STM32F09x/30xC */
+#endif /* !defined(STM32F030xC) */
+
+/****************** DMA1 remap bit field definition********************/
+/* DMA1 - Channel 1 */
+#define HAL_DMA1_CH1_DEFAULT (uint32_t) (DMA1_CHANNEL1_RMP | DMA1_CSELR_DEFAULT) /*!< Default remap position for DMA1 */
+#define HAL_DMA1_CH1_ADC (uint32_t) (DMA1_CHANNEL1_RMP | DMA1_CSELR_CH1_ADC) /*!< Remap ADC on DMA1 Channel 1*/
+#define HAL_DMA1_CH1_TIM17_CH1 (uint32_t) (DMA1_CHANNEL1_RMP | DMA1_CSELR_CH1_TIM17_CH1) /*!< Remap TIM17 channel 1 on DMA1 channel 1 */
+#define HAL_DMA1_CH1_TIM17_UP (uint32_t) (DMA1_CHANNEL1_RMP | DMA1_CSELR_CH1_TIM17_UP) /*!< Remap TIM17 up on DMA1 channel 1 */
+#define HAL_DMA1_CH1_USART1_RX (uint32_t) (DMA1_CHANNEL1_RMP | DMA1_CSELR_CH1_USART1_RX) /*!< Remap USART1 Rx on DMA1 channel 1 */
+#define HAL_DMA1_CH1_USART2_RX (uint32_t) (DMA1_CHANNEL1_RMP | DMA1_CSELR_CH1_USART2_RX) /*!< Remap USART2 Rx on DMA1 channel 1 */
+#define HAL_DMA1_CH1_USART3_RX (uint32_t) (DMA1_CHANNEL1_RMP | DMA1_CSELR_CH1_USART3_RX) /*!< Remap USART3 Rx on DMA1 channel 1 */
+#define HAL_DMA1_CH1_USART4_RX (uint32_t) (DMA1_CHANNEL1_RMP | DMA1_CSELR_CH1_USART4_RX) /*!< Remap USART4 Rx on DMA1 channel 1 */
+#define HAL_DMA1_CH1_USART5_RX (uint32_t) (DMA1_CHANNEL1_RMP | DMA1_CSELR_CH1_USART5_RX) /*!< Remap USART5 Rx on DMA1 channel 1 */
+#define HAL_DMA1_CH1_USART6_RX (uint32_t) (DMA1_CHANNEL1_RMP | DMA1_CSELR_CH1_USART6_RX) /*!< Remap USART6 Rx on DMA1 channel 1 */
+#if !defined(STM32F030xC)
+#define HAL_DMA1_CH1_USART7_RX (uint32_t) (DMA1_CHANNEL1_RMP | DMA1_CSELR_CH1_USART7_RX) /*!< Remap USART7 Rx on DMA1 channel 1 */
+#define HAL_DMA1_CH1_USART8_RX (uint32_t) (DMA1_CHANNEL1_RMP | DMA1_CSELR_CH1_USART8_RX) /*!< Remap USART8 Rx on DMA1 channel 1 */
+#endif /* !defined(STM32F030xC) */
+
+/* DMA1 - Channel 2 */
+#define HAL_DMA1_CH2_DEFAULT (uint32_t) (DMA1_CHANNEL2_RMP | DMA1_CSELR_DEFAULT) /*!< Default remap position for DMA1 */
+#define HAL_DMA1_CH2_ADC (uint32_t) (DMA1_CHANNEL2_RMP | DMA1_CSELR_CH2_ADC) /*!< Remap ADC on DMA1 channel 2 */
+#define HAL_DMA1_CH2_I2C1_TX (uint32_t) (DMA1_CHANNEL2_RMP | DMA1_CSELR_CH2_I2C1_TX) /*!< Remap I2C1 Tx on DMA1 channel 2 */
+#define HAL_DMA1_CH2_SPI1_RX (uint32_t) (DMA1_CHANNEL2_RMP | DMA1_CSELR_CH2_SPI1_RX) /*!< Remap SPI1 Rx on DMA1 channel 2 */
+#define HAL_DMA1_CH2_TIM1_CH1 (uint32_t) (DMA1_CHANNEL2_RMP | DMA1_CSELR_CH2_TIM1_CH1) /*!< Remap TIM1 channel 1 on DMA1 channel 2 */
+#define HAL_DMA1_CH2_TIM17_CH1 (uint32_t) (DMA1_CHANNEL2_RMP | DMA1_CSELR_CH2_TIM17_CH1) /*!< Remap TIM17 channel 1 on DMA1 channel 2 */
+#define HAL_DMA1_CH2_TIM17_UP (uint32_t) (DMA1_CHANNEL2_RMP | DMA1_CSELR_CH2_TIM17_UP) /*!< Remap TIM17 up on DMA1 channel 2 */
+#define HAL_DMA1_CH2_USART1_TX (uint32_t) (DMA1_CHANNEL2_RMP | DMA1_CSELR_CH2_USART1_TX) /*!< Remap USART1 Tx on DMA1 channel 2 */
+#define HAL_DMA1_CH2_USART2_TX (uint32_t) (DMA1_CHANNEL2_RMP | DMA1_CSELR_CH2_USART2_TX) /*!< Remap USART2 Tx on DMA1 channel 2 */
+#define HAL_DMA1_CH2_USART3_TX (uint32_t) (DMA1_CHANNEL2_RMP | DMA1_CSELR_CH2_USART3_TX) /*!< Remap USART3 Tx on DMA1 channel 2 */
+#define HAL_DMA1_CH2_USART4_TX (uint32_t) (DMA1_CHANNEL2_RMP | DMA1_CSELR_CH2_USART4_TX) /*!< Remap USART4 Tx on DMA1 channel 2 */
+#define HAL_DMA1_CH2_USART5_TX (uint32_t) (DMA1_CHANNEL2_RMP | DMA1_CSELR_CH2_USART5_TX) /*!< Remap USART5 Tx on DMA1 channel 2 */
+#define HAL_DMA1_CH2_USART6_TX (uint32_t) (DMA1_CHANNEL2_RMP | DMA1_CSELR_CH2_USART6_TX) /*!< Remap USART6 Tx on DMA1 channel 2 */
+#if !defined(STM32F030xC)
+#define HAL_DMA1_CH2_USART7_TX (uint32_t) (DMA1_CHANNEL2_RMP | DMA1_CSELR_CH2_USART7_TX) /*!< Remap USART7 Tx on DMA1 channel 2 */
+#define HAL_DMA1_CH2_USART8_TX (uint32_t) (DMA1_CHANNEL2_RMP | DMA1_CSELR_CH2_USART8_TX) /*!< Remap USART8 Tx on DMA1 channel 2 */
+#endif /* !defined(STM32F030xC) */
+
+/* DMA1 - Channel 3 */
+#define HAL_DMA1_CH3_DEFAULT (uint32_t) (DMA1_CHANNEL3_RMP | DMA1_CSELR_DEFAULT) /*!< Default remap position for DMA1 */
+#define HAL_DMA1_CH3_TIM6_UP (uint32_t) (DMA1_CHANNEL3_RMP | DMA1_CSELR_CH3_TIM6_UP) /*!< Remap TIM6 up on DMA1 channel 3 */
+#if !defined(STM32F030xC)
+#define HAL_DMA1_CH3_DAC_CH1 (uint32_t) (DMA1_CHANNEL3_RMP | DMA1_CSELR_CH3_DAC_CH1) /*!< Remap DAC Channel 1on DMA1 channel 3 */
+#endif /* !defined(STM32F030xC) */
+#define HAL_DMA1_CH3_I2C1_RX (uint32_t) (DMA1_CHANNEL3_RMP | DMA1_CSELR_CH3_I2C1_RX) /*!< Remap I2C1 Rx on DMA1 channel 3 */
+#define HAL_DMA1_CH3_SPI1_TX (uint32_t) (DMA1_CHANNEL3_RMP | DMA1_CSELR_CH3_SPI1_TX) /*!< Remap SPI1 Tx on DMA1 channel 3 */
+#define HAL_DMA1_CH3_TIM1_CH2 (uint32_t) (DMA1_CHANNEL3_RMP | DMA1_CSELR_CH3_TIM1_CH2) /*!< Remap TIM1 channel 2 on DMA1 channel 3 */
+#if !defined(STM32F030xC)
+#define HAL_DMA1_CH3_TIM2_CH2 (uint32_t) (DMA1_CHANNEL3_RMP | DMA1_CSELR_CH3_TIM2_CH2) /*!< Remap TIM2 channel 2 on DMA1 channel 3 */
+#endif /* !defined(STM32F030xC) */
+#define HAL_DMA1_CH3_TIM16_CH1 (uint32_t) (DMA1_CHANNEL3_RMP | DMA1_CSELR_CH3_TIM16_CH1) /*!< Remap TIM16 channel 1 on DMA1 channel 3 */
+#define HAL_DMA1_CH3_TIM16_UP (uint32_t) (DMA1_CHANNEL3_RMP | DMA1_CSELR_CH3_TIM16_UP) /*!< Remap TIM16 up on DMA1 channel 3 */
+#define HAL_DMA1_CH3_USART1_RX (uint32_t) (DMA1_CHANNEL3_RMP | DMA1_CSELR_CH3_USART1_RX) /*!< Remap USART1 Rx on DMA1 channel 3 */
+#define HAL_DMA1_CH3_USART2_RX (uint32_t) (DMA1_CHANNEL3_RMP | DMA1_CSELR_CH3_USART2_RX) /*!< Remap USART2 Rx on DMA1 channel 3 */
+#define HAL_DMA1_CH3_USART3_RX (uint32_t) (DMA1_CHANNEL3_RMP | DMA1_CSELR_CH3_USART3_RX) /*!< Remap USART3 Rx on DMA1 channel 3 */
+#define HAL_DMA1_CH3_USART4_RX (uint32_t) (DMA1_CHANNEL3_RMP | DMA1_CSELR_CH3_USART4_RX) /*!< Remap USART4 Rx on DMA1 channel 3 */
+#define HAL_DMA1_CH3_USART5_RX (uint32_t) (DMA1_CHANNEL3_RMP | DMA1_CSELR_CH3_USART5_RX) /*!< Remap USART5 Rx on DMA1 channel 3 */
+#define HAL_DMA1_CH3_USART6_RX (uint32_t) (DMA1_CHANNEL3_RMP | DMA1_CSELR_CH3_USART6_RX) /*!< Remap USART6 Rx on DMA1 channel 3 */
+#if !defined(STM32F030xC)
+#define HAL_DMA1_CH3_USART7_RX (uint32_t) (DMA1_CHANNEL3_RMP | DMA1_CSELR_CH3_USART7_RX) /*!< Remap USART7 Rx on DMA1 channel 3 */
+#define HAL_DMA1_CH3_USART8_RX (uint32_t) (DMA1_CHANNEL3_RMP | DMA1_CSELR_CH3_USART8_RX) /*!< Remap USART8 Rx on DMA1 channel 3 */
+#endif /* !defined(STM32F030xC) */
+
+/* DMA1 - Channel 4 */
+#define HAL_DMA1_CH4_DEFAULT (uint32_t) (DMA1_CHANNEL4_RMP | DMA1_CSELR_DEFAULT) /*!< Default remap position for DMA1 */
+#define HAL_DMA1_CH4_TIM7_UP (uint32_t) (DMA1_CHANNEL4_RMP | DMA1_CSELR_CH4_TIM7_UP) /*!< Remap TIM7 up on DMA1 channel 4 */
+#if !defined(STM32F030xC)
+#define HAL_DMA1_CH4_DAC_CH2 (uint32_t) (DMA1_CHANNEL4_RMP | DMA1_CSELR_CH4_DAC_CH2) /*!< Remap DAC Channel 2 on DMA1 channel 4 */
+#endif /* !defined(STM32F030xC) */
+#define HAL_DMA1_CH4_I2C2_TX (uint32_t) (DMA1_CHANNEL4_RMP | DMA1_CSELR_CH4_I2C2_TX) /*!< Remap I2C2 Tx on DMA1 channel 4 */
+#define HAL_DMA1_CH4_SPI2_RX (uint32_t) (DMA1_CHANNEL4_RMP | DMA1_CSELR_CH4_SPI2_RX) /*!< Remap SPI2 Rx on DMA1 channel 4 */
+#if !defined(STM32F030xC)
+#define HAL_DMA1_CH4_TIM2_CH4 (uint32_t) (DMA1_CHANNEL4_RMP | DMA1_CSELR_CH4_TIM2_CH4) /*!< Remap TIM2 channel 4 on DMA1 channel 4 */
+#endif /* !defined(STM32F030xC) */
+#define HAL_DMA1_CH4_TIM3_CH1 (uint32_t) (DMA1_CHANNEL4_RMP | DMA1_CSELR_CH4_TIM3_CH1) /*!< Remap TIM3 channel 1 on DMA1 channel 4 */
+#define HAL_DMA1_CH4_TIM3_TRIG (uint32_t) (DMA1_CHANNEL4_RMP | DMA1_CSELR_CH4_TIM3_TRIG) /*!< Remap TIM3 Trig on DMA1 channel 4 */
+#define HAL_DMA1_CH4_TIM16_CH1 (uint32_t) (DMA1_CHANNEL4_RMP | DMA1_CSELR_CH4_TIM16_CH1) /*!< Remap TIM16 channel 1 on DMA1 channel 4 */
+#define HAL_DMA1_CH4_TIM16_UP (uint32_t) (DMA1_CHANNEL4_RMP | DMA1_CSELR_CH4_TIM16_UP) /*!< Remap TIM16 up on DMA1 channel 4 */
+#define HAL_DMA1_CH4_USART1_TX (uint32_t) (DMA1_CHANNEL4_RMP | DMA1_CSELR_CH4_USART1_TX) /*!< Remap USART1 Tx on DMA1 channel 4 */
+#define HAL_DMA1_CH4_USART2_TX (uint32_t) (DMA1_CHANNEL4_RMP | DMA1_CSELR_CH4_USART2_TX) /*!< Remap USART2 Tx on DMA1 channel 4 */
+#define HAL_DMA1_CH4_USART3_TX (uint32_t) (DMA1_CHANNEL4_RMP | DMA1_CSELR_CH4_USART3_TX) /*!< Remap USART3 Tx on DMA1 channel 4 */
+#define HAL_DMA1_CH4_USART4_TX (uint32_t) (DMA1_CHANNEL4_RMP | DMA1_CSELR_CH4_USART4_TX) /*!< Remap USART4 Tx on DMA1 channel 4 */
+#define HAL_DMA1_CH4_USART5_TX (uint32_t) (DMA1_CHANNEL4_RMP | DMA1_CSELR_CH4_USART5_TX) /*!< Remap USART5 Tx on DMA1 channel 4 */
+#define HAL_DMA1_CH4_USART6_TX (uint32_t) (DMA1_CHANNEL4_RMP | DMA1_CSELR_CH4_USART6_TX) /*!< Remap USART6 Tx on DMA1 channel 4 */
+#if !defined(STM32F030xC)
+#define HAL_DMA1_CH4_USART7_TX (uint32_t) (DMA1_CHANNEL4_RMP | DMA1_CSELR_CH4_USART7_TX) /*!< Remap USART7 Tx on DMA1 channel 4 */
+#define HAL_DMA1_CH4_USART8_TX (uint32_t) (DMA1_CHANNEL4_RMP | DMA1_CSELR_CH4_USART8_TX) /*!< Remap USART8 Tx on DMA1 channel 4 */
+#endif /* !defined(STM32F030xC) */
+
+/* DMA1 - Channel 5 */
+#define HAL_DMA1_CH5_DEFAULT (uint32_t) (DMA1_CHANNEL5_RMP | DMA1_CSELR_DEFAULT) /*!< Default remap position for DMA1 */
+#define HAL_DMA1_CH5_I2C2_RX (uint32_t) (DMA1_CHANNEL5_RMP | DMA1_CSELR_CH5_I2C2_RX) /*!< Remap I2C2 Rx on DMA1 channel 5 */
+#define HAL_DMA1_CH5_SPI2_TX (uint32_t) (DMA1_CHANNEL5_RMP | DMA1_CSELR_CH5_SPI2_TX) /*!< Remap SPI1 Tx on DMA1 channel 5 */
+#define HAL_DMA1_CH5_TIM1_CH3 (uint32_t) (DMA1_CHANNEL5_RMP | DMA1_CSELR_CH5_TIM1_CH3) /*!< Remap TIM1 channel 3 on DMA1 channel 5 */
+#define HAL_DMA1_CH5_USART1_RX (uint32_t) (DMA1_CHANNEL5_RMP | DMA1_CSELR_CH5_USART1_RX) /*!< Remap USART1 Rx on DMA1 channel 5 */
+#define HAL_DMA1_CH5_USART2_RX (uint32_t) (DMA1_CHANNEL5_RMP | DMA1_CSELR_CH5_USART2_RX) /*!< Remap USART2 Rx on DMA1 channel 5 */
+#define HAL_DMA1_CH5_USART3_RX (uint32_t) (DMA1_CHANNEL5_RMP | DMA1_CSELR_CH5_USART3_RX) /*!< Remap USART3 Rx on DMA1 channel 5 */
+#define HAL_DMA1_CH5_USART4_RX (uint32_t) (DMA1_CHANNEL5_RMP | DMA1_CSELR_CH5_USART4_RX) /*!< Remap USART4 Rx on DMA1 channel 5 */
+#define HAL_DMA1_CH5_USART5_RX (uint32_t) (DMA1_CHANNEL5_RMP | DMA1_CSELR_CH5_USART5_RX) /*!< Remap USART5 Rx on DMA1 channel 5 */
+#define HAL_DMA1_CH5_USART6_RX (uint32_t) (DMA1_CHANNEL5_RMP | DMA1_CSELR_CH5_USART6_RX) /*!< Remap USART6 Rx on DMA1 channel 5 */
+#if !defined(STM32F030xC)
+#define HAL_DMA1_CH5_USART7_RX (uint32_t) (DMA1_CHANNEL5_RMP | DMA1_CSELR_CH5_USART7_RX) /*!< Remap USART7 Rx on DMA1 channel 5 */
+#define HAL_DMA1_CH5_USART8_RX (uint32_t) (DMA1_CHANNEL5_RMP | DMA1_CSELR_CH5_USART8_RX) /*!< Remap USART8 Rx on DMA1 channel 5 */
+#endif /* !defined(STM32F030xC) */
+
+#if !defined(STM32F030xC)
+/* DMA1 - Channel 6 */
+#define HAL_DMA1_CH6_DEFAULT (uint32_t) (DMA1_CHANNEL6_RMP | DMA1_CSELR_DEFAULT) /*!< Default remap position for DMA1 */
+#define HAL_DMA1_CH6_I2C1_TX (uint32_t) (DMA1_CHANNEL6_RMP | DMA1_CSELR_CH6_I2C1_TX) /*!< Remap I2C1 Tx on DMA1 channel 6 */
+#define HAL_DMA1_CH6_SPI2_RX (uint32_t) (DMA1_CHANNEL6_RMP | DMA1_CSELR_CH6_SPI2_RX) /*!< Remap SPI2 Rx on DMA1 channel 6 */
+#define HAL_DMA1_CH6_TIM1_CH1 (uint32_t) (DMA1_CHANNEL6_RMP | DMA1_CSELR_CH6_TIM1_CH1) /*!< Remap TIM1 channel 1 on DMA1 channel 6 */
+#define HAL_DMA1_CH6_TIM1_CH2 (uint32_t) (DMA1_CHANNEL6_RMP | DMA1_CSELR_CH6_TIM1_CH2) /*!< Remap TIM1 channel 2 on DMA1 channel 6 */
+#define HAL_DMA1_CH6_TIM1_CH3 (uint32_t) (DMA1_CHANNEL6_RMP | DMA1_CSELR_CH6_TIM1_CH3) /*!< Remap TIM1 channel 3 on DMA1 channel 6 */
+#define HAL_DMA1_CH6_TIM3_CH1 (uint32_t) (DMA1_CHANNEL6_RMP | DMA1_CSELR_CH6_TIM3_CH1) /*!< Remap TIM3 channel 1 on DMA1 channel 6 */
+#define HAL_DMA1_CH6_TIM3_TRIG (uint32_t) (DMA1_CHANNEL6_RMP | DMA1_CSELR_CH6_TIM3_TRIG) /*!< Remap TIM3 Trig on DMA1 channel 6 */
+#define HAL_DMA1_CH6_TIM16_CH1 (uint32_t) (DMA1_CHANNEL6_RMP | DMA1_CSELR_CH6_TIM16_CH1) /*!< Remap TIM16 channel 1 on DMA1 channel 6 */
+#define HAL_DMA1_CH6_TIM16_UP (uint32_t) (DMA1_CHANNEL6_RMP | DMA1_CSELR_CH6_TIM16_UP) /*!< Remap TIM16 up on DMA1 channel 6 */
+#define HAL_DMA1_CH6_USART1_RX (uint32_t) (DMA1_CHANNEL6_RMP | DMA1_CSELR_CH6_USART1_RX) /*!< Remap USART1 Rx on DMA1 channel 6 */
+#define HAL_DMA1_CH6_USART2_RX (uint32_t) (DMA1_CHANNEL6_RMP | DMA1_CSELR_CH6_USART2_RX) /*!< Remap USART2 Rx on DMA1 channel 6 */
+#define HAL_DMA1_CH6_USART3_RX (uint32_t) (DMA1_CHANNEL6_RMP | DMA1_CSELR_CH6_USART3_RX) /*!< Remap USART3 Rx on DMA1 channel 6 */
+#define HAL_DMA1_CH6_USART4_RX (uint32_t) (DMA1_CHANNEL6_RMP | DMA1_CSELR_CH6_USART4_RX) /*!< Remap USART4 Rx on DMA1 channel 6 */
+#define HAL_DMA1_CH6_USART5_RX (uint32_t) (DMA1_CHANNEL6_RMP | DMA1_CSELR_CH6_USART5_RX) /*!< Remap USART5 Rx on DMA1 channel 6 */
+#define HAL_DMA1_CH6_USART6_RX (uint32_t) (DMA1_CHANNEL6_RMP | DMA1_CSELR_CH6_USART6_RX) /*!< Remap USART6 Rx on DMA1 channel 6 */
+#define HAL_DMA1_CH6_USART7_RX (uint32_t) (DMA1_CHANNEL6_RMP | DMA1_CSELR_CH6_USART7_RX) /*!< Remap USART7 Rx on DMA1 channel 6 */
+#define HAL_DMA1_CH6_USART8_RX (uint32_t) (DMA1_CHANNEL6_RMP | DMA1_CSELR_CH6_USART8_RX) /*!< Remap USART8 Rx on DMA1 channel 6 */
+/* DMA1 - Channel 7 */
+#define HAL_DMA1_CH7_DEFAULT (uint32_t) (DMA1_CHANNEL7_RMP | DMA1_CSELR_DEFAULT) /*!< Default remap position for DMA1 */
+#define HAL_DMA1_CH7_I2C1_RX (uint32_t) (DMA1_CHANNEL7_RMP | DMA1_CSELR_CH7_I2C1_RX) /*!< Remap I2C1 Rx on DMA1 channel 7 */
+#define HAL_DMA1_CH7_SPI2_TX (uint32_t) (DMA1_CHANNEL7_RMP | DMA1_CSELR_CH7_SPI2_TX) /*!< Remap SPI2 Tx on DMA1 channel 7 */
+#define HAL_DMA1_CH7_TIM2_CH2 (uint32_t) (DMA1_CHANNEL7_RMP | DMA1_CSELR_CH7_TIM2_CH2) /*!< Remap TIM2 channel 2 on DMA1 channel 7 */
+#define HAL_DMA1_CH7_TIM2_CH4 (uint32_t) (DMA1_CHANNEL7_RMP | DMA1_CSELR_CH7_TIM2_CH4) /*!< Remap TIM2 channel 4 on DMA1 channel 7 */
+#define HAL_DMA1_CH7_TIM17_CH1 (uint32_t) (DMA1_CHANNEL7_RMP | DMA1_CSELR_CH7_TIM17_CH1) /*!< Remap TIM17 channel 1 on DMA1 channel 7 */
+#define HAL_DMA1_CH7_TIM17_UP (uint32_t) (DMA1_CHANNEL7_RMP | DMA1_CSELR_CH7_TIM17_UP) /*!< Remap TIM17 up on DMA1 channel 7 */
+#define HAL_DMA1_CH7_USART1_TX (uint32_t) (DMA1_CHANNEL7_RMP | DMA1_CSELR_CH7_USART1_TX) /*!< Remap USART1 Tx on DMA1 channel 7 */
+#define HAL_DMA1_CH7_USART2_TX (uint32_t) (DMA1_CHANNEL7_RMP | DMA1_CSELR_CH7_USART2_TX) /*!< Remap USART2 Tx on DMA1 channel 7 */
+#define HAL_DMA1_CH7_USART3_TX (uint32_t) (DMA1_CHANNEL7_RMP | DMA1_CSELR_CH7_USART3_TX) /*!< Remap USART3 Tx on DMA1 channel 7 */
+#define HAL_DMA1_CH7_USART4_TX (uint32_t) (DMA1_CHANNEL7_RMP | DMA1_CSELR_CH7_USART4_TX) /*!< Remap USART4 Tx on DMA1 channel 7 */
+#define HAL_DMA1_CH7_USART5_TX (uint32_t) (DMA1_CHANNEL7_RMP | DMA1_CSELR_CH7_USART5_TX) /*!< Remap USART5 Tx on DMA1 channel 7 */
+#define HAL_DMA1_CH7_USART6_TX (uint32_t) (DMA1_CHANNEL7_RMP | DMA1_CSELR_CH7_USART6_TX) /*!< Remap USART6 Tx on DMA1 channel 7 */
+#define HAL_DMA1_CH7_USART7_TX (uint32_t) (DMA1_CHANNEL7_RMP | DMA1_CSELR_CH7_USART7_TX) /*!< Remap USART7 Tx on DMA1 channel 7 */
+#define HAL_DMA1_CH7_USART8_TX (uint32_t) (DMA1_CHANNEL7_RMP | DMA1_CSELR_CH7_USART8_TX) /*!< Remap USART8 Tx on DMA1 channel 7 */
+
+/****************** DMA2 remap bit field definition********************/
+/* DMA2 - Channel 1 */
+#define HAL_DMA2_CH1_DEFAULT (uint32_t) (DMA2_CHANNEL1_RMP | DMA2_CSELR_DEFAULT) /*!< Default remap position for DMA2 */
+#define HAL_DMA2_CH1_I2C2_TX (uint32_t) (DMA2_CHANNEL1_RMP | DMA2_CSELR_CH1_I2C2_TX) /*!< Remap I2C2 TX on DMA2 channel 1 */
+#define HAL_DMA2_CH1_USART1_TX (uint32_t) (DMA2_CHANNEL1_RMP | DMA2_CSELR_CH1_USART1_TX) /*!< Remap USART1 Tx on DMA2 channel 1 */
+#define HAL_DMA2_CH1_USART2_TX (uint32_t) (DMA2_CHANNEL1_RMP | DMA2_CSELR_CH1_USART2_TX) /*!< Remap USART2 Tx on DMA2 channel 1 */
+#define HAL_DMA2_CH1_USART3_TX (uint32_t) (DMA2_CHANNEL1_RMP | DMA2_CSELR_CH1_USART3_TX) /*!< Remap USART3 Tx on DMA2 channel 1 */
+#define HAL_DMA2_CH1_USART4_TX (uint32_t) (DMA2_CHANNEL1_RMP | DMA2_CSELR_CH1_USART4_TX) /*!< Remap USART4 Tx on DMA2 channel 1 */
+#define HAL_DMA2_CH1_USART5_TX (uint32_t) (DMA2_CHANNEL1_RMP | DMA2_CSELR_CH1_USART5_TX) /*!< Remap USART5 Tx on DMA2 channel 1 */
+#define HAL_DMA2_CH1_USART6_TX (uint32_t) (DMA2_CHANNEL1_RMP | DMA2_CSELR_CH1_USART6_TX) /*!< Remap USART6 Tx on DMA2 channel 1 */
+#define HAL_DMA2_CH1_USART7_TX (uint32_t) (DMA2_CHANNEL1_RMP | DMA2_CSELR_CH1_USART7_TX) /*!< Remap USART7 Tx on DMA2 channel 1 */
+#define HAL_DMA2_CH1_USART8_TX (uint32_t) (DMA2_CHANNEL1_RMP | DMA2_CSELR_CH1_USART8_TX) /*!< Remap USART8 Tx on DMA2 channel 1 */
+/* DMA2 - Channel 2 */
+#define HAL_DMA2_CH2_DEFAULT (uint32_t) (DMA2_CHANNEL2_RMP | DMA2_CSELR_DEFAULT) /*!< Default remap position for DMA2 */
+#define HAL_DMA2_CH2_I2C2_RX (uint32_t) (DMA2_CHANNEL2_RMP | DMA2_CSELR_CH2_I2C2_RX) /*!< Remap I2C2 Rx on DMA2 channel 2 */
+#define HAL_DMA2_CH2_USART1_RX (uint32_t) (DMA2_CHANNEL2_RMP | DMA2_CSELR_CH2_USART1_RX) /*!< Remap USART1 Rx on DMA2 channel 2 */
+#define HAL_DMA2_CH2_USART2_RX (uint32_t) (DMA2_CHANNEL2_RMP | DMA2_CSELR_CH2_USART2_RX) /*!< Remap USART2 Rx on DMA2 channel 2 */
+#define HAL_DMA2_CH2_USART3_RX (uint32_t) (DMA2_CHANNEL2_RMP | DMA2_CSELR_CH2_USART3_RX) /*!< Remap USART3 Rx on DMA2 channel 2 */
+#define HAL_DMA2_CH2_USART4_RX (uint32_t) (DMA2_CHANNEL2_RMP | DMA2_CSELR_CH2_USART4_RX) /*!< Remap USART4 Rx on DMA2 channel 2 */
+#define HAL_DMA2_CH2_USART5_RX (uint32_t) (DMA2_CHANNEL2_RMP | DMA2_CSELR_CH2_USART5_RX) /*!< Remap USART5 Rx on DMA2 channel 2 */
+#define HAL_DMA2_CH2_USART6_RX (uint32_t) (DMA2_CHANNEL2_RMP | DMA2_CSELR_CH2_USART6_RX) /*!< Remap USART6 Rx on DMA2 channel 2 */
+#define HAL_DMA2_CH2_USART7_RX (uint32_t) (DMA2_CHANNEL2_RMP | DMA2_CSELR_CH2_USART7_RX) /*!< Remap USART7 Rx on DMA2 channel 2 */
+#define HAL_DMA2_CH2_USART8_RX (uint32_t) (DMA2_CHANNEL2_RMP | DMA2_CSELR_CH2_USART8_RX) /*!< Remap USART8 Rx on DMA2 channel 2 */
+/* DMA2 - Channel 3 */
+#define HAL_DMA2_CH3_DEFAULT (uint32_t) (DMA2_CHANNEL3_RMP | DMA2_CSELR_DEFAULT) /*!< Default remap position for DMA2 */
+#define HAL_DMA2_CH3_TIM6_UP (uint32_t) (DMA2_CHANNEL3_RMP | DMA2_CSELR_CH3_TIM6_UP) /*!< Remap TIM6 up on DMA2 channel 3 */
+#define HAL_DMA2_CH3_DAC_CH1 (uint32_t) (DMA2_CHANNEL3_RMP | DMA2_CSELR_CH3_DAC_CH1) /*!< Remap DAC channel 1 on DMA2 channel 3 */
+#define HAL_DMA2_CH3_SPI1_RX (uint32_t) (DMA2_CHANNEL3_RMP | DMA2_CSELR_CH3_SPI1_RX) /*!< Remap SPI1 Rx on DMA2 channel 3 */
+#define HAL_DMA2_CH3_USART1_RX (uint32_t) (DMA2_CHANNEL3_RMP | DMA2_CSELR_CH3_USART1_RX) /*!< Remap USART1 Rx on DMA2 channel 3 */
+#define HAL_DMA2_CH3_USART2_RX (uint32_t) (DMA2_CHANNEL3_RMP | DMA2_CSELR_CH3_USART2_RX) /*!< Remap USART2 Rx on DMA2 channel 3 */
+#define HAL_DMA2_CH3_USART3_RX (uint32_t) (DMA2_CHANNEL3_RMP | DMA2_CSELR_CH3_USART3_RX) /*!< Remap USART3 Rx on DMA2 channel 3 */
+#define HAL_DMA2_CH3_USART4_RX (uint32_t) (DMA2_CHANNEL3_RMP | DMA2_CSELR_CH3_USART4_RX) /*!< Remap USART4 Rx on DMA2 channel 3 */
+#define HAL_DMA2_CH3_USART5_RX (uint32_t) (DMA2_CHANNEL3_RMP | DMA2_CSELR_CH3_USART5_RX) /*!< Remap USART5 Rx on DMA2 channel 3 */
+#define HAL_DMA2_CH3_USART6_RX (uint32_t) (DMA2_CHANNEL3_RMP | DMA2_CSELR_CH3_USART6_RX) /*!< Remap USART6 Rx on DMA2 channel 3 */
+#define HAL_DMA2_CH3_USART7_RX (uint32_t) (DMA2_CHANNEL3_RMP | DMA2_CSELR_CH3_USART7_RX) /*!< Remap USART7 Rx on DMA2 channel 3 */
+#define HAL_DMA2_CH3_USART8_RX (uint32_t) (DMA2_CHANNEL3_RMP | DMA2_CSELR_CH3_USART8_RX) /*!< Remap USART8 Rx on DMA2 channel 3 */
+/* DMA2 - Channel 4 */
+#define HAL_DMA2_CH4_DEFAULT (uint32_t) (DMA2_CHANNEL4_RMP | DMA2_CSELR_DEFAULT) /*!< Default remap position for DMA2 */
+#define HAL_DMA2_CH4_TIM7_UP (uint32_t) (DMA2_CHANNEL4_RMP | DMA2_CSELR_CH4_TIM7_UP) /*!< Remap TIM7 up on DMA2 channel 4 */
+#define HAL_DMA2_CH4_DAC_CH2 (uint32_t) (DMA2_CHANNEL4_RMP | DMA2_CSELR_CH4_DAC_CH2) /*!< Remap DAC channel 2 on DMA2 channel 4 */
+#define HAL_DMA2_CH4_SPI1_TX (uint32_t) (DMA2_CHANNEL4_RMP | DMA2_CSELR_CH4_SPI1_TX) /*!< Remap SPI1 Tx on DMA2 channel 4 */
+#define HAL_DMA2_CH4_USART1_TX (uint32_t) (DMA2_CHANNEL4_RMP | DMA2_CSELR_CH4_USART1_TX) /*!< Remap USART1 Tx on DMA2 channel 4 */
+#define HAL_DMA2_CH4_USART2_TX (uint32_t) (DMA2_CHANNEL4_RMP | DMA2_CSELR_CH4_USART2_TX) /*!< Remap USART2 Tx on DMA2 channel 4 */
+#define HAL_DMA2_CH4_USART3_TX (uint32_t) (DMA2_CHANNEL4_RMP | DMA2_CSELR_CH4_USART3_TX) /*!< Remap USART3 Tx on DMA2 channel 4 */
+#define HAL_DMA2_CH4_USART4_TX (uint32_t) (DMA2_CHANNEL4_RMP | DMA2_CSELR_CH4_USART4_TX) /*!< Remap USART4 Tx on DMA2 channel 4 */
+#define HAL_DMA2_CH4_USART5_TX (uint32_t) (DMA2_CHANNEL4_RMP | DMA2_CSELR_CH4_USART5_TX) /*!< Remap USART5 Tx on DMA2 channel 4 */
+#define HAL_DMA2_CH4_USART6_TX (uint32_t) (DMA2_CHANNEL4_RMP | DMA2_CSELR_CH4_USART6_TX) /*!< Remap USART6 Tx on DMA2 channel 4 */
+#define HAL_DMA2_CH4_USART7_TX (uint32_t) (DMA2_CHANNEL4_RMP | DMA2_CSELR_CH4_USART7_TX) /*!< Remap USART7 Tx on DMA2 channel 4 */
+#define HAL_DMA2_CH4_USART8_TX (uint32_t) (DMA2_CHANNEL4_RMP | DMA2_CSELR_CH4_USART8_TX) /*!< Remap USART8 Tx on DMA2 channel 4 */
+/* DMA2 - Channel 5 */
+#define HAL_DMA2_CH5_DEFAULT (uint32_t) (DMA2_CHANNEL5_RMP | DMA2_CSELR_DEFAULT) /*!< Default remap position for DMA2 */
+#define HAL_DMA2_CH5_ADC (uint32_t) (DMA2_CHANNEL5_RMP | DMA2_CSELR_CH5_ADC) /*!< Remap ADC on DMA2 channel 5 */
+#define HAL_DMA2_CH5_USART1_TX (uint32_t) (DMA2_CHANNEL5_RMP | DMA2_CSELR_CH5_USART1_TX) /*!< Remap USART1 Tx on DMA2 channel 5 */
+#define HAL_DMA2_CH5_USART2_TX (uint32_t) (DMA2_CHANNEL5_RMP | DMA2_CSELR_CH5_USART2_TX) /*!< Remap USART2 Tx on DMA2 channel 5 */
+#define HAL_DMA2_CH5_USART3_TX (uint32_t) (DMA2_CHANNEL5_RMP | DMA2_CSELR_CH5_USART3_TX) /*!< Remap USART3 Tx on DMA2 channel 5 */
+#define HAL_DMA2_CH5_USART4_TX (uint32_t) (DMA2_CHANNEL5_RMP | DMA2_CSELR_CH5_USART4_TX) /*!< Remap USART4 Tx on DMA2 channel 5 */
+#define HAL_DMA2_CH5_USART5_TX (uint32_t) (DMA2_CHANNEL5_RMP | DMA2_CSELR_CH5_USART5_TX) /*!< Remap USART5 Tx on DMA2 channel 5 */
+#define HAL_DMA2_CH5_USART6_TX (uint32_t) (DMA2_CHANNEL5_RMP | DMA2_CSELR_CH5_USART6_TX) /*!< Remap USART6 Tx on DMA2 channel 5 */
+#define HAL_DMA2_CH5_USART7_TX (uint32_t) (DMA2_CHANNEL5_RMP | DMA2_CSELR_CH5_USART7_TX) /*!< Remap USART7 Tx on DMA2 channel 5 */
+#define HAL_DMA2_CH5_USART8_TX (uint32_t) (DMA2_CHANNEL5_RMP | DMA2_CSELR_CH5_USART8_TX) /*!< Remap USART8 Tx on DMA2 channel 5 */
+#endif /* !defined(STM32F030xC) */
+
+#if defined(STM32F091xC) || defined(STM32F098xx)
+#define IS_HAL_DMA1_REMAP(REQUEST) (((REQUEST) == HAL_DMA1_CH1_DEFAULT) ||\
+ ((REQUEST) == HAL_DMA1_CH1_ADC) ||\
+ ((REQUEST) == HAL_DMA1_CH1_TIM17_CH1) ||\
+ ((REQUEST) == HAL_DMA1_CH1_TIM17_UP) ||\
+ ((REQUEST) == HAL_DMA1_CH1_USART1_RX) ||\
+ ((REQUEST) == HAL_DMA1_CH1_USART2_RX) ||\
+ ((REQUEST) == HAL_DMA1_CH1_USART3_RX) ||\
+ ((REQUEST) == HAL_DMA1_CH1_USART4_RX) ||\
+ ((REQUEST) == HAL_DMA1_CH1_USART5_RX) ||\
+ ((REQUEST) == HAL_DMA1_CH1_USART6_RX) ||\
+ ((REQUEST) == HAL_DMA1_CH1_USART7_RX) ||\
+ ((REQUEST) == HAL_DMA1_CH1_USART8_RX) ||\
+ ((REQUEST) == HAL_DMA1_CH2_DEFAULT) ||\
+ ((REQUEST) == HAL_DMA1_CH2_ADC) ||\
+ ((REQUEST) == HAL_DMA1_CH2_I2C1_TX) ||\
+ ((REQUEST) == HAL_DMA1_CH2_SPI1_RX) ||\
+ ((REQUEST) == HAL_DMA1_CH2_TIM1_CH1) ||\
+ ((REQUEST) == HAL_DMA1_CH2_I2C1_TX) ||\
+ ((REQUEST) == HAL_DMA1_CH2_TIM17_CH1) ||\
+ ((REQUEST) == HAL_DMA1_CH2_TIM17_UP) ||\
+ ((REQUEST) == HAL_DMA1_CH2_USART1_TX) ||\
+ ((REQUEST) == HAL_DMA1_CH2_USART2_TX) ||\
+ ((REQUEST) == HAL_DMA1_CH2_USART3_TX) ||\
+ ((REQUEST) == HAL_DMA1_CH2_USART4_TX) ||\
+ ((REQUEST) == HAL_DMA1_CH2_USART5_TX) ||\
+ ((REQUEST) == HAL_DMA1_CH2_USART6_TX) ||\
+ ((REQUEST) == HAL_DMA1_CH2_USART7_TX) ||\
+ ((REQUEST) == HAL_DMA1_CH2_USART8_TX) ||\
+ ((REQUEST) == HAL_DMA1_CH3_DEFAULT) ||\
+ ((REQUEST) == HAL_DMA1_CH3_TIM6_UP) ||\
+ ((REQUEST) == HAL_DMA1_CH3_DAC_CH1) ||\
+ ((REQUEST) == HAL_DMA1_CH3_I2C1_RX) ||\
+ ((REQUEST) == HAL_DMA1_CH3_SPI1_TX) ||\
+ ((REQUEST) == HAL_DMA1_CH3_TIM1_CH2) ||\
+ ((REQUEST) == HAL_DMA1_CH3_TIM2_CH2) ||\
+ ((REQUEST) == HAL_DMA1_CH3_TIM16_CH1) ||\
+ ((REQUEST) == HAL_DMA1_CH3_TIM16_UP) ||\
+ ((REQUEST) == HAL_DMA1_CH3_USART1_RX) ||\
+ ((REQUEST) == HAL_DMA1_CH3_USART2_RX) ||\
+ ((REQUEST) == HAL_DMA1_CH3_USART3_RX) ||\
+ ((REQUEST) == HAL_DMA1_CH3_USART4_RX) ||\
+ ((REQUEST) == HAL_DMA1_CH3_USART5_RX) ||\
+ ((REQUEST) == HAL_DMA1_CH3_USART6_RX) ||\
+ ((REQUEST) == HAL_DMA1_CH3_USART7_RX) ||\
+ ((REQUEST) == HAL_DMA1_CH3_USART8_RX) ||\
+ ((REQUEST) == HAL_DMA1_CH4_DEFAULT) ||\
+ ((REQUEST) == HAL_DMA1_CH4_TIM7_UP) ||\
+ ((REQUEST) == HAL_DMA1_CH4_DAC_CH2) ||\
+ ((REQUEST) == HAL_DMA1_CH4_I2C2_TX) ||\
+ ((REQUEST) == HAL_DMA1_CH4_SPI2_RX) ||\
+ ((REQUEST) == HAL_DMA1_CH4_TIM2_CH4) ||\
+ ((REQUEST) == HAL_DMA1_CH4_TIM3_CH1) ||\
+ ((REQUEST) == HAL_DMA1_CH4_TIM3_TRIG) ||\
+ ((REQUEST) == HAL_DMA1_CH4_TIM16_CH1) ||\
+ ((REQUEST) == HAL_DMA1_CH4_TIM16_UP) ||\
+ ((REQUEST) == HAL_DMA1_CH4_USART1_TX) ||\
+ ((REQUEST) == HAL_DMA1_CH4_USART2_TX) ||\
+ ((REQUEST) == HAL_DMA1_CH4_USART3_TX) ||\
+ ((REQUEST) == HAL_DMA1_CH4_USART4_TX) ||\
+ ((REQUEST) == HAL_DMA1_CH4_USART5_TX) ||\
+ ((REQUEST) == HAL_DMA1_CH4_USART6_TX) ||\
+ ((REQUEST) == HAL_DMA1_CH4_USART7_TX) ||\
+ ((REQUEST) == HAL_DMA1_CH4_USART8_TX) ||\
+ ((REQUEST) == HAL_DMA1_CH5_DEFAULT) ||\
+ ((REQUEST) == HAL_DMA1_CH5_I2C2_RX) ||\
+ ((REQUEST) == HAL_DMA1_CH5_SPI2_TX) ||\
+ ((REQUEST) == HAL_DMA1_CH5_TIM1_CH3) ||\
+ ((REQUEST) == HAL_DMA1_CH5_USART1_RX) ||\
+ ((REQUEST) == HAL_DMA1_CH5_USART2_RX) ||\
+ ((REQUEST) == HAL_DMA1_CH5_USART3_RX) ||\
+ ((REQUEST) == HAL_DMA1_CH5_USART4_RX) ||\
+ ((REQUEST) == HAL_DMA1_CH5_USART5_RX) ||\
+ ((REQUEST) == HAL_DMA1_CH5_USART6_RX) ||\
+ ((REQUEST) == HAL_DMA1_CH5_USART7_RX) ||\
+ ((REQUEST) == HAL_DMA1_CH5_USART8_RX) ||\
+ ((REQUEST) == HAL_DMA1_CH6_DEFAULT) ||\
+ ((REQUEST) == HAL_DMA1_CH6_I2C1_TX) ||\
+ ((REQUEST) == HAL_DMA1_CH6_SPI2_RX) ||\
+ ((REQUEST) == HAL_DMA1_CH6_TIM1_CH1) ||\
+ ((REQUEST) == HAL_DMA1_CH6_TIM1_CH2) ||\
+ ((REQUEST) == HAL_DMA1_CH6_TIM1_CH3) ||\
+ ((REQUEST) == HAL_DMA1_CH6_TIM3_CH1) ||\
+ ((REQUEST) == HAL_DMA1_CH6_TIM3_TRIG) ||\
+ ((REQUEST) == HAL_DMA1_CH6_TIM16_CH1) ||\
+ ((REQUEST) == HAL_DMA1_CH6_TIM16_UP) ||\
+ ((REQUEST) == HAL_DMA1_CH6_USART1_RX) ||\
+ ((REQUEST) == HAL_DMA1_CH6_USART2_RX) ||\
+ ((REQUEST) == HAL_DMA1_CH6_USART3_RX) ||\
+ ((REQUEST) == HAL_DMA1_CH6_USART4_RX) ||\
+ ((REQUEST) == HAL_DMA1_CH6_USART5_RX) ||\
+ ((REQUEST) == HAL_DMA1_CH6_USART6_RX) ||\
+ ((REQUEST) == HAL_DMA1_CH6_USART7_RX) ||\
+ ((REQUEST) == HAL_DMA1_CH6_USART8_RX) ||\
+ ((REQUEST) == HAL_DMA1_CH7_DEFAULT) ||\
+ ((REQUEST) == HAL_DMA1_CH7_I2C1_RX) ||\
+ ((REQUEST) == HAL_DMA1_CH7_SPI2_TX) ||\
+ ((REQUEST) == HAL_DMA1_CH7_TIM2_CH2) ||\
+ ((REQUEST) == HAL_DMA1_CH7_TIM2_CH4) ||\
+ ((REQUEST) == HAL_DMA1_CH7_TIM17_CH1) ||\
+ ((REQUEST) == HAL_DMA1_CH7_TIM17_UP) ||\
+ ((REQUEST) == HAL_DMA1_CH7_USART1_TX) ||\
+ ((REQUEST) == HAL_DMA1_CH7_USART2_TX) ||\
+ ((REQUEST) == HAL_DMA1_CH7_USART3_TX) ||\
+ ((REQUEST) == HAL_DMA1_CH7_USART4_TX) ||\
+ ((REQUEST) == HAL_DMA1_CH7_USART5_TX) ||\
+ ((REQUEST) == HAL_DMA1_CH7_USART6_TX) ||\
+ ((REQUEST) == HAL_DMA1_CH7_USART7_TX) ||\
+ ((REQUEST) == HAL_DMA1_CH7_USART8_TX))
+
+#define IS_HAL_DMA2_REMAP(REQUEST) (((REQUEST) == HAL_DMA2_CH1_DEFAULT) ||\
+ ((REQUEST) == HAL_DMA2_CH1_I2C2_TX) ||\
+ ((REQUEST) == HAL_DMA2_CH1_USART1_TX) ||\
+ ((REQUEST) == HAL_DMA2_CH1_USART2_TX) ||\
+ ((REQUEST) == HAL_DMA2_CH1_USART3_TX) ||\
+ ((REQUEST) == HAL_DMA2_CH1_USART4_TX) ||\
+ ((REQUEST) == HAL_DMA2_CH1_USART5_TX) ||\
+ ((REQUEST) == HAL_DMA2_CH1_USART6_TX) ||\
+ ((REQUEST) == HAL_DMA2_CH1_USART7_TX) ||\
+ ((REQUEST) == HAL_DMA2_CH1_USART8_TX) ||\
+ ((REQUEST) == HAL_DMA2_CH2_DEFAULT) ||\
+ ((REQUEST) == HAL_DMA2_CH2_I2C2_RX) ||\
+ ((REQUEST) == HAL_DMA2_CH2_USART1_RX) ||\
+ ((REQUEST) == HAL_DMA2_CH2_USART2_RX) ||\
+ ((REQUEST) == HAL_DMA2_CH2_USART3_RX) ||\
+ ((REQUEST) == HAL_DMA2_CH2_USART4_RX) ||\
+ ((REQUEST) == HAL_DMA2_CH2_USART5_RX) ||\
+ ((REQUEST) == HAL_DMA2_CH2_USART6_RX) ||\
+ ((REQUEST) == HAL_DMA2_CH2_USART7_RX) ||\
+ ((REQUEST) == HAL_DMA2_CH2_USART8_RX) ||\
+ ((REQUEST) == HAL_DMA2_CH3_DEFAULT) ||\
+ ((REQUEST) == HAL_DMA2_CH3_TIM6_UP) ||\
+ ((REQUEST) == HAL_DMA2_CH3_DAC_CH1) ||\
+ ((REQUEST) == HAL_DMA2_CH3_SPI1_RX) ||\
+ ((REQUEST) == HAL_DMA2_CH3_USART1_RX) ||\
+ ((REQUEST) == HAL_DMA2_CH3_USART2_RX) ||\
+ ((REQUEST) == HAL_DMA2_CH3_USART3_RX) ||\
+ ((REQUEST) == HAL_DMA2_CH3_USART4_RX) ||\
+ ((REQUEST) == HAL_DMA2_CH3_USART5_RX) ||\
+ ((REQUEST) == HAL_DMA2_CH3_USART6_RX) ||\
+ ((REQUEST) == HAL_DMA2_CH3_USART7_RX) ||\
+ ((REQUEST) == HAL_DMA2_CH3_USART8_RX) ||\
+ ((REQUEST) == HAL_DMA2_CH4_DEFAULT) ||\
+ ((REQUEST) == HAL_DMA2_CH4_TIM7_UP) ||\
+ ((REQUEST) == HAL_DMA2_CH4_DAC_CH2) ||\
+ ((REQUEST) == HAL_DMA2_CH4_SPI1_TX) ||\
+ ((REQUEST) == HAL_DMA2_CH4_USART1_TX) ||\
+ ((REQUEST) == HAL_DMA2_CH4_USART2_TX) ||\
+ ((REQUEST) == HAL_DMA2_CH4_USART3_TX) ||\
+ ((REQUEST) == HAL_DMA2_CH4_USART4_TX) ||\
+ ((REQUEST) == HAL_DMA2_CH4_USART5_TX) ||\
+ ((REQUEST) == HAL_DMA2_CH4_USART6_TX) ||\
+ ((REQUEST) == HAL_DMA2_CH4_USART7_TX) ||\
+ ((REQUEST) == HAL_DMA2_CH4_USART8_TX) ||\
+ ((REQUEST) == HAL_DMA2_CH5_DEFAULT) ||\
+ ((REQUEST) == HAL_DMA2_CH5_ADC) ||\
+ ((REQUEST) == HAL_DMA2_CH5_USART1_TX) ||\
+ ((REQUEST) == HAL_DMA2_CH5_USART2_TX) ||\
+ ((REQUEST) == HAL_DMA2_CH5_USART3_TX) ||\
+ ((REQUEST) == HAL_DMA2_CH5_USART4_TX) ||\
+ ((REQUEST) == HAL_DMA2_CH5_USART5_TX) ||\
+ ((REQUEST) == HAL_DMA2_CH5_USART6_TX) ||\
+ ((REQUEST) == HAL_DMA2_CH5_USART7_TX) ||\
+ ((REQUEST) == HAL_DMA2_CH5_USART8_TX ))
+#endif /* STM32F091xC || STM32F098xx */
+
+#if defined(STM32F030xC)
+#define IS_HAL_DMA1_REMAP(REQUEST) (((REQUEST) == HAL_DMA1_CH1_DEFAULT) ||\
+ ((REQUEST) == HAL_DMA1_CH1_ADC) ||\
+ ((REQUEST) == HAL_DMA1_CH1_TIM17_CH1) ||\
+ ((REQUEST) == HAL_DMA1_CH1_TIM17_UP) ||\
+ ((REQUEST) == HAL_DMA1_CH1_USART1_RX) ||\
+ ((REQUEST) == HAL_DMA1_CH1_USART2_RX) ||\
+ ((REQUEST) == HAL_DMA1_CH1_USART3_RX) ||\
+ ((REQUEST) == HAL_DMA1_CH1_USART4_RX) ||\
+ ((REQUEST) == HAL_DMA1_CH1_USART5_RX) ||\
+ ((REQUEST) == HAL_DMA1_CH1_USART6_RX) ||\
+ ((REQUEST) == HAL_DMA1_CH2_DEFAULT) ||\
+ ((REQUEST) == HAL_DMA1_CH2_ADC) ||\
+ ((REQUEST) == HAL_DMA1_CH2_I2C1_TX) ||\
+ ((REQUEST) == HAL_DMA1_CH2_SPI1_RX) ||\
+ ((REQUEST) == HAL_DMA1_CH2_TIM1_CH1) ||\
+ ((REQUEST) == HAL_DMA1_CH2_I2C1_TX) ||\
+ ((REQUEST) == HAL_DMA1_CH2_TIM17_CH1) ||\
+ ((REQUEST) == HAL_DMA1_CH2_TIM17_UP) ||\
+ ((REQUEST) == HAL_DMA1_CH2_USART1_TX) ||\
+ ((REQUEST) == HAL_DMA1_CH2_USART2_TX) ||\
+ ((REQUEST) == HAL_DMA1_CH2_USART3_TX) ||\
+ ((REQUEST) == HAL_DMA1_CH2_USART4_TX) ||\
+ ((REQUEST) == HAL_DMA1_CH2_USART5_TX) ||\
+ ((REQUEST) == HAL_DMA1_CH2_USART6_TX) ||\
+ ((REQUEST) == HAL_DMA1_CH3_DEFAULT) ||\
+ ((REQUEST) == HAL_DMA1_CH3_TIM6_UP) ||\
+ ((REQUEST) == HAL_DMA1_CH3_I2C1_RX) ||\
+ ((REQUEST) == HAL_DMA1_CH3_SPI1_TX) ||\
+ ((REQUEST) == HAL_DMA1_CH3_TIM1_CH2) ||\
+ ((REQUEST) == HAL_DMA1_CH3_TIM16_CH1) ||\
+ ((REQUEST) == HAL_DMA1_CH3_TIM16_UP) ||\
+ ((REQUEST) == HAL_DMA1_CH3_USART1_RX) ||\
+ ((REQUEST) == HAL_DMA1_CH3_USART2_RX) ||\
+ ((REQUEST) == HAL_DMA1_CH3_USART3_RX) ||\
+ ((REQUEST) == HAL_DMA1_CH3_USART4_RX) ||\
+ ((REQUEST) == HAL_DMA1_CH3_USART5_RX) ||\
+ ((REQUEST) == HAL_DMA1_CH3_USART6_RX) ||\
+ ((REQUEST) == HAL_DMA1_CH4_DEFAULT) ||\
+ ((REQUEST) == HAL_DMA1_CH4_TIM7_UP) ||\
+ ((REQUEST) == HAL_DMA1_CH4_I2C2_TX) ||\
+ ((REQUEST) == HAL_DMA1_CH4_SPI2_RX) ||\
+ ((REQUEST) == HAL_DMA1_CH4_TIM3_CH1) ||\
+ ((REQUEST) == HAL_DMA1_CH4_TIM3_TRIG) ||\
+ ((REQUEST) == HAL_DMA1_CH4_TIM16_CH1) ||\
+ ((REQUEST) == HAL_DMA1_CH4_TIM16_UP) ||\
+ ((REQUEST) == HAL_DMA1_CH4_USART1_TX) ||\
+ ((REQUEST) == HAL_DMA1_CH4_USART2_TX) ||\
+ ((REQUEST) == HAL_DMA1_CH4_USART3_TX) ||\
+ ((REQUEST) == HAL_DMA1_CH4_USART4_TX) ||\
+ ((REQUEST) == HAL_DMA1_CH4_USART5_TX) ||\
+ ((REQUEST) == HAL_DMA1_CH4_USART6_TX) ||\
+ ((REQUEST) == HAL_DMA1_CH5_DEFAULT) ||\
+ ((REQUEST) == HAL_DMA1_CH5_I2C2_RX) ||\
+ ((REQUEST) == HAL_DMA1_CH5_SPI2_TX) ||\
+ ((REQUEST) == HAL_DMA1_CH5_TIM1_CH3) ||\
+ ((REQUEST) == HAL_DMA1_CH5_USART1_RX) ||\
+ ((REQUEST) == HAL_DMA1_CH5_USART2_RX) ||\
+ ((REQUEST) == HAL_DMA1_CH5_USART3_RX) ||\
+ ((REQUEST) == HAL_DMA1_CH5_USART4_RX) ||\
+ ((REQUEST) == HAL_DMA1_CH5_USART5_RX) ||\
+ ((REQUEST) == HAL_DMA1_CH5_USART6_RX))
+#endif /* STM32F030xC */
+
+/**
+ * @}
+ */
+#endif /* STM32F091xC || STM32F098xx || STM32F030xC */
+
+/* Exported macros -----------------------------------------------------------*/
+
+/** @defgroup DMAEx_Exported_Macros DMAEx Exported Macros
+ * @{
+ */
+/* Interrupt & Flag management */
+
+#if defined(STM32F071xB) || defined(STM32F072xB) || defined(STM32F078xx)
+/**
+ * @brief Returns the current DMA Channel transfer complete flag.
+ * @param __HANDLE__ DMA handle
+ * @retval The specified transfer complete flag index.
+ */
+#define __HAL_DMA_GET_TC_FLAG_INDEX(__HANDLE__) \
+(((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel1))? DMA_FLAG_TC1 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel2))? DMA_FLAG_TC2 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel3))? DMA_FLAG_TC3 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel4))? DMA_FLAG_TC4 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel5))? DMA_FLAG_TC5 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel6))? DMA_FLAG_TC6 :\
+ DMA_FLAG_TC7)
+
+/**
+ * @brief Returns the current DMA Channel half transfer complete flag.
+ * @param __HANDLE__ DMA handle
+ * @retval The specified half transfer complete flag index.
+ */
+#define __HAL_DMA_GET_HT_FLAG_INDEX(__HANDLE__)\
+(((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel1))? DMA_FLAG_HT1 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel2))? DMA_FLAG_HT2 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel3))? DMA_FLAG_HT3 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel4))? DMA_FLAG_HT4 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel5))? DMA_FLAG_HT5 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel6))? DMA_FLAG_HT6 :\
+ DMA_FLAG_HT7)
+
+/**
+ * @brief Returns the current DMA Channel transfer error flag.
+ * @param __HANDLE__ DMA handle
+ * @retval The specified transfer error flag index.
+ */
+#define __HAL_DMA_GET_TE_FLAG_INDEX(__HANDLE__)\
+(((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel1))? DMA_FLAG_TE1 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel2))? DMA_FLAG_TE2 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel3))? DMA_FLAG_TE3 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel4))? DMA_FLAG_TE4 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel5))? DMA_FLAG_TE5 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel6))? DMA_FLAG_TE6 :\
+ DMA_FLAG_TE7)
+
+/**
+ * @brief Return the current DMA Channel Global interrupt flag.
+ * @param __HANDLE__ DMA handle
+ * @retval The specified transfer error flag index.
+ */
+#define __HAL_DMA_GET_GI_FLAG_INDEX(__HANDLE__)\
+(((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel1))? DMA_FLAG_GL1 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel2))? DMA_FLAG_GL2 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel3))? DMA_FLAG_GL3 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel4))? DMA_FLAG_GL4 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel5))? DMA_FLAG_GL5 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel6))? DMA_FLAG_GL6 :\
+ DMA_FLAG_GL7)
+
+/**
+ * @brief Get the DMA Channel pending flags.
+ * @param __HANDLE__ DMA handle
+ * @param __FLAG__ Get the specified flag.
+ * This parameter can be any combination of the following values:
+ * @arg DMA_FLAG_TCx: Transfer complete flag
+ * @arg DMA_FLAG_HTx: Half transfer complete flag
+ * @arg DMA_FLAG_TEx: Transfer error flag
+ * Where x can be 1_7 to select the DMA Channel flag.
+ * @retval The state of FLAG (SET or RESET).
+ */
+
+#define __HAL_DMA_GET_FLAG(__HANDLE__, __FLAG__) (DMA1->ISR & (__FLAG__))
+
+/**
+ * @brief Clears the DMA Channel pending flags.
+ * @param __HANDLE__ DMA handle
+ * @param __FLAG__ specifies the flag to clear.
+ * This parameter can be any combination of the following values:
+ * @arg DMA_FLAG_TCx: Transfer complete flag
+ * @arg DMA_FLAG_HTx: Half transfer complete flag
+ * @arg DMA_FLAG_TEx: Transfer error flag
+ * Where x can be 1_7 to select the DMA Channel flag.
+ * @retval None
+ */
+#define __HAL_DMA_CLEAR_FLAG(__HANDLE__, __FLAG__) (DMA1->IFCR = (__FLAG__))
+
+#elif defined(STM32F091xC) || defined(STM32F098xx)
+/**
+ * @brief Returns the current DMA Channel transfer complete flag.
+ * @param __HANDLE__ DMA handle
+ * @retval The specified transfer complete flag index.
+ */
+#define __HAL_DMA_GET_TC_FLAG_INDEX(__HANDLE__) \
+(((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel1))? DMA_FLAG_TC1 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel2))? DMA_FLAG_TC2 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel3))? DMA_FLAG_TC3 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel4))? DMA_FLAG_TC4 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel5))? DMA_FLAG_TC5 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel6))? DMA_FLAG_TC6 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel7))? DMA_FLAG_TC7 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Channel1))? DMA_FLAG_TC1 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Channel2))? DMA_FLAG_TC2 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Channel3))? DMA_FLAG_TC3 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Channel4))? DMA_FLAG_TC4 :\
+ DMA_FLAG_TC5)
+
+/**
+ * @brief Returns the current DMA Channel half transfer complete flag.
+ * @param __HANDLE__ DMA handle
+ * @retval The specified half transfer complete flag index.
+ */
+#define __HAL_DMA_GET_HT_FLAG_INDEX(__HANDLE__)\
+(((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel1))? DMA_FLAG_HT1 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel2))? DMA_FLAG_HT2 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel3))? DMA_FLAG_HT3 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel4))? DMA_FLAG_HT4 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel5))? DMA_FLAG_HT5 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel6))? DMA_FLAG_HT6 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel7))? DMA_FLAG_HT7 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Channel1))? DMA_FLAG_HT1 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Channel2))? DMA_FLAG_HT2 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Channel3))? DMA_FLAG_HT3 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Channel4))? DMA_FLAG_HT4 :\
+ DMA_FLAG_HT5)
+
+/**
+ * @brief Returns the current DMA Channel transfer error flag.
+ * @param __HANDLE__ DMA handle
+ * @retval The specified transfer error flag index.
+ */
+#define __HAL_DMA_GET_TE_FLAG_INDEX(__HANDLE__)\
+(((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel1))? DMA_FLAG_TE1 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel2))? DMA_FLAG_TE2 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel3))? DMA_FLAG_TE3 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel4))? DMA_FLAG_TE4 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel5))? DMA_FLAG_TE5 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel6))? DMA_FLAG_TE6 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel7))? DMA_FLAG_TE7 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Channel1))? DMA_FLAG_TE1 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Channel2))? DMA_FLAG_TE2 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Channel3))? DMA_FLAG_TE3 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Channel4))? DMA_FLAG_TE4 :\
+ DMA_FLAG_TE5)
+
+/**
+ * @brief Return the current DMA Channel Global interrupt flag.
+ * @param __HANDLE__ DMA handle
+ * @retval The specified transfer error flag index.
+ */
+#define __HAL_DMA_GET_GI_FLAG_INDEX(__HANDLE__)\
+(((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel1))? DMA_FLAG_GL1 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel2))? DMA_FLAG_GL2 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel3))? DMA_FLAG_GL3 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel4))? DMA_FLAG_GL4 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel5))? DMA_FLAG_GL5 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel6))? DMA_FLAG_GL6 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel7))? DMA_FLAG_GL7 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Channel1))? DMA_FLAG_GL1 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Channel2))? DMA_FLAG_GL2 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Channel3))? DMA_FLAG_GL3 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Channel4))? DMA_FLAG_GL4 :\
+ DMA_FLAG_GL5)
+
+/**
+ * @brief Get the DMA Channel pending flags.
+ * @param __HANDLE__ DMA handle
+ * @param __FLAG__ Get the specified flag.
+ * This parameter can be any combination of the following values:
+ * @arg DMA_FLAG_TCx: Transfer complete flag
+ * @arg DMA_FLAG_HTx: Half transfer complete flag
+ * @arg DMA_FLAG_TEx: Transfer error flag
+ * Where x can be 0_4, 1_5, 2_6 or 3_7 to select the DMA Channel flag.
+ * @retval The state of FLAG (SET or RESET).
+ */
+
+#define __HAL_DMA_GET_FLAG(__HANDLE__, __FLAG__)\
+(((uint32_t)((__HANDLE__)->Instance) > (uint32_t)DMA1_Channel7)? (DMA2->ISR & (__FLAG__)) :\
+ (DMA1->ISR & (__FLAG__)))
+
+/**
+ * @brief Clears the DMA Channel pending flags.
+ * @param __HANDLE__ DMA handle
+ * @param __FLAG__ specifies the flag to clear.
+ * This parameter can be any combination of the following values:
+ * @arg DMA_FLAG_TCx: Transfer complete flag
+ * @arg DMA_FLAG_HTx: Half transfer complete flag
+ * @arg DMA_FLAG_TEx: Transfer error flag
+ * Where x can be 0_4, 1_5, 2_6 or 3_7 to select the DMA Channel flag.
+ * @retval None
+ */
+#define __HAL_DMA_CLEAR_FLAG(__HANDLE__, __FLAG__) \
+(((uint32_t)((__HANDLE__)->Instance) > (uint32_t)DMA1_Channel7)? (DMA2->IFCR = (__FLAG__)) :\
+ (DMA1->IFCR = (__FLAG__)))
+
+#else /* STM32F030x8_STM32F030xC_STM32F031x6_STM32F038xx_STM32F051x8_STM32F058xx_STM32F070x6_STM32F070xB Product devices */
+/**
+ * @brief Returns the current DMA Channel transfer complete flag.
+ * @param __HANDLE__ DMA handle
+ * @retval The specified transfer complete flag index.
+ */
+#define __HAL_DMA_GET_TC_FLAG_INDEX(__HANDLE__) \
+(((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel1))? DMA_FLAG_TC1 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel2))? DMA_FLAG_TC2 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel3))? DMA_FLAG_TC3 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel4))? DMA_FLAG_TC4 :\
+ DMA_FLAG_TC5)
+
+/**
+ * @brief Returns the current DMA Channel half transfer complete flag.
+ * @param __HANDLE__ DMA handle
+ * @retval The specified half transfer complete flag index.
+ */
+#define __HAL_DMA_GET_HT_FLAG_INDEX(__HANDLE__)\
+(((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel1))? DMA_FLAG_HT1 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel2))? DMA_FLAG_HT2 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel3))? DMA_FLAG_HT3 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel4))? DMA_FLAG_HT4 :\
+ DMA_FLAG_HT5)
+
+/**
+ * @brief Returns the current DMA Channel transfer error flag.
+ * @param __HANDLE__ DMA handle
+ * @retval The specified transfer error flag index.
+ */
+#define __HAL_DMA_GET_TE_FLAG_INDEX(__HANDLE__)\
+(((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel1))? DMA_FLAG_TE1 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel2))? DMA_FLAG_TE2 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel3))? DMA_FLAG_TE3 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel4))? DMA_FLAG_TE4 :\
+ DMA_FLAG_TE5)
+
+/**
+ * @brief Return the current DMA Channel Global interrupt flag.
+ * @param __HANDLE__ DMA handle
+ * @retval The specified transfer error flag index.
+ */
+#define __HAL_DMA_GET_GI_FLAG_INDEX(__HANDLE__)\
+(((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel1))? DMA_FLAG_GL1 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel2))? DMA_FLAG_GL2 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel3))? DMA_FLAG_GL3 :\
+ ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Channel4))? DMA_FLAG_GL4 :\
+ DMA_FLAG_GL5)
+
+/**
+ * @brief Get the DMA Channel pending flags.
+ * @param __HANDLE__ DMA handle
+ * @param __FLAG__ Get the specified flag.
+ * This parameter can be any combination of the following values:
+ * @arg DMA_FLAG_TCx: Transfer complete flag
+ * @arg DMA_FLAG_HTx: Half transfer complete flag
+ * @arg DMA_FLAG_TEx: Transfer error flag
+ * Where x can be 1_5 to select the DMA Channel flag.
+ * @retval The state of FLAG (SET or RESET).
+ */
+
+#define __HAL_DMA_GET_FLAG(__HANDLE__, __FLAG__) (DMA1->ISR & (__FLAG__))
+
+/**
+ * @brief Clears the DMA Channel pending flags.
+ * @param __HANDLE__ DMA handle
+ * @param __FLAG__ specifies the flag to clear.
+ * This parameter can be any combination of the following values:
+ * @arg DMA_FLAG_TCx: Transfer complete flag
+ * @arg DMA_FLAG_HTx: Half transfer complete flag
+ * @arg DMA_FLAG_TEx: Transfer error flag
+ * Where x can be 1_5 to select the DMA Channel flag.
+ * @retval None
+ */
+#define __HAL_DMA_CLEAR_FLAG(__HANDLE__, __FLAG__) (DMA1->IFCR = (__FLAG__))
+
+#endif
+
+
+#if defined(STM32F091xC) || defined(STM32F098xx) || defined(STM32F030xC)
+#define __HAL_DMA1_REMAP(__REQUEST__) \
+ do { assert_param(IS_HAL_DMA1_REMAP(__REQUEST__)); \
+ DMA1->CSELR &= ~(0x0FU << (uint32_t)(((__REQUEST__) >> 28U) * 4U)); \
+ DMA1->CSELR |= (uint32_t)((__REQUEST__) & 0x0FFFFFFFU); \
+ }while(0)
+
+#if defined(STM32F091xC) || defined(STM32F098xx)
+#define __HAL_DMA2_REMAP(__REQUEST__) \
+ do { assert_param(IS_HAL_DMA2_REMAP(__REQUEST__)); \
+ DMA2->CSELR &= ~(0x0FU << (uint32_t)(((__REQUEST__) >> 28U) * 4U)); \
+ DMA2->CSELR |= (uint32_t)((__REQUEST__) & 0x0FFFFFFFU); \
+ }while(0)
+#endif /* STM32F091xC || STM32F098xx */
+
+#endif /* STM32F091xC || STM32F098xx || STM32F030xC */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __STM32F0xx_HAL_DMA_EX_H */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal_exti.h b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal_exti.h
new file mode 100644
index 0000000..4e0248e
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal_exti.h
@@ -0,0 +1,375 @@
+/**
+ ******************************************************************************
+ * @file stm32f0xx_hal_exti.h
+ * @author MCD Application Team
+ * @brief Header file of EXTI HAL module.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2019 STMicroelectronics.
+ * All rights reserved.
+ *
+ * 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 STM32F0xx_HAL_EXTI_H
+#define STM32F0xx_HAL_EXTI_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f0xx_hal_def.h"
+
+/** @addtogroup STM32F0xx_HAL_Driver
+ * @{
+ */
+
+/** @defgroup EXTI EXTI
+ * @brief EXTI HAL module driver
+ * @{
+ */
+
+/* Exported types ------------------------------------------------------------*/
+
+/** @defgroup EXTI_Exported_Types EXTI Exported Types
+ * @{
+ */
+
+/**
+ * @brief HAL EXTI common Callback ID enumeration definition
+ */
+typedef enum
+{
+ HAL_EXTI_COMMON_CB_ID = 0x00U
+} EXTI_CallbackIDTypeDef;
+
+/**
+ * @brief EXTI Handle structure definition
+ */
+typedef struct
+{
+ uint32_t Line; /*!< Exti line number */
+ void (* PendingCallback)(void); /*!< Exti pending callback */
+} EXTI_HandleTypeDef;
+
+/**
+ * @brief EXTI Configuration structure definition
+ */
+typedef struct
+{
+ uint32_t Line; /*!< The Exti line to be configured. This parameter
+ can be a value of @ref EXTI_Line */
+ uint32_t Mode; /*!< The Exit Mode to be configured for a core.
+ This parameter can be a combination of @ref EXTI_Mode */
+ uint32_t Trigger; /*!< The Exti Trigger to be configured. This parameter
+ can be a value of @ref EXTI_Trigger */
+ uint32_t GPIOSel; /*!< The Exti GPIO multiplexer selection to be configured.
+ This parameter is only possible for line 0 to 15. It
+ can be a value of @ref EXTI_GPIOSel */
+} EXTI_ConfigTypeDef;
+
+/**
+ * @}
+ */
+
+/* Exported constants --------------------------------------------------------*/
+/** @defgroup EXTI_Exported_Constants EXTI Exported Constants
+ * @{
+ */
+
+/** @defgroup EXTI_Line EXTI Line
+ * @{
+ */
+#define EXTI_LINE_0 (EXTI_GPIO | 0x00u) /*!< External interrupt line 0 */
+#define EXTI_LINE_1 (EXTI_GPIO | 0x01u) /*!< External interrupt line 1 */
+#define EXTI_LINE_2 (EXTI_GPIO | 0x02u) /*!< External interrupt line 2 */
+#define EXTI_LINE_3 (EXTI_GPIO | 0x03u) /*!< External interrupt line 3 */
+#define EXTI_LINE_4 (EXTI_GPIO | 0x04u) /*!< External interrupt line 4 */
+#define EXTI_LINE_5 (EXTI_GPIO | 0x05u) /*!< External interrupt line 5 */
+#define EXTI_LINE_6 (EXTI_GPIO | 0x06u) /*!< External interrupt line 6 */
+#define EXTI_LINE_7 (EXTI_GPIO | 0x07u) /*!< External interrupt line 7 */
+#define EXTI_LINE_8 (EXTI_GPIO | 0x08u) /*!< External interrupt line 8 */
+#define EXTI_LINE_9 (EXTI_GPIO | 0x09u) /*!< External interrupt line 9 */
+#define EXTI_LINE_10 (EXTI_GPIO | 0x0Au) /*!< External interrupt line 10 */
+#define EXTI_LINE_11 (EXTI_GPIO | 0x0Bu) /*!< External interrupt line 11 */
+#define EXTI_LINE_12 (EXTI_GPIO | 0x0Cu) /*!< External interrupt line 12 */
+#define EXTI_LINE_13 (EXTI_GPIO | 0x0Du) /*!< External interrupt line 13 */
+#define EXTI_LINE_14 (EXTI_GPIO | 0x0Eu) /*!< External interrupt line 14 */
+#define EXTI_LINE_15 (EXTI_GPIO | 0x0Fu) /*!< External interrupt line 15 */
+
+#if defined (EXTI_IMR_MR16)
+#define EXTI_LINE_16 (EXTI_CONFIG | 0x10u) /*!< External interrupt line 16 Connected to the PVD Output */
+#else
+#define EXTI_LINE_16 (EXTI_RESERVED | 0x10u)
+#endif /* EXTI_IMR_MR16 */
+
+#define EXTI_LINE_17 (EXTI_CONFIG | 0x11u) /*!< External interrupt line 17 Connected to the RTC Alarm event */
+
+#if defined (EXTI_IMR_MR18)
+#define EXTI_LINE_18 (EXTI_CONFIG | 0x12u) /*!< External interrupt line 18 Connected to the USB OTG FS Wakeup from suspend event */
+#else
+#define EXTI_LINE_18 (EXTI_RESERVED | 0x12u)
+#endif /* EXTI_IMR_MR18 */
+
+#define EXTI_LINE_19 (EXTI_CONFIG | 0x13u) /*!< External interrupt line 19 Connected to the Ethernet Wakeup event */
+
+#if defined (EXTI_IMR_MR20)
+#define EXTI_LINE_20 (EXTI_CONFIG | 0x14u) /*!< External interrupt line 20 Connected to the USB OTG HS (configured in FS) Wakeup event */
+#else
+#define EXTI_LINE_20 (EXTI_RESERVED | 0x14u)
+#endif /* EXTI_IMR_MR20 */
+
+#if defined (EXTI_IMR_MR21)
+#define EXTI_LINE_21 (EXTI_CONFIG | 0x15u) /*!< External interrupt line 21 Connected to the Comparator 1 output */
+#else
+#define EXTI_LINE_21 (EXTI_RESERVED | 0x15u)
+#endif /* EXTI_IMR_MR21 */
+
+#if defined (EXTI_IMR_MR22)
+#define EXTI_LINE_22 (EXTI_CONFIG | 0x16u) /*!< External interrupt line 22 Connected to the Comparator 2 output */
+#else
+#define EXTI_LINE_22 (EXTI_RESERVED | 0x16u)
+#endif /* EXTI_IMR_MR22 */
+
+#if defined (EXTI_IMR_MR23)
+#define EXTI_LINE_23 (EXTI_DIRECT | 0x17u) /*!< External interrupt line 23 Connected to the internal I2C1 wakeup event */
+#else
+#define EXTI_LINE_23 (EXTI_RESERVED | 0x17u)
+#endif /* EXTI_IMR_MR23 */
+
+#define EXTI_LINE_24 (EXTI_RESERVED | 0x18u)
+
+#if defined (EXTI_IMR_MR25)
+#define EXTI_LINE_25 (EXTI_CONFIG | 0x19u) /*!< External interrupt line 25 Connected to the internal USART1 wakeup event */
+#else
+#define EXTI_LINE_25 (EXTI_RESERVED | 0x19u)
+#endif /* EXTI_IMR_MR25 */
+
+#if defined (EXTI_IMR_MR26)
+#define EXTI_LINE_26 (EXTI_CONFIG | 0x1Au) /*!< External interrupt line 26 Connected to the internal USART2 wakeup event */
+#else
+#define EXTI_LINE_26 (EXTI_RESERVED | 0x1Au)
+#endif /* EXTI_IMR_MR26 */
+
+#if defined (EXTI_IMR_MR27)
+#define EXTI_LINE_27 (EXTI_CONFIG | 0x1Bu) /*!< External interrupt line 27 Connected to the internal CEC wakeup event */
+#else
+#define EXTI_LINE_27 (EXTI_RESERVED | 0x1Bu)
+#endif /* EXTI_IMR_MR27 */
+
+#if defined (EXTI_IMR_MR28)
+#define EXTI_LINE_28 (EXTI_CONFIG | 0x1Cu) /*!< External interrupt line 28 Connected to the internal USART3 wakeup event */
+#else
+#define EXTI_LINE_28 (EXTI_RESERVED | 0x1Cu)
+#endif /* EXTI_IMR_MR28 */
+
+#define EXTI_LINE_29 (EXTI_RESERVED | 0x1Du)
+#define EXTI_LINE_30 (EXTI_RESERVED | 0x1Eu)
+
+#if defined (EXTI_IMR_MR31)
+#define EXTI_LINE_31 (EXTI_CONFIG | 0x1Fu) /*!< External interrupt line 31 Connected to the VDDIO2 supply comparator output */
+#else
+#define EXTI_LINE_31 (EXTI_RESERVED | 0x1Fu)
+#endif /* EXTI_IMR_MR31 */
+
+/**
+ * @}
+ */
+
+/** @defgroup EXTI_Mode EXTI Mode
+ * @{
+ */
+#define EXTI_MODE_NONE 0x00000000u
+#define EXTI_MODE_INTERRUPT 0x00000001u
+#define EXTI_MODE_EVENT 0x00000002u
+/**
+ * @}
+ */
+
+/** @defgroup EXTI_Trigger EXTI Trigger
+ * @{
+ */
+#define EXTI_TRIGGER_NONE 0x00000000u
+#define EXTI_TRIGGER_RISING 0x00000001u
+#define EXTI_TRIGGER_FALLING 0x00000002u
+#define EXTI_TRIGGER_RISING_FALLING (EXTI_TRIGGER_RISING | EXTI_TRIGGER_FALLING)
+/**
+ * @}
+ */
+
+/** @defgroup EXTI_GPIOSel EXTI GPIOSel
+ * @brief
+ * @{
+ */
+#define EXTI_GPIOA 0x00000000u
+#define EXTI_GPIOB 0x00000001u
+#define EXTI_GPIOC 0x00000002u
+#if defined (GPIOD)
+#define EXTI_GPIOD 0x00000003u
+#endif /* GPIOD */
+#if defined (GPIOE)
+#define EXTI_GPIOE 0x00000004u
+#endif /* GPIOE */
+#define EXTI_GPIOF 0x00000005u
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/* Exported macro ------------------------------------------------------------*/
+/** @defgroup EXTI_Exported_Macros EXTI Exported Macros
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/* Private constants --------------------------------------------------------*/
+/** @defgroup EXTI_Private_Constants EXTI Private Constants
+ * @{
+ */
+/**
+ * @brief EXTI Line property definition
+ */
+#define EXTI_PROPERTY_SHIFT 24u
+#define EXTI_DIRECT (0x01uL << EXTI_PROPERTY_SHIFT)
+#define EXTI_CONFIG (0x02uL << EXTI_PROPERTY_SHIFT)
+#define EXTI_GPIO ((0x04uL << EXTI_PROPERTY_SHIFT) | EXTI_CONFIG)
+#define EXTI_RESERVED (0x08uL << EXTI_PROPERTY_SHIFT)
+#define EXTI_PROPERTY_MASK (EXTI_DIRECT | EXTI_CONFIG | EXTI_GPIO)
+
+/**
+ * @brief EXTI bit usage
+ */
+#define EXTI_PIN_MASK 0x0000001Fu
+
+/**
+ * @brief EXTI Mask for interrupt & event mode
+ */
+#define EXTI_MODE_MASK (EXTI_MODE_EVENT | EXTI_MODE_INTERRUPT)
+
+/**
+ * @brief EXTI Mask for trigger possibilities
+ */
+#define EXTI_TRIGGER_MASK (EXTI_TRIGGER_RISING | EXTI_TRIGGER_FALLING)
+
+/**
+ * @brief EXTI Line number
+ */
+#define EXTI_LINE_NB 32uL
+
+/**
+ * @}
+ */
+
+/* Private macros ------------------------------------------------------------*/
+/** @defgroup EXTI_Private_Macros EXTI Private Macros
+ * @{
+ */
+#define IS_EXTI_LINE(__EXTI_LINE__) ((((__EXTI_LINE__) & ~(EXTI_PROPERTY_MASK | EXTI_PIN_MASK)) == 0x00u) && \
+ ((((__EXTI_LINE__) & EXTI_PROPERTY_MASK) == EXTI_DIRECT) || \
+ (((__EXTI_LINE__) & EXTI_PROPERTY_MASK) == EXTI_CONFIG) || \
+ (((__EXTI_LINE__) & EXTI_PROPERTY_MASK) == EXTI_GPIO)) && \
+ (((__EXTI_LINE__) & EXTI_PIN_MASK) < EXTI_LINE_NB))
+
+#define IS_EXTI_MODE(__EXTI_LINE__) ((((__EXTI_LINE__) & EXTI_MODE_MASK) != 0x00u) && \
+ (((__EXTI_LINE__) & ~EXTI_MODE_MASK) == 0x00u))
+
+#define IS_EXTI_TRIGGER(__EXTI_LINE__) (((__EXTI_LINE__) & ~EXTI_TRIGGER_MASK) == 0x00u)
+
+#define IS_EXTI_PENDING_EDGE(__EXTI_LINE__) ((__EXTI_LINE__) == EXTI_TRIGGER_RISING_FALLING)
+
+#define IS_EXTI_CONFIG_LINE(__EXTI_LINE__) (((__EXTI_LINE__) & EXTI_CONFIG) != 0x00u)
+
+#if defined (GPIOE)
+#define IS_EXTI_GPIO_PORT(__PORT__) (((__PORT__) == EXTI_GPIOA) || \
+ ((__PORT__) == EXTI_GPIOB) || \
+ ((__PORT__) == EXTI_GPIOC) || \
+ ((__PORT__) == EXTI_GPIOD) || \
+ ((__PORT__) == EXTI_GPIOE) || \
+ ((__PORT__) == EXTI_GPIOF))
+#elif defined (GPIOD)
+#define IS_EXTI_GPIO_PORT(__PORT__) (((__PORT__) == EXTI_GPIOA) || \
+ ((__PORT__) == EXTI_GPIOB) || \
+ ((__PORT__) == EXTI_GPIOC) || \
+ ((__PORT__) == EXTI_GPIOD) || \
+ ((__PORT__) == EXTI_GPIOF))
+#else
+#define IS_EXTI_GPIO_PORT(__PORT__) (((__PORT__) == EXTI_GPIOA) || \
+ ((__PORT__) == EXTI_GPIOB) || \
+ ((__PORT__) == EXTI_GPIOC) || \
+ ((__PORT__) == EXTI_GPIOF))
+#endif /* GPIOE */
+
+#define IS_EXTI_GPIO_PIN(__PIN__) ((__PIN__) < 16u)
+
+/**
+ * @}
+ */
+
+
+/* Exported functions --------------------------------------------------------*/
+/** @defgroup EXTI_Exported_Functions EXTI Exported Functions
+ * @brief EXTI Exported Functions
+ * @{
+ */
+
+/** @defgroup EXTI_Exported_Functions_Group1 Configuration functions
+ * @brief Configuration functions
+ * @{
+ */
+/* Configuration functions ****************************************************/
+HAL_StatusTypeDef HAL_EXTI_SetConfigLine(EXTI_HandleTypeDef *hexti, EXTI_ConfigTypeDef *pExtiConfig);
+HAL_StatusTypeDef HAL_EXTI_GetConfigLine(EXTI_HandleTypeDef *hexti, EXTI_ConfigTypeDef *pExtiConfig);
+HAL_StatusTypeDef HAL_EXTI_ClearConfigLine(EXTI_HandleTypeDef *hexti);
+HAL_StatusTypeDef HAL_EXTI_RegisterCallback(EXTI_HandleTypeDef *hexti, EXTI_CallbackIDTypeDef CallbackID, void (*pPendingCbfn)(void));
+HAL_StatusTypeDef HAL_EXTI_GetHandle(EXTI_HandleTypeDef *hexti, uint32_t ExtiLine);
+/**
+ * @}
+ */
+
+/** @defgroup EXTI_Exported_Functions_Group2 IO operation functions
+ * @brief IO operation functions
+ * @{
+ */
+/* IO operation functions *****************************************************/
+void HAL_EXTI_IRQHandler(EXTI_HandleTypeDef *hexti);
+uint32_t HAL_EXTI_GetPending(EXTI_HandleTypeDef *hexti, uint32_t Edge);
+void HAL_EXTI_ClearPending(EXTI_HandleTypeDef *hexti, uint32_t Edge);
+void HAL_EXTI_GenerateSWI(EXTI_HandleTypeDef *hexti);
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* STM32F0xx_HAL_EXTI_H */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal_flash.h b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal_flash.h
new file mode 100644
index 0000000..0302037
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal_flash.h
@@ -0,0 +1,353 @@
+/**
+ ******************************************************************************
+ * @file stm32f0xx_hal_flash.h
+ * @author MCD Application Team
+ * @brief Header file of Flash HAL module.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2016 STMicroelectronics.
+ * All rights reserved.
+ *
+ * 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 __STM32F0xx_HAL_FLASH_H
+#define __STM32F0xx_HAL_FLASH_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f0xx_hal_def.h"
+
+/** @addtogroup STM32F0xx_HAL_Driver
+ * @{
+ */
+
+/** @addtogroup FLASH
+ * @{
+ */
+
+/** @addtogroup FLASH_Private_Constants
+ * @{
+ */
+#define FLASH_TIMEOUT_VALUE (50000U) /* 50 s */
+/**
+ * @}
+ */
+
+/** @addtogroup FLASH_Private_Macros
+ * @{
+ */
+
+#define IS_FLASH_TYPEPROGRAM(VALUE) (((VALUE) == FLASH_TYPEPROGRAM_HALFWORD) || \
+ ((VALUE) == FLASH_TYPEPROGRAM_WORD) || \
+ ((VALUE) == FLASH_TYPEPROGRAM_DOUBLEWORD))
+
+#define IS_FLASH_LATENCY(__LATENCY__) (((__LATENCY__) == FLASH_LATENCY_0) || \
+ ((__LATENCY__) == FLASH_LATENCY_1))
+
+/**
+ * @}
+ */
+
+/* Exported types ------------------------------------------------------------*/
+/** @defgroup FLASH_Exported_Types FLASH Exported Types
+ * @{
+ */
+
+/**
+ * @brief FLASH Procedure structure definition
+ */
+typedef enum
+{
+ FLASH_PROC_NONE = 0U,
+ FLASH_PROC_PAGEERASE = 1U,
+ FLASH_PROC_MASSERASE = 2U,
+ FLASH_PROC_PROGRAMHALFWORD = 3U,
+ FLASH_PROC_PROGRAMWORD = 4U,
+ FLASH_PROC_PROGRAMDOUBLEWORD = 5U
+} FLASH_ProcedureTypeDef;
+
+/**
+ * @brief FLASH handle Structure definition
+ */
+typedef struct
+{
+ __IO FLASH_ProcedureTypeDef ProcedureOnGoing; /*!< Internal variable to indicate which procedure is ongoing or not in IT context */
+
+ __IO uint32_t DataRemaining; /*!< Internal variable to save the remaining pages to erase or half-word to program in IT context */
+
+ __IO uint32_t Address; /*!< Internal variable to save address selected for program or erase */
+
+ __IO uint64_t Data; /*!< Internal variable to save data to be programmed */
+
+ HAL_LockTypeDef Lock; /*!< FLASH locking object */
+
+ __IO uint32_t ErrorCode; /*!< FLASH error code
+ This parameter can be a value of @ref FLASH_Error_Codes */
+} FLASH_ProcessTypeDef;
+
+/**
+ * @}
+ */
+
+/* Exported constants --------------------------------------------------------*/
+/** @defgroup FLASH_Exported_Constants FLASH Exported Constants
+ * @{
+ */
+
+/** @defgroup FLASH_Error_Codes FLASH Error Codes
+ * @{
+ */
+
+#define HAL_FLASH_ERROR_NONE 0x00U /*!< No error */
+#define HAL_FLASH_ERROR_PROG 0x01U /*!< Programming error */
+#define HAL_FLASH_ERROR_WRP 0x02U /*!< Write protection error */
+
+/**
+ * @}
+ */
+
+/** @defgroup FLASH_Type_Program FLASH Type Program
+ * @{
+ */
+#define FLASH_TYPEPROGRAM_HALFWORD (0x01U) /*!ACR = (FLASH->ACR&(~FLASH_ACR_LATENCY)) | (__LATENCY__))
+
+
+/**
+ * @brief Get the FLASH Latency.
+ * @retval FLASH Latency
+ * The value of this parameter depend on device used within the same series
+ */
+#define __HAL_FLASH_GET_LATENCY() (READ_BIT((FLASH->ACR), FLASH_ACR_LATENCY))
+
+/**
+ * @}
+ */
+
+/** @defgroup FLASH_Prefetch FLASH Prefetch
+ * @brief macros to handle FLASH Prefetch buffer
+ * @{
+ */
+/**
+ * @brief Enable the FLASH prefetch buffer.
+ * @retval None
+ */
+#define __HAL_FLASH_PREFETCH_BUFFER_ENABLE() (FLASH->ACR |= FLASH_ACR_PRFTBE)
+
+/**
+ * @brief Disable the FLASH prefetch buffer.
+ * @retval None
+ */
+#define __HAL_FLASH_PREFETCH_BUFFER_DISABLE() (FLASH->ACR &= (~FLASH_ACR_PRFTBE))
+
+/**
+ * @}
+ */
+
+/** @defgroup FLASH_Interrupt FLASH Interrupts
+ * @brief macros to handle FLASH interrupts
+ * @{
+ */
+
+/**
+ * @brief Enable the specified FLASH interrupt.
+ * @param __INTERRUPT__ FLASH interrupt
+ * This parameter can be any combination of the following values:
+ * @arg @ref FLASH_IT_EOP End of FLASH Operation Interrupt
+ * @arg @ref FLASH_IT_ERR Error Interrupt
+ * @retval none
+ */
+#define __HAL_FLASH_ENABLE_IT(__INTERRUPT__) SET_BIT((FLASH->CR), (__INTERRUPT__))
+
+/**
+ * @brief Disable the specified FLASH interrupt.
+ * @param __INTERRUPT__ FLASH interrupt
+ * This parameter can be any combination of the following values:
+ * @arg @ref FLASH_IT_EOP End of FLASH Operation Interrupt
+ * @arg @ref FLASH_IT_ERR Error Interrupt
+ * @retval none
+ */
+#define __HAL_FLASH_DISABLE_IT(__INTERRUPT__) CLEAR_BIT((FLASH->CR), (uint32_t)(__INTERRUPT__))
+
+/**
+ * @brief Get the specified FLASH flag status.
+ * @param __FLAG__ specifies the FLASH flag to check.
+ * This parameter can be one of the following values:
+ * @arg @ref FLASH_FLAG_BSY FLASH Busy flag
+ * @arg @ref FLASH_FLAG_EOP FLASH End of Operation flag
+ * @arg @ref FLASH_FLAG_WRPERR FLASH Write protected error flag
+ * @arg @ref FLASH_FLAG_PGERR FLASH Programming error flag
+ * @retval The new state of __FLAG__ (SET or RESET).
+ */
+#define __HAL_FLASH_GET_FLAG(__FLAG__) (((FLASH->SR) & (__FLAG__)) == (__FLAG__))
+
+/**
+ * @brief Clear the specified FLASH flag.
+ * @param __FLAG__ specifies the FLASH flags to clear.
+ * This parameter can be any combination of the following values:
+ * @arg @ref FLASH_FLAG_EOP FLASH End of Operation flag
+ * @arg @ref FLASH_FLAG_WRPERR FLASH Write protected error flag
+ * @arg @ref FLASH_FLAG_PGERR FLASH Programming error flag
+ * @retval none
+ */
+#define __HAL_FLASH_CLEAR_FLAG(__FLAG__) ((FLASH->SR) = (__FLAG__))
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/* Include FLASH HAL Extended module */
+#include "stm32f0xx_hal_flash_ex.h"
+
+/* Exported functions --------------------------------------------------------*/
+/** @addtogroup FLASH_Exported_Functions
+ * @{
+ */
+
+/** @addtogroup FLASH_Exported_Functions_Group1
+ * @{
+ */
+/* IO operation functions *****************************************************/
+HAL_StatusTypeDef HAL_FLASH_Program(uint32_t TypeProgram, uint32_t Address, uint64_t Data);
+HAL_StatusTypeDef HAL_FLASH_Program_IT(uint32_t TypeProgram, uint32_t Address, uint64_t Data);
+
+/* FLASH IRQ handler function */
+void HAL_FLASH_IRQHandler(void);
+/* Callbacks in non blocking modes */
+void HAL_FLASH_EndOfOperationCallback(uint32_t ReturnValue);
+void HAL_FLASH_OperationErrorCallback(uint32_t ReturnValue);
+
+/**
+ * @}
+ */
+
+/** @addtogroup FLASH_Exported_Functions_Group2
+ * @{
+ */
+/* Peripheral Control functions ***********************************************/
+HAL_StatusTypeDef HAL_FLASH_Unlock(void);
+HAL_StatusTypeDef HAL_FLASH_Lock(void);
+HAL_StatusTypeDef HAL_FLASH_OB_Unlock(void);
+HAL_StatusTypeDef HAL_FLASH_OB_Lock(void);
+HAL_StatusTypeDef HAL_FLASH_OB_Launch(void);
+
+/**
+ * @}
+ */
+
+/** @addtogroup FLASH_Exported_Functions_Group3
+ * @{
+ */
+/* Peripheral State and Error functions ***************************************/
+uint32_t HAL_FLASH_GetError(void);
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/* Private function -------------------------------------------------*/
+/** @addtogroup FLASH_Private_Functions
+ * @{
+ */
+HAL_StatusTypeDef FLASH_WaitForLastOperation(uint32_t Timeout);
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __STM32F0xx_HAL_FLASH_H */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
+
diff --git a/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal_flash_ex.h b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal_flash_ex.h
new file mode 100644
index 0000000..ddd5ea3
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal_flash_ex.h
@@ -0,0 +1,448 @@
+/**
+ ******************************************************************************
+ * @file stm32f0xx_hal_flash_ex.h
+ * @author MCD Application Team
+ * @brief Header file of Flash HAL Extended module.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2016 STMicroelectronics.
+ * All rights reserved.
+ *
+ * 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 __STM32F0xx_HAL_FLASH_EX_H
+#define __STM32F0xx_HAL_FLASH_EX_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f0xx_hal_def.h"
+
+/** @addtogroup STM32F0xx_HAL_Driver
+ * @{
+ */
+
+/** @addtogroup FLASHEx
+ * @{
+ */
+
+/** @addtogroup FLASHEx_Private_Macros
+ * @{
+ */
+#define IS_FLASH_TYPEERASE(VALUE) (((VALUE) == FLASH_TYPEERASE_PAGES) || \
+ ((VALUE) == FLASH_TYPEERASE_MASSERASE))
+
+#define IS_OPTIONBYTE(VALUE) ((VALUE) <= (OPTIONBYTE_WRP | OPTIONBYTE_RDP | OPTIONBYTE_USER | OPTIONBYTE_DATA))
+
+#define IS_WRPSTATE(VALUE) (((VALUE) == OB_WRPSTATE_DISABLE) || \
+ ((VALUE) == OB_WRPSTATE_ENABLE))
+
+#define IS_OB_DATA_ADDRESS(ADDRESS) (((ADDRESS) == OB_DATA_ADDRESS_DATA0) || ((ADDRESS) == OB_DATA_ADDRESS_DATA1))
+
+#define IS_OB_RDP_LEVEL(LEVEL) (((LEVEL) == OB_RDP_LEVEL_0) ||\
+ ((LEVEL) == OB_RDP_LEVEL_1))/*||\
+ ((LEVEL) == OB_RDP_LEVEL_2))*/
+
+#define IS_OB_IWDG_SOURCE(SOURCE) (((SOURCE) == OB_IWDG_SW) || ((SOURCE) == OB_IWDG_HW))
+
+#define IS_OB_STOP_SOURCE(SOURCE) (((SOURCE) == OB_STOP_NO_RST) || ((SOURCE) == OB_STOP_RST))
+
+#define IS_OB_STDBY_SOURCE(SOURCE) (((SOURCE) == OB_STDBY_NO_RST) || ((SOURCE) == OB_STDBY_RST))
+
+#define IS_OB_BOOT1(BOOT1) (((BOOT1) == OB_BOOT1_RESET) || ((BOOT1) == OB_BOOT1_SET))
+
+#define IS_OB_VDDA_ANALOG(ANALOG) (((ANALOG) == OB_VDDA_ANALOG_ON) || ((ANALOG) == OB_VDDA_ANALOG_OFF))
+
+#define IS_OB_SRAM_PARITY(PARITY) (((PARITY) == OB_SRAM_PARITY_SET) || ((PARITY) == OB_SRAM_PARITY_RESET))
+
+#if defined(FLASH_OBR_BOOT_SEL)
+#define IS_OB_BOOT_SEL(BOOT_SEL) (((BOOT_SEL) == OB_BOOT_SEL_RESET) || ((BOOT_SEL) == OB_BOOT_SEL_SET))
+#define IS_OB_BOOT0(BOOT0) (((BOOT0) == OB_BOOT0_RESET) || ((BOOT0) == OB_BOOT0_SET))
+#endif /* FLASH_OBR_BOOT_SEL */
+
+
+#define IS_OB_WRP(PAGE) (((PAGE) != 0x0000000U))
+
+#define IS_FLASH_NB_PAGES(ADDRESS,NBPAGES) ((ADDRESS)+((NBPAGES)*FLASH_PAGE_SIZE)-1 <= FLASH_BANK1_END)
+
+#define IS_FLASH_PROGRAM_ADDRESS(ADDRESS) (((ADDRESS) >= FLASH_BASE) && ((ADDRESS) <= FLASH_BANK1_END))
+
+/**
+ * @}
+ */
+
+/* Exported types ------------------------------------------------------------*/
+/** @defgroup FLASHEx_Exported_Types FLASHEx Exported Types
+ * @{
+ */
+/**
+ * @brief FLASH Erase structure definition
+ */
+typedef struct
+{
+ uint32_t TypeErase; /*!< TypeErase: Mass erase or page erase.
+ This parameter can be a value of @ref FLASHEx_Type_Erase */
+
+ uint32_t PageAddress; /*!< PageAdress: Initial FLASH page address to erase when mass erase is disabled
+ This parameter must be a number between Min_Data = FLASH_BASE and Max_Data = FLASH_BANK1_END */
+
+ uint32_t NbPages; /*!< NbPages: Number of pagess to be erased.
+ This parameter must be a value between Min_Data = 1 and Max_Data = (max number of pages - value of initial page)*/
+
+} FLASH_EraseInitTypeDef;
+
+/**
+ * @brief FLASH Options bytes program structure definition
+ */
+typedef struct
+{
+ uint32_t OptionType; /*!< OptionType: Option byte to be configured.
+ This parameter can be a value of @ref FLASHEx_OB_Type */
+
+ uint32_t WRPState; /*!< WRPState: Write protection activation or deactivation.
+ This parameter can be a value of @ref FLASHEx_OB_WRP_State */
+
+ uint32_t WRPPage; /*!< WRPPage: specifies the page(s) to be write protected
+ This parameter can be a value of @ref FLASHEx_OB_Write_Protection */
+
+ uint8_t RDPLevel; /*!< RDPLevel: Set the read protection level..
+ This parameter can be a value of @ref FLASHEx_OB_Read_Protection */
+
+ uint8_t USERConfig; /*!< USERConfig: Program the FLASH User Option Byte:
+ IWDG / STOP / STDBY / BOOT1 / VDDA_ANALOG / SRAM_PARITY
+ This parameter can be a combination of @ref FLASHEx_OB_IWatchdog, @ref FLASHEx_OB_nRST_STOP,
+ @ref FLASHEx_OB_nRST_STDBY, @ref FLASHEx_OB_BOOT1, @ref FLASHEx_OB_VDDA_Analog_Monitoring and
+ @ref FLASHEx_OB_RAM_Parity_Check_Enable */
+
+ uint32_t DATAAddress; /*!< DATAAddress: Address of the option byte DATA to be programmed
+ This parameter can be a value of @ref FLASHEx_OB_Data_Address */
+
+ uint8_t DATAData; /*!< DATAData: Data to be stored in the option byte DATA
+ This parameter must be a number between Min_Data = 0x00 and Max_Data = 0xFF */
+} FLASH_OBProgramInitTypeDef;
+/**
+ * @}
+ */
+
+/* Exported constants --------------------------------------------------------*/
+/** @defgroup FLASHEx_Exported_Constants FLASHEx Exported Constants
+ * @{
+ */
+
+/** @defgroup FLASHEx_Page_Size FLASHEx Page Size
+ * @{
+ */
+#if defined(STM32F030x6) || defined(STM32F030x8) || defined(STM32F031x6) || defined(STM32F038xx) \
+ || defined(STM32F051x8) || defined(STM32F042x6) || defined(STM32F048xx) || defined(STM32F058xx) || defined(STM32F070x6)
+#define FLASH_PAGE_SIZE 0x400U
+#endif /* STM32F030x6 || STM32F030x8 || STM32F031x6 || STM32F051x8 || STM32F042x6 || STM32F048xx || STM32F058xx || STM32F070x6 */
+
+#if defined(STM32F071xB) || defined(STM32F072xB) || defined(STM32F078xx) || defined(STM32F070xB) \
+ || defined(STM32F091xC) || defined(STM32F098xx) || defined(STM32F030xC)
+#define FLASH_PAGE_SIZE 0x800U
+#endif /* STM32F071xB || STM32F072xB || STM32F078xx || STM32F091xC || STM32F098xx || STM32F030xC */
+/**
+ * @}
+ */
+
+/** @defgroup FLASHEx_Type_Erase FLASH Type Erase
+ * @{
+ */
+#define FLASH_TYPEERASE_PAGES (0x00U) /*!© Copyright (c) 2016 STMicroelectronics.
+ * All rights reserved.
+ *
+ * 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 __STM32F0xx_HAL_GPIO_H
+#define __STM32F0xx_HAL_GPIO_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f0xx_hal_def.h"
+
+/** @addtogroup STM32F0xx_HAL_Driver
+ * @{
+ */
+
+/** @addtogroup GPIO
+ * @{
+ */
+
+/* Exported types ------------------------------------------------------------*/
+
+/** @defgroup GPIO_Exported_Types GPIO Exported Types
+ * @{
+ */
+/**
+ * @brief GPIO Init structure definition
+ */
+typedef struct
+{
+ uint32_t Pin; /*!< Specifies the GPIO pins to be configured.
+ This parameter can be any value of @ref GPIO_pins */
+
+ uint32_t Mode; /*!< Specifies the operating mode for the selected pins.
+ This parameter can be a value of @ref GPIO_mode */
+
+ uint32_t Pull; /*!< Specifies the Pull-up or Pull-Down activation for the selected pins.
+ This parameter can be a value of @ref GPIO_pull */
+
+ uint32_t Speed; /*!< Specifies the speed for the selected pins.
+ This parameter can be a value of @ref GPIO_speed */
+
+ uint32_t Alternate; /*!< Peripheral to be connected to the selected pins
+ This parameter can be a value of @ref GPIOEx_Alternate_function_selection */
+}GPIO_InitTypeDef;
+
+/**
+ * @brief GPIO Bit SET and Bit RESET enumeration
+ */
+typedef enum
+{
+ GPIO_PIN_RESET = 0U,
+ GPIO_PIN_SET
+}GPIO_PinState;
+/**
+ * @}
+ */
+
+/* Exported constants --------------------------------------------------------*/
+/** @defgroup GPIO_Exported_Constants GPIO Exported Constants
+ * @{
+ */
+/** @defgroup GPIO_pins GPIO pins
+ * @{
+ */
+#define GPIO_PIN_0 ((uint16_t)0x0001U) /* Pin 0 selected */
+#define GPIO_PIN_1 ((uint16_t)0x0002U) /* Pin 1 selected */
+#define GPIO_PIN_2 ((uint16_t)0x0004U) /* Pin 2 selected */
+#define GPIO_PIN_3 ((uint16_t)0x0008U) /* Pin 3 selected */
+#define GPIO_PIN_4 ((uint16_t)0x0010U) /* Pin 4 selected */
+#define GPIO_PIN_5 ((uint16_t)0x0020U) /* Pin 5 selected */
+#define GPIO_PIN_6 ((uint16_t)0x0040U) /* Pin 6 selected */
+#define GPIO_PIN_7 ((uint16_t)0x0080U) /* Pin 7 selected */
+#define GPIO_PIN_8 ((uint16_t)0x0100U) /* Pin 8 selected */
+#define GPIO_PIN_9 ((uint16_t)0x0200U) /* Pin 9 selected */
+#define GPIO_PIN_10 ((uint16_t)0x0400U) /* Pin 10 selected */
+#define GPIO_PIN_11 ((uint16_t)0x0800U) /* Pin 11 selected */
+#define GPIO_PIN_12 ((uint16_t)0x1000U) /* Pin 12 selected */
+#define GPIO_PIN_13 ((uint16_t)0x2000U) /* Pin 13 selected */
+#define GPIO_PIN_14 ((uint16_t)0x4000U) /* Pin 14 selected */
+#define GPIO_PIN_15 ((uint16_t)0x8000U) /* Pin 15 selected */
+#define GPIO_PIN_All ((uint16_t)0xFFFFU) /* All pins selected */
+
+#define GPIO_PIN_MASK (0x0000FFFFU) /* PIN mask for assert test */
+/**
+ * @}
+ */
+
+/** @defgroup GPIO_mode GPIO mode
+ * @brief GPIO Configuration Mode
+ * Elements values convention: 0x00WX00YZ
+ * - W : EXTI trigger detection on 3 bits
+ * - X : EXTI mode (IT or Event) on 2 bits
+ * - Y : Output type (Push Pull or Open Drain) on 1 bit
+ * - Z : GPIO mode (Input, Output, Alternate or Analog) on 2 bits
+ * @{
+ */
+#define GPIO_MODE_INPUT MODE_INPUT /*!< Input Floating Mode */
+#define GPIO_MODE_OUTPUT_PP (MODE_OUTPUT | OUTPUT_PP) /*!< Output Push Pull Mode */
+#define GPIO_MODE_OUTPUT_OD (MODE_OUTPUT | OUTPUT_OD) /*!< Output Open Drain Mode */
+#define GPIO_MODE_AF_PP (MODE_AF | OUTPUT_PP) /*!< Alternate Function Push Pull Mode */
+#define GPIO_MODE_AF_OD (MODE_AF | OUTPUT_OD) /*!< Alternate Function Open Drain Mode */
+
+#define GPIO_MODE_ANALOG MODE_ANALOG /*!< Analog Mode */
+
+#define GPIO_MODE_IT_RISING (MODE_INPUT | EXTI_IT | TRIGGER_RISING) /*!< External Interrupt Mode with Rising edge trigger detection */
+#define GPIO_MODE_IT_FALLING (MODE_INPUT | EXTI_IT | TRIGGER_FALLING) /*!< External Interrupt Mode with Falling edge trigger detection */
+#define GPIO_MODE_IT_RISING_FALLING (MODE_INPUT | EXTI_IT | TRIGGER_RISING | TRIGGER_FALLING) /*!< External Interrupt Mode with Rising/Falling edge trigger detection */
+
+#define GPIO_MODE_EVT_RISING (MODE_INPUT | EXTI_EVT | TRIGGER_RISING) /*!< External Event Mode with Rising edge trigger detection */
+#define GPIO_MODE_EVT_FALLING (MODE_INPUT | EXTI_EVT | TRIGGER_FALLING) /*!< External Event Mode with Falling edge trigger detection */
+#define GPIO_MODE_EVT_RISING_FALLING (MODE_INPUT | EXTI_EVT | TRIGGER_RISING | TRIGGER_FALLING) /*!< External Event Mode with Rising/Falling edge trigger detection *//**
+ * @}
+ */
+
+/** @defgroup GPIO_speed GPIO speed
+ * @brief GPIO Output Maximum frequency
+ * @{
+ */
+#define GPIO_SPEED_FREQ_LOW (0x00000000U) /*!< range up to 2 MHz, please refer to the product datasheet */
+#define GPIO_SPEED_FREQ_MEDIUM (0x00000001U) /*!< range 4 MHz to 10 MHz, please refer to the product datasheet */
+#define GPIO_SPEED_FREQ_HIGH (0x00000003U) /*!< range 10 MHz to 50 MHz, please refer to the product datasheet */
+/**
+ * @}
+ */
+
+ /** @defgroup GPIO_pull GPIO pull
+ * @brief GPIO Pull-Up or Pull-Down Activation
+ * @{
+ */
+#define GPIO_NOPULL (0x00000000U) /*!< No Pull-up or Pull-down activation */
+#define GPIO_PULLUP (0x00000001U) /*!< Pull-up activation */
+#define GPIO_PULLDOWN (0x00000002U) /*!< Pull-down activation */
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/* Exported macro ------------------------------------------------------------*/
+/** @defgroup GPIO_Exported_Macros GPIO Exported Macros
+ * @{
+ */
+
+/**
+ * @brief Check whether the specified EXTI line flag is set or not.
+ * @param __EXTI_LINE__ specifies the EXTI line flag to check.
+ * This parameter can be GPIO_PIN_x where x can be(0..15)
+ * @retval The new state of __EXTI_LINE__ (SET or RESET).
+ */
+#define __HAL_GPIO_EXTI_GET_FLAG(__EXTI_LINE__) (EXTI->PR & (__EXTI_LINE__))
+
+/**
+ * @brief Clear the EXTI's line pending flags.
+ * @param __EXTI_LINE__ specifies the EXTI lines flags to clear.
+ * This parameter can be any combination of GPIO_PIN_x where x can be (0..15)
+ * @retval None
+ */
+#define __HAL_GPIO_EXTI_CLEAR_FLAG(__EXTI_LINE__) (EXTI->PR = (__EXTI_LINE__))
+
+/**
+ * @brief Check whether the specified EXTI line is asserted or not.
+ * @param __EXTI_LINE__ specifies the EXTI line to check.
+ * This parameter can be GPIO_PIN_x where x can be(0..15)
+ * @retval The new state of __EXTI_LINE__ (SET or RESET).
+ */
+#define __HAL_GPIO_EXTI_GET_IT(__EXTI_LINE__) (EXTI->PR & (__EXTI_LINE__))
+
+/**
+ * @brief Clear the EXTI's line pending bits.
+ * @param __EXTI_LINE__ specifies the EXTI lines to clear.
+ * This parameter can be any combination of GPIO_PIN_x where x can be (0..15)
+ * @retval None
+ */
+#define __HAL_GPIO_EXTI_CLEAR_IT(__EXTI_LINE__) (EXTI->PR = (__EXTI_LINE__))
+
+/**
+ * @brief Generate a Software interrupt on selected EXTI line.
+ * @param __EXTI_LINE__ specifies the EXTI line to check.
+ * This parameter can be GPIO_PIN_x where x can be(0..15)
+ * @retval None
+ */
+#define __HAL_GPIO_EXTI_GENERATE_SWIT(__EXTI_LINE__) (EXTI->SWIER |= (__EXTI_LINE__))
+
+/**
+ * @}
+ */
+
+/* Private macros ------------------------------------------------------------*/
+/** @defgroup GPIO_Private_Constants GPIO Private Constants
+ * @{
+ */
+#define GPIO_MODE_Pos 0U
+#define GPIO_MODE (0x3UL << GPIO_MODE_Pos)
+#define MODE_INPUT (0x0UL << GPIO_MODE_Pos)
+#define MODE_OUTPUT (0x1UL << GPIO_MODE_Pos)
+#define MODE_AF (0x2UL << GPIO_MODE_Pos)
+#define MODE_ANALOG (0x3UL << GPIO_MODE_Pos)
+#define OUTPUT_TYPE_Pos 4U
+#define OUTPUT_TYPE (0x1UL << OUTPUT_TYPE_Pos)
+#define OUTPUT_PP (0x0UL << OUTPUT_TYPE_Pos)
+#define OUTPUT_OD (0x1UL << OUTPUT_TYPE_Pos)
+#define EXTI_MODE_Pos 16U
+#define EXTI_MODE (0x3UL << EXTI_MODE_Pos)
+#define EXTI_IT (0x1UL << EXTI_MODE_Pos)
+#define EXTI_EVT (0x2UL << EXTI_MODE_Pos)
+#define TRIGGER_MODE_Pos 20U
+#define TRIGGER_MODE (0x7UL << TRIGGER_MODE_Pos)
+#define TRIGGER_RISING (0x1UL << TRIGGER_MODE_Pos)
+#define TRIGGER_FALLING (0x2UL << TRIGGER_MODE_Pos)
+/**
+ * @}
+ */
+
+/** @addtogroup GPIO_Private_Macros GPIO Private Macros
+ * @{
+ */
+#define IS_GPIO_PIN_ACTION(ACTION) (((ACTION) == GPIO_PIN_RESET) || ((ACTION) == GPIO_PIN_SET))
+
+#define IS_GPIO_PIN(__PIN__) (((((uint32_t)__PIN__) & GPIO_PIN_MASK) != 0x00U) &&\
+ ((((uint32_t)__PIN__) & ~GPIO_PIN_MASK) == 0x00U))
+
+#define IS_GPIO_MODE(__MODE__) (((__MODE__) == GPIO_MODE_INPUT) ||\
+ ((__MODE__) == GPIO_MODE_OUTPUT_PP) ||\
+ ((__MODE__) == GPIO_MODE_OUTPUT_OD) ||\
+ ((__MODE__) == GPIO_MODE_AF_PP) ||\
+ ((__MODE__) == GPIO_MODE_AF_OD) ||\
+ ((__MODE__) == GPIO_MODE_IT_RISING) ||\
+ ((__MODE__) == GPIO_MODE_IT_FALLING) ||\
+ ((__MODE__) == GPIO_MODE_IT_RISING_FALLING) ||\
+ ((__MODE__) == GPIO_MODE_EVT_RISING) ||\
+ ((__MODE__) == GPIO_MODE_EVT_FALLING) ||\
+ ((__MODE__) == GPIO_MODE_EVT_RISING_FALLING) ||\
+ ((__MODE__) == GPIO_MODE_ANALOG))
+
+#define IS_GPIO_SPEED(__SPEED__) (((__SPEED__) == GPIO_SPEED_FREQ_LOW) ||\
+ ((__SPEED__) == GPIO_SPEED_FREQ_MEDIUM) ||\
+ ((__SPEED__) == GPIO_SPEED_FREQ_HIGH))
+
+#define IS_GPIO_PULL(__PULL__) (((__PULL__) == GPIO_NOPULL) ||\
+ ((__PULL__) == GPIO_PULLUP) || \
+ ((__PULL__) == GPIO_PULLDOWN))
+/**
+ * @}
+ */
+
+/* Include GPIO HAL Extended module */
+#include "stm32f0xx_hal_gpio_ex.h"
+
+/* Exported functions --------------------------------------------------------*/
+/** @addtogroup GPIO_Exported_Functions GPIO Exported Functions
+ * @{
+ */
+
+/** @addtogroup GPIO_Exported_Functions_Group1 Initialization/de-initialization functions
+ * @brief Initialization and Configuration functions
+ * @{
+ */
+
+/* Initialization and de-initialization functions *****************************/
+void HAL_GPIO_Init(GPIO_TypeDef *GPIOx, GPIO_InitTypeDef *GPIO_Init);
+void HAL_GPIO_DeInit(GPIO_TypeDef *GPIOx, uint32_t GPIO_Pin);
+
+/**
+ * @}
+ */
+
+/** @addtogroup GPIO_Exported_Functions_Group2 IO operation functions
+ * @{
+ */
+
+/* IO operation functions *****************************************************/
+GPIO_PinState HAL_GPIO_ReadPin(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin);
+void HAL_GPIO_WritePin(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin, GPIO_PinState PinState);
+void HAL_GPIO_TogglePin(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin);
+HAL_StatusTypeDef HAL_GPIO_LockPin(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin);
+void HAL_GPIO_EXTI_IRQHandler(uint16_t GPIO_Pin);
+void HAL_GPIO_EXTI_Callback(uint16_t GPIO_Pin);
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __STM32F0xx_HAL_GPIO_H */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal_gpio_ex.h b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal_gpio_ex.h
new file mode 100644
index 0000000..3a6d604
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal_gpio_ex.h
@@ -0,0 +1,800 @@
+/**
+ ******************************************************************************
+ * @file stm32f0xx_hal_gpio_ex.h
+ * @author MCD Application Team
+ * @brief Header file of GPIO HAL Extension module.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2016 STMicroelectronics.
+ * All rights reserved.
+ *
+ * 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 __STM32F0xx_HAL_GPIO_EX_H
+#define __STM32F0xx_HAL_GPIO_EX_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f0xx_hal_def.h"
+
+/** @addtogroup STM32F0xx_HAL_Driver
+ * @{
+ */
+
+/** @defgroup GPIOEx GPIOEx
+ * @{
+ */
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/** @defgroup GPIOEx_Exported_Constants GPIOEx Exported Constants
+ * @{
+ */
+
+/** @defgroup GPIOEx_Alternate_function_selection GPIOEx Alternate function selection
+ * @{
+ */
+
+#if defined (STM32F030x6)
+/*------------------------- STM32F030x6---------------------------*/
+/* AF 0 */
+#define GPIO_AF0_EVENTOUT ((uint8_t)0x00U) /*!< AF0: EVENTOUT Alternate Function mapping */
+#define GPIO_AF0_MCO ((uint8_t)0x00U) /*!< AF0: MCO Alternate Function mapping */
+#define GPIO_AF0_SPI1 ((uint8_t)0x00U) /*!< AF0: SPI1 Alternate Function mapping */
+#define GPIO_AF0_TIM17 ((uint8_t)0x00U) /*!< AF0: TIM17 Alternate Function mapping */
+#define GPIO_AF0_SWDIO ((uint8_t)0x00U) /*!< AF0: SWDIO Alternate Function mapping */
+#define GPIO_AF0_SWCLK ((uint8_t)0x00U) /*!< AF0: SWCLK Alternate Function mapping */
+#define GPIO_AF0_TIM14 ((uint8_t)0x00U) /*!< AF0: TIM14 Alternate Function mapping */
+#define GPIO_AF0_USART1 ((uint8_t)0x00U) /*!< AF0: USART1 Alternate Function mapping */
+#define GPIO_AF0_IR ((uint8_t)0x00U) /*!< AF0: IR Alternate Function mapping */
+#define GPIO_AF0_TIM3 ((uint8_t)0x00U) /*!< AF0: TIM3 Alternate Function mapping */
+
+/* AF 1 */
+#define GPIO_AF1_TIM3 ((uint8_t)0x01U) /*!< AF1: TIM3 Alternate Function mapping */
+#define GPIO_AF1_USART1 ((uint8_t)0x01U) /*!< AF1: USART1 Alternate Function mapping */
+#define GPIO_AF1_EVENTOUT ((uint8_t)0x01U) /*!< AF1: EVENTOUT Alternate Function mapping */
+#define GPIO_AF1_I2C1 ((uint8_t)0x01U) /*!< AF1: I2C1 Alternate Function mapping */
+#define GPIO_AF1_IR ((uint8_t)0x01U) /*!< AF1: IR Alternate Function mapping */
+
+/* AF 2 */
+#define GPIO_AF2_TIM1 ((uint8_t)0x02U) /*!< AF2: TIM1 Alternate Function mapping */
+#define GPIO_AF2_TIM16 ((uint8_t)0x02U) /*!< AF2: TIM16 Alternate Function mapping */
+#define GPIO_AF2_TIM17 ((uint8_t)0x02U) /*!< AF2: TIM17 Alternate Function mapping */
+#define GPIO_AF2_EVENTOUT ((uint8_t)0x02U) /*!< AF2: EVENTOUT Alternate Function mapping */
+
+/* AF 3 */
+#define GPIO_AF3_EVENTOUT ((uint8_t)0x03U) /*!< AF3: EVENTOUT Alternate Function mapping */
+#define GPIO_AF3_I2C1 ((uint8_t)0x03U) /*!< AF3: I2C1 Alternate Function mapping */
+
+/* AF 4 */
+#define GPIO_AF4_TIM14 ((uint8_t)0x04U) /*!< AF4: TIM14 Alternate Function mapping */
+#define GPIO_AF4_I2C1 ((uint8_t)0x04U) /*!< AF4: I2C1 Alternate Function mapping */
+
+/* AF 5 */
+#define GPIO_AF5_TIM16 ((uint8_t)0x05U) /*!< AF5: TIM16 Alternate Function mapping */
+#define GPIO_AF5_TIM17 ((uint8_t)0x05U) /*!< AF5: TIM17 Alternate Function mapping */
+
+/* AF 6 */
+#define GPIO_AF6_EVENTOUT ((uint8_t)0x06U) /*!< AF6: EVENTOUT Alternate Function mapping */
+
+#define IS_GPIO_AF(AF) ((AF) <= (uint8_t)0x06U)
+
+#endif /* STM32F030x6 */
+
+/*---------------------------------- STM32F030x8 -------------------------------------------*/
+#if defined (STM32F030x8)
+/* AF 0 */
+#define GPIO_AF0_EVENTOUT ((uint8_t)0x00U) /*!< AF0: EVENTOUT Alternate Function mapping */
+#define GPIO_AF0_MCO ((uint8_t)0x00U) /*!< AF0: MCO Alternate Function mapping */
+#define GPIO_AF0_SPI1 ((uint8_t)0x00U) /*!< AF0: SPI1 Alternate Function mapping */
+#define GPIO_AF0_SPI2 ((uint8_t)0x00U) /*!< AF0: SPI2 Alternate Function mapping */
+#define GPIO_AF0_TIM15 ((uint8_t)0x00U) /*!< AF0: TIM15 Alternate Function mapping */
+#define GPIO_AF0_TIM17 ((uint8_t)0x00U) /*!< AF0: TIM17 Alternate Function mapping */
+#define GPIO_AF0_SWDIO ((uint8_t)0x00U) /*!< AF0: SWDIO Alternate Function mapping */
+#define GPIO_AF0_SWCLK ((uint8_t)0x00U) /*!< AF0: SWCLK Alternate Function mapping */
+#define GPIO_AF0_TIM14 ((uint8_t)0x00U) /*!< AF0: TIM14 Alternate Function mapping */
+#define GPIO_AF0_USART1 ((uint8_t)0x00U) /*!< AF0: USART1 Alternate Function mapping */
+#define GPIO_AF0_IR ((uint8_t)0x00U) /*!< AF0: IR Alternate Function mapping */
+#define GPIO_AF0_TIM3 ((uint8_t)0x00U) /*!< AF0: TIM3 Alternate Function mapping */
+
+/* AF 1 */
+#define GPIO_AF1_TIM3 ((uint8_t)0x01U) /*!< AF1: TIM3 Alternate Function mapping */
+#define GPIO_AF1_TIM15 ((uint8_t)0x01U) /*!< AF1: TIM15 Alternate Function mapping */
+#define GPIO_AF1_USART1 ((uint8_t)0x01U) /*!< AF1: USART1 Alternate Function mapping */
+#define GPIO_AF1_USART2 ((uint8_t)0x01U) /*!< AF1: USART2 Alternate Function mapping */
+#define GPIO_AF1_EVENTOUT ((uint8_t)0x01U) /*!< AF1: EVENTOUT Alternate Function mapping */
+#define GPIO_AF1_I2C1 ((uint8_t)0x01U) /*!< AF1: I2C1 Alternate Function mapping */
+#define GPIO_AF1_I2C2 ((uint8_t)0x01U) /*!< AF1: I2C2 Alternate Function mapping */
+#define GPIO_AF1_IR ((uint8_t)0x01U) /*!< AF1: IR Alternate Function mapping */
+
+/* AF 2 */
+#define GPIO_AF2_TIM1 ((uint8_t)0x02U) /*!< AF2: TIM1 Alternate Function mapping */
+#define GPIO_AF2_TIM16 ((uint8_t)0x02U) /*!< AF2: TIM16 Alternate Function mapping */
+#define GPIO_AF2_TIM17 ((uint8_t)0x02U) /*!< AF2: TIM17 Alternate Function mapping */
+#define GPIO_AF2_EVENTOUT ((uint8_t)0x02U) /*!< AF2: EVENTOUT Alternate Function mapping */
+
+/* AF 3 */
+#define GPIO_AF3_EVENTOUT ((uint8_t)0x03U) /*!< AF3: EVENTOUT Alternate Function mapping */
+#define GPIO_AF3_I2C1 ((uint8_t)0x03U) /*!< AF3: I2C1 Alternate Function mapping */
+#define GPIO_AF3_TIM15 ((uint8_t)0x03U) /*!< AF3: TIM15 Alternate Function mapping */
+
+/* AF 4 */
+#define GPIO_AF4_TIM14 ((uint8_t)0x04U) /*!< AF4: TIM14 Alternate Function mapping */
+
+/* AF 5 */
+#define GPIO_AF5_TIM16 ((uint8_t)0x05U) /*!< AF5: TIM16 Alternate Function mapping */
+#define GPIO_AF5_TIM17 ((uint8_t)0x05U) /*!< AF5: TIM17 Alternate Function mapping */
+
+/* AF 6 */
+#define GPIO_AF6_EVENTOUT ((uint8_t)0x06U) /*!< AF6: EVENTOUT Alternate Function mapping */
+
+#define IS_GPIO_AF(AF) ((AF) <= (uint8_t)0x06U)
+
+#endif /* STM32F030x8 */
+
+#if defined (STM32F031x6) || defined (STM32F038xx)
+/*--------------------------- STM32F031x6/STM32F038xx ---------------------------*/
+/* AF 0 */
+#define GPIO_AF0_EVENTOUT ((uint8_t)0x00U) /*!< AF0: EVENTOUT Alternate Function mapping */
+#define GPIO_AF0_MCO ((uint8_t)0x00U) /*!< AF0: MCO Alternate Function mapping */
+#define GPIO_AF0_SPI1 ((uint8_t)0x00U) /*!< AF0: SPI1/I2S1 Alternate Function mapping */
+#define GPIO_AF0_TIM17 ((uint8_t)0x00U) /*!< AF0: TIM17 Alternate Function mapping */
+#define GPIO_AF0_SWDAT ((uint8_t)0x00U) /*!< AF0: SWDAT Alternate Function mapping */
+#define GPIO_AF0_SWCLK ((uint8_t)0x00U) /*!< AF0: SWCLK Alternate Function mapping */
+#define GPIO_AF0_TIM14 ((uint8_t)0x00U) /*!< AF0: TIM14 Alternate Function mapping */
+#define GPIO_AF0_USART1 ((uint8_t)0x00U) /*!< AF0: USART1 Alternate Function mapping */
+#define GPIO_AF0_IR ((uint8_t)0x00U) /*!< AF0: IR Alternate Function mapping */
+
+/* AF 1 */
+#define GPIO_AF1_TIM3 ((uint8_t)0x01U) /*!< AF1: TIM3 Alternate Function mapping */
+#define GPIO_AF1_USART1 ((uint8_t)0x01U) /*!< AF1: USART1 Alternate Function mapping */
+#define GPIO_AF1_IR ((uint8_t)0x01U) /*!< AF1: IR Alternate Function mapping */
+#define GPIO_AF1_EVENTOUT ((uint8_t)0x01U) /*!< AF1: EVENTOUT Alternate Function mapping */
+#define GPIO_AF1_I2C1 ((uint8_t)0x01U) /*!< AF1: I2C1 Alternate Function mapping */
+
+/* AF 2 */
+#define GPIO_AF2_TIM1 ((uint8_t)0x02U) /*!< AF2: TIM1 Alternate Function mapping */
+#define GPIO_AF2_TIM2 ((uint8_t)0x02U) /*!< AF2: TIM2 Alternate Function mapping */
+#define GPIO_AF2_TIM16 ((uint8_t)0x02U) /*!< AF2: TIM16 Alternate Function mapping */
+#define GPIO_AF2_TIM17 ((uint8_t)0x02U) /*!< AF2: TIM17 Alternate Function mapping */
+#define GPIO_AF2_EVENTOUT ((uint8_t)0x02U) /*!< AF2: EVENTOUT Alternate Function mapping */
+
+/* AF 3 */
+#define GPIO_AF3_EVENTOUT ((uint8_t)0x03U) /*!< AF3: EVENTOUT Alternate Function mapping */
+#define GPIO_AF3_I2C1 ((uint8_t)0x03U) /*!< AF3: I2C1 Alternate Function mapping */
+
+/* AF 4 */
+#define GPIO_AF4_TIM14 ((uint8_t)0x04U) /*!< AF4: TIM14 Alternate Function mapping */
+#define GPIO_AF4_I2C1 ((uint8_t)0x04U) /*!< AF4: I2C1 Alternate Function mapping */
+
+/* AF 5 */
+#define GPIO_AF5_TIM16 ((uint8_t)0x05U) /*!< AF5: TIM16 Alternate Function mapping */
+#define GPIO_AF5_TIM17 ((uint8_t)0x05U) /*!< AF5: TIM17 Alternate Function mapping */
+
+/* AF 6 */
+#define GPIO_AF6_EVENTOUT ((uint8_t)0x06U) /*!< AF6: EVENTOUT Alternate Function mapping */
+
+#define IS_GPIO_AF(AF) ((AF) <= (uint8_t)0x06U)
+
+#endif /* STM32F031x6 || STM32F038xx */
+
+#if defined (STM32F051x8) || defined (STM32F058xx)
+/*--------------------------- STM32F051x8/STM32F058xx---------------------------*/
+/* AF 0 */
+#define GPIO_AF0_EVENTOUT ((uint8_t)0x00U) /*!< AF0: EVENTOUT Alternate Function mapping */
+#define GPIO_AF0_MCO ((uint8_t)0x00U) /*!< AF0: MCO Alternate Function mapping */
+#define GPIO_AF0_SPI1 ((uint8_t)0x00U) /*!< AF0: SPI1/I2S1 Alternate Function mapping */
+#define GPIO_AF0_SPI2 ((uint8_t)0x00U) /*!< AF0: SPI2 Alternate Function mapping */
+#define GPIO_AF0_TIM15 ((uint8_t)0x00U) /*!< AF0: TIM15 Alternate Function mapping */
+#define GPIO_AF0_TIM17 ((uint8_t)0x00U) /*!< AF0: TIM17 Alternate Function mapping */
+#define GPIO_AF0_SWDIO ((uint8_t)0x00U) /*!< AF0: SWDIO Alternate Function mapping */
+#define GPIO_AF0_SWCLK ((uint8_t)0x00U) /*!< AF0: SWCLK Alternate Function mapping */
+#define GPIO_AF0_TIM14 ((uint8_t)0x00U) /*!< AF0: TIM14 Alternate Function mapping */
+#define GPIO_AF0_USART1 ((uint8_t)0x00U) /*!< AF0: USART1 Alternate Function mapping */
+#define GPIO_AF0_IR ((uint8_t)0x00U) /*!< AF0: IR Alternate Function mapping */
+#define GPIO_AF0_CEC ((uint8_t)0x00U) /*!< AF0: CEC Alternate Function mapping */
+
+/* AF 1 */
+#define GPIO_AF1_TIM3 ((uint8_t)0x01U) /*!< AF1: TIM3 Alternate Function mapping */
+#define GPIO_AF1_TIM15 ((uint8_t)0x01U) /*!< AF1: TIM15 Alternate Function mapping */
+#define GPIO_AF1_USART1 ((uint8_t)0x01U) /*!< AF1: USART1 Alternate Function mapping */
+#define GPIO_AF1_USART2 ((uint8_t)0x01U) /*!< AF1: USART2 Alternate Function mapping */
+#define GPIO_AF1_EVENTOUT ((uint8_t)0x01U) /*!< AF1: EVENTOUT Alternate Function mapping */
+#define GPIO_AF1_I2C1 ((uint8_t)0x01U) /*!< AF1: I2C1 Alternate Function mapping */
+#define GPIO_AF1_I2C2 ((uint8_t)0x01U) /*!< AF1: I2C2 Alternate Function mapping */
+#define GPIO_AF1_IR ((uint8_t)0x01U) /*!< AF1: IR Alternate Function mapping */
+#define GPIO_AF1_CEC ((uint8_t)0x01U) /*!< AF1: CEC Alternate Function mapping */
+
+/* AF 2 */
+#define GPIO_AF2_TIM1 ((uint8_t)0x02U) /*!< AF2: TIM1 Alternate Function mapping */
+#define GPIO_AF2_TIM2 ((uint8_t)0x02U) /*!< AF2: TIM2 Alternate Function mapping */
+#define GPIO_AF2_TIM16 ((uint8_t)0x02U) /*!< AF2: TIM16 Alternate Function mapping */
+#define GPIO_AF2_TIM17 ((uint8_t)0x02U) /*!< AF2: TIM17 Alternate Function mapping */
+#define GPIO_AF2_EVENTOUT ((uint8_t)0x02U) /*!< AF2: EVENTOUT Alternate Function mapping */
+
+/* AF 3 */
+#define GPIO_AF3_EVENTOUT ((uint8_t)0x03U) /*!< AF3: EVENTOUT Alternate Function mapping */
+#define GPIO_AF3_I2C1 ((uint8_t)0x03U) /*!< AF3: I2C1 Alternate Function mapping */
+#define GPIO_AF3_TIM15 ((uint8_t)0x03U) /*!< AF3: TIM15 Alternate Function mapping */
+#define GPIO_AF3_TSC ((uint8_t)0x03U) /*!< AF3: TSC Alternate Function mapping */
+
+/* AF 4 */
+#define GPIO_AF4_TIM14 ((uint8_t)0x04U) /*!< AF4: TIM14 Alternate Function mapping */
+
+/* AF 5 */
+#define GPIO_AF5_TIM16 ((uint8_t)0x05U) /*!< AF5: TIM16 Alternate Function mapping */
+#define GPIO_AF5_TIM17 ((uint8_t)0x05U) /*!< AF5: TIM17 Alternate Function mapping */
+
+/* AF 6 */
+#define GPIO_AF6_EVENTOUT ((uint8_t)0x06U) /*!< AF6: EVENTOUT Alternate Function mapping */
+
+/* AF 7 */
+#define GPIO_AF7_COMP1 ((uint8_t)0x07U) /*!< AF7: COMP1 Alternate Function mapping */
+#define GPIO_AF7_COMP2 ((uint8_t)0x07U) /*!< AF7: COMP2 Alternate Function mapping */
+
+#define IS_GPIO_AF(AF) ((AF) <= (uint8_t)0x07U)
+
+#endif /* STM32F051x8/STM32F058xx */
+
+#if defined (STM32F071xB)
+/*--------------------------- STM32F071xB ---------------------------*/
+/* AF 0 */
+#define GPIO_AF0_EVENTOUT ((uint8_t)0x00U) /*!< AF0: AEVENTOUT Alternate Function mapping */
+#define GPIO_AF0_SWDIO ((uint8_t)0x00U) /*!< AF0: SWDIO Alternate Function mapping */
+#define GPIO_AF0_SWCLK ((uint8_t)0x00U) /*!< AF0: SWCLK Alternate Function mapping */
+#define GPIO_AF0_MCO ((uint8_t)0x00U) /*!< AF0: MCO Alternate Function mapping */
+#define GPIO_AF0_CEC ((uint8_t)0x00U) /*!< AF0: CEC Alternate Function mapping */
+#define GPIO_AF0_CRS ((uint8_t)0x00U) /*!< AF0: CRS Alternate Function mapping */
+#define GPIO_AF0_IR ((uint8_t)0x00U) /*!< AF0: IR Alternate Function mapping */
+#define GPIO_AF0_SPI1 ((uint8_t)0x00U) /*!< AF0: SPI1/I2S1 Alternate Function mapping */
+#define GPIO_AF0_SPI2 ((uint8_t)0x00U) /*!< AF0: SPI2/I2S2 Alternate Function mapping */
+#define GPIO_AF0_TIM1 ((uint8_t)0x00U) /*!< AF0: TIM1 Alternate Function mapping */
+#define GPIO_AF0_TIM3 ((uint8_t)0x00U) /*!< AF0: TIM3 Alternate Function mapping */
+#define GPIO_AF0_TIM14 ((uint8_t)0x00U) /*!< AF0: TIM14 Alternate Function mapping */
+#define GPIO_AF0_TIM15 ((uint8_t)0x00U) /*!< AF0: TIM15 Alternate Function mapping */
+#define GPIO_AF0_TIM16 ((uint8_t)0x00U) /*!< AF0: TIM16 Alternate Function mapping */
+#define GPIO_AF0_TIM17 ((uint8_t)0x00U) /*!< AF0: TIM17 Alternate Function mapping */
+#define GPIO_AF0_TSC ((uint8_t)0x00U) /*!< AF0: TSC Alternate Function mapping */
+#define GPIO_AF0_USART1 ((uint8_t)0x00U) /*!< AF0: USART1 Alternate Function mapping */
+#define GPIO_AF0_USART2 ((uint8_t)0x00U) /*!< AF0: USART2 Alternate Function mapping */
+#define GPIO_AF0_USART3 ((uint8_t)0x00U) /*!< AF0: USART3 Alternate Function mapping */
+#define GPIO_AF0_USART4 ((uint8_t)0x00U) /*!< AF0: USART4 Alternate Function mapping */
+
+/* AF 1 */
+#define GPIO_AF1_TIM3 ((uint8_t)0x01U) /*!< AF1: TIM3 Alternate Function mapping */
+#define GPIO_AF1_TIM15 ((uint8_t)0x01U) /*!< AF1: TIM15 Alternate Function mapping */
+#define GPIO_AF1_USART1 ((uint8_t)0x01U) /*!< AF1: USART1 Alternate Function mapping */
+#define GPIO_AF1_USART2 ((uint8_t)0x01U) /*!< AF1: USART2 Alternate Function mapping */
+#define GPIO_AF1_USART3 ((uint8_t)0x01U) /*!< AF1: USART3 Alternate Function mapping */
+#define GPIO_AF1_IR ((uint8_t)0x01U) /*!< AF1: IR Alternate Function mapping */
+#define GPIO_AF1_CEC ((uint8_t)0x01U) /*!< AF1: CEC Alternate Function mapping */
+#define GPIO_AF1_EVENTOUT ((uint8_t)0x01U) /*!< AF1: EVENTOUT Alternate Function mapping */
+#define GPIO_AF1_I2C1 ((uint8_t)0x01U) /*!< AF1: I2C1 Alternate Function mapping */
+#define GPIO_AF1_I2C2 ((uint8_t)0x01U) /*!< AF1: I2C2 Alternate Function mapping */
+#define GPIO_AF1_TSC ((uint8_t)0x01U) /*!< AF1: TSC Alternate Function mapping */
+#define GPIO_AF1_SPI1 ((uint8_t)0x01U) /*!< AF1: SPI1 Alternate Function mapping */
+#define GPIO_AF1_SPI2 ((uint8_t)0x01U) /*!< AF1: SPI2 Alternate Function mapping */
+
+/* AF 2 */
+#define GPIO_AF2_TIM1 ((uint8_t)0x02U) /*!< AF2: TIM1 Alternate Function mapping */
+#define GPIO_AF2_TIM2 ((uint8_t)0x02U) /*!< AF2: TIM2 Alternate Function mapping */
+#define GPIO_AF2_TIM16 ((uint8_t)0x02U) /*!< AF2: TIM16 Alternate Function mapping */
+#define GPIO_AF2_TIM17 ((uint8_t)0x02U) /*!< AF2: TIM17 Alternate Function mapping */
+#define GPIO_AF2_EVENTOUT ((uint8_t)0x02U) /*!< AF2: EVENTOUT Alternate Function mapping */
+
+/* AF 3 */
+#define GPIO_AF3_EVENTOUT ((uint8_t)0x03U) /*!< AF3: EVENTOUT Alternate Function mapping */
+#define GPIO_AF3_TSC ((uint8_t)0x03U) /*!< AF3: TSC Alternate Function mapping */
+#define GPIO_AF3_TIM15 ((uint8_t)0x03U) /*!< AF3: TIM15 Alternate Function mapping */
+#define GPIO_AF3_I2C1 ((uint8_t)0x03U) /*!< AF3: I2C1 Alternate Function mapping */
+
+/* AF 4 */
+#define GPIO_AF4_TIM14 ((uint8_t)0x04U) /*!< AF4: TIM14 Alternate Function mapping */
+#define GPIO_AF4_USART4 ((uint8_t)0x04U) /*!< AF4: USART4 Alternate Function mapping */
+#define GPIO_AF4_USART3 ((uint8_t)0x04U) /*!< AF4: USART3 Alternate Function mapping */
+#define GPIO_AF4_CRS ((uint8_t)0x04U) /*!< AF4: CRS Alternate Function mapping */
+
+/* AF 5 */
+#define GPIO_AF5_TIM15 ((uint8_t)0x05U) /*!< AF5: TIM15 Alternate Function mapping */
+#define GPIO_AF5_TIM16 ((uint8_t)0x05U) /*!< AF5: TIM16 Alternate Function mapping */
+#define GPIO_AF5_TIM17 ((uint8_t)0x05U) /*!< AF5: TIM17 Alternate Function mapping */
+#define GPIO_AF5_SPI2 ((uint8_t)0x05U) /*!< AF5: SPI2 Alternate Function mapping */
+#define GPIO_AF5_I2C2 ((uint8_t)0x05U) /*!< AF5: I2C2 Alternate Function mapping */
+
+/* AF 6 */
+#define GPIO_AF6_EVENTOUT ((uint8_t)0x06U) /*!< AF6: EVENTOUT Alternate Function mapping */
+
+/* AF 7 */
+#define GPIO_AF7_COMP1 ((uint8_t)0x07U) /*!< AF7: COMP1 Alternate Function mapping */
+#define GPIO_AF7_COMP2 ((uint8_t)0x07U) /*!< AF7: COMP2 Alternate Function mapping */
+
+#define IS_GPIO_AF(AF) ((AF) <= (uint8_t)0x07U)
+
+#endif /* STM32F071xB */
+
+
+#if defined(STM32F091xC) || defined(STM32F098xx)
+/*--------------------------- STM32F091xC || STM32F098xx ------------------------------*/
+/* AF 0 */
+#define GPIO_AF0_EVENTOUT ((uint8_t)0x00U) /*!< AF0: EVENTOUT Alternate Function mapping */
+#define GPIO_AF0_SWDIO ((uint8_t)0x00U) /*!< AF0: SWDIO Alternate Function mapping */
+#define GPIO_AF0_SWCLK ((uint8_t)0x00U) /*!< AF0: SWCLK Alternate Function mapping */
+#define GPIO_AF0_MCO ((uint8_t)0x00U) /*!< AF0: MCO Alternate Function mapping */
+#define GPIO_AF0_CEC ((uint8_t)0x00U) /*!< AF0: CEC Alternate Function mapping */
+#define GPIO_AF0_CRS ((uint8_t)0x00U) /*!< AF0: CRS Alternate Function mapping */
+#define GPIO_AF0_IR ((uint8_t)0x00U) /*!< AF0: IR Alternate Function mapping */
+#define GPIO_AF0_SPI1 ((uint8_t)0x00U) /*!< AF0: SPI1/I2S1 Alternate Function mapping */
+#define GPIO_AF0_SPI2 ((uint8_t)0x00U) /*!< AF0: SPI2/I2S2 Alternate Function mapping */
+#define GPIO_AF0_TIM1 ((uint8_t)0x00U) /*!< AF0: TIM1 Alternate Function mapping */
+#define GPIO_AF0_TIM3 ((uint8_t)0x00U) /*!< AF0: TIM3 Alternate Function mapping */
+#define GPIO_AF0_TIM14 ((uint8_t)0x00U) /*!< AF0: TIM14 Alternate Function mapping */
+#define GPIO_AF0_TIM15 ((uint8_t)0x00U) /*!< AF0: TIM15 Alternate Function mapping */
+#define GPIO_AF0_TIM16 ((uint8_t)0x00U) /*!< AF0: TIM16 Alternate Function mapping */
+#define GPIO_AF0_TIM17 ((uint8_t)0x00U) /*!< AF0: TIM17 Alternate Function mapping */
+#define GPIO_AF0_TSC ((uint8_t)0x00U) /*!< AF0: TSC Alternate Function mapping */
+#define GPIO_AF0_USART1 ((uint8_t)0x00U) /*!< AF0: USART1 Alternate Function mapping */
+#define GPIO_AF0_USART2 ((uint8_t)0x00U) /*!< AF0: USART2 Alternate Function mapping */
+#define GPIO_AF0_USART3 ((uint8_t)0x00U) /*!< AF0: USART3 Alternate Function mapping */
+#define GPIO_AF0_USART4 ((uint8_t)0x00U) /*!< AF0: USART4 Alternate Function mapping */
+#define GPIO_AF0_USART8 ((uint8_t)0x00U) /*!< AF0: USART8 Alternate Function mapping */
+#define GPIO_AF0_CAN ((uint8_t)0x00U) /*!< AF0: CAN Alternate Function mapping */
+
+/* AF 1 */
+#define GPIO_AF1_TIM3 ((uint8_t)0x01U) /*!< AF1: TIM3 Alternate Function mapping */
+#define GPIO_AF1_TIM15 ((uint8_t)0x01U) /*!< AF1: TIM15 Alternate Function mapping */
+#define GPIO_AF1_USART1 ((uint8_t)0x01U) /*!< AF1: USART1 Alternate Function mapping */
+#define GPIO_AF1_USART2 ((uint8_t)0x01U) /*!< AF1: USART2 Alternate Function mapping */
+#define GPIO_AF1_USART3 ((uint8_t)0x01U) /*!< AF1: USART3 Alternate Function mapping */
+#define GPIO_AF1_USART4 ((uint8_t)0x01U) /*!< AF1: USART4 Alternate Function mapping */
+#define GPIO_AF1_USART5 ((uint8_t)0x01U) /*!< AF1: USART5 Alternate Function mapping */
+#define GPIO_AF1_USART6 ((uint8_t)0x01U) /*!< AF1: USART6 Alternate Function mapping */
+#define GPIO_AF1_USART7 ((uint8_t)0x01U) /*!< AF1: USART7 Alternate Function mapping */
+#define GPIO_AF1_USART8 ((uint8_t)0x01U) /*!< AF1: USART8 Alternate Function mapping */
+#define GPIO_AF1_IR ((uint8_t)0x01U) /*!< AF1: IR Alternate Function mapping */
+#define GPIO_AF1_CEC ((uint8_t)0x01U) /*!< AF1: CEC Alternate Function mapping */
+#define GPIO_AF1_EVENTOUT ((uint8_t)0x01U) /*!< AF1: EVENTOUT Alternate Function mapping */
+#define GPIO_AF1_I2C1 ((uint8_t)0x01U) /*!< AF1: I2C1 Alternate Function mapping */
+#define GPIO_AF1_I2C2 ((uint8_t)0x01U) /*!< AF1: I2C2 Alternate Function mapping */
+#define GPIO_AF1_TSC ((uint8_t)0x01U) /*!< AF1: TSC Alternate Function mapping */
+#define GPIO_AF1_SPI1 ((uint8_t)0x01U) /*!< AF1: SPI1 Alternate Function mapping */
+#define GPIO_AF1_SPI2 ((uint8_t)0x01U) /*!< AF1: SPI2 Alternate Function mapping */
+
+/* AF 2 */
+#define GPIO_AF2_TIM1 ((uint8_t)0x02U) /*!< AF2: TIM1 Alternate Function mapping */
+#define GPIO_AF2_TIM2 ((uint8_t)0x02U) /*!< AF2: TIM2 Alternate Function mapping */
+#define GPIO_AF2_TIM16 ((uint8_t)0x02U) /*!< AF2: TIM16 Alternate Function mapping */
+#define GPIO_AF2_TIM17 ((uint8_t)0x02U) /*!< AF2: TIM17 Alternate Function mapping */
+#define GPIO_AF2_EVENTOUT ((uint8_t)0x02U) /*!< AF2: EVENTOUT Alternate Function mapping */
+#define GPIO_AF2_USART5 ((uint8_t)0x02U) /*!< AF2: USART5 Alternate Function mapping */
+#define GPIO_AF2_USART6 ((uint8_t)0x02U) /*!< AF2: USART6 Alternate Function mapping */
+#define GPIO_AF2_USART7 ((uint8_t)0x02U) /*!< AF2: USART7 Alternate Function mapping */
+#define GPIO_AF2_USART8 ((uint8_t)0x02U) /*!< AF2: USART8 Alternate Function mapping */
+
+/* AF 3 */
+#define GPIO_AF3_EVENTOUT ((uint8_t)0x03U) /*!< AF3: EVENTOUT Alternate Function mapping */
+#define GPIO_AF3_TSC ((uint8_t)0x03U) /*!< AF3: TSC Alternate Function mapping */
+#define GPIO_AF3_TIM15 ((uint8_t)0x03U) /*!< AF3: TIM15 Alternate Function mapping */
+#define GPIO_AF3_I2C1 ((uint8_t)0x03U) /*!< AF3: I2C1 Alternate Function mapping */
+
+/* AF 4 */
+#define GPIO_AF4_TIM14 ((uint8_t)0x04U) /*!< AF4: TIM14 Alternate Function mapping */
+#define GPIO_AF4_USART4 ((uint8_t)0x04U) /*!< AF4: USART4 Alternate Function mapping */
+#define GPIO_AF4_USART3 ((uint8_t)0x04U) /*!< AF4: USART3 Alternate Function mapping */
+#define GPIO_AF4_CRS ((uint8_t)0x04U) /*!< AF4: CRS Alternate Function mapping */
+#define GPIO_AF4_CAN ((uint8_t)0x04U) /*!< AF4: CAN Alternate Function mapping */
+#define GPIO_AF4_I2C1 ((uint8_t)0x04U) /*!< AF4: I2C1 Alternate Function mapping */
+#define GPIO_AF4_USART5 ((uint8_t)0x04U) /*!< AF4: USART5 Alternate Function mapping */
+
+/* AF 5 */
+#define GPIO_AF5_TIM15 ((uint8_t)0x05U) /*!< AF5: TIM15 Alternate Function mapping */
+#define GPIO_AF5_TIM16 ((uint8_t)0x05U) /*!< AF5: TIM16 Alternate Function mapping */
+#define GPIO_AF5_TIM17 ((uint8_t)0x05U) /*!< AF5: TIM17 Alternate Function mapping */
+#define GPIO_AF5_SPI2 ((uint8_t)0x05U) /*!< AF5: SPI2 Alternate Function mapping */
+#define GPIO_AF5_I2C2 ((uint8_t)0x05U) /*!< AF5: I2C2 Alternate Function mapping */
+#define GPIO_AF5_MCO ((uint8_t)0x05U) /*!< AF5: MCO Alternate Function mapping */
+#define GPIO_AF5_USART6 ((uint8_t)0x05U) /*!< AF5: USART6 Alternate Function mapping */
+
+/* AF 6 */
+#define GPIO_AF6_EVENTOUT ((uint8_t)0x06U) /*!< AF6: EVENTOUT Alternate Function mapping */
+
+/* AF 7 */
+#define GPIO_AF7_COMP1 ((uint8_t)0x07U) /*!< AF7: COMP1 Alternate Function mapping */
+#define GPIO_AF7_COMP2 ((uint8_t)0x07U) /*!< AF7: COMP2 Alternate Function mapping */
+
+#define IS_GPIO_AF(AF) ((AF) <= (uint8_t)0x07U)
+
+#endif /* STM32F091xC || STM32F098xx */
+
+#if defined(STM32F030xC)
+/*--------------------------- STM32F030xC ----------------------------------------------------*/
+/* AF 0 */
+#define GPIO_AF0_EVENTOUT ((uint8_t)0x00U) /*!< AF0: EVENTOUT Alternate Function mapping */
+#define GPIO_AF0_SWDIO ((uint8_t)0x00U) /*!< AF0: SWDIO Alternate Function mapping */
+#define GPIO_AF0_SWCLK ((uint8_t)0x00U) /*!< AF0: SWCLK Alternate Function mapping */
+#define GPIO_AF0_MCO ((uint8_t)0x00U) /*!< AF0: MCO Alternate Function mapping */
+#define GPIO_AF0_IR ((uint8_t)0x00U) /*!< AF0: IR Alternate Function mapping */
+#define GPIO_AF0_SPI1 ((uint8_t)0x00U) /*!< AF0: SPI1 Alternate Function mapping */
+#define GPIO_AF0_SPI2 ((uint8_t)0x00U) /*!< AF0: SPI2 Alternate Function mapping */
+#define GPIO_AF0_TIM3 ((uint8_t)0x00U) /*!< AF0: TIM3 Alternate Function mapping */
+#define GPIO_AF0_TIM14 ((uint8_t)0x00U) /*!< AF0: TIM14 Alternate Function mapping */
+#define GPIO_AF0_TIM15 ((uint8_t)0x00U) /*!< AF0: TIM15 Alternate Function mapping */
+#define GPIO_AF0_TIM17 ((uint8_t)0x00U) /*!< AF0: TIM17 Alternate Function mapping */
+#define GPIO_AF0_USART1 ((uint8_t)0x00U) /*!< AF0: USART1 Alternate Function mapping */
+#define GPIO_AF0_USART4 ((uint8_t)0x00U) /*!< AF0: USART4 Alternate Function mapping */
+
+/* AF 1 */
+#define GPIO_AF1_TIM3 ((uint8_t)0x01U) /*!< AF1: TIM3 Alternate Function mapping */
+#define GPIO_AF1_TIM15 ((uint8_t)0x01U) /*!< AF1: TIM15 Alternate Function mapping */
+#define GPIO_AF1_USART1 ((uint8_t)0x01U) /*!< AF1: USART1 Alternate Function mapping */
+#define GPIO_AF1_USART2 ((uint8_t)0x01U) /*!< AF1: USART2 Alternate Function mapping */
+#define GPIO_AF1_USART3 ((uint8_t)0x01U) /*!< AF1: USART3 Alternate Function mapping */
+#define GPIO_AF1_IR ((uint8_t)0x01U) /*!< AF1: IR Alternate Function mapping */
+#define GPIO_AF1_EVENTOUT ((uint8_t)0x01U) /*!< AF1: EVENTOUT Alternate Function mapping */
+#define GPIO_AF1_I2C1 ((uint8_t)0x01U) /*!< AF1: I2C1 Alternate Function mapping */
+#define GPIO_AF1_I2C2 ((uint8_t)0x01U) /*!< AF1: I2C2 Alternate Function mapping */
+#define GPIO_AF1_SPI2 ((uint8_t)0x01U) /*!< AF1: SPI2 Alternate Function mapping */
+
+/* AF 2 */
+#define GPIO_AF2_TIM1 ((uint8_t)0x02U) /*!< AF2: TIM1 Alternate Function mapping */
+#define GPIO_AF2_TIM16 ((uint8_t)0x02U) /*!< AF2: TIM16 Alternate Function mapping */
+#define GPIO_AF2_TIM17 ((uint8_t)0x02U) /*!< AF2: TIM17 Alternate Function mapping */
+#define GPIO_AF2_EVENTOUT ((uint8_t)0x02U) /*!< AF2: EVENTOUT Alternate Function mapping */
+#define GPIO_AF2_USART5 ((uint8_t)0x02U) /*!< AF2: USART5 Alternate Function mapping */
+#define GPIO_AF2_USART6 ((uint8_t)0x02U) /*!< AF2: USART6 Alternate Function mapping */
+
+/* AF 3 */
+#define GPIO_AF3_EVENTOUT ((uint8_t)0x03U) /*!< AF3: EVENTOUT Alternate Function mapping */
+#define GPIO_AF3_TIM15 ((uint8_t)0x03U) /*!< AF3: TIM15 Alternate Function mapping */
+#define GPIO_AF3_I2C1 ((uint8_t)0x03U) /*!< AF3: I2C1 Alternate Function mapping */
+
+/* AF 4 */
+#define GPIO_AF4_TIM14 ((uint8_t)0x04U) /*!< AF4: TIM14 Alternate Function mapping */
+#define GPIO_AF4_USART4 ((uint8_t)0x04U) /*!< AF4: USART4 Alternate Function mapping */
+#define GPIO_AF4_USART3 ((uint8_t)0x04U) /*!< AF4: USART3 Alternate Function mapping */
+#define GPIO_AF4_I2C1 ((uint8_t)0x04U) /*!< AF4: I2C1 Alternate Function mapping */
+#define GPIO_AF4_USART5 ((uint8_t)0x04U) /*!< AF4: USART5 Alternate Function mapping */
+
+/* AF 5 */
+#define GPIO_AF5_TIM15 ((uint8_t)0x05U) /*!< AF5: TIM15 Alternate Function mapping */
+#define GPIO_AF5_TIM16 ((uint8_t)0x05U) /*!< AF5: TIM16 Alternate Function mapping */
+#define GPIO_AF5_TIM17 ((uint8_t)0x05U) /*!< AF5: TIM17 Alternate Function mapping */
+#define GPIO_AF5_SPI2 ((uint8_t)0x05U) /*!< AF5: SPI2 Alternate Function mapping */
+#define GPIO_AF5_I2C2 ((uint8_t)0x05U) /*!< AF5: I2C2 Alternate Function mapping */
+#define GPIO_AF5_MCO ((uint8_t)0x05U) /*!< AF5: MCO Alternate Function mapping */
+#define GPIO_AF5_USART6 ((uint8_t)0x05U) /*!< AF5: USART6 Alternate Function mapping */
+
+/* AF 6 */
+#define GPIO_AF6_EVENTOUT ((uint8_t)0x06U) /*!< AF6: EVENTOUT Alternate Function mapping */
+
+#define IS_GPIO_AF(AF) ((AF) <= (uint8_t)0x06U)
+
+#endif /* STM32F030xC */
+
+#if defined (STM32F072xB) || defined (STM32F078xx)
+/*--------------------------- STM32F072xB/STM32F078xx ---------------------------*/
+/* AF 0 */
+#define GPIO_AF0_EVENTOUT ((uint8_t)0x00U) /*!< AF0: EVENTOUT Alternate Function mapping */
+#define GPIO_AF0_SWDIO ((uint8_t)0x00U) /*!< AF0: SWDIO Alternate Function mapping */
+#define GPIO_AF0_SWCLK ((uint8_t)0x00U) /*!< AF0: SWCLK Alternate Function mapping */
+#define GPIO_AF0_MCO ((uint8_t)0x00U) /*!< AF0: MCO Alternate Function mapping */
+#define GPIO_AF0_CEC ((uint8_t)0x00U) /*!< AF0: CEC Alternate Function mapping */
+#define GPIO_AF0_CRS ((uint8_t)0x00U) /*!< AF0: CRS Alternate Function mapping */
+#define GPIO_AF0_IR ((uint8_t)0x00U) /*!< AF0: IR Alternate Function mapping */
+#define GPIO_AF0_SPI1 ((uint8_t)0x00U) /*!< AF0: SPI1/I2S1 Alternate Function mapping */
+#define GPIO_AF0_SPI2 ((uint8_t)0x00U) /*!< AF0: SPI2/I2S2 Alternate Function mapping */
+#define GPIO_AF0_TIM1 ((uint8_t)0x00U) /*!< AF0: TIM1 Alternate Function mapping */
+#define GPIO_AF0_TIM3 ((uint8_t)0x00U) /*!< AF0: TIM3 Alternate Function mapping */
+#define GPIO_AF0_TIM14 ((uint8_t)0x00U) /*!< AF0: TIM14 Alternate Function mapping */
+#define GPIO_AF0_TIM15 ((uint8_t)0x00U) /*!< AF0: TIM15 Alternate Function mapping */
+#define GPIO_AF0_TIM16 ((uint8_t)0x00U) /*!< AF0: TIM16 Alternate Function mapping */
+#define GPIO_AF0_TIM17 ((uint8_t)0x00U) /*!< AF0: TIM17 Alternate Function mapping */
+#define GPIO_AF0_TSC ((uint8_t)0x00U) /*!< AF0: TSC Alternate Function mapping */
+#define GPIO_AF0_USART1 ((uint8_t)0x00U) /*!< AF0: USART1 Alternate Function mapping */
+#define GPIO_AF0_USART2 ((uint8_t)0x00U) /*!< AF0: USART2 Alternate Function mapping */
+#define GPIO_AF0_USART3 ((uint8_t)0x00U) /*!< AF0: USART2 Alternate Function mapping */
+#define GPIO_AF0_USART4 ((uint8_t)0x00U) /*!< AF0: USART4 Alternate Function mapping */
+#define GPIO_AF0_CAN ((uint8_t)0x00U) /*!< AF0: CAN Alternate Function mapping */
+
+/* AF 1 */
+#define GPIO_AF1_TIM3 ((uint8_t)0x01U) /*!< AF1: TIM3 Alternate Function mapping */
+#define GPIO_AF1_TIM15 ((uint8_t)0x01U) /*!< AF1: TIM15 Alternate Function mapping */
+#define GPIO_AF1_USART1 ((uint8_t)0x01U) /*!< AF1: USART1 Alternate Function mapping */
+#define GPIO_AF1_USART2 ((uint8_t)0x01U) /*!< AF1: USART2 Alternate Function mapping */
+#define GPIO_AF1_USART3 ((uint8_t)0x01U) /*!< AF1: USART3 Alternate Function mapping */
+#define GPIO_AF1_IR ((uint8_t)0x01U) /*!< AF1: IR Alternate Function mapping */
+#define GPIO_AF1_CEC ((uint8_t)0x01U) /*!< AF1: CEC Alternate Function mapping */
+#define GPIO_AF1_EVENTOUT ((uint8_t)0x01U) /*!< AF1: EVENTOUT Alternate Function mapping */
+#define GPIO_AF1_I2C1 ((uint8_t)0x01U) /*!< AF1: I2C1 Alternate Function mapping */
+#define GPIO_AF1_I2C2 ((uint8_t)0x01U) /*!< AF1: I2C1 Alternate Function mapping */
+#define GPIO_AF1_TSC ((uint8_t)0x01U) /*!< AF1: I2C1 Alternate Function mapping */
+#define GPIO_AF1_SPI1 ((uint8_t)0x01U) /*!< AF1: SPI1 Alternate Function mapping */
+#define GPIO_AF1_SPI2 ((uint8_t)0x01U) /*!< AF1: SPI2 Alternate Function mapping */
+
+/* AF 2 */
+#define GPIO_AF2_TIM1 ((uint8_t)0x02U) /*!< AF2: TIM1 Alternate Function mapping */
+#define GPIO_AF2_TIM2 ((uint8_t)0x02U) /*!< AF2: TIM2 Alternate Function mapping */
+#define GPIO_AF2_TIM16 ((uint8_t)0x02U) /*!< AF2: TIM16 Alternate Function mapping */
+#define GPIO_AF2_TIM17 ((uint8_t)0x02U) /*!< AF2: TIM17 Alternate Function mapping */
+#define GPIO_AF2_EVENTOUT ((uint8_t)0x02U) /*!< AF2: EVENTOUT Alternate Function mapping */
+#define GPIO_AF2_USB ((uint8_t)0x02U) /*!< AF2: USB Alternate Function mapping */
+
+/* AF 3 */
+#define GPIO_AF3_EVENTOUT ((uint8_t)0x03U) /*!< AF3: EVENTOUT Alternate Function mapping */
+#define GPIO_AF3_TSC ((uint8_t)0x03U) /*!< AF3: TSC Alternate Function mapping */
+#define GPIO_AF3_TIM15 ((uint8_t)0x03U) /*!< AF3: TIM15 Alternate Function mapping */
+#define GPIO_AF3_I2C1 ((uint8_t)0x03U) /*!< AF3: I2C1 Alternate Function mapping */
+
+/* AF 4 */
+#define GPIO_AF4_TIM14 ((uint8_t)0x04U) /*!< AF4: TIM14 Alternate Function mapping */
+#define GPIO_AF4_USART4 ((uint8_t)0x04U) /*!< AF4: USART4 Alternate Function mapping */
+#define GPIO_AF4_USART3 ((uint8_t)0x04U) /*!< AF4: USART3 Alternate Function mapping */
+#define GPIO_AF4_CRS ((uint8_t)0x04U) /*!< AF4: CRS Alternate Function mapping */
+#define GPIO_AF4_CAN ((uint8_t)0x04U) /*!< AF4: CAN Alternate Function mapping */
+
+/* AF 5 */
+#define GPIO_AF5_TIM15 ((uint8_t)0x05U) /*!< AF5: TIM15 Alternate Function mapping */
+#define GPIO_AF5_TIM16 ((uint8_t)0x05U) /*!< AF5: TIM16 Alternate Function mapping */
+#define GPIO_AF5_TIM17 ((uint8_t)0x05U) /*!< AF5: TIM17 Alternate Function mapping */
+#define GPIO_AF5_SPI2 ((uint8_t)0x05U) /*!< AF5: SPI2 Alternate Function mapping */
+#define GPIO_AF5_I2C2 ((uint8_t)0x05U) /*!< AF5: I2C2 Alternate Function mapping */
+
+/* AF 6 */
+#define GPIO_AF6_EVENTOUT ((uint8_t)0x06U) /*!< AF6: EVENTOUT Alternate Function mapping */
+
+/* AF 7 */
+#define GPIO_AF7_COMP1 ((uint8_t)0x07U) /*!< AF7: COMP1 Alternate Function mapping */
+#define GPIO_AF7_COMP2 ((uint8_t)0x07U) /*!< AF7: COMP2 Alternate Function mapping */
+
+#define IS_GPIO_AF(AF) ((AF) <= (uint8_t)0x07U)
+
+#endif /* STM32F072xB || STM32F078xx */
+
+#if defined (STM32F070xB)
+/*---------------------------------- STM32F070xB ---------------------------------------------*/
+/* AF 0 */
+#define GPIO_AF0_EVENTOUT ((uint8_t)0x00U) /*!< AF0: EVENTOUT Alternate Function mapping */
+#define GPIO_AF0_SWDIO ((uint8_t)0x00U) /*!< AF0: SWDIO Alternate Function mapping */
+#define GPIO_AF0_SWCLK ((uint8_t)0x00U) /*!< AF0: SWCLK Alternate Function mapping */
+#define GPIO_AF0_MCO ((uint8_t)0x00U) /*!< AF0: MCO Alternate Function mapping */
+#define GPIO_AF0_IR ((uint8_t)0x00U) /*!< AF0: IR Alternate Function mapping */
+#define GPIO_AF0_SPI1 ((uint8_t)0x00U) /*!< AF0: SPI1 Alternate Function mapping */
+#define GPIO_AF0_SPI2 ((uint8_t)0x00U) /*!< AF0: SPI2 Alternate Function mapping */
+#define GPIO_AF0_TIM3 ((uint8_t)0x00U) /*!< AF0: TIM3 Alternate Function mapping */
+#define GPIO_AF0_TIM14 ((uint8_t)0x00U) /*!< AF0: TIM14 Alternate Function mapping */
+#define GPIO_AF0_TIM15 ((uint8_t)0x00U) /*!< AF0: TIM15 Alternate Function mapping */
+#define GPIO_AF0_TIM17 ((uint8_t)0x00U) /*!< AF0: TIM17 Alternate Function mapping */
+#define GPIO_AF0_USART1 ((uint8_t)0x00U) /*!< AF0: USART1 Alternate Function mapping */
+#define GPIO_AF0_USART4 ((uint8_t)0x00U) /*!< AF0: USART4 Alternate Function mapping */
+
+/* AF 1 */
+#define GPIO_AF1_TIM3 ((uint8_t)0x01U) /*!< AF1: TIM3 Alternate Function mapping */
+#define GPIO_AF1_TIM15 ((uint8_t)0x01U) /*!< AF1: TIM15 Alternate Function mapping */
+#define GPIO_AF1_USART1 ((uint8_t)0x01U) /*!< AF1: USART1 Alternate Function mapping */
+#define GPIO_AF1_USART2 ((uint8_t)0x01U) /*!< AF1: USART2 Alternate Function mapping */
+#define GPIO_AF1_USART3 ((uint8_t)0x01U) /*!< AF1: USART4 Alternate Function mapping */
+#define GPIO_AF1_IR ((uint8_t)0x01U) /*!< AF1: IR Alternate Function mapping */
+#define GPIO_AF1_EVENTOUT ((uint8_t)0x01U) /*!< AF1: EVENTOUT Alternate Function mapping */
+#define GPIO_AF1_I2C1 ((uint8_t)0x01U) /*!< AF1: I2C1 Alternate Function mapping */
+#define GPIO_AF1_I2C2 ((uint8_t)0x01U) /*!< AF1: I2C1 Alternate Function mapping */
+#define GPIO_AF1_SPI2 ((uint8_t)0x01U) /*!< AF1: SPI2 Alternate Function mapping */
+
+/* AF 2 */
+#define GPIO_AF2_TIM1 ((uint8_t)0x02U) /*!< AF2: TIM1 Alternate Function mapping */
+#define GPIO_AF2_TIM16 ((uint8_t)0x02U) /*!< AF2: TIM16 Alternate Function mapping */
+#define GPIO_AF2_TIM17 ((uint8_t)0x02U) /*!< AF2: TIM17 Alternate Function mapping */
+#define GPIO_AF2_EVENTOUT ((uint8_t)0x02U) /*!< AF2: EVENTOUT Alternate Function mapping */
+#define GPIO_AF2_USB ((uint8_t)0x02U) /*!< AF2: USB Alternate Function mapping */
+
+/* AF 3 */
+#define GPIO_AF3_EVENTOUT ((uint8_t)0x03U) /*!< AF3: EVENTOUT Alternate Function mapping */
+#define GPIO_AF3_I2C1 ((uint8_t)0x03U) /*!< AF3: I2C1 Alternate Function mapping */
+#define GPIO_AF3_TIM15 ((uint8_t)0x03U) /*!< AF3: TIM15 Alternate Function mapping */
+
+/* AF 4 */
+#define GPIO_AF4_TIM14 ((uint8_t)0x04U) /*!< AF4: TIM14 Alternate Function mapping */
+#define GPIO_AF4_USART4 ((uint8_t)0x04U) /*!< AF4: USART4 Alternate Function mapping */
+#define GPIO_AF4_USART3 ((uint8_t)0x04U) /*!< AF4: USART3 Alternate Function mapping */
+
+/* AF 5 */
+#define GPIO_AF5_TIM15 ((uint8_t)0x05U) /*!< AF5: TIM15 Alternate Function mapping */
+#define GPIO_AF5_TIM16 ((uint8_t)0x05U) /*!< AF5: TIM16 Alternate Function mapping */
+#define GPIO_AF5_TIM17 ((uint8_t)0x05U) /*!< AF5: TIM17 Alternate Function mapping */
+#define GPIO_AF5_SPI2 ((uint8_t)0x05U) /*!< AF5: SPI2 Alternate Function mapping */
+#define GPIO_AF5_I2C2 ((uint8_t)0x05U) /*!< AF5: I2C2 Alternate Function mapping */
+
+/* AF 6 */
+#define GPIO_AF6_EVENTOUT ((uint8_t)0x06U) /*!< AF6: EVENTOUT Alternate Function mapping */
+
+#define IS_GPIO_AF(AF) ((AF) <= (uint8_t)0x06U)
+
+#endif /* STM32F070xB */
+
+#if defined (STM32F042x6) || defined (STM32F048xx)
+/*--------------------------- STM32F042x6/STM32F048xx ---------------------------*/
+/* AF 0 */
+#define GPIO_AF0_EVENTOUT ((uint8_t)0x00U) /*!< AF0: EVENTOUT Alternate Function mapping */
+#define GPIO_AF0_CEC ((uint8_t)0x00U) /*!< AF0: CEC Alternate Function mapping */
+#define GPIO_AF0_CRS ((uint8_t)0x00U) /*!< AF0: CRS Alternate Function mapping */
+#define GPIO_AF0_IR ((uint8_t)0x00U) /*!< AF0: IR Alternate Function mapping */
+#define GPIO_AF0_MCO ((uint8_t)0x00U) /*!< AF0: MCO Alternate Function mapping */
+#define GPIO_AF0_SPI1 ((uint8_t)0x00U) /*!< AF0: SPI1/I2S1 Alternate Function mapping */
+#define GPIO_AF0_SPI2 ((uint8_t)0x00U) /*!< AF0: SPI2/I2S2 Alternate Function mapping */
+#define GPIO_AF0_SWDIO ((uint8_t)0x00U) /*!< AF0: SWDIO Alternate Function mapping */
+#define GPIO_AF0_SWCLK ((uint8_t)0x00U) /*!< AF0: SWCLK Alternate Function mapping */
+#define GPIO_AF0_TIM14 ((uint8_t)0x00U) /*!< AF0: TIM14 Alternate Function mapping */
+#define GPIO_AF0_TIM17 ((uint8_t)0x00U) /*!< AF0: TIM17 Alternate Function mapping */
+#define GPIO_AF0_USART1 ((uint8_t)0x00U) /*!< AF0: USART1 Alternate Function mapping */
+
+/* AF 1 */
+#define GPIO_AF1_CEC ((uint8_t)0x01U) /*!< AF1: CEC Alternate Function mapping */
+#define GPIO_AF1_EVENTOUT ((uint8_t)0x01U) /*!< AF1: EVENTOUT Alternate Function mapping */
+#define GPIO_AF1_I2C1 ((uint8_t)0x01U) /*!< AF1: I2C1 Alternate Function mapping */
+#define GPIO_AF1_IR ((uint8_t)0x01U) /*!< AF1: IR Alternate Function mapping */
+#define GPIO_AF1_USART1 ((uint8_t)0x01U) /*!< AF1: USART1 Alternate Function mapping */
+#define GPIO_AF1_USART2 ((uint8_t)0x01U) /*!< AF1: USART2 Alternate Function mapping */
+#define GPIO_AF1_TIM3 ((uint8_t)0x01U) /*!< AF1: TIM3 Alternate Function mapping */
+
+/* AF 2 */
+#define GPIO_AF2_EVENTOUT ((uint8_t)0x02U) /*!< AF2: EVENTOUT Alternate Function mapping */
+#define GPIO_AF2_TIM1 ((uint8_t)0x02U) /*!< AF2: TIM1 Alternate Function mapping */
+#define GPIO_AF2_TIM2 ((uint8_t)0x02U) /*!< AF2: TIM2 Alternate Function mapping */
+#define GPIO_AF2_TIM16 ((uint8_t)0x02U) /*!< AF2: TIM16 Alternate Function mapping */
+#define GPIO_AF2_TIM17 ((uint8_t)0x02U) /*!< AF2: TIM17 Alternate Function mapping */
+#define GPIO_AF2_USB ((uint8_t)0x02U) /*!< AF2: USB Alternate Function mapping */
+
+/* AF 3 */
+#define GPIO_AF3_EVENTOUT ((uint8_t)0x03U) /*!< AF3: EVENTOUT Alternate Function mapping */
+#define GPIO_AF3_I2C1 ((uint8_t)0x03U) /*!< AF3: I2C1 Alternate Function mapping */
+#define GPIO_AF3_TSC ((uint8_t)0x03U) /*!< AF3: TSC Alternate Function mapping */
+
+/* AF 4 */
+#define GPIO_AF4_TIM14 ((uint8_t)0x04U) /*!< AF4: TIM14 Alternate Function mapping */
+#define GPIO_AF4_CAN ((uint8_t)0x04U) /*!< AF4: CAN Alternate Function mapping */
+#define GPIO_AF4_CRS ((uint8_t)0x04U) /*!< AF4: CRS Alternate Function mapping */
+#define GPIO_AF4_I2C1 ((uint8_t)0x04U) /*!< AF4: I2C1 Alternate Function mapping */
+
+/* AF 5 */
+#define GPIO_AF5_MCO ((uint8_t)0x05U) /*!< AF5: MCO Alternate Function mapping */
+#define GPIO_AF5_I2C1 ((uint8_t)0x05U) /*!< AF5: I2C1 Alternate Function mapping */
+#define GPIO_AF5_I2C2 ((uint8_t)0x05U) /*!< AF5: I2C2 Alternate Function mapping */
+#define GPIO_AF5_SPI2 ((uint8_t)0x05U) /*!< AF5: SPI2 Alternate Function mapping */
+#define GPIO_AF5_TIM16 ((uint8_t)0x05U) /*!< AF5: TIM16 Alternate Function mapping */
+#define GPIO_AF5_TIM17 ((uint8_t)0x05U) /*!< AF5: TIM17 Alternate Function mapping */
+#define GPIO_AF5_USB ((uint8_t)0x05U) /*!< AF5: USB Alternate Function mapping */
+
+/* AF 6 */
+#define GPIO_AF6_EVENTOUT ((uint8_t)0x06U) /*!< AF6: EVENTOUT Alternate Function mapping */
+
+#define IS_GPIO_AF(AF) ((AF) <= (uint8_t)0x06U)
+
+#endif /* STM32F042x6 || STM32F048xx */
+
+#if defined (STM32F070x6)
+/*--------------------------------------- STM32F070x6 ----------------------------------------*/
+/* AF 0 */
+#define GPIO_AF0_EVENTOUT ((uint8_t)0x00U) /*!< AF0: EVENTOUT Alternate Function mapping */
+#define GPIO_AF0_IR ((uint8_t)0x00U) /*!< AF0: IR Alternate Function mapping */
+#define GPIO_AF0_MCO ((uint8_t)0x00U) /*!< AF0: MCO Alternate Function mapping */
+#define GPIO_AF0_SPI1 ((uint8_t)0x00U) /*!< AF0: SPI1 Alternate Function mapping */
+#define GPIO_AF0_SWDIO ((uint8_t)0x00U) /*!< AF0: SWDIO Alternate Function mapping */
+#define GPIO_AF0_SWCLK ((uint8_t)0x00U) /*!< AF0: SWCLK Alternate Function mapping */
+#define GPIO_AF0_TIM14 ((uint8_t)0x00U) /*!< AF0: TIM14 Alternate Function mapping */
+#define GPIO_AF0_TIM17 ((uint8_t)0x00U) /*!< AF0: TIM17 Alternate Function mapping */
+#define GPIO_AF0_USART1 ((uint8_t)0x00U) /*!< AF0: USART1 Alternate Function mapping */
+
+/* AF 1 */
+#define GPIO_AF1_EVENTOUT ((uint8_t)0x01U) /*!< AF1: EVENTOUT Alternate Function mapping */
+#define GPIO_AF1_I2C1 ((uint8_t)0x01U) /*!< AF1: I2C1 Alternate Function mapping */
+#define GPIO_AF1_IR ((uint8_t)0x01U) /*!< AF1: IR Alternate Function mapping */
+#define GPIO_AF1_USART1 ((uint8_t)0x01U) /*!< AF1: USART1 Alternate Function mapping */
+#define GPIO_AF1_USART2 ((uint8_t)0x01U) /*!< AF1: USART2 Alternate Function mapping */
+#define GPIO_AF1_TIM3 ((uint8_t)0x01U) /*!< AF1: TIM3 Alternate Function mapping */
+
+/* AF 2 */
+#define GPIO_AF2_EVENTOUT ((uint8_t)0x02U) /*!< AF2: EVENTOUT Alternate Function mapping */
+#define GPIO_AF2_TIM1 ((uint8_t)0x02U) /*!< AF2: TIM1 Alternate Function mapping */
+#define GPIO_AF2_TIM16 ((uint8_t)0x02U) /*!< AF2: TIM16 Alternate Function mapping */
+#define GPIO_AF2_TIM17 ((uint8_t)0x02U) /*!< AF2: TIM17 Alternate Function mapping */
+#define GPIO_AF2_USB ((uint8_t)0x02U) /*!< AF2: USB Alternate Function mapping */
+
+/* AF 3 */
+#define GPIO_AF3_EVENTOUT ((uint8_t)0x03U) /*!< AF3: EVENTOUT Alternate Function mapping */
+#define GPIO_AF3_I2C1 ((uint8_t)0x03U) /*!< AF3: I2C1 Alternate Function mapping */
+
+/* AF 4 */
+#define GPIO_AF4_TIM14 ((uint8_t)0x04U) /*!< AF4: TIM14 Alternate Function mapping */
+#define GPIO_AF4_I2C1 ((uint8_t)0x04U) /*!< AF4: I2C1 Alternate Function mapping */
+
+/* AF 5 */
+#define GPIO_AF5_MCO ((uint8_t)0x05U) /*!< AF5: MCO Alternate Function mapping */
+#define GPIO_AF5_I2C1 ((uint8_t)0x05U) /*!< AF5: I2C1 Alternate Function mapping */
+#define GPIO_AF5_TIM16 ((uint8_t)0x05U) /*!< AF5: TIM16 Alternate Function mapping */
+#define GPIO_AF5_TIM17 ((uint8_t)0x05U) /*!< AF5: TIM17 Alternate Function mapping */
+#define GPIO_AF5_USB ((uint8_t)0x05U) /*!< AF5: USB Alternate Function mapping */
+
+/* AF 6 */
+#define GPIO_AF6_EVENTOUT ((uint8_t)0x06U) /*!< AF6: EVENTOUT Alternate Function mapping */
+
+#define IS_GPIO_AF(AF) ((AF) <= (uint8_t)0x06U)
+
+#endif /* STM32F070x6 */
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/* Exported macro ------------------------------------------------------------*/
+/** @defgroup GPIOEx_Exported_Macros GPIOEx Exported Macros
+ * @{
+ */
+
+/** @defgroup GPIOEx_Get_Port_Index GPIOEx_Get Port Index
+* @{
+ */
+#if defined(GPIOD) && defined(GPIOE)
+#define GPIO_GET_INDEX(__GPIOx__) (((__GPIOx__) == (GPIOA))? 0U :\
+ ((__GPIOx__) == (GPIOB))? 1U :\
+ ((__GPIOx__) == (GPIOC))? 2U :\
+ ((__GPIOx__) == (GPIOD))? 3U :\
+ ((__GPIOx__) == (GPIOE))? 4U : 5U)
+#endif
+
+#if defined(GPIOD) && !defined(GPIOE)
+#define GPIO_GET_INDEX(__GPIOx__) (((__GPIOx__) == (GPIOA))? 0U :\
+ ((__GPIOx__) == (GPIOB))? 1U :\
+ ((__GPIOx__) == (GPIOC))? 2U :\
+ ((__GPIOx__) == (GPIOD))? 3U : 5U)
+#endif
+
+#if !defined(GPIOD) && defined(GPIOE)
+#define GPIO_GET_INDEX(__GPIOx__) (((__GPIOx__) == (GPIOA))? 0U :\
+ ((__GPIOx__) == (GPIOB))? 1U :\
+ ((__GPIOx__) == (GPIOC))? 2U :\
+ ((__GPIOx__) == (GPIOE))? 4U : 5U)
+#endif
+
+#if !defined(GPIOD) && !defined(GPIOE)
+#define GPIO_GET_INDEX(__GPIOx__) (((__GPIOx__) == (GPIOA))? 0U :\
+ ((__GPIOx__) == (GPIOB))? 1U :\
+ ((__GPIOx__) == (GPIOC))? 2U : 5U)
+#endif
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/* Exported functions --------------------------------------------------------*/
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __STM32F0xx_HAL_GPIO_EX_H */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
+
diff --git a/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal_i2c.h b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal_i2c.h
new file mode 100644
index 0000000..3c913d0
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal_i2c.h
@@ -0,0 +1,838 @@
+/**
+ ******************************************************************************
+ * @file stm32f0xx_hal_i2c.h
+ * @author MCD Application Team
+ * @brief Header file of I2C HAL module.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2016 STMicroelectronics.
+ * All rights reserved.
+ *
+ * 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 STM32F0xx_HAL_I2C_H
+#define STM32F0xx_HAL_I2C_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f0xx_hal_def.h"
+
+/** @addtogroup STM32F0xx_HAL_Driver
+ * @{
+ */
+
+/** @addtogroup I2C
+ * @{
+ */
+
+/* Exported types ------------------------------------------------------------*/
+/** @defgroup I2C_Exported_Types I2C Exported Types
+ * @{
+ */
+
+/** @defgroup I2C_Configuration_Structure_definition I2C Configuration Structure definition
+ * @brief I2C Configuration Structure definition
+ * @{
+ */
+typedef struct
+{
+ uint32_t Timing; /*!< Specifies the I2C_TIMINGR_register value.
+ This parameter calculated by referring to I2C initialization section
+ in Reference manual */
+
+ uint32_t OwnAddress1; /*!< Specifies the first device own address.
+ This parameter can be a 7-bit or 10-bit address. */
+
+ uint32_t AddressingMode; /*!< Specifies if 7-bit or 10-bit addressing mode is selected.
+ This parameter can be a value of @ref I2C_ADDRESSING_MODE */
+
+ uint32_t DualAddressMode; /*!< Specifies if dual addressing mode is selected.
+ This parameter can be a value of @ref I2C_DUAL_ADDRESSING_MODE */
+
+ uint32_t OwnAddress2; /*!< Specifies the second device own address if dual addressing mode is selected
+ This parameter can be a 7-bit address. */
+
+ uint32_t OwnAddress2Masks; /*!< Specifies the acknowledge mask address second device own address if dual addressing
+ mode is selected.
+ This parameter can be a value of @ref I2C_OWN_ADDRESS2_MASKS */
+
+ uint32_t GeneralCallMode; /*!< Specifies if general call mode is selected.
+ This parameter can be a value of @ref I2C_GENERAL_CALL_ADDRESSING_MODE */
+
+ uint32_t NoStretchMode; /*!< Specifies if nostretch mode is selected.
+ This parameter can be a value of @ref I2C_NOSTRETCH_MODE */
+
+} I2C_InitTypeDef;
+
+/**
+ * @}
+ */
+
+/** @defgroup HAL_state_structure_definition HAL state structure definition
+ * @brief HAL State structure definition
+ * @note HAL I2C State value coding follow below described bitmap :\n
+ * b7-b6 Error information\n
+ * 00 : No Error\n
+ * 01 : Abort (Abort user request on going)\n
+ * 10 : Timeout\n
+ * 11 : Error\n
+ * b5 Peripheral initialization status\n
+ * 0 : Reset (peripheral not initialized)\n
+ * 1 : Init done (peripheral initialized and ready to use. HAL I2C Init function called)\n
+ * b4 (not used)\n
+ * x : Should be set to 0\n
+ * b3\n
+ * 0 : Ready or Busy (No Listen mode ongoing)\n
+ * 1 : Listen (peripheral in Address Listen Mode)\n
+ * b2 Intrinsic process state\n
+ * 0 : Ready\n
+ * 1 : Busy (peripheral busy with some configuration or internal operations)\n
+ * b1 Rx state\n
+ * 0 : Ready (no Rx operation ongoing)\n
+ * 1 : Busy (Rx operation ongoing)\n
+ * b0 Tx state\n
+ * 0 : Ready (no Tx operation ongoing)\n
+ * 1 : Busy (Tx operation ongoing)
+ * @{
+ */
+typedef enum
+{
+ HAL_I2C_STATE_RESET = 0x00U, /*!< Peripheral is not yet Initialized */
+ HAL_I2C_STATE_READY = 0x20U, /*!< Peripheral Initialized and ready for use */
+ HAL_I2C_STATE_BUSY = 0x24U, /*!< An internal process is ongoing */
+ HAL_I2C_STATE_BUSY_TX = 0x21U, /*!< Data Transmission process is ongoing */
+ HAL_I2C_STATE_BUSY_RX = 0x22U, /*!< Data Reception process is ongoing */
+ HAL_I2C_STATE_LISTEN = 0x28U, /*!< Address Listen Mode is ongoing */
+ HAL_I2C_STATE_BUSY_TX_LISTEN = 0x29U, /*!< Address Listen Mode and Data Transmission
+ process is ongoing */
+ HAL_I2C_STATE_BUSY_RX_LISTEN = 0x2AU, /*!< Address Listen Mode and Data Reception
+ process is ongoing */
+ HAL_I2C_STATE_ABORT = 0x60U, /*!< Abort user request ongoing */
+ HAL_I2C_STATE_TIMEOUT = 0xA0U, /*!< Timeout state */
+ HAL_I2C_STATE_ERROR = 0xE0U /*!< Error */
+
+} HAL_I2C_StateTypeDef;
+
+/**
+ * @}
+ */
+
+/** @defgroup HAL_mode_structure_definition HAL mode structure definition
+ * @brief HAL Mode structure definition
+ * @note HAL I2C Mode value coding follow below described bitmap :\n
+ * b7 (not used)\n
+ * x : Should be set to 0\n
+ * b6\n
+ * 0 : None\n
+ * 1 : Memory (HAL I2C communication is in Memory Mode)\n
+ * b5\n
+ * 0 : None\n
+ * 1 : Slave (HAL I2C communication is in Slave Mode)\n
+ * b4\n
+ * 0 : None\n
+ * 1 : Master (HAL I2C communication is in Master Mode)\n
+ * b3-b2-b1-b0 (not used)\n
+ * xxxx : Should be set to 0000
+ * @{
+ */
+typedef enum
+{
+ HAL_I2C_MODE_NONE = 0x00U, /*!< No I2C communication on going */
+ HAL_I2C_MODE_MASTER = 0x10U, /*!< I2C communication is in Master Mode */
+ HAL_I2C_MODE_SLAVE = 0x20U, /*!< I2C communication is in Slave Mode */
+ HAL_I2C_MODE_MEM = 0x40U /*!< I2C communication is in Memory Mode */
+
+} HAL_I2C_ModeTypeDef;
+
+/**
+ * @}
+ */
+
+/** @defgroup I2C_Error_Code_definition I2C Error Code definition
+ * @brief I2C Error Code definition
+ * @{
+ */
+#define HAL_I2C_ERROR_NONE (0x00000000U) /*!< No error */
+#define HAL_I2C_ERROR_BERR (0x00000001U) /*!< BERR error */
+#define HAL_I2C_ERROR_ARLO (0x00000002U) /*!< ARLO error */
+#define HAL_I2C_ERROR_AF (0x00000004U) /*!< ACKF error */
+#define HAL_I2C_ERROR_OVR (0x00000008U) /*!< OVR error */
+#define HAL_I2C_ERROR_DMA (0x00000010U) /*!< DMA transfer error */
+#define HAL_I2C_ERROR_TIMEOUT (0x00000020U) /*!< Timeout error */
+#define HAL_I2C_ERROR_SIZE (0x00000040U) /*!< Size Management error */
+#define HAL_I2C_ERROR_DMA_PARAM (0x00000080U) /*!< DMA Parameter Error */
+#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1)
+#define HAL_I2C_ERROR_INVALID_CALLBACK (0x00000100U) /*!< Invalid Callback error */
+#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */
+#define HAL_I2C_ERROR_INVALID_PARAM (0x00000200U) /*!< Invalid Parameters error */
+/**
+ * @}
+ */
+
+/** @defgroup I2C_handle_Structure_definition I2C handle Structure definition
+ * @brief I2C handle Structure definition
+ * @{
+ */
+typedef struct __I2C_HandleTypeDef
+{
+ I2C_TypeDef *Instance; /*!< I2C registers base address */
+
+ I2C_InitTypeDef Init; /*!< I2C communication parameters */
+
+ uint8_t *pBuffPtr; /*!< Pointer to I2C transfer buffer */
+
+ uint16_t XferSize; /*!< I2C transfer size */
+
+ __IO uint16_t XferCount; /*!< I2C transfer counter */
+
+ __IO uint32_t XferOptions; /*!< I2C sequantial transfer options, this parameter can
+ be a value of @ref I2C_XFEROPTIONS */
+
+ __IO uint32_t PreviousState; /*!< I2C communication Previous state */
+
+ HAL_StatusTypeDef(*XferISR)(struct __I2C_HandleTypeDef *hi2c, uint32_t ITFlags, uint32_t ITSources);
+ /*!< I2C transfer IRQ handler function pointer */
+
+ DMA_HandleTypeDef *hdmatx; /*!< I2C Tx DMA handle parameters */
+
+ DMA_HandleTypeDef *hdmarx; /*!< I2C Rx DMA handle parameters */
+
+ HAL_LockTypeDef Lock; /*!< I2C locking object */
+
+ __IO HAL_I2C_StateTypeDef State; /*!< I2C communication state */
+
+ __IO HAL_I2C_ModeTypeDef Mode; /*!< I2C communication mode */
+
+ __IO uint32_t ErrorCode; /*!< I2C Error code */
+
+ __IO uint32_t AddrEventCount; /*!< I2C Address Event counter */
+
+#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1)
+ void (* MasterTxCpltCallback)(struct __I2C_HandleTypeDef *hi2c);
+ /*!< I2C Master Tx Transfer completed callback */
+ void (* MasterRxCpltCallback)(struct __I2C_HandleTypeDef *hi2c);
+ /*!< I2C Master Rx Transfer completed callback */
+ void (* SlaveTxCpltCallback)(struct __I2C_HandleTypeDef *hi2c);
+ /*!< I2C Slave Tx Transfer completed callback */
+ void (* SlaveRxCpltCallback)(struct __I2C_HandleTypeDef *hi2c);
+ /*!< I2C Slave Rx Transfer completed callback */
+ void (* ListenCpltCallback)(struct __I2C_HandleTypeDef *hi2c);
+ /*!< I2C Listen Complete callback */
+ void (* MemTxCpltCallback)(struct __I2C_HandleTypeDef *hi2c);
+ /*!< I2C Memory Tx Transfer completed callback */
+ void (* MemRxCpltCallback)(struct __I2C_HandleTypeDef *hi2c);
+ /*!< I2C Memory Rx Transfer completed callback */
+ void (* ErrorCallback)(struct __I2C_HandleTypeDef *hi2c);
+ /*!< I2C Error callback */
+ void (* AbortCpltCallback)(struct __I2C_HandleTypeDef *hi2c);
+ /*!< I2C Abort callback */
+
+ void (* AddrCallback)(struct __I2C_HandleTypeDef *hi2c, uint8_t TransferDirection, uint16_t AddrMatchCode);
+ /*!< I2C Slave Address Match callback */
+
+ void (* MspInitCallback)(struct __I2C_HandleTypeDef *hi2c);
+ /*!< I2C Msp Init callback */
+ void (* MspDeInitCallback)(struct __I2C_HandleTypeDef *hi2c);
+ /*!< I2C Msp DeInit callback */
+
+#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */
+} I2C_HandleTypeDef;
+
+#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1)
+/**
+ * @brief HAL I2C Callback ID enumeration definition
+ */
+typedef enum
+{
+ HAL_I2C_MASTER_TX_COMPLETE_CB_ID = 0x00U, /*!< I2C Master Tx Transfer completed callback ID */
+ HAL_I2C_MASTER_RX_COMPLETE_CB_ID = 0x01U, /*!< I2C Master Rx Transfer completed callback ID */
+ HAL_I2C_SLAVE_TX_COMPLETE_CB_ID = 0x02U, /*!< I2C Slave Tx Transfer completed callback ID */
+ HAL_I2C_SLAVE_RX_COMPLETE_CB_ID = 0x03U, /*!< I2C Slave Rx Transfer completed callback ID */
+ HAL_I2C_LISTEN_COMPLETE_CB_ID = 0x04U, /*!< I2C Listen Complete callback ID */
+ HAL_I2C_MEM_TX_COMPLETE_CB_ID = 0x05U, /*!< I2C Memory Tx Transfer callback ID */
+ HAL_I2C_MEM_RX_COMPLETE_CB_ID = 0x06U, /*!< I2C Memory Rx Transfer completed callback ID */
+ HAL_I2C_ERROR_CB_ID = 0x07U, /*!< I2C Error callback ID */
+ HAL_I2C_ABORT_CB_ID = 0x08U, /*!< I2C Abort callback ID */
+
+ HAL_I2C_MSPINIT_CB_ID = 0x09U, /*!< I2C Msp Init callback ID */
+ HAL_I2C_MSPDEINIT_CB_ID = 0x0AU /*!< I2C Msp DeInit callback ID */
+
+} HAL_I2C_CallbackIDTypeDef;
+
+/**
+ * @brief HAL I2C Callback pointer definition
+ */
+typedef void (*pI2C_CallbackTypeDef)(I2C_HandleTypeDef *hi2c);
+/*!< pointer to an I2C callback function */
+typedef void (*pI2C_AddrCallbackTypeDef)(I2C_HandleTypeDef *hi2c, uint8_t TransferDirection,
+ uint16_t AddrMatchCode);
+/*!< pointer to an I2C Address Match callback function */
+
+#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+/* Exported constants --------------------------------------------------------*/
+
+/** @defgroup I2C_Exported_Constants I2C Exported Constants
+ * @{
+ */
+
+/** @defgroup I2C_XFEROPTIONS I2C Sequential Transfer Options
+ * @{
+ */
+#define I2C_FIRST_FRAME ((uint32_t)I2C_SOFTEND_MODE)
+#define I2C_FIRST_AND_NEXT_FRAME ((uint32_t)(I2C_RELOAD_MODE | I2C_SOFTEND_MODE))
+#define I2C_NEXT_FRAME ((uint32_t)(I2C_RELOAD_MODE | I2C_SOFTEND_MODE))
+#define I2C_FIRST_AND_LAST_FRAME ((uint32_t)I2C_AUTOEND_MODE)
+#define I2C_LAST_FRAME ((uint32_t)I2C_AUTOEND_MODE)
+#define I2C_LAST_FRAME_NO_STOP ((uint32_t)I2C_SOFTEND_MODE)
+
+/* List of XferOptions in usage of :
+ * 1- Restart condition in all use cases (direction change or not)
+ */
+#define I2C_OTHER_FRAME (0x000000AAU)
+#define I2C_OTHER_AND_LAST_FRAME (0x0000AA00U)
+/**
+ * @}
+ */
+
+/** @defgroup I2C_ADDRESSING_MODE I2C Addressing Mode
+ * @{
+ */
+#define I2C_ADDRESSINGMODE_7BIT (0x00000001U)
+#define I2C_ADDRESSINGMODE_10BIT (0x00000002U)
+/**
+ * @}
+ */
+
+/** @defgroup I2C_DUAL_ADDRESSING_MODE I2C Dual Addressing Mode
+ * @{
+ */
+#define I2C_DUALADDRESS_DISABLE (0x00000000U)
+#define I2C_DUALADDRESS_ENABLE I2C_OAR2_OA2EN
+/**
+ * @}
+ */
+
+/** @defgroup I2C_OWN_ADDRESS2_MASKS I2C Own Address2 Masks
+ * @{
+ */
+#define I2C_OA2_NOMASK ((uint8_t)0x00U)
+#define I2C_OA2_MASK01 ((uint8_t)0x01U)
+#define I2C_OA2_MASK02 ((uint8_t)0x02U)
+#define I2C_OA2_MASK03 ((uint8_t)0x03U)
+#define I2C_OA2_MASK04 ((uint8_t)0x04U)
+#define I2C_OA2_MASK05 ((uint8_t)0x05U)
+#define I2C_OA2_MASK06 ((uint8_t)0x06U)
+#define I2C_OA2_MASK07 ((uint8_t)0x07U)
+/**
+ * @}
+ */
+
+/** @defgroup I2C_GENERAL_CALL_ADDRESSING_MODE I2C General Call Addressing Mode
+ * @{
+ */
+#define I2C_GENERALCALL_DISABLE (0x00000000U)
+#define I2C_GENERALCALL_ENABLE I2C_CR1_GCEN
+/**
+ * @}
+ */
+
+/** @defgroup I2C_NOSTRETCH_MODE I2C No-Stretch Mode
+ * @{
+ */
+#define I2C_NOSTRETCH_DISABLE (0x00000000U)
+#define I2C_NOSTRETCH_ENABLE I2C_CR1_NOSTRETCH
+/**
+ * @}
+ */
+
+/** @defgroup I2C_MEMORY_ADDRESS_SIZE I2C Memory Address Size
+ * @{
+ */
+#define I2C_MEMADD_SIZE_8BIT (0x00000001U)
+#define I2C_MEMADD_SIZE_16BIT (0x00000002U)
+/**
+ * @}
+ */
+
+/** @defgroup I2C_XFERDIRECTION I2C Transfer Direction Master Point of View
+ * @{
+ */
+#define I2C_DIRECTION_TRANSMIT (0x00000000U)
+#define I2C_DIRECTION_RECEIVE (0x00000001U)
+/**
+ * @}
+ */
+
+/** @defgroup I2C_RELOAD_END_MODE I2C Reload End Mode
+ * @{
+ */
+#define I2C_RELOAD_MODE I2C_CR2_RELOAD
+#define I2C_AUTOEND_MODE I2C_CR2_AUTOEND
+#define I2C_SOFTEND_MODE (0x00000000U)
+/**
+ * @}
+ */
+
+/** @defgroup I2C_START_STOP_MODE I2C Start or Stop Mode
+ * @{
+ */
+#define I2C_NO_STARTSTOP (0x00000000U)
+#define I2C_GENERATE_STOP (uint32_t)(0x80000000U | I2C_CR2_STOP)
+#define I2C_GENERATE_START_READ (uint32_t)(0x80000000U | I2C_CR2_START | I2C_CR2_RD_WRN)
+#define I2C_GENERATE_START_WRITE (uint32_t)(0x80000000U | I2C_CR2_START)
+/**
+ * @}
+ */
+
+/** @defgroup I2C_Interrupt_configuration_definition I2C Interrupt configuration definition
+ * @brief I2C Interrupt definition
+ * Elements values convention: 0xXXXXXXXX
+ * - XXXXXXXX : Interrupt control mask
+ * @{
+ */
+#define I2C_IT_ERRI I2C_CR1_ERRIE
+#define I2C_IT_TCI I2C_CR1_TCIE
+#define I2C_IT_STOPI I2C_CR1_STOPIE
+#define I2C_IT_NACKI I2C_CR1_NACKIE
+#define I2C_IT_ADDRI I2C_CR1_ADDRIE
+#define I2C_IT_RXI I2C_CR1_RXIE
+#define I2C_IT_TXI I2C_CR1_TXIE
+/**
+ * @}
+ */
+
+/** @defgroup I2C_Flag_definition I2C Flag definition
+ * @{
+ */
+#define I2C_FLAG_TXE I2C_ISR_TXE
+#define I2C_FLAG_TXIS I2C_ISR_TXIS
+#define I2C_FLAG_RXNE I2C_ISR_RXNE
+#define I2C_FLAG_ADDR I2C_ISR_ADDR
+#define I2C_FLAG_AF I2C_ISR_NACKF
+#define I2C_FLAG_STOPF I2C_ISR_STOPF
+#define I2C_FLAG_TC I2C_ISR_TC
+#define I2C_FLAG_TCR I2C_ISR_TCR
+#define I2C_FLAG_BERR I2C_ISR_BERR
+#define I2C_FLAG_ARLO I2C_ISR_ARLO
+#define I2C_FLAG_OVR I2C_ISR_OVR
+#define I2C_FLAG_PECERR I2C_ISR_PECERR
+#define I2C_FLAG_TIMEOUT I2C_ISR_TIMEOUT
+#define I2C_FLAG_ALERT I2C_ISR_ALERT
+#define I2C_FLAG_BUSY I2C_ISR_BUSY
+#define I2C_FLAG_DIR I2C_ISR_DIR
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/* Exported macros -----------------------------------------------------------*/
+
+/** @defgroup I2C_Exported_Macros I2C Exported Macros
+ * @{
+ */
+
+/** @brief Reset I2C handle state.
+ * @param __HANDLE__ specifies the I2C Handle.
+ * @retval None
+ */
+#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1)
+#define __HAL_I2C_RESET_HANDLE_STATE(__HANDLE__) do{ \
+ (__HANDLE__)->State = HAL_I2C_STATE_RESET; \
+ (__HANDLE__)->MspInitCallback = NULL; \
+ (__HANDLE__)->MspDeInitCallback = NULL; \
+ } while(0)
+#else
+#define __HAL_I2C_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_I2C_STATE_RESET)
+#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */
+
+/** @brief Enable the specified I2C interrupt.
+ * @param __HANDLE__ specifies the I2C Handle.
+ * @param __INTERRUPT__ specifies the interrupt source to enable.
+ * This parameter can be one of the following values:
+ * @arg @ref I2C_IT_ERRI Errors interrupt enable
+ * @arg @ref I2C_IT_TCI Transfer complete interrupt enable
+ * @arg @ref I2C_IT_STOPI STOP detection interrupt enable
+ * @arg @ref I2C_IT_NACKI NACK received interrupt enable
+ * @arg @ref I2C_IT_ADDRI Address match interrupt enable
+ * @arg @ref I2C_IT_RXI RX interrupt enable
+ * @arg @ref I2C_IT_TXI TX interrupt enable
+ *
+ * @retval None
+ */
+#define __HAL_I2C_ENABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->CR1 |= (__INTERRUPT__))
+
+/** @brief Disable the specified I2C interrupt.
+ * @param __HANDLE__ specifies the I2C Handle.
+ * @param __INTERRUPT__ specifies the interrupt source to disable.
+ * This parameter can be one of the following values:
+ * @arg @ref I2C_IT_ERRI Errors interrupt enable
+ * @arg @ref I2C_IT_TCI Transfer complete interrupt enable
+ * @arg @ref I2C_IT_STOPI STOP detection interrupt enable
+ * @arg @ref I2C_IT_NACKI NACK received interrupt enable
+ * @arg @ref I2C_IT_ADDRI Address match interrupt enable
+ * @arg @ref I2C_IT_RXI RX interrupt enable
+ * @arg @ref I2C_IT_TXI TX interrupt enable
+ *
+ * @retval None
+ */
+#define __HAL_I2C_DISABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->CR1 &= (~(__INTERRUPT__)))
+
+/** @brief Check whether the specified I2C interrupt source is enabled or not.
+ * @param __HANDLE__ specifies the I2C Handle.
+ * @param __INTERRUPT__ specifies the I2C interrupt source to check.
+ * This parameter can be one of the following values:
+ * @arg @ref I2C_IT_ERRI Errors interrupt enable
+ * @arg @ref I2C_IT_TCI Transfer complete interrupt enable
+ * @arg @ref I2C_IT_STOPI STOP detection interrupt enable
+ * @arg @ref I2C_IT_NACKI NACK received interrupt enable
+ * @arg @ref I2C_IT_ADDRI Address match interrupt enable
+ * @arg @ref I2C_IT_RXI RX interrupt enable
+ * @arg @ref I2C_IT_TXI TX interrupt enable
+ *
+ * @retval The new state of __INTERRUPT__ (SET or RESET).
+ */
+#define __HAL_I2C_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) ((((__HANDLE__)->Instance->CR1 & \
+ (__INTERRUPT__)) == (__INTERRUPT__)) ? SET : RESET)
+
+/** @brief Check whether the specified I2C flag is set or not.
+ * @param __HANDLE__ specifies the I2C Handle.
+ * @param __FLAG__ specifies the flag to check.
+ * This parameter can be one of the following values:
+ * @arg @ref I2C_FLAG_TXE Transmit data register empty
+ * @arg @ref I2C_FLAG_TXIS Transmit interrupt status
+ * @arg @ref I2C_FLAG_RXNE Receive data register not empty
+ * @arg @ref I2C_FLAG_ADDR Address matched (slave mode)
+ * @arg @ref I2C_FLAG_AF Acknowledge failure received flag
+ * @arg @ref I2C_FLAG_STOPF STOP detection flag
+ * @arg @ref I2C_FLAG_TC Transfer complete (master mode)
+ * @arg @ref I2C_FLAG_TCR Transfer complete reload
+ * @arg @ref I2C_FLAG_BERR Bus error
+ * @arg @ref I2C_FLAG_ARLO Arbitration lost
+ * @arg @ref I2C_FLAG_OVR Overrun/Underrun
+ * @arg @ref I2C_FLAG_PECERR PEC error in reception
+ * @arg @ref I2C_FLAG_TIMEOUT Timeout or Tlow detection flag
+ * @arg @ref I2C_FLAG_ALERT SMBus alert
+ * @arg @ref I2C_FLAG_BUSY Bus busy
+ * @arg @ref I2C_FLAG_DIR Transfer direction (slave mode)
+ *
+ * @retval The new state of __FLAG__ (SET or RESET).
+ */
+#define I2C_FLAG_MASK (0x0001FFFFU)
+#define __HAL_I2C_GET_FLAG(__HANDLE__, __FLAG__) (((((__HANDLE__)->Instance->ISR) & \
+ (__FLAG__)) == (__FLAG__)) ? SET : RESET)
+
+/** @brief Clear the I2C pending flags which are cleared by writing 1 in a specific bit.
+ * @param __HANDLE__ specifies the I2C Handle.
+ * @param __FLAG__ specifies the flag to clear.
+ * This parameter can be any combination of the following values:
+ * @arg @ref I2C_FLAG_TXE Transmit data register empty
+ * @arg @ref I2C_FLAG_ADDR Address matched (slave mode)
+ * @arg @ref I2C_FLAG_AF Acknowledge failure received flag
+ * @arg @ref I2C_FLAG_STOPF STOP detection flag
+ * @arg @ref I2C_FLAG_BERR Bus error
+ * @arg @ref I2C_FLAG_ARLO Arbitration lost
+ * @arg @ref I2C_FLAG_OVR Overrun/Underrun
+ * @arg @ref I2C_FLAG_PECERR PEC error in reception
+ * @arg @ref I2C_FLAG_TIMEOUT Timeout or Tlow detection flag
+ * @arg @ref I2C_FLAG_ALERT SMBus alert
+ *
+ * @retval None
+ */
+#define __HAL_I2C_CLEAR_FLAG(__HANDLE__, __FLAG__) (((__FLAG__) == I2C_FLAG_TXE) ? \
+ ((__HANDLE__)->Instance->ISR |= (__FLAG__)) : \
+ ((__HANDLE__)->Instance->ICR = (__FLAG__)))
+
+/** @brief Enable the specified I2C peripheral.
+ * @param __HANDLE__ specifies the I2C Handle.
+ * @retval None
+ */
+#define __HAL_I2C_ENABLE(__HANDLE__) (SET_BIT((__HANDLE__)->Instance->CR1, I2C_CR1_PE))
+
+/** @brief Disable the specified I2C peripheral.
+ * @param __HANDLE__ specifies the I2C Handle.
+ * @retval None
+ */
+#define __HAL_I2C_DISABLE(__HANDLE__) (CLEAR_BIT((__HANDLE__)->Instance->CR1, I2C_CR1_PE))
+
+/** @brief Generate a Non-Acknowledge I2C peripheral in Slave mode.
+ * @param __HANDLE__ specifies the I2C Handle.
+ * @retval None
+ */
+#define __HAL_I2C_GENERATE_NACK(__HANDLE__) (SET_BIT((__HANDLE__)->Instance->CR2, I2C_CR2_NACK))
+/**
+ * @}
+ */
+
+/* Include I2C HAL Extended module */
+#include "stm32f0xx_hal_i2c_ex.h"
+
+/* Exported functions --------------------------------------------------------*/
+/** @addtogroup I2C_Exported_Functions
+ * @{
+ */
+
+/** @addtogroup I2C_Exported_Functions_Group1 Initialization and de-initialization functions
+ * @{
+ */
+/* Initialization and de-initialization functions******************************/
+HAL_StatusTypeDef HAL_I2C_Init(I2C_HandleTypeDef *hi2c);
+HAL_StatusTypeDef HAL_I2C_DeInit(I2C_HandleTypeDef *hi2c);
+void HAL_I2C_MspInit(I2C_HandleTypeDef *hi2c);
+void HAL_I2C_MspDeInit(I2C_HandleTypeDef *hi2c);
+
+/* Callbacks Register/UnRegister functions ***********************************/
+#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1)
+HAL_StatusTypeDef HAL_I2C_RegisterCallback(I2C_HandleTypeDef *hi2c, HAL_I2C_CallbackIDTypeDef CallbackID,
+ pI2C_CallbackTypeDef pCallback);
+HAL_StatusTypeDef HAL_I2C_UnRegisterCallback(I2C_HandleTypeDef *hi2c, HAL_I2C_CallbackIDTypeDef CallbackID);
+
+HAL_StatusTypeDef HAL_I2C_RegisterAddrCallback(I2C_HandleTypeDef *hi2c, pI2C_AddrCallbackTypeDef pCallback);
+HAL_StatusTypeDef HAL_I2C_UnRegisterAddrCallback(I2C_HandleTypeDef *hi2c);
+#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */
+/**
+ * @}
+ */
+
+/** @addtogroup I2C_Exported_Functions_Group2 Input and Output operation functions
+ * @{
+ */
+/* IO operation functions ****************************************************/
+/******* Blocking mode: Polling */
+HAL_StatusTypeDef HAL_I2C_Master_Transmit(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData,
+ uint16_t Size, uint32_t Timeout);
+HAL_StatusTypeDef HAL_I2C_Master_Receive(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData,
+ uint16_t Size, uint32_t Timeout);
+HAL_StatusTypeDef HAL_I2C_Slave_Transmit(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size,
+ uint32_t Timeout);
+HAL_StatusTypeDef HAL_I2C_Slave_Receive(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size,
+ uint32_t Timeout);
+HAL_StatusTypeDef HAL_I2C_Mem_Write(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress,
+ uint16_t MemAddSize, uint8_t *pData, uint16_t Size, uint32_t Timeout);
+HAL_StatusTypeDef HAL_I2C_Mem_Read(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress,
+ uint16_t MemAddSize, uint8_t *pData, uint16_t Size, uint32_t Timeout);
+HAL_StatusTypeDef HAL_I2C_IsDeviceReady(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint32_t Trials,
+ uint32_t Timeout);
+
+/******* Non-Blocking mode: Interrupt */
+HAL_StatusTypeDef HAL_I2C_Master_Transmit_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData,
+ uint16_t Size);
+HAL_StatusTypeDef HAL_I2C_Master_Receive_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData,
+ uint16_t Size);
+HAL_StatusTypeDef HAL_I2C_Slave_Transmit_IT(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size);
+HAL_StatusTypeDef HAL_I2C_Slave_Receive_IT(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size);
+HAL_StatusTypeDef HAL_I2C_Mem_Write_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress,
+ uint16_t MemAddSize, uint8_t *pData, uint16_t Size);
+HAL_StatusTypeDef HAL_I2C_Mem_Read_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress,
+ uint16_t MemAddSize, uint8_t *pData, uint16_t Size);
+
+HAL_StatusTypeDef HAL_I2C_Master_Seq_Transmit_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData,
+ uint16_t Size, uint32_t XferOptions);
+HAL_StatusTypeDef HAL_I2C_Master_Seq_Receive_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData,
+ uint16_t Size, uint32_t XferOptions);
+HAL_StatusTypeDef HAL_I2C_Slave_Seq_Transmit_IT(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size,
+ uint32_t XferOptions);
+HAL_StatusTypeDef HAL_I2C_Slave_Seq_Receive_IT(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size,
+ uint32_t XferOptions);
+HAL_StatusTypeDef HAL_I2C_EnableListen_IT(I2C_HandleTypeDef *hi2c);
+HAL_StatusTypeDef HAL_I2C_DisableListen_IT(I2C_HandleTypeDef *hi2c);
+HAL_StatusTypeDef HAL_I2C_Master_Abort_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress);
+
+/******* Non-Blocking mode: DMA */
+HAL_StatusTypeDef HAL_I2C_Master_Transmit_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData,
+ uint16_t Size);
+HAL_StatusTypeDef HAL_I2C_Master_Receive_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData,
+ uint16_t Size);
+HAL_StatusTypeDef HAL_I2C_Slave_Transmit_DMA(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size);
+HAL_StatusTypeDef HAL_I2C_Slave_Receive_DMA(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size);
+HAL_StatusTypeDef HAL_I2C_Mem_Write_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress,
+ uint16_t MemAddSize, uint8_t *pData, uint16_t Size);
+HAL_StatusTypeDef HAL_I2C_Mem_Read_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress,
+ uint16_t MemAddSize, uint8_t *pData, uint16_t Size);
+
+HAL_StatusTypeDef HAL_I2C_Master_Seq_Transmit_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData,
+ uint16_t Size, uint32_t XferOptions);
+HAL_StatusTypeDef HAL_I2C_Master_Seq_Receive_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData,
+ uint16_t Size, uint32_t XferOptions);
+HAL_StatusTypeDef HAL_I2C_Slave_Seq_Transmit_DMA(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size,
+ uint32_t XferOptions);
+HAL_StatusTypeDef HAL_I2C_Slave_Seq_Receive_DMA(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size,
+ uint32_t XferOptions);
+/**
+ * @}
+ */
+
+/** @addtogroup I2C_IRQ_Handler_and_Callbacks IRQ Handler and Callbacks
+ * @{
+ */
+/******* I2C IRQHandler and Callbacks used in non blocking modes (Interrupt and DMA) */
+void HAL_I2C_EV_IRQHandler(I2C_HandleTypeDef *hi2c);
+void HAL_I2C_ER_IRQHandler(I2C_HandleTypeDef *hi2c);
+void HAL_I2C_MasterTxCpltCallback(I2C_HandleTypeDef *hi2c);
+void HAL_I2C_MasterRxCpltCallback(I2C_HandleTypeDef *hi2c);
+void HAL_I2C_SlaveTxCpltCallback(I2C_HandleTypeDef *hi2c);
+void HAL_I2C_SlaveRxCpltCallback(I2C_HandleTypeDef *hi2c);
+void HAL_I2C_AddrCallback(I2C_HandleTypeDef *hi2c, uint8_t TransferDirection, uint16_t AddrMatchCode);
+void HAL_I2C_ListenCpltCallback(I2C_HandleTypeDef *hi2c);
+void HAL_I2C_MemTxCpltCallback(I2C_HandleTypeDef *hi2c);
+void HAL_I2C_MemRxCpltCallback(I2C_HandleTypeDef *hi2c);
+void HAL_I2C_ErrorCallback(I2C_HandleTypeDef *hi2c);
+void HAL_I2C_AbortCpltCallback(I2C_HandleTypeDef *hi2c);
+/**
+ * @}
+ */
+
+/** @addtogroup I2C_Exported_Functions_Group3 Peripheral State, Mode and Error functions
+ * @{
+ */
+/* Peripheral State, Mode and Error functions *********************************/
+HAL_I2C_StateTypeDef HAL_I2C_GetState(I2C_HandleTypeDef *hi2c);
+HAL_I2C_ModeTypeDef HAL_I2C_GetMode(I2C_HandleTypeDef *hi2c);
+uint32_t HAL_I2C_GetError(I2C_HandleTypeDef *hi2c);
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/* Private constants ---------------------------------------------------------*/
+/** @defgroup I2C_Private_Constants I2C Private Constants
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/* Private macros ------------------------------------------------------------*/
+/** @defgroup I2C_Private_Macro I2C Private Macros
+ * @{
+ */
+
+#define IS_I2C_ADDRESSING_MODE(MODE) (((MODE) == I2C_ADDRESSINGMODE_7BIT) || \
+ ((MODE) == I2C_ADDRESSINGMODE_10BIT))
+
+#define IS_I2C_DUAL_ADDRESS(ADDRESS) (((ADDRESS) == I2C_DUALADDRESS_DISABLE) || \
+ ((ADDRESS) == I2C_DUALADDRESS_ENABLE))
+
+#define IS_I2C_OWN_ADDRESS2_MASK(MASK) (((MASK) == I2C_OA2_NOMASK) || \
+ ((MASK) == I2C_OA2_MASK01) || \
+ ((MASK) == I2C_OA2_MASK02) || \
+ ((MASK) == I2C_OA2_MASK03) || \
+ ((MASK) == I2C_OA2_MASK04) || \
+ ((MASK) == I2C_OA2_MASK05) || \
+ ((MASK) == I2C_OA2_MASK06) || \
+ ((MASK) == I2C_OA2_MASK07))
+
+#define IS_I2C_GENERAL_CALL(CALL) (((CALL) == I2C_GENERALCALL_DISABLE) || \
+ ((CALL) == I2C_GENERALCALL_ENABLE))
+
+#define IS_I2C_NO_STRETCH(STRETCH) (((STRETCH) == I2C_NOSTRETCH_DISABLE) || \
+ ((STRETCH) == I2C_NOSTRETCH_ENABLE))
+
+#define IS_I2C_MEMADD_SIZE(SIZE) (((SIZE) == I2C_MEMADD_SIZE_8BIT) || \
+ ((SIZE) == I2C_MEMADD_SIZE_16BIT))
+
+#define IS_TRANSFER_MODE(MODE) (((MODE) == I2C_RELOAD_MODE) || \
+ ((MODE) == I2C_AUTOEND_MODE) || \
+ ((MODE) == I2C_SOFTEND_MODE))
+
+#define IS_TRANSFER_REQUEST(REQUEST) (((REQUEST) == I2C_GENERATE_STOP) || \
+ ((REQUEST) == I2C_GENERATE_START_READ) || \
+ ((REQUEST) == I2C_GENERATE_START_WRITE) || \
+ ((REQUEST) == I2C_NO_STARTSTOP))
+
+#define IS_I2C_TRANSFER_OPTIONS_REQUEST(REQUEST) (((REQUEST) == I2C_FIRST_FRAME) || \
+ ((REQUEST) == I2C_FIRST_AND_NEXT_FRAME) || \
+ ((REQUEST) == I2C_NEXT_FRAME) || \
+ ((REQUEST) == I2C_FIRST_AND_LAST_FRAME) || \
+ ((REQUEST) == I2C_LAST_FRAME) || \
+ ((REQUEST) == I2C_LAST_FRAME_NO_STOP) || \
+ IS_I2C_TRANSFER_OTHER_OPTIONS_REQUEST(REQUEST))
+
+#define IS_I2C_TRANSFER_OTHER_OPTIONS_REQUEST(REQUEST) (((REQUEST) == I2C_OTHER_FRAME) || \
+ ((REQUEST) == I2C_OTHER_AND_LAST_FRAME))
+
+#define I2C_RESET_CR2(__HANDLE__) ((__HANDLE__)->Instance->CR2 &= \
+ (uint32_t)~((uint32_t)(I2C_CR2_SADD | I2C_CR2_HEAD10R | \
+ I2C_CR2_NBYTES | I2C_CR2_RELOAD | \
+ I2C_CR2_RD_WRN)))
+
+#define I2C_GET_ADDR_MATCH(__HANDLE__) ((uint16_t)(((__HANDLE__)->Instance->ISR & I2C_ISR_ADDCODE) \
+ >> 16U))
+#define I2C_GET_DIR(__HANDLE__) ((uint8_t)(((__HANDLE__)->Instance->ISR & I2C_ISR_DIR) \
+ >> 16U))
+#define I2C_GET_STOP_MODE(__HANDLE__) ((__HANDLE__)->Instance->CR2 & I2C_CR2_AUTOEND)
+#define I2C_GET_OWN_ADDRESS1(__HANDLE__) ((uint16_t)((__HANDLE__)->Instance->OAR1 & I2C_OAR1_OA1))
+#define I2C_GET_OWN_ADDRESS2(__HANDLE__) ((uint16_t)((__HANDLE__)->Instance->OAR2 & I2C_OAR2_OA2))
+
+#define IS_I2C_OWN_ADDRESS1(ADDRESS1) ((ADDRESS1) <= 0x000003FFU)
+#define IS_I2C_OWN_ADDRESS2(ADDRESS2) ((ADDRESS2) <= (uint16_t)0x00FFU)
+
+#define I2C_MEM_ADD_MSB(__ADDRESS__) ((uint8_t)((uint16_t)(((uint16_t)((__ADDRESS__) & \
+ (uint16_t)(0xFF00U))) >> 8U)))
+#define I2C_MEM_ADD_LSB(__ADDRESS__) ((uint8_t)((uint16_t)((__ADDRESS__) & (uint16_t)(0x00FFU))))
+
+#define I2C_GENERATE_START(__ADDMODE__,__ADDRESS__) (((__ADDMODE__) == I2C_ADDRESSINGMODE_7BIT) ? \
+ (uint32_t)((((uint32_t)(__ADDRESS__) & (I2C_CR2_SADD)) | \
+ (I2C_CR2_START) | (I2C_CR2_AUTOEND)) & \
+ (~I2C_CR2_RD_WRN)) : \
+ (uint32_t)((((uint32_t)(__ADDRESS__) & (I2C_CR2_SADD)) | \
+ (I2C_CR2_ADD10) | (I2C_CR2_START)) & \
+ (~I2C_CR2_RD_WRN)))
+
+#define I2C_CHECK_FLAG(__ISR__, __FLAG__) ((((__ISR__) & ((__FLAG__) & I2C_FLAG_MASK)) == \
+ ((__FLAG__) & I2C_FLAG_MASK)) ? SET : RESET)
+#define I2C_CHECK_IT_SOURCE(__CR1__, __IT__) ((((__CR1__) & (__IT__)) == (__IT__)) ? SET : RESET)
+/**
+ * @}
+ */
+
+/* Private Functions ---------------------------------------------------------*/
+/** @defgroup I2C_Private_Functions I2C Private Functions
+ * @{
+ */
+/* Private functions are defined in stm32f0xx_hal_i2c.c file */
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+#ifdef __cplusplus
+}
+#endif
+
+
+#endif /* STM32F0xx_HAL_I2C_H */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal_i2c_ex.h b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal_i2c_ex.h
new file mode 100644
index 0000000..f61046a
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal_i2c_ex.h
@@ -0,0 +1,193 @@
+/**
+ ******************************************************************************
+ * @file stm32f0xx_hal_i2c_ex.h
+ * @author MCD Application Team
+ * @brief Header file of I2C HAL Extended module.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2016 STMicroelectronics.
+ * All rights reserved.
+ *
+ * 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 STM32F0xx_HAL_I2C_EX_H
+#define STM32F0xx_HAL_I2C_EX_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f0xx_hal_def.h"
+
+/** @addtogroup STM32F0xx_HAL_Driver
+ * @{
+ */
+
+/** @addtogroup I2CEx
+ * @{
+ */
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+
+/** @defgroup I2CEx_Exported_Constants I2C Extended Exported Constants
+ * @{
+ */
+
+/** @defgroup I2CEx_Analog_Filter I2C Extended Analog Filter
+ * @{
+ */
+#define I2C_ANALOGFILTER_ENABLE 0x00000000U
+#define I2C_ANALOGFILTER_DISABLE I2C_CR1_ANFOFF
+/**
+ * @}
+ */
+
+/** @defgroup I2CEx_FastModePlus I2C Extended Fast Mode Plus
+ * @{
+ */
+#define I2C_FMP_NOT_SUPPORTED 0xAAAA0000U /*!< Fast Mode Plus not supported */
+#if defined(SYSCFG_CFGR1_I2C_FMP_PA9)
+#define I2C_FASTMODEPLUS_PA9 SYSCFG_CFGR1_I2C_FMP_PA9 /*!< Enable Fast Mode Plus on PA9 */
+#define I2C_FASTMODEPLUS_PA10 SYSCFG_CFGR1_I2C_FMP_PA10 /*!< Enable Fast Mode Plus on PA10 */
+#else
+#define I2C_FASTMODEPLUS_PA9 (uint32_t)(0x00000001U | I2C_FMP_NOT_SUPPORTED) /*!< Fast Mode Plus PA9 not supported */
+#define I2C_FASTMODEPLUS_PA10 (uint32_t)(0x00000002U | I2C_FMP_NOT_SUPPORTED) /*!< Fast Mode Plus PA10 not supported */
+#endif /* SYSCFG_CFGR1_I2C_FMP_PA9 */
+#define I2C_FASTMODEPLUS_PB6 SYSCFG_CFGR1_I2C_FMP_PB6 /*!< Enable Fast Mode Plus on PB6 */
+#define I2C_FASTMODEPLUS_PB7 SYSCFG_CFGR1_I2C_FMP_PB7 /*!< Enable Fast Mode Plus on PB7 */
+#define I2C_FASTMODEPLUS_PB8 SYSCFG_CFGR1_I2C_FMP_PB8 /*!< Enable Fast Mode Plus on PB8 */
+#define I2C_FASTMODEPLUS_PB9 SYSCFG_CFGR1_I2C_FMP_PB9 /*!< Enable Fast Mode Plus on PB9 */
+#if defined(SYSCFG_CFGR1_I2C_FMP_I2C1)
+#define I2C_FASTMODEPLUS_I2C1 SYSCFG_CFGR1_I2C_FMP_I2C1 /*!< Enable Fast Mode Plus on I2C1 pins */
+#else
+#define I2C_FASTMODEPLUS_I2C1 (uint32_t)(0x00000100U | I2C_FMP_NOT_SUPPORTED) /*!< Fast Mode Plus I2C1 not supported */
+#endif /* SYSCFG_CFGR1_I2C_FMP_I2C1 */
+#if defined(SYSCFG_CFGR1_I2C_FMP_I2C2)
+#define I2C_FASTMODEPLUS_I2C2 SYSCFG_CFGR1_I2C_FMP_I2C2 /*!< Enable Fast Mode Plus on I2C2 pins */
+#else
+#define I2C_FASTMODEPLUS_I2C2 (uint32_t)(0x00000200U | I2C_FMP_NOT_SUPPORTED) /*!< Fast Mode Plus I2C2 not supported */
+#endif /* SYSCFG_CFGR1_I2C_FMP_I2C2 */
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions --------------------------------------------------------*/
+
+/** @addtogroup I2CEx_Exported_Functions I2C Extended Exported Functions
+ * @{
+ */
+
+/** @addtogroup I2CEx_Exported_Functions_Group1 Extended features functions
+ * @brief Extended features functions
+ * @{
+ */
+
+/** @addtogroup I2CEx_Exported_Functions_Group1 Filter Mode Functions
+ * @{
+ */
+HAL_StatusTypeDef HAL_I2CEx_ConfigAnalogFilter(I2C_HandleTypeDef *hi2c,
+ uint32_t AnalogFilter);
+HAL_StatusTypeDef HAL_I2CEx_ConfigDigitalFilter(I2C_HandleTypeDef *hi2c,
+ uint32_t DigitalFilter);
+/**
+ * @}
+ */
+#if defined(I2C_CR1_WUPEN)
+
+/** @addtogroup I2CEx_Exported_Functions_Group2 WakeUp Mode Functions
+ * @{
+ */
+HAL_StatusTypeDef HAL_I2CEx_EnableWakeUp(I2C_HandleTypeDef *hi2c);
+HAL_StatusTypeDef HAL_I2CEx_DisableWakeUp(I2C_HandleTypeDef *hi2c);
+/**
+ * @}
+ */
+#endif /* I2C_CR1_WUPEN */
+
+/** @addtogroup I2CEx_Exported_Functions_Group3 Fast Mode Plus Functions
+ * @{
+ */
+void HAL_I2CEx_EnableFastModePlus(uint32_t ConfigFastModePlus);
+void HAL_I2CEx_DisableFastModePlus(uint32_t ConfigFastModePlus);
+/**
+ * @}
+ */
+
+/* Private constants ---------------------------------------------------------*/
+/** @defgroup I2CEx_Private_Constants I2C Extended Private Constants
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/* Private macros ------------------------------------------------------------*/
+/** @defgroup I2CEx_Private_Macro I2C Extended Private Macros
+ * @{
+ */
+#define IS_I2C_ANALOG_FILTER(FILTER) (((FILTER) == I2C_ANALOGFILTER_ENABLE) || \
+ ((FILTER) == I2C_ANALOGFILTER_DISABLE))
+
+#define IS_I2C_DIGITAL_FILTER(FILTER) ((FILTER) <= 0x0000000FU)
+
+#define IS_I2C_FASTMODEPLUS(__CONFIG__) ((((__CONFIG__) & I2C_FMP_NOT_SUPPORTED) != I2C_FMP_NOT_SUPPORTED) && \
+ ((((__CONFIG__) & (I2C_FASTMODEPLUS_PA9)) == I2C_FASTMODEPLUS_PA9) || \
+ (((__CONFIG__) & (I2C_FASTMODEPLUS_PA10)) == I2C_FASTMODEPLUS_PA10) || \
+ (((__CONFIG__) & (I2C_FASTMODEPLUS_PB6)) == I2C_FASTMODEPLUS_PB6) || \
+ (((__CONFIG__) & (I2C_FASTMODEPLUS_PB7)) == I2C_FASTMODEPLUS_PB7) || \
+ (((__CONFIG__) & (I2C_FASTMODEPLUS_PB8)) == I2C_FASTMODEPLUS_PB8) || \
+ (((__CONFIG__) & (I2C_FASTMODEPLUS_PB9)) == I2C_FASTMODEPLUS_PB9) || \
+ (((__CONFIG__) & (I2C_FASTMODEPLUS_I2C1)) == I2C_FASTMODEPLUS_I2C1) || \
+ (((__CONFIG__) & (I2C_FASTMODEPLUS_I2C2)) == I2C_FASTMODEPLUS_I2C2)))
+/**
+ * @}
+ */
+
+/* Private Functions ---------------------------------------------------------*/
+/** @defgroup I2CEx_Private_Functions I2C Extended Private Functions
+ * @{
+ */
+/* Private functions are defined in stm32f0xx_hal_i2c_ex.c file */
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* STM32F0xx_HAL_I2C_EX_H */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal_pwr.h b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal_pwr.h
new file mode 100644
index 0000000..bab5997
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal_pwr.h
@@ -0,0 +1,189 @@
+/**
+ ******************************************************************************
+ * @file stm32f0xx_hal_pwr.h
+ * @author MCD Application Team
+ * @brief Header file of PWR HAL module.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2016 STMicroelectronics.
+ * All rights reserved.
+ *
+ * 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 __STM32F0xx_HAL_PWR_H
+#define __STM32F0xx_HAL_PWR_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f0xx_hal_def.h"
+
+/** @addtogroup STM32F0xx_HAL_Driver
+ * @{
+ */
+
+/** @addtogroup PWR PWR
+ * @{
+ */
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+
+/** @defgroup PWR_Exported_Constants PWR Exported Constants
+ * @{
+ */
+
+/** @defgroup PWR_Regulator_state_in_STOP_mode PWR Regulator state in STOP mode
+ * @{
+ */
+#define PWR_MAINREGULATOR_ON (0x00000000U)
+#define PWR_LOWPOWERREGULATOR_ON PWR_CR_LPDS
+
+#define IS_PWR_REGULATOR(REGULATOR) (((REGULATOR) == PWR_MAINREGULATOR_ON) || \
+ ((REGULATOR) == PWR_LOWPOWERREGULATOR_ON))
+/**
+ * @}
+ */
+
+/** @defgroup PWR_SLEEP_mode_entry PWR SLEEP mode entry
+ * @{
+ */
+#define PWR_SLEEPENTRY_WFI ((uint8_t)0x01U)
+#define PWR_SLEEPENTRY_WFE ((uint8_t)0x02U)
+#define IS_PWR_SLEEP_ENTRY(ENTRY) (((ENTRY) == PWR_SLEEPENTRY_WFI) || ((ENTRY) == PWR_SLEEPENTRY_WFE))
+/**
+ * @}
+ */
+
+/** @defgroup PWR_STOP_mode_entry PWR STOP mode entry
+ * @{
+ */
+#define PWR_STOPENTRY_WFI ((uint8_t)0x01U)
+#define PWR_STOPENTRY_WFE ((uint8_t)0x02U)
+#define IS_PWR_STOP_ENTRY(ENTRY) (((ENTRY) == PWR_STOPENTRY_WFI) || ((ENTRY) == PWR_STOPENTRY_WFE))
+/**
+ * @}
+ */
+
+
+/**
+ * @}
+ */
+
+/* Exported macro ------------------------------------------------------------*/
+/** @defgroup PWR_Exported_Macro PWR Exported Macro
+ * @{
+ */
+
+/** @brief Check PWR flag is set or not.
+ * @param __FLAG__ specifies the flag to check.
+ * This parameter can be one of the following values:
+ * @arg PWR_FLAG_WU: Wake Up flag. This flag indicates that a wakeup event
+ * was received from the WKUP pin or from the RTC alarm (Alarm A),
+ * RTC Tamper event, RTC TimeStamp event or RTC Wakeup.
+ * An additional wakeup event is detected if the WKUP pin is enabled
+ * (by setting the EWUP bit) when the WKUP pin level is already high.
+ * @arg PWR_FLAG_SB: StandBy flag. This flag indicates that the system was
+ * resumed from StandBy mode.
+ * @arg PWR_FLAG_PVDO: PVD Output. This flag is valid only if PVD is enabled
+ * by the HAL_PWR_EnablePVD() function. The PVD is stopped by Standby mode
+ * For this reason, this bit is equal to 0 after Standby or reset
+ * until the PVDE bit is set.
+ * Warning: this Flag is not available on STM32F030x8 products
+ * @arg PWR_FLAG_VREFINTRDY: This flag indicates that the internal reference
+ * voltage VREFINT is ready.
+ * Warning: this Flag is not available on STM32F030x8 products
+ * @retval The new state of __FLAG__ (TRUE or FALSE).
+ */
+#define __HAL_PWR_GET_FLAG(__FLAG__) ((PWR->CSR & (__FLAG__)) == (__FLAG__))
+
+/** @brief Clear the PWR's pending flags.
+ * @param __FLAG__ specifies the flag to clear.
+ * This parameter can be one of the following values:
+ * @arg PWR_FLAG_WU: Wake Up flag
+ * @arg PWR_FLAG_SB: StandBy flag
+ */
+#define __HAL_PWR_CLEAR_FLAG(__FLAG__) (PWR->CR |= (__FLAG__) << 2U)
+
+
+/**
+ * @}
+ */
+
+/* Include PWR HAL Extension module */
+#include "stm32f0xx_hal_pwr_ex.h"
+
+/* Exported functions --------------------------------------------------------*/
+
+/** @addtogroup PWR_Exported_Functions PWR Exported Functions
+ * @{
+ */
+
+/** @addtogroup PWR_Exported_Functions_Group1 Initialization and de-initialization functions
+ * @{
+ */
+
+/* Initialization and de-initialization functions *****************************/
+void HAL_PWR_DeInit(void);
+
+/**
+ * @}
+ */
+
+/** @addtogroup PWR_Exported_Functions_Group2 Peripheral Control functions
+ * @{
+ */
+
+/* Peripheral Control functions **********************************************/
+void HAL_PWR_EnableBkUpAccess(void);
+void HAL_PWR_DisableBkUpAccess(void);
+
+/* WakeUp pins configuration functions ****************************************/
+void HAL_PWR_EnableWakeUpPin(uint32_t WakeUpPinx);
+void HAL_PWR_DisableWakeUpPin(uint32_t WakeUpPinx);
+
+/* Low Power modes configuration functions ************************************/
+void HAL_PWR_EnterSTOPMode(uint32_t Regulator, uint8_t STOPEntry);
+void HAL_PWR_EnterSLEEPMode(uint32_t Regulator, uint8_t SLEEPEntry);
+void HAL_PWR_EnterSTANDBYMode(void);
+
+void HAL_PWR_EnableSleepOnExit(void);
+void HAL_PWR_DisableSleepOnExit(void);
+void HAL_PWR_EnableSEVOnPend(void);
+void HAL_PWR_DisableSEVOnPend(void);
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+#ifdef __cplusplus
+}
+#endif
+
+
+#endif /* __STM32F0xx_HAL_PWR_H */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
+
diff --git a/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal_pwr_ex.h b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal_pwr_ex.h
new file mode 100644
index 0000000..4fbac5c
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal_pwr_ex.h
@@ -0,0 +1,459 @@
+/**
+ ******************************************************************************
+ * @file stm32f0xx_hal_pwr_ex.h
+ * @author MCD Application Team
+ * @brief Header file of PWR HAL Extension module.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2016 STMicroelectronics.
+ * All rights reserved.
+ *
+ * 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 __STM32F0xx_HAL_PWR_EX_H
+#define __STM32F0xx_HAL_PWR_EX_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f0xx_hal_def.h"
+
+/** @addtogroup STM32F0xx_HAL_Driver
+ * @{
+ */
+
+/** @addtogroup PWREx
+ * @{
+ */
+
+/* Exported types ------------------------------------------------------------*/
+
+/** @defgroup PWREx_Exported_Types PWREx Exported Types
+ * @{
+ */
+
+#if defined (STM32F031x6) || defined (STM32F042x6) || defined (STM32F051x8) || \
+ defined (STM32F071xB) || defined (STM32F072xB) || \
+ defined (STM32F091xC)
+
+/**
+ * @brief PWR PVD configuration structure definition
+ */
+typedef struct
+{
+ uint32_t PVDLevel; /*!< PVDLevel: Specifies the PVD detection level
+ This parameter can be a value of @ref PWREx_PVD_detection_level */
+
+ uint32_t Mode; /*!< Mode: Specifies the operating mode for the selected pins.
+ This parameter can be a value of @ref PWREx_PVD_Mode */
+}PWR_PVDTypeDef;
+
+#endif /* defined (STM32F031x6) || defined (STM32F042x6) || defined (STM32F051x8) || */
+ /* defined (STM32F071xB) || defined (STM32F072xB) || */
+ /* defined (STM32F091xC) */
+/**
+ * @}
+ */
+/* Exported constants --------------------------------------------------------*/
+
+/** @defgroup PWREx_Exported_Constants PWREx Exported Constants
+ * @{
+ */
+
+
+/** @defgroup PWREx_WakeUp_Pins PWREx Wakeup Pins
+ * @{
+ */
+#if defined (STM32F071xB) || defined (STM32F072xB) || defined (STM32F078xx) || \
+ defined (STM32F091xC) || defined (STM32F098xx)
+#define PWR_WAKEUP_PIN1 ((uint32_t)PWR_CSR_EWUP1)
+#define PWR_WAKEUP_PIN2 ((uint32_t)PWR_CSR_EWUP2)
+#define PWR_WAKEUP_PIN3 ((uint32_t)PWR_CSR_EWUP3)
+#define PWR_WAKEUP_PIN4 ((uint32_t)PWR_CSR_EWUP4)
+#define PWR_WAKEUP_PIN5 ((uint32_t)PWR_CSR_EWUP5)
+#define PWR_WAKEUP_PIN6 ((uint32_t)PWR_CSR_EWUP6)
+#define PWR_WAKEUP_PIN7 ((uint32_t)PWR_CSR_EWUP7)
+#define PWR_WAKEUP_PIN8 ((uint32_t)PWR_CSR_EWUP8)
+
+#define IS_PWR_WAKEUP_PIN(PIN) (((PIN) == PWR_WAKEUP_PIN1) || \
+ ((PIN) == PWR_WAKEUP_PIN2) || \
+ ((PIN) == PWR_WAKEUP_PIN3) || \
+ ((PIN) == PWR_WAKEUP_PIN4) || \
+ ((PIN) == PWR_WAKEUP_PIN5) || \
+ ((PIN) == PWR_WAKEUP_PIN6) || \
+ ((PIN) == PWR_WAKEUP_PIN7) || \
+ ((PIN) == PWR_WAKEUP_PIN8))
+
+#elif defined(STM32F030xC) || defined (STM32F070xB)
+#define PWR_WAKEUP_PIN1 ((uint32_t)PWR_CSR_EWUP1)
+#define PWR_WAKEUP_PIN2 ((uint32_t)PWR_CSR_EWUP2)
+#define PWR_WAKEUP_PIN4 ((uint32_t)PWR_CSR_EWUP4)
+#define PWR_WAKEUP_PIN5 ((uint32_t)PWR_CSR_EWUP5)
+#define PWR_WAKEUP_PIN6 ((uint32_t)PWR_CSR_EWUP6)
+#define PWR_WAKEUP_PIN7 ((uint32_t)PWR_CSR_EWUP7)
+
+#define IS_PWR_WAKEUP_PIN(PIN) (((PIN) == PWR_WAKEUP_PIN1) || \
+ ((PIN) == PWR_WAKEUP_PIN2) || \
+ ((PIN) == PWR_WAKEUP_PIN4) || \
+ ((PIN) == PWR_WAKEUP_PIN5) || \
+ ((PIN) == PWR_WAKEUP_PIN6) || \
+ ((PIN) == PWR_WAKEUP_PIN7))
+
+#elif defined(STM32F042x6) || defined (STM32F048xx)
+#define PWR_WAKEUP_PIN1 ((uint32_t)PWR_CSR_EWUP1)
+#define PWR_WAKEUP_PIN2 ((uint32_t)PWR_CSR_EWUP2)
+#define PWR_WAKEUP_PIN4 ((uint32_t)PWR_CSR_EWUP4)
+#define PWR_WAKEUP_PIN6 ((uint32_t)PWR_CSR_EWUP6)
+#define PWR_WAKEUP_PIN7 ((uint32_t)PWR_CSR_EWUP7)
+
+#define IS_PWR_WAKEUP_PIN(PIN) (((PIN) == PWR_WAKEUP_PIN1) || \
+ ((PIN) == PWR_WAKEUP_PIN2) || \
+ ((PIN) == PWR_WAKEUP_PIN4) || \
+ ((PIN) == PWR_WAKEUP_PIN6) || \
+ ((PIN) == PWR_WAKEUP_PIN7))
+
+#else
+#define PWR_WAKEUP_PIN1 ((uint32_t)PWR_CSR_EWUP1)
+#define PWR_WAKEUP_PIN2 ((uint32_t)PWR_CSR_EWUP2)
+
+
+#define IS_PWR_WAKEUP_PIN(PIN) (((PIN) == PWR_WAKEUP_PIN1) || \
+ ((PIN) == PWR_WAKEUP_PIN2))
+
+#endif
+
+/**
+ * @}
+ */
+
+/** @defgroup PWREx_EXTI_Line PWREx EXTI Line
+ * @{
+ */
+#if defined (STM32F031x6) || defined (STM32F042x6) || defined (STM32F051x8) || \
+ defined (STM32F071xB) || defined (STM32F072xB) || \
+ defined (STM32F091xC)
+
+#define PWR_EXTI_LINE_PVD ((uint32_t)EXTI_IMR_MR16) /*!< External interrupt line 16 Connected to the PVD EXTI Line */
+
+#endif /* defined (STM32F031x6) || defined (STM32F042x6) || defined (STM32F051x8) || */
+ /* defined (STM32F071xB) || defined (STM32F072xB) || */
+ /* defined (STM32F091xC) */
+
+#if defined (STM32F042x6) || defined (STM32F048xx) || \
+ defined (STM32F071xB) || defined (STM32F072xB) || defined (STM32F078xx) || \
+ defined (STM32F091xC) || defined (STM32F098xx)
+
+#define PWR_EXTI_LINE_VDDIO2 ((uint32_t)EXTI_IMR_MR31) /*!< External interrupt line 31 Connected to the Vddio2 Monitor EXTI Line */
+
+#endif /* defined (STM32F042x6) || defined (STM32F048xx) ||\
+ defined (STM32F071xB) || defined (STM32F072xB) || defined (STM32F078xx) || \
+ defined (STM32F091xC) || defined (STM32F098xx) ||*/
+/**
+ * @}
+ */
+
+#if defined (STM32F031x6) || defined (STM32F042x6) || defined (STM32F051x8) || \
+ defined (STM32F071xB) || defined (STM32F072xB) || \
+ defined (STM32F091xC)
+/** @defgroup PWREx_PVD_detection_level PWREx PVD detection level
+ * @{
+ */
+#define PWR_PVDLEVEL_0 PWR_CR_PLS_LEV0
+#define PWR_PVDLEVEL_1 PWR_CR_PLS_LEV1
+#define PWR_PVDLEVEL_2 PWR_CR_PLS_LEV2
+#define PWR_PVDLEVEL_3 PWR_CR_PLS_LEV3
+#define PWR_PVDLEVEL_4 PWR_CR_PLS_LEV4
+#define PWR_PVDLEVEL_5 PWR_CR_PLS_LEV5
+#define PWR_PVDLEVEL_6 PWR_CR_PLS_LEV6
+#define PWR_PVDLEVEL_7 PWR_CR_PLS_LEV7
+#define IS_PWR_PVD_LEVEL(LEVEL) (((LEVEL) == PWR_PVDLEVEL_0) || ((LEVEL) == PWR_PVDLEVEL_1)|| \
+ ((LEVEL) == PWR_PVDLEVEL_2) || ((LEVEL) == PWR_PVDLEVEL_3)|| \
+ ((LEVEL) == PWR_PVDLEVEL_4) || ((LEVEL) == PWR_PVDLEVEL_5)|| \
+ ((LEVEL) == PWR_PVDLEVEL_6) || ((LEVEL) == PWR_PVDLEVEL_7))
+/**
+ * @}
+ */
+
+/** @defgroup PWREx_PVD_Mode PWREx PVD Mode
+ * @{
+ */
+#define PWR_PVD_MODE_NORMAL (0x00000000U) /*!< basic mode is used */
+#define PWR_PVD_MODE_IT_RISING (0x00010001U) /*!< External Interrupt Mode with Rising edge trigger detection */
+#define PWR_PVD_MODE_IT_FALLING (0x00010002U) /*!< External Interrupt Mode with Falling edge trigger detection */
+#define PWR_PVD_MODE_IT_RISING_FALLING (0x00010003U) /*!< External Interrupt Mode with Rising/Falling edge trigger detection */
+#define PWR_PVD_MODE_EVENT_RISING (0x00020001U) /*!< Event Mode with Rising edge trigger detection */
+#define PWR_PVD_MODE_EVENT_FALLING (0x00020002U) /*!< Event Mode with Falling edge trigger detection */
+#define PWR_PVD_MODE_EVENT_RISING_FALLING (0x00020003U) /*!< Event Mode with Rising/Falling edge trigger detection */
+
+#define IS_PWR_PVD_MODE(MODE) (((MODE) == PWR_PVD_MODE_IT_RISING)|| ((MODE) == PWR_PVD_MODE_IT_FALLING) || \
+ ((MODE) == PWR_PVD_MODE_IT_RISING_FALLING) || ((MODE) == PWR_PVD_MODE_EVENT_RISING) || \
+ ((MODE) == PWR_PVD_MODE_EVENT_FALLING) || ((MODE) == PWR_PVD_MODE_EVENT_RISING_FALLING) || \
+ ((MODE) == PWR_PVD_MODE_NORMAL))
+/**
+ * @}
+ */
+#endif /* defined (STM32F031x6) || defined (STM32F042x6) || defined (STM32F051x8) || */
+ /* defined (STM32F071xB) || defined (STM32F072xB) || */
+ /* defined (STM32F091xC) */
+
+/** @defgroup PWREx_Flag PWREx Flag
+ * @{
+ */
+#if defined (STM32F031x6) || defined (STM32F042x6) || defined (STM32F051x8) || \
+ defined (STM32F071xB) || defined (STM32F072xB) || \
+ defined (STM32F091xC)
+
+#define PWR_FLAG_WU PWR_CSR_WUF
+#define PWR_FLAG_SB PWR_CSR_SBF
+#define PWR_FLAG_PVDO PWR_CSR_PVDO
+#define PWR_FLAG_VREFINTRDY PWR_CSR_VREFINTRDYF
+#elif defined (STM32F070x6) || defined (STM32F070xB) || defined (STM32F030xC)
+#define PWR_FLAG_WU PWR_CSR_WUF
+#define PWR_FLAG_SB PWR_CSR_SBF
+#define PWR_FLAG_VREFINTRDY PWR_CSR_VREFINTRDYF
+#else
+#define PWR_FLAG_WU PWR_CSR_WUF
+#define PWR_FLAG_SB PWR_CSR_SBF
+
+#endif /* defined (STM32F031x6) || defined (STM32F042x6) || defined (STM32F051x8) || */
+ /* defined (STM32F071xB) || defined (STM32F072xB) || */
+ /* defined (STM32F091xC) */
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/* Exported macro ------------------------------------------------------------*/
+/** @defgroup PWREx_Exported_Macros PWREx Exported Macros
+ * @{
+ */
+#if defined (STM32F031x6) || defined (STM32F042x6) || defined (STM32F051x8) || \
+ defined (STM32F071xB) || defined (STM32F072xB) || \
+ defined (STM32F091xC)
+/**
+ * @brief Enable interrupt on PVD Exti Line 16.
+ * @retval None.
+ */
+#define __HAL_PWR_PVD_EXTI_ENABLE_IT() (EXTI->IMR |= (PWR_EXTI_LINE_PVD))
+
+/**
+ * @brief Disable interrupt on PVD Exti Line 16.
+ * @retval None.
+ */
+#define __HAL_PWR_PVD_EXTI_DISABLE_IT() (EXTI->IMR &= ~(PWR_EXTI_LINE_PVD))
+
+/**
+ * @brief Enable event on PVD Exti Line 16.
+ * @retval None.
+ */
+#define __HAL_PWR_PVD_EXTI_ENABLE_EVENT() (EXTI->EMR |= (PWR_EXTI_LINE_PVD))
+
+/**
+ * @brief Disable event on PVD Exti Line 16.
+ * @retval None.
+ */
+#define __HAL_PWR_PVD_EXTI_DISABLE_EVENT() (EXTI->EMR &= ~(PWR_EXTI_LINE_PVD))
+
+/**
+ * @brief Disable the PVD Extended Interrupt Rising Trigger.
+ * @retval None.
+ */
+#define __HAL_PWR_PVD_EXTI_DISABLE_RISING_EDGE() CLEAR_BIT(EXTI->RTSR, PWR_EXTI_LINE_PVD)
+
+/**
+ * @brief Disable the PVD Extended Interrupt Falling Trigger.
+ * @retval None.
+ */
+#define __HAL_PWR_PVD_EXTI_DISABLE_FALLING_EDGE() CLEAR_BIT(EXTI->FTSR, PWR_EXTI_LINE_PVD)
+
+/**
+ * @brief Disable the PVD Extended Interrupt Rising & Falling Trigger.
+ * @retval None
+ */
+#define __HAL_PWR_PVD_EXTI_DISABLE_RISING_FALLING_EDGE() __HAL_PWR_PVD_EXTI_DISABLE_RISING_EDGE();__HAL_PWR_PVD_EXTI_DISABLE_FALLING_EDGE();
+
+
+/**
+ * @brief PVD EXTI line configuration: set falling edge trigger.
+ * @retval None.
+ */
+#define __HAL_PWR_PVD_EXTI_ENABLE_FALLING_EDGE() EXTI->FTSR |= (PWR_EXTI_LINE_PVD)
+
+/**
+ * @brief PVD EXTI line configuration: set rising edge trigger.
+ * @retval None.
+ */
+#define __HAL_PWR_PVD_EXTI_ENABLE_RISING_EDGE() EXTI->RTSR |= (PWR_EXTI_LINE_PVD)
+
+/**
+ * @brief Enable the PVD Extended Interrupt Rising & Falling Trigger.
+ * @retval None
+ */
+#define __HAL_PWR_PVD_EXTI_ENABLE_RISING_FALLING_EDGE() __HAL_PWR_PVD_EXTI_ENABLE_RISING_EDGE();__HAL_PWR_PVD_EXTI_ENABLE_FALLING_EDGE();
+
+/**
+ * @brief Check whether the specified PVD EXTI interrupt flag is set or not.
+ * @retval EXTI PVD Line Status.
+ */
+#define __HAL_PWR_PVD_EXTI_GET_FLAG() (EXTI->PR & (PWR_EXTI_LINE_PVD))
+
+/**
+ * @brief Clear the PVD EXTI flag.
+ * @retval None.
+ */
+#define __HAL_PWR_PVD_EXTI_CLEAR_FLAG() (EXTI->PR = (PWR_EXTI_LINE_PVD))
+
+/**
+ * @brief Generate a Software interrupt on selected EXTI line.
+ * @retval None.
+ */
+#define __HAL_PWR_PVD_EXTI_GENERATE_SWIT() (EXTI->SWIER |= (PWR_EXTI_LINE_PVD))
+
+#endif /* defined (STM32F031x6) || defined (STM32F042x6) || defined (STM32F051x8) || */
+ /* defined (STM32F071xB) || defined (STM32F072xB) || */
+ /* defined (STM32F091xC) */
+
+
+#if defined (STM32F042x6) || defined (STM32F048xx) || \
+ defined (STM32F071xB) || defined (STM32F072xB) || defined (STM32F078xx) || \
+ defined (STM32F091xC) || defined (STM32F098xx)
+/**
+ * @brief Enable interrupt on Vddio2 Monitor Exti Line 31.
+ * @retval None.
+ */
+#define __HAL_PWR_VDDIO2_EXTI_ENABLE_IT() (EXTI->IMR |= (PWR_EXTI_LINE_VDDIO2))
+
+/**
+ * @brief Disable interrupt on Vddio2 Monitor Exti Line 31.
+ * @retval None.
+ */
+#define __HAL_PWR_VDDIO2_EXTI_DISABLE_IT() (EXTI->IMR &= ~(PWR_EXTI_LINE_VDDIO2))
+
+/**
+ * @brief Vddio2 Monitor EXTI line configuration: clear falling edge and rising edge trigger.
+ * @retval None.
+ */
+#define __HAL_PWR_VDDIO2_EXTI_DISABLE_FALLING_EDGE() \
+ do{ \
+ EXTI->FTSR &= ~(PWR_EXTI_LINE_VDDIO2); \
+ EXTI->RTSR &= ~(PWR_EXTI_LINE_VDDIO2); \
+ } while(0)
+
+/**
+ * @brief Vddio2 Monitor EXTI line configuration: set falling edge trigger.
+ * @retval None.
+ */
+#define __HAL_PWR_VDDIO2_EXTI_ENABLE_FALLING_EDGE() EXTI->FTSR |= (PWR_EXTI_LINE_VDDIO2)
+
+/**
+ * @brief Check whether the specified VDDIO2 monitor EXTI interrupt flag is set or not.
+ * @retval EXTI VDDIO2 Monitor Line Status.
+ */
+#define __HAL_PWR_VDDIO2_EXTI_GET_FLAG() (EXTI->PR & (PWR_EXTI_LINE_VDDIO2))
+
+/**
+ * @brief Clear the VDDIO2 Monitor EXTI flag.
+ * @retval None.
+ */
+#define __HAL_PWR_VDDIO2_EXTI_CLEAR_FLAG() (EXTI->PR = (PWR_EXTI_LINE_VDDIO2))
+
+/**
+ * @brief Generate a Software interrupt on selected EXTI line.
+ * @retval None.
+ */
+#define __HAL_PWR_VDDIO2_EXTI_GENERATE_SWIT() (EXTI->SWIER |= (PWR_EXTI_LINE_VDDIO2))
+
+
+#endif /* defined (STM32F042x6) || defined (STM32F048xx) ||\
+ defined (STM32F071xB) || defined (STM32F072xB) || defined (STM32F078xx) || \
+ defined (STM32F091xC) || defined (STM32F098xx) */
+
+/**
+ * @}
+ */
+
+/* Exported functions --------------------------------------------------------*/
+
+/** @addtogroup PWREx_Exported_Functions PWREx Exported Functions
+ * @{
+ */
+
+/** @addtogroup PWREx_Exported_Functions_Group1
+ * @{
+ */
+/* I/O operation functions ***************************************************/
+#if defined (STM32F031x6) || defined (STM32F042x6) || defined (STM32F051x8) || \
+ defined (STM32F071xB) || defined (STM32F072xB) || \
+ defined (STM32F091xC)
+void HAL_PWR_PVD_IRQHandler(void);
+void HAL_PWR_PVDCallback(void);
+#endif /* defined (STM32F031x6) || defined (STM32F042x6) || defined (STM32F051x8) || */
+ /* defined (STM32F071xB) || defined (STM32F072xB) || */
+ /* defined (STM32F091xC) */
+
+#if defined (STM32F042x6) || defined (STM32F048xx) || \
+ defined (STM32F071xB) || defined (STM32F072xB) || defined (STM32F078xx) || \
+ defined (STM32F091xC) || defined (STM32F098xx)
+void HAL_PWREx_Vddio2Monitor_IRQHandler(void);
+void HAL_PWREx_Vddio2MonitorCallback(void);
+#endif /* defined (STM32F042x6) || defined (STM32F048xx) || \
+ defined (STM32F071xB) || defined (STM32F072xB) || defined (STM32F078xx) || \
+ defined (STM32F091xC) || defined (STM32F098xx) */
+
+/* Peripheral Control functions **********************************************/
+#if defined (STM32F031x6) || defined (STM32F042x6) || defined (STM32F051x8) || \
+ defined (STM32F071xB) || defined (STM32F072xB) || \
+ defined (STM32F091xC)
+void HAL_PWR_ConfigPVD(PWR_PVDTypeDef *sConfigPVD);
+void HAL_PWR_EnablePVD(void);
+void HAL_PWR_DisablePVD(void);
+#endif /* defined (STM32F031x6) || defined (STM32F042x6) || defined (STM32F051x8) || */
+ /* defined (STM32F071xB) || defined (STM32F072xB) || */
+ /* defined (STM32F091xC) */
+
+#if defined (STM32F042x6) || defined (STM32F048xx) || \
+ defined (STM32F071xB) || defined (STM32F072xB) || defined (STM32F078xx) || \
+ defined (STM32F091xC) || defined (STM32F098xx)
+void HAL_PWREx_EnableVddio2Monitor(void);
+void HAL_PWREx_DisableVddio2Monitor(void);
+#endif /* defined (STM32F042x6) || defined (STM32F048xx) || \
+ defined (STM32F071xB) || defined (STM32F072xB) || defined (STM32F078xx) || \
+ defined (STM32F091xC) || defined (STM32F098xx) */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __STM32F0xx_HAL_PWR_EX_H */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
+
diff --git a/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal_rcc.h b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal_rcc.h
new file mode 100644
index 0000000..acd386c
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal_rcc.h
@@ -0,0 +1,1686 @@
+/**
+ ******************************************************************************
+ * @file stm32f0xx_hal_rcc.h
+ * @author MCD Application Team
+ * @brief Header file of RCC HAL module.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2016 STMicroelectronics.
+ * All rights reserved.
+ *
+ * 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 __STM32F0xx_HAL_RCC_H
+#define __STM32F0xx_HAL_RCC_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f0xx_hal_def.h"
+
+/** @addtogroup STM32F0xx_HAL_Driver
+ * @{
+ */
+
+/** @addtogroup RCC
+ * @{
+ */
+
+/** @addtogroup RCC_Private_Constants
+ * @{
+ */
+
+/** @defgroup RCC_Timeout RCC Timeout
+ * @{
+ */
+
+/* Disable Backup domain write protection state change timeout */
+#define RCC_DBP_TIMEOUT_VALUE (100U) /* 100 ms */
+/* LSE state change timeout */
+#define RCC_LSE_TIMEOUT_VALUE LSE_STARTUP_TIMEOUT
+#define CLOCKSWITCH_TIMEOUT_VALUE (5000U) /* 5 s */
+#define HSE_TIMEOUT_VALUE HSE_STARTUP_TIMEOUT
+#define HSI_TIMEOUT_VALUE (2U) /* 2 ms (minimum Tick + 1U) */
+#define LSI_TIMEOUT_VALUE (2U) /* 2 ms (minimum Tick + 1U) */
+#define PLL_TIMEOUT_VALUE (2U) /* 2 ms (minimum Tick + 1U) */
+#define HSI14_TIMEOUT_VALUE (2U) /* 2 ms (minimum Tick + 1U) */
+#if defined(RCC_HSI48_SUPPORT)
+#define HSI48_TIMEOUT_VALUE (2U) /* 2 ms (minimum Tick + 1U) */
+#endif /* RCC_HSI48_SUPPORT */
+/**
+ * @}
+ */
+
+/** @defgroup RCC_Register_Offset Register offsets
+ * @{
+ */
+#define RCC_OFFSET (RCC_BASE - PERIPH_BASE)
+#define RCC_CR_OFFSET 0x00
+#define RCC_CFGR_OFFSET 0x04
+#define RCC_CIR_OFFSET 0x08
+#define RCC_BDCR_OFFSET 0x20
+#define RCC_CSR_OFFSET 0x24
+
+/**
+ * @}
+ */
+
+
+/* CR register byte 2 (Bits[23:16]) base address */
+#define RCC_CR_BYTE2_ADDRESS ((uint32_t)(RCC_BASE + RCC_CR_OFFSET + 0x02U))
+
+/* CIR register byte 1 (Bits[15:8]) base address */
+#define RCC_CIR_BYTE1_ADDRESS ((uint32_t)(RCC_BASE + RCC_CIR_OFFSET + 0x01U))
+
+/* CIR register byte 2 (Bits[23:16]) base address */
+#define RCC_CIR_BYTE2_ADDRESS ((uint32_t)(RCC_BASE + RCC_CIR_OFFSET + 0x02U))
+
+/* Defines used for Flags */
+#define CR_REG_INDEX ((uint8_t)1U)
+#define CR2_REG_INDEX ((uint8_t)2U)
+#define BDCR_REG_INDEX ((uint8_t)3U)
+#define CSR_REG_INDEX ((uint8_t)4U)
+
+/* Bits position in in the CFGR register */
+#define RCC_CFGR_PLLMUL_BITNUMBER 18U
+#define RCC_CFGR_HPRE_BITNUMBER 4U
+#define RCC_CFGR_PPRE_BITNUMBER 8U
+/* Flags in the CFGR2 register */
+#define RCC_CFGR2_PREDIV_BITNUMBER 0
+/* Flags in the CR register */
+#define RCC_CR_HSIRDY_BitNumber 1
+#define RCC_CR_HSERDY_BitNumber 17
+#define RCC_CR_PLLRDY_BitNumber 25
+/* Flags in the CR2 register */
+#define RCC_CR2_HSI14RDY_BitNumber 1
+#define RCC_CR2_HSI48RDY_BitNumber 16
+/* Flags in the BDCR register */
+#define RCC_BDCR_LSERDY_BitNumber 1
+/* Flags in the CSR register */
+#define RCC_CSR_LSIRDY_BitNumber 1
+#define RCC_CSR_V18PWRRSTF_BitNumber 23
+#define RCC_CSR_RMVF_BitNumber 24
+#define RCC_CSR_OBLRSTF_BitNumber 25
+#define RCC_CSR_PINRSTF_BitNumber 26
+#define RCC_CSR_PORRSTF_BitNumber 27
+#define RCC_CSR_SFTRSTF_BitNumber 28
+#define RCC_CSR_IWDGRSTF_BitNumber 29
+#define RCC_CSR_WWDGRSTF_BitNumber 30
+#define RCC_CSR_LPWRRSTF_BitNumber 31
+/* Flags in the HSITRIM register */
+#define RCC_CR_HSITRIM_BitNumber 3
+#define RCC_HSI14TRIM_BIT_NUMBER 3
+#define RCC_FLAG_MASK ((uint8_t)0x1FU)
+
+/**
+ * @}
+ */
+
+/** @addtogroup RCC_Private_Macros
+ * @{
+ */
+#define IS_RCC_HSE(__HSE__) (((__HSE__) == RCC_HSE_OFF) || ((__HSE__) == RCC_HSE_ON) || \
+ ((__HSE__) == RCC_HSE_BYPASS))
+#define IS_RCC_LSE(__LSE__) (((__LSE__) == RCC_LSE_OFF) || ((__LSE__) == RCC_LSE_ON) || \
+ ((__LSE__) == RCC_LSE_BYPASS))
+#define IS_RCC_HSI(__HSI__) (((__HSI__) == RCC_HSI_OFF) || ((__HSI__) == RCC_HSI_ON))
+#define IS_RCC_HSI14(__HSI14__) (((__HSI14__) == RCC_HSI14_OFF) || ((__HSI14__) == RCC_HSI14_ON) || ((__HSI14__) == RCC_HSI14_ADC_CONTROL))
+#define IS_RCC_CALIBRATION_VALUE(__VALUE__) ((__VALUE__) <= 0x1FU)
+#define IS_RCC_LSI(__LSI__) (((__LSI__) == RCC_LSI_OFF) || ((__LSI__) == RCC_LSI_ON))
+#define IS_RCC_PLL(__PLL__) (((__PLL__) == RCC_PLL_NONE) || ((__PLL__) == RCC_PLL_OFF) || \
+ ((__PLL__) == RCC_PLL_ON))
+#define IS_RCC_PREDIV(__PREDIV__) (((__PREDIV__) == RCC_PREDIV_DIV1) || ((__PREDIV__) == RCC_PREDIV_DIV2) || \
+ ((__PREDIV__) == RCC_PREDIV_DIV3) || ((__PREDIV__) == RCC_PREDIV_DIV4) || \
+ ((__PREDIV__) == RCC_PREDIV_DIV5) || ((__PREDIV__) == RCC_PREDIV_DIV6) || \
+ ((__PREDIV__) == RCC_PREDIV_DIV7) || ((__PREDIV__) == RCC_PREDIV_DIV8) || \
+ ((__PREDIV__) == RCC_PREDIV_DIV9) || ((__PREDIV__) == RCC_PREDIV_DIV10) || \
+ ((__PREDIV__) == RCC_PREDIV_DIV11) || ((__PREDIV__) == RCC_PREDIV_DIV12) || \
+ ((__PREDIV__) == RCC_PREDIV_DIV13) || ((__PREDIV__) == RCC_PREDIV_DIV14) || \
+ ((__PREDIV__) == RCC_PREDIV_DIV15) || ((__PREDIV__) == RCC_PREDIV_DIV16))
+
+#define IS_RCC_PLL_MUL(__MUL__) (((__MUL__) == RCC_PLL_MUL2) || ((__MUL__) == RCC_PLL_MUL3) || \
+ ((__MUL__) == RCC_PLL_MUL4) || ((__MUL__) == RCC_PLL_MUL5) || \
+ ((__MUL__) == RCC_PLL_MUL6) || ((__MUL__) == RCC_PLL_MUL7) || \
+ ((__MUL__) == RCC_PLL_MUL8) || ((__MUL__) == RCC_PLL_MUL9) || \
+ ((__MUL__) == RCC_PLL_MUL10) || ((__MUL__) == RCC_PLL_MUL11) || \
+ ((__MUL__) == RCC_PLL_MUL12) || ((__MUL__) == RCC_PLL_MUL13) || \
+ ((__MUL__) == RCC_PLL_MUL14) || ((__MUL__) == RCC_PLL_MUL15) || \
+ ((__MUL__) == RCC_PLL_MUL16))
+#define IS_RCC_CLOCKTYPE(__CLK__) ((((__CLK__) & RCC_CLOCKTYPE_SYSCLK) == RCC_CLOCKTYPE_SYSCLK) || \
+ (((__CLK__) & RCC_CLOCKTYPE_HCLK) == RCC_CLOCKTYPE_HCLK) || \
+ (((__CLK__) & RCC_CLOCKTYPE_PCLK1) == RCC_CLOCKTYPE_PCLK1))
+#define IS_RCC_HCLK(__HCLK__) (((__HCLK__) == RCC_SYSCLK_DIV1) || ((__HCLK__) == RCC_SYSCLK_DIV2) || \
+ ((__HCLK__) == RCC_SYSCLK_DIV4) || ((__HCLK__) == RCC_SYSCLK_DIV8) || \
+ ((__HCLK__) == RCC_SYSCLK_DIV16) || ((__HCLK__) == RCC_SYSCLK_DIV64) || \
+ ((__HCLK__) == RCC_SYSCLK_DIV128) || ((__HCLK__) == RCC_SYSCLK_DIV256) || \
+ ((__HCLK__) == RCC_SYSCLK_DIV512))
+#define IS_RCC_PCLK(__PCLK__) (((__PCLK__) == RCC_HCLK_DIV1) || ((__PCLK__) == RCC_HCLK_DIV2) || \
+ ((__PCLK__) == RCC_HCLK_DIV4) || ((__PCLK__) == RCC_HCLK_DIV8) || \
+ ((__PCLK__) == RCC_HCLK_DIV16))
+#define IS_RCC_MCO(__MCO__) ((__MCO__) == RCC_MCO)
+#define IS_RCC_RTCCLKSOURCE(__SOURCE__) (((__SOURCE__) == RCC_RTCCLKSOURCE_NO_CLK) || \
+ ((__SOURCE__) == RCC_RTCCLKSOURCE_LSE) || \
+ ((__SOURCE__) == RCC_RTCCLKSOURCE_LSI) || \
+ ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV32))
+#define IS_RCC_USART1CLKSOURCE(__SOURCE__) (((__SOURCE__) == RCC_USART1CLKSOURCE_PCLK1) || \
+ ((__SOURCE__) == RCC_USART1CLKSOURCE_SYSCLK) || \
+ ((__SOURCE__) == RCC_USART1CLKSOURCE_LSE) || \
+ ((__SOURCE__) == RCC_USART1CLKSOURCE_HSI))
+#define IS_RCC_I2C1CLKSOURCE(__SOURCE__) (((__SOURCE__) == RCC_I2C1CLKSOURCE_HSI) || \
+ ((__SOURCE__) == RCC_I2C1CLKSOURCE_SYSCLK))
+
+/**
+ * @}
+ */
+
+/* Exported types ------------------------------------------------------------*/
+
+/** @defgroup RCC_Exported_Types RCC Exported Types
+ * @{
+ */
+
+/**
+ * @brief RCC PLL configuration structure definition
+ */
+typedef struct
+{
+ uint32_t PLLState; /*!< PLLState: The new state of the PLL.
+ This parameter can be a value of @ref RCC_PLL_Config */
+
+ uint32_t PLLSource; /*!< PLLSource: PLL entry clock source.
+ This parameter must be a value of @ref RCC_PLL_Clock_Source */
+
+ uint32_t PLLMUL; /*!< PLLMUL: Multiplication factor for PLL VCO input clock
+ This parameter must be a value of @ref RCC_PLL_Multiplication_Factor*/
+
+ uint32_t PREDIV; /*!< PREDIV: Predivision factor for PLL VCO input clock
+ This parameter must be a value of @ref RCC_PLL_Prediv_Factor */
+
+} RCC_PLLInitTypeDef;
+
+/**
+ * @brief RCC Internal/External Oscillator (HSE, HSI, LSE and LSI) configuration structure definition
+ */
+typedef struct
+{
+ uint32_t OscillatorType; /*!< The oscillators to be configured.
+ This parameter can be a value of @ref RCC_Oscillator_Type */
+
+ uint32_t HSEState; /*!< The new state of the HSE.
+ This parameter can be a value of @ref RCC_HSE_Config */
+
+ uint32_t LSEState; /*!< The new state of the LSE.
+ This parameter can be a value of @ref RCC_LSE_Config */
+
+ uint32_t HSIState; /*!< The new state of the HSI.
+ This parameter can be a value of @ref RCC_HSI_Config */
+
+ uint32_t HSICalibrationValue; /*!< The HSI calibration trimming value (default is RCC_HSICALIBRATION_DEFAULT).
+ This parameter must be a number between Min_Data = 0x00 and Max_Data = 0x1FU */
+
+ uint32_t HSI14State; /*!< The new state of the HSI14.
+ This parameter can be a value of @ref RCC_HSI14_Config */
+
+ uint32_t HSI14CalibrationValue; /*!< The HSI14 calibration trimming value (default is RCC_HSI14CALIBRATION_DEFAULT).
+ This parameter must be a number between Min_Data = 0x00 and Max_Data = 0x1FU */
+
+ uint32_t LSIState; /*!< The new state of the LSI.
+ This parameter can be a value of @ref RCC_LSI_Config */
+
+#if defined(RCC_HSI48_SUPPORT)
+ uint32_t HSI48State; /*!< The new state of the HSI48.
+ This parameter can be a value of @ref RCC_HSI48_Config */
+
+#endif /* RCC_HSI48_SUPPORT */
+ RCC_PLLInitTypeDef PLL; /*!< PLL structure parameters */
+
+} RCC_OscInitTypeDef;
+
+/**
+ * @brief RCC System, AHB and APB busses clock configuration structure definition
+ */
+typedef struct
+{
+ uint32_t ClockType; /*!< The clock to be configured.
+ This parameter can be a value of @ref RCC_System_Clock_Type */
+
+ uint32_t SYSCLKSource; /*!< The clock source (SYSCLKS) used as system clock.
+ This parameter can be a value of @ref RCC_System_Clock_Source */
+
+ uint32_t AHBCLKDivider; /*!< The AHB clock (HCLK) divider. This clock is derived from the system clock (SYSCLK).
+ This parameter can be a value of @ref RCC_AHB_Clock_Source */
+
+ uint32_t APB1CLKDivider; /*!< The APB1 clock (PCLK1) divider. This clock is derived from the AHB clock (HCLK).
+ This parameter can be a value of @ref RCC_APB1_Clock_Source */
+
+} RCC_ClkInitTypeDef;
+
+/**
+ * @}
+ */
+
+/* Exported constants --------------------------------------------------------*/
+/** @defgroup RCC_Exported_Constants RCC Exported Constants
+ * @{
+ */
+
+/** @defgroup RCC_PLL_Clock_Source PLL Clock Source
+ * @{
+ */
+
+#define RCC_PLLSOURCE_HSE RCC_CFGR_PLLSRC_HSE_PREDIV /*!< HSE clock selected as PLL entry clock source */
+
+/**
+ * @}
+ */
+
+/** @defgroup RCC_Oscillator_Type Oscillator Type
+ * @{
+ */
+#define RCC_OSCILLATORTYPE_NONE (0x00000000U)
+#define RCC_OSCILLATORTYPE_HSE (0x00000001U)
+#define RCC_OSCILLATORTYPE_HSI (0x00000002U)
+#define RCC_OSCILLATORTYPE_LSE (0x00000004U)
+#define RCC_OSCILLATORTYPE_LSI (0x00000008U)
+#define RCC_OSCILLATORTYPE_HSI14 (0x00000010U)
+#if defined(RCC_HSI48_SUPPORT)
+#define RCC_OSCILLATORTYPE_HSI48 (0x00000020U)
+#endif /* RCC_HSI48_SUPPORT */
+/**
+ * @}
+ */
+
+/** @defgroup RCC_HSE_Config HSE Config
+ * @{
+ */
+#define RCC_HSE_OFF (0x00000000U) /*!< HSE clock deactivation */
+#define RCC_HSE_ON (0x00000001U) /*!< HSE clock activation */
+#define RCC_HSE_BYPASS (0x00000005U) /*!< External clock source for HSE clock */
+/**
+ * @}
+ */
+
+/** @defgroup RCC_LSE_Config LSE Config
+ * @{
+ */
+#define RCC_LSE_OFF (0x00000000U) /*!< LSE clock deactivation */
+#define RCC_LSE_ON (0x00000001U) /*!< LSE clock activation */
+#define RCC_LSE_BYPASS (0x00000005U) /*!< External clock source for LSE clock */
+
+/**
+ * @}
+ */
+
+/** @defgroup RCC_HSI_Config HSI Config
+ * @{
+ */
+#define RCC_HSI_OFF (0x00000000U) /*!< HSI clock deactivation */
+#define RCC_HSI_ON RCC_CR_HSION /*!< HSI clock activation */
+
+#define RCC_HSICALIBRATION_DEFAULT (0x10U) /* Default HSI calibration trimming value */
+
+/**
+ * @}
+ */
+
+/** @defgroup RCC_HSI14_Config RCC HSI14 Config
+ * @{
+ */
+#define RCC_HSI14_OFF (0x00000000U)
+#define RCC_HSI14_ON RCC_CR2_HSI14ON
+#define RCC_HSI14_ADC_CONTROL (~RCC_CR2_HSI14DIS)
+
+#define RCC_HSI14CALIBRATION_DEFAULT (0x10U) /* Default HSI14 calibration trimming value */
+/**
+ * @}
+ */
+
+/** @defgroup RCC_LSI_Config LSI Config
+ * @{
+ */
+#define RCC_LSI_OFF (0x00000000U) /*!< LSI clock deactivation */
+#define RCC_LSI_ON RCC_CSR_LSION /*!< LSI clock activation */
+
+/**
+ * @}
+ */
+
+#if defined(RCC_HSI48_SUPPORT)
+/** @defgroup RCC_HSI48_Config HSI48 Config
+ * @{
+ */
+#define RCC_HSI48_OFF ((uint8_t)0x00U)
+#define RCC_HSI48_ON ((uint8_t)0x01U)
+
+/**
+ * @}
+ */
+#endif /* RCC_HSI48_SUPPORT */
+
+/** @defgroup RCC_PLL_Config PLL Config
+ * @{
+ */
+#define RCC_PLL_NONE (0x00000000U) /*!< PLL is not configured */
+#define RCC_PLL_OFF (0x00000001U) /*!< PLL deactivation */
+#define RCC_PLL_ON (0x00000002U) /*!< PLL activation */
+
+/**
+ * @}
+ */
+
+/** @defgroup RCC_System_Clock_Type System Clock Type
+ * @{
+ */
+#define RCC_CLOCKTYPE_SYSCLK (0x00000001U) /*!< SYSCLK to configure */
+#define RCC_CLOCKTYPE_HCLK (0x00000002U) /*!< HCLK to configure */
+#define RCC_CLOCKTYPE_PCLK1 (0x00000004U) /*!< PCLK1 to configure */
+
+/**
+ * @}
+ */
+
+/** @defgroup RCC_System_Clock_Source System Clock Source
+ * @{
+ */
+#define RCC_SYSCLKSOURCE_HSI RCC_CFGR_SW_HSI /*!< HSI selected as system clock */
+#define RCC_SYSCLKSOURCE_HSE RCC_CFGR_SW_HSE /*!< HSE selected as system clock */
+#define RCC_SYSCLKSOURCE_PLLCLK RCC_CFGR_SW_PLL /*!< PLL selected as system clock */
+
+/**
+ * @}
+ */
+
+/** @defgroup RCC_System_Clock_Source_Status System Clock Source Status
+ * @{
+ */
+#define RCC_SYSCLKSOURCE_STATUS_HSI RCC_CFGR_SWS_HSI /*!< HSI used as system clock */
+#define RCC_SYSCLKSOURCE_STATUS_HSE RCC_CFGR_SWS_HSE /*!< HSE used as system clock */
+#define RCC_SYSCLKSOURCE_STATUS_PLLCLK RCC_CFGR_SWS_PLL /*!< PLL used as system clock */
+
+/**
+ * @}
+ */
+
+/** @defgroup RCC_AHB_Clock_Source AHB Clock Source
+ * @{
+ */
+#define RCC_SYSCLK_DIV1 RCC_CFGR_HPRE_DIV1 /*!< SYSCLK not divided */
+#define RCC_SYSCLK_DIV2 RCC_CFGR_HPRE_DIV2 /*!< SYSCLK divided by 2 */
+#define RCC_SYSCLK_DIV4 RCC_CFGR_HPRE_DIV4 /*!< SYSCLK divided by 4 */
+#define RCC_SYSCLK_DIV8 RCC_CFGR_HPRE_DIV8 /*!< SYSCLK divided by 8 */
+#define RCC_SYSCLK_DIV16 RCC_CFGR_HPRE_DIV16 /*!< SYSCLK divided by 16 */
+#define RCC_SYSCLK_DIV64 RCC_CFGR_HPRE_DIV64 /*!< SYSCLK divided by 64 */
+#define RCC_SYSCLK_DIV128 RCC_CFGR_HPRE_DIV128 /*!< SYSCLK divided by 128 */
+#define RCC_SYSCLK_DIV256 RCC_CFGR_HPRE_DIV256 /*!< SYSCLK divided by 256 */
+#define RCC_SYSCLK_DIV512 RCC_CFGR_HPRE_DIV512 /*!< SYSCLK divided by 512 */
+
+/**
+ * @}
+ */
+
+/** @defgroup RCC_APB1_Clock_Source RCC APB1 Clock Source
+ * @{
+ */
+#define RCC_HCLK_DIV1 RCC_CFGR_PPRE_DIV1 /*!< HCLK not divided */
+#define RCC_HCLK_DIV2 RCC_CFGR_PPRE_DIV2 /*!< HCLK divided by 2 */
+#define RCC_HCLK_DIV4 RCC_CFGR_PPRE_DIV4 /*!< HCLK divided by 4 */
+#define RCC_HCLK_DIV8 RCC_CFGR_PPRE_DIV8 /*!< HCLK divided by 8 */
+#define RCC_HCLK_DIV16 RCC_CFGR_PPRE_DIV16 /*!< HCLK divided by 16 */
+
+/**
+ * @}
+ */
+
+/** @defgroup RCC_RTC_Clock_Source RTC Clock Source
+ * @{
+ */
+#define RCC_RTCCLKSOURCE_NO_CLK (0x00000000U) /*!< No clock */
+#define RCC_RTCCLKSOURCE_LSE RCC_BDCR_RTCSEL_LSE /*!< LSE oscillator clock used as RTC clock */
+#define RCC_RTCCLKSOURCE_LSI RCC_BDCR_RTCSEL_LSI /*!< LSI oscillator clock used as RTC clock */
+#define RCC_RTCCLKSOURCE_HSE_DIV32 RCC_BDCR_RTCSEL_HSE /*!< HSE oscillator clock divided by 32 used as RTC clock */
+/**
+ * @}
+ */
+
+/** @defgroup RCC_PLL_Multiplication_Factor RCC PLL Multiplication Factor
+ * @{
+ */
+#define RCC_PLL_MUL2 RCC_CFGR_PLLMUL2
+#define RCC_PLL_MUL3 RCC_CFGR_PLLMUL3
+#define RCC_PLL_MUL4 RCC_CFGR_PLLMUL4
+#define RCC_PLL_MUL5 RCC_CFGR_PLLMUL5
+#define RCC_PLL_MUL6 RCC_CFGR_PLLMUL6
+#define RCC_PLL_MUL7 RCC_CFGR_PLLMUL7
+#define RCC_PLL_MUL8 RCC_CFGR_PLLMUL8
+#define RCC_PLL_MUL9 RCC_CFGR_PLLMUL9
+#define RCC_PLL_MUL10 RCC_CFGR_PLLMUL10
+#define RCC_PLL_MUL11 RCC_CFGR_PLLMUL11
+#define RCC_PLL_MUL12 RCC_CFGR_PLLMUL12
+#define RCC_PLL_MUL13 RCC_CFGR_PLLMUL13
+#define RCC_PLL_MUL14 RCC_CFGR_PLLMUL14
+#define RCC_PLL_MUL15 RCC_CFGR_PLLMUL15
+#define RCC_PLL_MUL16 RCC_CFGR_PLLMUL16
+
+/**
+ * @}
+ */
+
+/** @defgroup RCC_PLL_Prediv_Factor RCC PLL Prediv Factor
+ * @{
+ */
+
+#define RCC_PREDIV_DIV1 RCC_CFGR2_PREDIV_DIV1
+#define RCC_PREDIV_DIV2 RCC_CFGR2_PREDIV_DIV2
+#define RCC_PREDIV_DIV3 RCC_CFGR2_PREDIV_DIV3
+#define RCC_PREDIV_DIV4 RCC_CFGR2_PREDIV_DIV4
+#define RCC_PREDIV_DIV5 RCC_CFGR2_PREDIV_DIV5
+#define RCC_PREDIV_DIV6 RCC_CFGR2_PREDIV_DIV6
+#define RCC_PREDIV_DIV7 RCC_CFGR2_PREDIV_DIV7
+#define RCC_PREDIV_DIV8 RCC_CFGR2_PREDIV_DIV8
+#define RCC_PREDIV_DIV9 RCC_CFGR2_PREDIV_DIV9
+#define RCC_PREDIV_DIV10 RCC_CFGR2_PREDIV_DIV10
+#define RCC_PREDIV_DIV11 RCC_CFGR2_PREDIV_DIV11
+#define RCC_PREDIV_DIV12 RCC_CFGR2_PREDIV_DIV12
+#define RCC_PREDIV_DIV13 RCC_CFGR2_PREDIV_DIV13
+#define RCC_PREDIV_DIV14 RCC_CFGR2_PREDIV_DIV14
+#define RCC_PREDIV_DIV15 RCC_CFGR2_PREDIV_DIV15
+#define RCC_PREDIV_DIV16 RCC_CFGR2_PREDIV_DIV16
+
+/**
+ * @}
+ */
+
+
+/** @defgroup RCC_USART1_Clock_Source RCC USART1 Clock Source
+ * @{
+ */
+#define RCC_USART1CLKSOURCE_PCLK1 RCC_CFGR3_USART1SW_PCLK
+#define RCC_USART1CLKSOURCE_SYSCLK RCC_CFGR3_USART1SW_SYSCLK
+#define RCC_USART1CLKSOURCE_LSE RCC_CFGR3_USART1SW_LSE
+#define RCC_USART1CLKSOURCE_HSI RCC_CFGR3_USART1SW_HSI
+
+/**
+ * @}
+ */
+
+/** @defgroup RCC_I2C1_Clock_Source RCC I2C1 Clock Source
+ * @{
+ */
+#define RCC_I2C1CLKSOURCE_HSI RCC_CFGR3_I2C1SW_HSI
+#define RCC_I2C1CLKSOURCE_SYSCLK RCC_CFGR3_I2C1SW_SYSCLK
+
+/**
+ * @}
+ */
+/** @defgroup RCC_MCO_Index MCO Index
+ * @{
+ */
+#define RCC_MCO1 (0x00000000U)
+#define RCC_MCO RCC_MCO1 /*!< MCO1 to be compliant with other families with 2 MCOs*/
+
+/**
+ * @}
+ */
+
+/** @defgroup RCC_MCO_Clock_Source RCC MCO Clock Source
+ * @{
+ */
+#define RCC_MCO1SOURCE_NOCLOCK RCC_CFGR_MCO_NOCLOCK
+#define RCC_MCO1SOURCE_LSI RCC_CFGR_MCO_LSI
+#define RCC_MCO1SOURCE_LSE RCC_CFGR_MCO_LSE
+#define RCC_MCO1SOURCE_SYSCLK RCC_CFGR_MCO_SYSCLK
+#define RCC_MCO1SOURCE_HSI RCC_CFGR_MCO_HSI
+#define RCC_MCO1SOURCE_HSE RCC_CFGR_MCO_HSE
+#define RCC_MCO1SOURCE_PLLCLK_DIV2 RCC_CFGR_MCO_PLL
+#define RCC_MCO1SOURCE_HSI14 RCC_CFGR_MCO_HSI14
+
+/**
+ * @}
+ */
+
+/** @defgroup RCC_Interrupt Interrupts
+ * @{
+ */
+#define RCC_IT_LSIRDY ((uint8_t)RCC_CIR_LSIRDYF) /*!< LSI Ready Interrupt flag */
+#define RCC_IT_LSERDY ((uint8_t)RCC_CIR_LSERDYF) /*!< LSE Ready Interrupt flag */
+#define RCC_IT_HSIRDY ((uint8_t)RCC_CIR_HSIRDYF) /*!< HSI Ready Interrupt flag */
+#define RCC_IT_HSERDY ((uint8_t)RCC_CIR_HSERDYF) /*!< HSE Ready Interrupt flag */
+#define RCC_IT_PLLRDY ((uint8_t)RCC_CIR_PLLRDYF) /*!< PLL Ready Interrupt flag */
+#define RCC_IT_HSI14RDY ((uint8_t)RCC_CIR_HSI14RDYF) /*!< HSI14 Ready Interrupt flag */
+#if defined(RCC_CIR_HSI48RDYF)
+#define RCC_IT_HSI48RDY ((uint8_t)RCC_CIR_HSI48RDYF) /*!< HSI48 Ready Interrupt flag */
+#endif
+#define RCC_IT_CSS ((uint8_t)RCC_CIR_CSSF) /*!< Clock Security System Interrupt flag */
+/**
+ * @}
+ */
+
+/** @defgroup RCC_Flag Flags
+ * Elements values convention: XXXYYYYYb
+ * - YYYYY : Flag position in the register
+ * - XXX : Register index
+ * - 001: CR register
+ * - 010: CR2 register
+ * - 011: BDCR register
+ * - 0100: CSR register
+ * @{
+ */
+/* Flags in the CR register */
+#define RCC_FLAG_HSIRDY ((uint8_t)((CR_REG_INDEX << 5U) | RCC_CR_HSIRDY_BitNumber))
+#define RCC_FLAG_HSERDY ((uint8_t)((CR_REG_INDEX << 5U) | RCC_CR_HSERDY_BitNumber))
+#define RCC_FLAG_PLLRDY ((uint8_t)((CR_REG_INDEX << 5U) | RCC_CR_PLLRDY_BitNumber))
+/* Flags in the CR2 register */
+#define RCC_FLAG_HSI14RDY ((uint8_t)((CR2_REG_INDEX << 5U) | RCC_CR2_HSI14RDY_BitNumber))
+
+/* Flags in the CSR register */
+#define RCC_FLAG_LSIRDY ((uint8_t)((CSR_REG_INDEX << 5U) | RCC_CSR_LSIRDY_BitNumber))
+#if defined(RCC_CSR_V18PWRRSTF)
+#define RCC_FLAG_V18PWRRST ((uint8_t)((CSR_REG_INDEX << 5U) | RCC_CSR_V18PWRRSTF_BitNumber))
+#endif
+#define RCC_FLAG_OBLRST ((uint8_t)((CSR_REG_INDEX << 5U) | RCC_CSR_OBLRSTF_BitNumber))
+#define RCC_FLAG_PINRST ((uint8_t)((CSR_REG_INDEX << 5U) | RCC_CSR_PINRSTF_BitNumber)) /*!< PIN reset flag */
+#define RCC_FLAG_PORRST ((uint8_t)((CSR_REG_INDEX << 5U) | RCC_CSR_PORRSTF_BitNumber)) /*!< POR/PDR reset flag */
+#define RCC_FLAG_SFTRST ((uint8_t)((CSR_REG_INDEX << 5U) | RCC_CSR_SFTRSTF_BitNumber)) /*!< Software Reset flag */
+#define RCC_FLAG_IWDGRST ((uint8_t)((CSR_REG_INDEX << 5U) | RCC_CSR_IWDGRSTF_BitNumber)) /*!< Independent Watchdog reset flag */
+#define RCC_FLAG_WWDGRST ((uint8_t)((CSR_REG_INDEX << 5U) | RCC_CSR_WWDGRSTF_BitNumber)) /*!< Window watchdog reset flag */
+#define RCC_FLAG_LPWRRST ((uint8_t)((CSR_REG_INDEX << 5U) | RCC_CSR_LPWRRSTF_BitNumber)) /*!< Low-Power reset flag */
+
+/* Flags in the BDCR register */
+#define RCC_FLAG_LSERDY ((uint8_t)((BDCR_REG_INDEX << 5U) | RCC_BDCR_LSERDY_BitNumber)) /*!< External Low Speed oscillator Ready */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/* Exported macro ------------------------------------------------------------*/
+
+/** @defgroup RCC_Exported_Macros RCC Exported Macros
+ * @{
+ */
+
+/** @defgroup RCC_AHB_Clock_Enable_Disable RCC AHB Clock Enable Disable
+ * @brief Enable or disable the AHB peripheral clock.
+ * @note After reset, the peripheral clock (used for registers read/write access)
+ * is disabled and the application software has to enable this clock before
+ * using it.
+ * @{
+ */
+#define __HAL_RCC_GPIOA_CLK_ENABLE() do { \
+ __IO uint32_t tmpreg; \
+ SET_BIT(RCC->AHBENR, RCC_AHBENR_GPIOAEN);\
+ /* Delay after an RCC peripheral clock enabling */\
+ tmpreg = READ_BIT(RCC->AHBENR, RCC_AHBENR_GPIOAEN);\
+ UNUSED(tmpreg); \
+ } while(0U)
+#define __HAL_RCC_GPIOB_CLK_ENABLE() do { \
+ __IO uint32_t tmpreg; \
+ SET_BIT(RCC->AHBENR, RCC_AHBENR_GPIOBEN);\
+ /* Delay after an RCC peripheral clock enabling */\
+ tmpreg = READ_BIT(RCC->AHBENR, RCC_AHBENR_GPIOBEN);\
+ UNUSED(tmpreg); \
+ } while(0U)
+#define __HAL_RCC_GPIOC_CLK_ENABLE() do { \
+ __IO uint32_t tmpreg; \
+ SET_BIT(RCC->AHBENR, RCC_AHBENR_GPIOCEN);\
+ /* Delay after an RCC peripheral clock enabling */\
+ tmpreg = READ_BIT(RCC->AHBENR, RCC_AHBENR_GPIOCEN);\
+ UNUSED(tmpreg); \
+ } while(0U)
+#define __HAL_RCC_GPIOF_CLK_ENABLE() do { \
+ __IO uint32_t tmpreg; \
+ SET_BIT(RCC->AHBENR, RCC_AHBENR_GPIOFEN);\
+ /* Delay after an RCC peripheral clock enabling */\
+ tmpreg = READ_BIT(RCC->AHBENR, RCC_AHBENR_GPIOFEN);\
+ UNUSED(tmpreg); \
+ } while(0U)
+#define __HAL_RCC_CRC_CLK_ENABLE() do { \
+ __IO uint32_t tmpreg; \
+ SET_BIT(RCC->AHBENR, RCC_AHBENR_CRCEN);\
+ /* Delay after an RCC peripheral clock enabling */\
+ tmpreg = READ_BIT(RCC->AHBENR, RCC_AHBENR_CRCEN);\
+ UNUSED(tmpreg); \
+ } while(0U)
+#define __HAL_RCC_DMA1_CLK_ENABLE() do { \
+ __IO uint32_t tmpreg; \
+ SET_BIT(RCC->AHBENR, RCC_AHBENR_DMA1EN);\
+ /* Delay after an RCC peripheral clock enabling */\
+ tmpreg = READ_BIT(RCC->AHBENR, RCC_AHBENR_DMA1EN);\
+ UNUSED(tmpreg); \
+ } while(0U)
+#define __HAL_RCC_SRAM_CLK_ENABLE() do { \
+ __IO uint32_t tmpreg; \
+ SET_BIT(RCC->AHBENR, RCC_AHBENR_SRAMEN);\
+ /* Delay after an RCC peripheral clock enabling */\
+ tmpreg = READ_BIT(RCC->AHBENR, RCC_AHBENR_SRAMEN);\
+ UNUSED(tmpreg); \
+ } while(0U)
+#define __HAL_RCC_FLITF_CLK_ENABLE() do { \
+ __IO uint32_t tmpreg; \
+ SET_BIT(RCC->AHBENR, RCC_AHBENR_FLITFEN);\
+ /* Delay after an RCC peripheral clock enabling */\
+ tmpreg = READ_BIT(RCC->AHBENR, RCC_AHBENR_FLITFEN);\
+ UNUSED(tmpreg); \
+ } while(0U)
+
+#define __HAL_RCC_GPIOA_CLK_DISABLE() (RCC->AHBENR &= ~(RCC_AHBENR_GPIOAEN))
+#define __HAL_RCC_GPIOB_CLK_DISABLE() (RCC->AHBENR &= ~(RCC_AHBENR_GPIOBEN))
+#define __HAL_RCC_GPIOC_CLK_DISABLE() (RCC->AHBENR &= ~(RCC_AHBENR_GPIOCEN))
+#define __HAL_RCC_GPIOF_CLK_DISABLE() (RCC->AHBENR &= ~(RCC_AHBENR_GPIOFEN))
+#define __HAL_RCC_CRC_CLK_DISABLE() (RCC->AHBENR &= ~(RCC_AHBENR_CRCEN))
+#define __HAL_RCC_DMA1_CLK_DISABLE() (RCC->AHBENR &= ~(RCC_AHBENR_DMA1EN))
+#define __HAL_RCC_SRAM_CLK_DISABLE() (RCC->AHBENR &= ~(RCC_AHBENR_SRAMEN))
+#define __HAL_RCC_FLITF_CLK_DISABLE() (RCC->AHBENR &= ~(RCC_AHBENR_FLITFEN))
+/**
+ * @}
+ */
+
+/** @defgroup RCC_AHB_Peripheral_Clock_Enable_Disable_Status AHB Peripheral Clock Enable Disable Status
+ * @brief Get the enable or disable status of the AHB peripheral clock.
+ * @note After reset, the peripheral clock (used for registers read/write access)
+ * is disabled and the application software has to enable this clock before
+ * using it.
+ * @{
+ */
+#define __HAL_RCC_GPIOA_IS_CLK_ENABLED() ((RCC->AHBENR & (RCC_AHBENR_GPIOAEN)) != RESET)
+#define __HAL_RCC_GPIOB_IS_CLK_ENABLED() ((RCC->AHBENR & (RCC_AHBENR_GPIOBEN)) != RESET)
+#define __HAL_RCC_GPIOC_IS_CLK_ENABLED() ((RCC->AHBENR & (RCC_AHBENR_GPIOCEN)) != RESET)
+#define __HAL_RCC_GPIOF_IS_CLK_ENABLED() ((RCC->AHBENR & (RCC_AHBENR_GPIOFEN)) != RESET)
+#define __HAL_RCC_CRC_IS_CLK_ENABLED() ((RCC->AHBENR & (RCC_AHBENR_CRCEN)) != RESET)
+#define __HAL_RCC_DMA1_IS_CLK_ENABLED() ((RCC->AHBENR & (RCC_AHBENR_DMA1EN)) != RESET)
+#define __HAL_RCC_SRAM_IS_CLK_ENABLED() ((RCC->AHBENR & (RCC_AHBENR_SRAMEN)) != RESET)
+#define __HAL_RCC_FLITF_IS_CLK_ENABLED() ((RCC->AHBENR & (RCC_AHBENR_FLITFEN)) != RESET)
+#define __HAL_RCC_GPIOA_IS_CLK_DISABLED() ((RCC->AHBENR & (RCC_AHBENR_GPIOAEN)) == RESET)
+#define __HAL_RCC_GPIOB_IS_CLK_DISABLED() ((RCC->AHBENR & (RCC_AHBENR_GPIOBEN)) == RESET)
+#define __HAL_RCC_GPIOC_IS_CLK_DISABLED() ((RCC->AHBENR & (RCC_AHBENR_GPIOCEN)) == RESET)
+#define __HAL_RCC_GPIOF_IS_CLK_DISABLED() ((RCC->AHBENR & (RCC_AHBENR_GPIOFEN)) == RESET)
+#define __HAL_RCC_CRC_IS_CLK_DISABLED() ((RCC->AHBENR & (RCC_AHBENR_CRCEN)) == RESET)
+#define __HAL_RCC_DMA1_IS_CLK_DISABLED() ((RCC->AHBENR & (RCC_AHBENR_DMA1EN)) == RESET)
+#define __HAL_RCC_SRAM_IS_CLK_DISABLED() ((RCC->AHBENR & (RCC_AHBENR_SRAMEN)) == RESET)
+#define __HAL_RCC_FLITF_IS_CLK_DISABLED() ((RCC->AHBENR & (RCC_AHBENR_FLITFEN)) == RESET)
+/**
+ * @}
+ */
+
+/** @defgroup RCC_APB1_Clock_Enable_Disable RCC APB1 Clock Enable Disable
+ * @brief Enable or disable the Low Speed APB (APB1) peripheral clock.
+ * @note After reset, the peripheral clock (used for registers read/write access)
+ * is disabled and the application software has to enable this clock before
+ * using it.
+ * @{
+ */
+#define __HAL_RCC_TIM3_CLK_ENABLE() do { \
+ __IO uint32_t tmpreg; \
+ SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM3EN);\
+ /* Delay after an RCC peripheral clock enabling */\
+ tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM3EN);\
+ UNUSED(tmpreg); \
+ } while(0U)
+#define __HAL_RCC_TIM14_CLK_ENABLE() do { \
+ __IO uint32_t tmpreg; \
+ SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM14EN);\
+ /* Delay after an RCC peripheral clock enabling */\
+ tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM14EN);\
+ UNUSED(tmpreg); \
+ } while(0U)
+#define __HAL_RCC_WWDG_CLK_ENABLE() do { \
+ __IO uint32_t tmpreg; \
+ SET_BIT(RCC->APB1ENR, RCC_APB1ENR_WWDGEN);\
+ /* Delay after an RCC peripheral clock enabling */\
+ tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_WWDGEN);\
+ UNUSED(tmpreg); \
+ } while(0U)
+#define __HAL_RCC_I2C1_CLK_ENABLE() do { \
+ __IO uint32_t tmpreg; \
+ SET_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C1EN);\
+ /* Delay after an RCC peripheral clock enabling */\
+ tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C1EN);\
+ UNUSED(tmpreg); \
+ } while(0U)
+#define __HAL_RCC_PWR_CLK_ENABLE() do { \
+ __IO uint32_t tmpreg; \
+ SET_BIT(RCC->APB1ENR, RCC_APB1ENR_PWREN);\
+ /* Delay after an RCC peripheral clock enabling */\
+ tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_PWREN);\
+ UNUSED(tmpreg); \
+ } while(0U)
+
+#define __HAL_RCC_TIM3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM3EN))
+#define __HAL_RCC_TIM14_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM14EN))
+#define __HAL_RCC_WWDG_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_WWDGEN))
+#define __HAL_RCC_I2C1_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_I2C1EN))
+#define __HAL_RCC_PWR_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_PWREN))
+/**
+ * @}
+ */
+
+/** @defgroup RCC_APB1_Peripheral_Clock_Enable_Disable_Status APB1 Peripheral Clock Enable Disable Status
+ * @brief Get the enable or disable status of the APB1 peripheral clock.
+ * @note After reset, the peripheral clock (used for registers read/write access)
+ * is disabled and the application software has to enable this clock before
+ * using it.
+ * @{
+ */
+#define __HAL_RCC_TIM3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM3EN)) != RESET)
+#define __HAL_RCC_TIM14_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM14EN)) != RESET)
+#define __HAL_RCC_WWDG_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_WWDGEN)) != RESET)
+#define __HAL_RCC_I2C1_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C1EN)) != RESET)
+#define __HAL_RCC_PWR_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_PWREN)) != RESET)
+#define __HAL_RCC_TIM3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM3EN)) == RESET)
+#define __HAL_RCC_TIM14_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM14EN)) == RESET)
+#define __HAL_RCC_WWDG_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_WWDGEN)) == RESET)
+#define __HAL_RCC_I2C1_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C1EN)) == RESET)
+#define __HAL_RCC_PWR_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_PWREN)) == RESET)
+/**
+ * @}
+ */
+
+
+/** @defgroup RCC_APB2_Clock_Enable_Disable RCC APB2 Clock Enable Disable
+ * @brief Enable or disable the High Speed APB (APB2) peripheral clock.
+ * @note After reset, the peripheral clock (used for registers read/write access)
+ * is disabled and the application software has to enable this clock before
+ * using it.
+ * @{
+ */
+#define __HAL_RCC_SYSCFG_CLK_ENABLE() do { \
+ __IO uint32_t tmpreg; \
+ SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SYSCFGEN);\
+ /* Delay after an RCC peripheral clock enabling */\
+ tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SYSCFGEN);\
+ UNUSED(tmpreg); \
+ } while(0U)
+#define __HAL_RCC_ADC1_CLK_ENABLE() do { \
+ __IO uint32_t tmpreg; \
+ SET_BIT(RCC->APB2ENR, RCC_APB2ENR_ADC1EN);\
+ /* Delay after an RCC peripheral clock enabling */\
+ tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_ADC1EN);\
+ UNUSED(tmpreg); \
+ } while(0U)
+#define __HAL_RCC_TIM1_CLK_ENABLE() do { \
+ __IO uint32_t tmpreg; \
+ SET_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM1EN);\
+ /* Delay after an RCC peripheral clock enabling */\
+ tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM1EN);\
+ UNUSED(tmpreg); \
+ } while(0U)
+#define __HAL_RCC_SPI1_CLK_ENABLE() do { \
+ __IO uint32_t tmpreg; \
+ SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI1EN);\
+ /* Delay after an RCC peripheral clock enabling */\
+ tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI1EN);\
+ UNUSED(tmpreg); \
+ } while(0U)
+#define __HAL_RCC_TIM16_CLK_ENABLE() do { \
+ __IO uint32_t tmpreg; \
+ SET_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM16EN);\
+ /* Delay after an RCC peripheral clock enabling */\
+ tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM16EN);\
+ UNUSED(tmpreg); \
+ } while(0U)
+#define __HAL_RCC_TIM17_CLK_ENABLE() do { \
+ __IO uint32_t tmpreg; \
+ SET_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM17EN);\
+ /* Delay after an RCC peripheral clock enabling */\
+ tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM17EN);\
+ UNUSED(tmpreg); \
+ } while(0U)
+#define __HAL_RCC_USART1_CLK_ENABLE() do { \
+ __IO uint32_t tmpreg; \
+ SET_BIT(RCC->APB2ENR, RCC_APB2ENR_USART1EN);\
+ /* Delay after an RCC peripheral clock enabling */\
+ tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_USART1EN);\
+ UNUSED(tmpreg); \
+ } while(0U)
+#define __HAL_RCC_DBGMCU_CLK_ENABLE() do { \
+ __IO uint32_t tmpreg; \
+ SET_BIT(RCC->APB2ENR, RCC_APB2ENR_DBGMCUEN);\
+ /* Delay after an RCC peripheral clock enabling */\
+ tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_DBGMCUEN);\
+ UNUSED(tmpreg); \
+ } while(0U)
+
+#define __HAL_RCC_SYSCFG_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SYSCFGEN))
+#define __HAL_RCC_ADC1_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_ADC1EN))
+#define __HAL_RCC_TIM1_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_TIM1EN))
+#define __HAL_RCC_SPI1_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SPI1EN))
+#define __HAL_RCC_TIM16_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_TIM16EN))
+#define __HAL_RCC_TIM17_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_TIM17EN))
+#define __HAL_RCC_USART1_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_USART1EN))
+#define __HAL_RCC_DBGMCU_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_DBGMCUEN))
+/**
+ * @}
+ */
+
+/** @defgroup RCC_APB2_Peripheral_Clock_Enable_Disable_Status APB2 Peripheral Clock Enable Disable Status
+ * @brief Get the enable or disable status of the APB2 peripheral clock.
+ * @note After reset, the peripheral clock (used for registers read/write access)
+ * is disabled and the application software has to enable this clock before
+ * using it.
+ * @{
+ */
+#define __HAL_RCC_SYSCFG_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SYSCFGEN)) != RESET)
+#define __HAL_RCC_ADC1_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_ADC1EN)) != RESET)
+#define __HAL_RCC_TIM1_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM1EN)) != RESET)
+#define __HAL_RCC_SPI1_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI1EN)) != RESET)
+#define __HAL_RCC_TIM16_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM16EN)) != RESET)
+#define __HAL_RCC_TIM17_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM17EN)) != RESET)
+#define __HAL_RCC_USART1_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_USART1EN)) != RESET)
+#define __HAL_RCC_DBGMCU_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_DBGMCUEN)) != RESET)
+#define __HAL_RCC_SYSCFG_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SYSCFGEN)) == RESET)
+#define __HAL_RCC_ADC1_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_ADC1EN)) == RESET)
+#define __HAL_RCC_TIM1_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM1EN)) == RESET)
+#define __HAL_RCC_SPI1_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI1EN)) == RESET)
+#define __HAL_RCC_TIM16_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM16EN)) == RESET)
+#define __HAL_RCC_TIM17_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM17EN)) == RESET)
+#define __HAL_RCC_USART1_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_USART1EN)) == RESET)
+#define __HAL_RCC_DBGMCU_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_DBGMCUEN)) == RESET)
+/**
+ * @}
+ */
+
+/** @defgroup RCC_AHB_Force_Release_Reset RCC AHB Force Release Reset
+ * @brief Force or release AHB peripheral reset.
+ * @{
+ */
+#define __HAL_RCC_AHB_FORCE_RESET() (RCC->AHBRSTR = 0xFFFFFFFFU)
+#define __HAL_RCC_GPIOA_FORCE_RESET() (RCC->AHBRSTR |= (RCC_AHBRSTR_GPIOARST))
+#define __HAL_RCC_GPIOB_FORCE_RESET() (RCC->AHBRSTR |= (RCC_AHBRSTR_GPIOBRST))
+#define __HAL_RCC_GPIOC_FORCE_RESET() (RCC->AHBRSTR |= (RCC_AHBRSTR_GPIOCRST))
+#define __HAL_RCC_GPIOF_FORCE_RESET() (RCC->AHBRSTR |= (RCC_AHBRSTR_GPIOFRST))
+
+#define __HAL_RCC_AHB_RELEASE_RESET() (RCC->AHBRSTR = 0x00000000U)
+#define __HAL_RCC_GPIOA_RELEASE_RESET() (RCC->AHBRSTR &= ~(RCC_AHBRSTR_GPIOARST))
+#define __HAL_RCC_GPIOB_RELEASE_RESET() (RCC->AHBRSTR &= ~(RCC_AHBRSTR_GPIOBRST))
+#define __HAL_RCC_GPIOC_RELEASE_RESET() (RCC->AHBRSTR &= ~(RCC_AHBRSTR_GPIOCRST))
+#define __HAL_RCC_GPIOF_RELEASE_RESET() (RCC->AHBRSTR &= ~(RCC_AHBRSTR_GPIOFRST))
+/**
+ * @}
+ */
+
+/** @defgroup RCC_APB1_Force_Release_Reset RCC APB1 Force Release Reset
+ * @brief Force or release APB1 peripheral reset.
+ * @{
+ */
+#define __HAL_RCC_APB1_FORCE_RESET() (RCC->APB1RSTR = 0xFFFFFFFFU)
+#define __HAL_RCC_TIM3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM3RST))
+#define __HAL_RCC_TIM14_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM14RST))
+#define __HAL_RCC_WWDG_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_WWDGRST))
+#define __HAL_RCC_I2C1_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_I2C1RST))
+#define __HAL_RCC_PWR_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_PWRRST))
+
+#define __HAL_RCC_APB1_RELEASE_RESET() (RCC->APB1RSTR = 0x00000000U)
+#define __HAL_RCC_TIM3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM3RST))
+#define __HAL_RCC_TIM14_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM14RST))
+#define __HAL_RCC_WWDG_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_WWDGRST))
+#define __HAL_RCC_I2C1_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_I2C1RST))
+#define __HAL_RCC_PWR_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_PWRRST))
+/**
+ * @}
+ */
+
+/** @defgroup RCC_APB2_Force_Release_Reset RCC APB2 Force Release Reset
+ * @brief Force or release APB2 peripheral reset.
+ * @{
+ */
+#define __HAL_RCC_APB2_FORCE_RESET() (RCC->APB2RSTR = 0xFFFFFFFFU)
+#define __HAL_RCC_SYSCFG_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SYSCFGRST))
+#define __HAL_RCC_ADC1_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_ADC1RST))
+#define __HAL_RCC_TIM1_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_TIM1RST))
+#define __HAL_RCC_SPI1_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SPI1RST))
+#define __HAL_RCC_USART1_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_USART1RST))
+#define __HAL_RCC_TIM16_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_TIM16RST))
+#define __HAL_RCC_TIM17_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_TIM17RST))
+#define __HAL_RCC_DBGMCU_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_DBGMCURST))
+
+#define __HAL_RCC_APB2_RELEASE_RESET() (RCC->APB2RSTR = 0x00000000U)
+#define __HAL_RCC_SYSCFG_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SYSCFGRST))
+#define __HAL_RCC_ADC1_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_ADC1RST))
+#define __HAL_RCC_TIM1_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_TIM1RST))
+#define __HAL_RCC_SPI1_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SPI1RST))
+#define __HAL_RCC_USART1_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_USART1RST))
+#define __HAL_RCC_TIM16_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_TIM16RST))
+#define __HAL_RCC_TIM17_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_TIM17RST))
+#define __HAL_RCC_DBGMCU_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_DBGMCURST))
+/**
+ * @}
+ */
+/** @defgroup RCC_HSI_Configuration HSI Configuration
+ * @{
+ */
+
+/** @brief Macros to enable or disable the Internal High Speed oscillator (HSI).
+ * @note The HSI is stopped by hardware when entering STOP and STANDBY modes.
+ * @note HSI can not be stopped if it is used as system clock source. In this case,
+ * you have to select another source of the system clock then stop the HSI.
+ * @note After enabling the HSI, the application software should wait on HSIRDY
+ * flag to be set indicating that HSI clock is stable and can be used as
+ * system clock source.
+ * @note When the HSI is stopped, HSIRDY flag goes low after 6 HSI oscillator
+ * clock cycles.
+ */
+#define __HAL_RCC_HSI_ENABLE() SET_BIT(RCC->CR, RCC_CR_HSION)
+#define __HAL_RCC_HSI_DISABLE() CLEAR_BIT(RCC->CR, RCC_CR_HSION)
+
+/** @brief Macro to adjust the Internal High Speed oscillator (HSI) calibration value.
+ * @note The calibration is used to compensate for the variations in voltage
+ * and temperature that influence the frequency of the internal HSI RC.
+ * @param _HSICALIBRATIONVALUE_ specifies the calibration trimming value.
+ * (default is RCC_HSICALIBRATION_DEFAULT).
+ * This parameter must be a number between 0 and 0x1F.
+ */
+#define __HAL_RCC_HSI_CALIBRATIONVALUE_ADJUST(_HSICALIBRATIONVALUE_) \
+ MODIFY_REG(RCC->CR, RCC_CR_HSITRIM, (uint32_t)(_HSICALIBRATIONVALUE_) << RCC_CR_HSITRIM_BitNumber)
+
+/**
+ * @}
+ */
+
+/** @defgroup RCC_LSI_Configuration LSI Configuration
+ * @{
+ */
+
+/** @brief Macro to enable the Internal Low Speed oscillator (LSI).
+ * @note After enabling the LSI, the application software should wait on
+ * LSIRDY flag to be set indicating that LSI clock is stable and can
+ * be used to clock the IWDG and/or the RTC.
+ */
+#define __HAL_RCC_LSI_ENABLE() SET_BIT(RCC->CSR, RCC_CSR_LSION)
+
+/** @brief Macro to disable the Internal Low Speed oscillator (LSI).
+ * @note LSI can not be disabled if the IWDG is running.
+ * @note When the LSI is stopped, LSIRDY flag goes low after 6 LSI oscillator
+ * clock cycles.
+ */
+#define __HAL_RCC_LSI_DISABLE() CLEAR_BIT(RCC->CSR, RCC_CSR_LSION)
+
+/**
+ * @}
+ */
+
+/** @defgroup RCC_HSE_Configuration HSE Configuration
+ * @{
+ */
+
+/**
+ * @brief Macro to configure the External High Speed oscillator (HSE).
+ * @note Transition HSE Bypass to HSE On and HSE On to HSE Bypass are not
+ * supported by this macro. User should request a transition to HSE Off
+ * first and then HSE On or HSE Bypass.
+ * @note After enabling the HSE (RCC_HSE_ON or RCC_HSE_Bypass), the application
+ * software should wait on HSERDY flag to be set indicating that HSE clock
+ * is stable and can be used to clock the PLL and/or system clock.
+ * @note HSE state can not be changed if it is used directly or through the
+ * PLL as system clock. In this case, you have to select another source
+ * of the system clock then change the HSE state (ex. disable it).
+ * @note The HSE is stopped by hardware when entering STOP and STANDBY modes.
+ * @note This function reset the CSSON bit, so if the clock security system(CSS)
+ * was previously enabled you have to enable it again after calling this
+ * function.
+ * @param __STATE__ specifies the new state of the HSE.
+ * This parameter can be one of the following values:
+ * @arg @ref RCC_HSE_OFF turn OFF the HSE oscillator, HSERDY flag goes low after
+ * 6 HSE oscillator clock cycles.
+ * @arg @ref RCC_HSE_ON turn ON the HSE oscillator
+ * @arg @ref RCC_HSE_BYPASS HSE oscillator bypassed with external clock
+ */
+#define __HAL_RCC_HSE_CONFIG(__STATE__) \
+ do{ \
+ if ((__STATE__) == RCC_HSE_ON) \
+ { \
+ SET_BIT(RCC->CR, RCC_CR_HSEON); \
+ } \
+ else if ((__STATE__) == RCC_HSE_OFF) \
+ { \
+ CLEAR_BIT(RCC->CR, RCC_CR_HSEON); \
+ CLEAR_BIT(RCC->CR, RCC_CR_HSEBYP); \
+ } \
+ else if ((__STATE__) == RCC_HSE_BYPASS) \
+ { \
+ SET_BIT(RCC->CR, RCC_CR_HSEBYP); \
+ SET_BIT(RCC->CR, RCC_CR_HSEON); \
+ } \
+ else \
+ { \
+ CLEAR_BIT(RCC->CR, RCC_CR_HSEON); \
+ CLEAR_BIT(RCC->CR, RCC_CR_HSEBYP); \
+ } \
+ }while(0U)
+
+/**
+ * @brief Macro to configure the External High Speed oscillator (HSE) Predivision factor for PLL.
+ * @note Predivision factor can not be changed if PLL is used as system clock
+ * In this case, you have to select another source of the system clock, disable the PLL and
+ * then change the HSE predivision factor.
+ * @param __HSE_PREDIV_VALUE__ specifies the division value applied to HSE.
+ * This parameter must be a number between RCC_HSE_PREDIV_DIV1 and RCC_HSE_PREDIV_DIV16.
+ */
+#define __HAL_RCC_HSE_PREDIV_CONFIG(__HSE_PREDIV_VALUE__) \
+ MODIFY_REG(RCC->CFGR2, RCC_CFGR2_PREDIV, (uint32_t)(__HSE_PREDIV_VALUE__))
+
+/**
+ * @}
+ */
+
+/** @defgroup RCC_LSE_Configuration LSE Configuration
+ * @{
+ */
+
+/**
+ * @brief Macro to configure the External Low Speed oscillator (LSE).
+ * @note Transitions LSE Bypass to LSE On and LSE On to LSE Bypass are not supported by this macro.
+ * @note As the LSE is in the Backup domain and write access is denied to
+ * this domain after reset, you have to enable write access using
+ * @ref HAL_PWR_EnableBkUpAccess() function before to configure the LSE
+ * (to be done once after reset).
+ * @note After enabling the LSE (RCC_LSE_ON or RCC_LSE_BYPASS), the application
+ * software should wait on LSERDY flag to be set indicating that LSE clock
+ * is stable and can be used to clock the RTC.
+ * @param __STATE__ specifies the new state of the LSE.
+ * This parameter can be one of the following values:
+ * @arg @ref RCC_LSE_OFF turn OFF the LSE oscillator, LSERDY flag goes low after
+ * 6 LSE oscillator clock cycles.
+ * @arg @ref RCC_LSE_ON turn ON the LSE oscillator.
+ * @arg @ref RCC_LSE_BYPASS LSE oscillator bypassed with external clock.
+ */
+#define __HAL_RCC_LSE_CONFIG(__STATE__) \
+ do{ \
+ if ((__STATE__) == RCC_LSE_ON) \
+ { \
+ SET_BIT(RCC->BDCR, RCC_BDCR_LSEON); \
+ } \
+ else if ((__STATE__) == RCC_LSE_OFF) \
+ { \
+ CLEAR_BIT(RCC->BDCR, RCC_BDCR_LSEON); \
+ CLEAR_BIT(RCC->BDCR, RCC_BDCR_LSEBYP); \
+ } \
+ else if ((__STATE__) == RCC_LSE_BYPASS) \
+ { \
+ SET_BIT(RCC->BDCR, RCC_BDCR_LSEBYP); \
+ SET_BIT(RCC->BDCR, RCC_BDCR_LSEON); \
+ } \
+ else \
+ { \
+ CLEAR_BIT(RCC->BDCR, RCC_BDCR_LSEON); \
+ CLEAR_BIT(RCC->BDCR, RCC_BDCR_LSEBYP); \
+ } \
+ }while(0U)
+
+/**
+ * @}
+ */
+
+/** @defgroup RCC_HSI14_Configuration RCC_HSI14_Configuration
+ * @{
+ */
+
+/** @brief Macro to enable the Internal 14Mhz High Speed oscillator (HSI14).
+ * @note After enabling the HSI14 with @ref __HAL_RCC_HSI14_ENABLE(), the application software
+ * should wait on HSI14RDY flag to be set indicating that HSI clock is stable and can be
+ * used as system clock source. This is not necessary if @ref HAL_RCC_OscConfig() is used.
+ * clock cycles.
+ */
+#define __HAL_RCC_HSI14_ENABLE() SET_BIT(RCC->CR2, RCC_CR2_HSI14ON)
+
+/** @brief Macro to disable the Internal 14Mhz High Speed oscillator (HSI14).
+ * @note The HSI14 is stopped by hardware when entering STOP and STANDBY modes.
+ * @note HSI14 can not be stopped if it is used as system clock source. In this case,
+ * you have to select another source of the system clock then stop the HSI14.
+ * @note When the HSI14 is stopped, HSI14RDY flag goes low after 6 HSI14 oscillator
+ * clock cycles.
+ */
+#define __HAL_RCC_HSI14_DISABLE() CLEAR_BIT(RCC->CR2, RCC_CR2_HSI14ON)
+
+/** @brief Macro to enable the Internal 14Mhz High Speed oscillator (HSI14) used by ADC.
+ */
+#define __HAL_RCC_HSI14ADC_ENABLE() CLEAR_BIT(RCC->CR2, RCC_CR2_HSI14DIS)
+
+/** @brief Macro to disable the Internal 14Mhz High Speed oscillator (HSI14) used by ADC.
+ */
+#define __HAL_RCC_HSI14ADC_DISABLE() SET_BIT(RCC->CR2, RCC_CR2_HSI14DIS)
+
+/** @brief Macro to adjust the Internal 14Mhz High Speed oscillator (HSI) calibration value.
+ * @note The calibration is used to compensate for the variations in voltage
+ * and temperature that influence the frequency of the internal HSI14 RC.
+ * @param __HSI14CALIBRATIONVALUE__ specifies the calibration trimming value
+ * (default is RCC_HSI14CALIBRATION_DEFAULT).
+ * This parameter must be a number between 0 and 0x1F.
+ */
+#define __HAL_RCC_HSI14_CALIBRATIONVALUE_ADJUST(__HSI14CALIBRATIONVALUE__) \
+ MODIFY_REG(RCC->CR2, RCC_CR2_HSI14TRIM, (uint32_t)(__HSI14CALIBRATIONVALUE__) << RCC_HSI14TRIM_BIT_NUMBER)
+/**
+ * @}
+ */
+
+/** @defgroup RCC_USARTx_Clock_Config RCC USARTx Clock Config
+ * @{
+ */
+
+/** @brief Macro to configure the USART1 clock (USART1CLK).
+ * @param __USART1CLKSOURCE__ specifies the USART1 clock source.
+ * This parameter can be one of the following values:
+ * @arg @ref RCC_USART1CLKSOURCE_PCLK1 PCLK1 selected as USART1 clock
+ * @arg @ref RCC_USART1CLKSOURCE_HSI HSI selected as USART1 clock
+ * @arg @ref RCC_USART1CLKSOURCE_SYSCLK System Clock selected as USART1 clock
+ * @arg @ref RCC_USART1CLKSOURCE_LSE LSE selected as USART1 clock
+ */
+#define __HAL_RCC_USART1_CONFIG(__USART1CLKSOURCE__) \
+ MODIFY_REG(RCC->CFGR3, RCC_CFGR3_USART1SW, (uint32_t)(__USART1CLKSOURCE__))
+
+/** @brief Macro to get the USART1 clock source.
+ * @retval The clock source can be one of the following values:
+ * @arg @ref RCC_USART1CLKSOURCE_PCLK1 PCLK1 selected as USART1 clock
+ * @arg @ref RCC_USART1CLKSOURCE_HSI HSI selected as USART1 clock
+ * @arg @ref RCC_USART1CLKSOURCE_SYSCLK System Clock selected as USART1 clock
+ * @arg @ref RCC_USART1CLKSOURCE_LSE LSE selected as USART1 clock
+ */
+#define __HAL_RCC_GET_USART1_SOURCE() ((uint32_t)(READ_BIT(RCC->CFGR3, RCC_CFGR3_USART1SW)))
+
+/**
+ * @}
+ */
+
+/** @defgroup RCC_I2Cx_Clock_Config RCC I2Cx Clock Config
+ * @{
+ */
+
+/** @brief Macro to configure the I2C1 clock (I2C1CLK).
+ * @param __I2C1CLKSOURCE__ specifies the I2C1 clock source.
+ * This parameter can be one of the following values:
+ * @arg @ref RCC_I2C1CLKSOURCE_HSI HSI selected as I2C1 clock
+ * @arg @ref RCC_I2C1CLKSOURCE_SYSCLK System Clock selected as I2C1 clock
+ */
+#define __HAL_RCC_I2C1_CONFIG(__I2C1CLKSOURCE__) \
+ MODIFY_REG(RCC->CFGR3, RCC_CFGR3_I2C1SW, (uint32_t)(__I2C1CLKSOURCE__))
+
+/** @brief Macro to get the I2C1 clock source.
+ * @retval The clock source can be one of the following values:
+ * @arg @ref RCC_I2C1CLKSOURCE_HSI HSI selected as I2C1 clock
+ * @arg @ref RCC_I2C1CLKSOURCE_SYSCLK System Clock selected as I2C1 clock
+ */
+#define __HAL_RCC_GET_I2C1_SOURCE() ((uint32_t)(READ_BIT(RCC->CFGR3, RCC_CFGR3_I2C1SW)))
+/**
+ * @}
+ */
+
+/** @defgroup RCC_PLL_Configuration PLL Configuration
+ * @{
+ */
+
+/** @brief Macro to enable the main PLL.
+ * @note After enabling the main PLL, the application software should wait on
+ * PLLRDY flag to be set indicating that PLL clock is stable and can
+ * be used as system clock source.
+ * @note The main PLL is disabled by hardware when entering STOP and STANDBY modes.
+ */
+#define __HAL_RCC_PLL_ENABLE() SET_BIT(RCC->CR, RCC_CR_PLLON)
+
+/** @brief Macro to disable the main PLL.
+ * @note The main PLL can not be disabled if it is used as system clock source
+ */
+#define __HAL_RCC_PLL_DISABLE() CLEAR_BIT(RCC->CR, RCC_CR_PLLON)
+
+/** @brief Macro to configure the PLL clock source, multiplication and division factors.
+ * @note This function must be used only when the main PLL is disabled.
+ *
+ * @param __RCC_PLLSOURCE__ specifies the PLL entry clock source.
+ * This parameter can be one of the following values:
+ * @arg @ref RCC_PLLSOURCE_HSI HSI oscillator clock selected as PLL clock entry
+ * @arg @ref RCC_PLLSOURCE_HSE HSE oscillator clock selected as PLL clock entry
+ * @param __PLLMUL__ specifies the multiplication factor for PLL VCO output clock
+ * This parameter can be one of the following values:
+ * This parameter must be a number between RCC_PLL_MUL2 and RCC_PLL_MUL16.
+ * @param __PREDIV__ specifies the predivider factor for PLL VCO input clock
+ * This parameter must be a number between RCC_PREDIV_DIV1 and RCC_PREDIV_DIV16.
+ *
+ */
+#define __HAL_RCC_PLL_CONFIG(__RCC_PLLSOURCE__ , __PREDIV__, __PLLMUL__) \
+ do { \
+ MODIFY_REG(RCC->CFGR2, RCC_CFGR2_PREDIV, (__PREDIV__)); \
+ MODIFY_REG(RCC->CFGR, RCC_CFGR_PLLMUL | RCC_CFGR_PLLSRC, (uint32_t)((__PLLMUL__)|(__RCC_PLLSOURCE__))); \
+ } while(0U)
+
+
+/** @brief Get oscillator clock selected as PLL input clock
+ * @retval The clock source used for PLL entry. The returned value can be one
+ * of the following:
+ * @arg @ref RCC_PLLSOURCE_HSE HSE oscillator clock selected as PLL input clock
+ */
+#define __HAL_RCC_GET_PLL_OSCSOURCE() ((uint32_t)(READ_BIT(RCC->CFGR, RCC_CFGR_PLLSRC)))
+
+/**
+ * @}
+ */
+
+/** @defgroup RCC_Get_Clock_source Get Clock source
+ * @{
+ */
+
+/**
+ * @brief Macro to configure the system clock source.
+ * @param __SYSCLKSOURCE__ specifies the system clock source.
+ * This parameter can be one of the following values:
+ * @arg @ref RCC_SYSCLKSOURCE_HSI HSI oscillator is used as system clock source.
+ * @arg @ref RCC_SYSCLKSOURCE_HSE HSE oscillator is used as system clock source.
+ * @arg @ref RCC_SYSCLKSOURCE_PLLCLK PLL output is used as system clock source.
+ */
+#define __HAL_RCC_SYSCLK_CONFIG(__SYSCLKSOURCE__) \
+ MODIFY_REG(RCC->CFGR, RCC_CFGR_SW, (__SYSCLKSOURCE__))
+
+/** @brief Macro to get the clock source used as system clock.
+ * @retval The clock source used as system clock. The returned value can be one
+ * of the following:
+ * @arg @ref RCC_SYSCLKSOURCE_STATUS_HSI HSI used as system clock
+ * @arg @ref RCC_SYSCLKSOURCE_STATUS_HSE HSE used as system clock
+ * @arg @ref RCC_SYSCLKSOURCE_STATUS_PLLCLK PLL used as system clock
+ */
+#define __HAL_RCC_GET_SYSCLK_SOURCE() ((uint32_t)(RCC->CFGR & RCC_CFGR_SWS))
+
+/**
+ * @}
+ */
+
+/** @defgroup RCCEx_MCOx_Clock_Config RCC Extended MCOx Clock Config
+ * @{
+ */
+
+#if defined(RCC_CFGR_MCOPRE)
+/** @brief Macro to configure the MCO clock.
+ * @param __MCOCLKSOURCE__ specifies the MCO clock source.
+ * This parameter can be one of the following values:
+ * @arg @ref RCC_MCO1SOURCE_NOCLOCK No clock selected as MCO clock
+ * @arg @ref RCC_MCO1SOURCE_SYSCLK System Clock selected as MCO clock
+ * @arg @ref RCC_MCO1SOURCE_HSI HSI oscillator clock selected as MCO clock
+ * @arg @ref RCC_MCO1SOURCE_HSE HSE selected as MCO clock
+ * @arg @ref RCC_MCO1SOURCE_LSI LSI selected as MCO clock
+ * @arg @ref RCC_MCO1SOURCE_LSE LSE selected as MCO clock
+ * @arg @ref RCC_MCO1SOURCE_HSI14 HSI14 selected as MCO clock
+ @if STM32F042x6
+ * @arg @ref RCC_MCO1SOURCE_HSI48 HSI48 selected as MCO clock
+ * @arg @ref RCC_MCO1SOURCE_PLLCLK PLLCLK selected as MCO clock
+ @elseif STM32F048xx
+ * @arg @ref RCC_MCO1SOURCE_HSI48 HSI48 selected as MCO clock
+ * @arg @ref RCC_MCO1SOURCE_PLLCLK PLLCLK selected as MCO clock
+ @elseif STM32F071xB
+ * @arg @ref RCC_MCO1SOURCE_HSI48 HSI48 selected as MCO clock
+ * @arg @ref RCC_MCO1SOURCE_PLLCLK PLLCLK selected as MCO clock
+ @elseif STM32F072xB
+ * @arg @ref RCC_MCO1SOURCE_HSI48 HSI48 selected as MCO clock
+ * @arg @ref RCC_MCO1SOURCE_PLLCLK PLLCLK selected as MCO clock
+ @elseif STM32F078xx
+ * @arg @ref RCC_MCO1SOURCE_HSI48 HSI48 selected as MCO clock
+ * @arg @ref RCC_MCO1SOURCE_PLLCLK PLLCLK selected as MCO clock
+ @elseif STM32F091xC
+ * @arg @ref RCC_MCO1SOURCE_HSI48 HSI48 selected as MCO clock
+ * @arg @ref RCC_MCO1SOURCE_PLLCLK PLLCLK selected as MCO clock
+ @elseif STM32F098xx
+ * @arg @ref RCC_MCO1SOURCE_HSI48 HSI48 selected as MCO clock
+ * @arg @ref RCC_MCO1SOURCE_PLLCLK PLLCLK selected as MCO clock
+ @elseif STM32F030x6
+ * @arg @ref RCC_MCO1SOURCE_PLLCLK PLLCLK selected as MCO clock
+ @elseif STM32F030xC
+ * @arg @ref RCC_MCO1SOURCE_PLLCLK PLLCLK selected as MCO clock
+ @elseif STM32F031x6
+ * @arg @ref RCC_MCO1SOURCE_PLLCLK PLLCLK selected as MCO clock
+ @elseif STM32F038xx
+ * @arg @ref RCC_MCO1SOURCE_PLLCLK PLLCLK selected as MCO clock
+ @elseif STM32F070x6
+ * @arg @ref RCC_MCO1SOURCE_PLLCLK PLLCLK selected as MCO clock
+ @elseif STM32F070xB
+ * @arg @ref RCC_MCO1SOURCE_PLLCLK PLLCLK selected as MCO clock
+ @endif
+ * @arg @ref RCC_MCO1SOURCE_PLLCLK_DIV2 PLLCLK Divided by 2 selected as MCO clock
+ * @param __MCODIV__ specifies the MCO clock prescaler.
+ * This parameter can be one of the following values:
+ * @arg @ref RCC_MCODIV_1 MCO clock source is divided by 1
+ * @arg @ref RCC_MCODIV_2 MCO clock source is divided by 2
+ * @arg @ref RCC_MCODIV_4 MCO clock source is divided by 4
+ * @arg @ref RCC_MCODIV_8 MCO clock source is divided by 8
+ * @arg @ref RCC_MCODIV_16 MCO clock source is divided by 16
+ * @arg @ref RCC_MCODIV_32 MCO clock source is divided by 32
+ * @arg @ref RCC_MCODIV_64 MCO clock source is divided by 64
+ * @arg @ref RCC_MCODIV_128 MCO clock source is divided by 128
+ */
+#else
+/** @brief Macro to configure the MCO clock.
+ * @param __MCOCLKSOURCE__ specifies the MCO clock source.
+ * This parameter can be one of the following values:
+ * @arg @ref RCC_MCO1SOURCE_NOCLOCK No clock selected as MCO clock
+ * @arg @ref RCC_MCO1SOURCE_SYSCLK System Clock selected as MCO clock
+ * @arg @ref RCC_MCO1SOURCE_HSI HSI selected as MCO clock
+ * @arg @ref RCC_MCO1SOURCE_HSE HSE selected as MCO clock
+ * @arg @ref RCC_MCO1SOURCE_LSI LSI selected as MCO clock
+ * @arg @ref RCC_MCO1SOURCE_LSE LSE selected as MCO clock
+ * @arg @ref RCC_MCO1SOURCE_HSI14 HSI14 selected as MCO clock
+ * @arg @ref RCC_MCO1SOURCE_PLLCLK_DIV2 PLLCLK Divided by 2 selected as MCO clock
+ * @param __MCODIV__ specifies the MCO clock prescaler.
+ * This parameter can be one of the following values:
+ * @arg @ref RCC_MCODIV_1 No division applied on MCO clock source
+ */
+#endif
+#if defined(RCC_CFGR_MCOPRE)
+#define __HAL_RCC_MCO1_CONFIG(__MCOCLKSOURCE__, __MCODIV__) \
+ MODIFY_REG(RCC->CFGR, (RCC_CFGR_MCO | RCC_CFGR_MCOPRE), ((__MCOCLKSOURCE__) | (__MCODIV__)))
+#else
+
+#define __HAL_RCC_MCO1_CONFIG(__MCOCLKSOURCE__, __MCODIV__) \
+ MODIFY_REG(RCC->CFGR, RCC_CFGR_MCO, (__MCOCLKSOURCE__))
+
+#endif
+
+/**
+ * @}
+ */
+
+ /** @defgroup RCC_RTC_Clock_Configuration RCC RTC Clock Configuration
+ * @{
+ */
+
+/** @brief Macro to configure the RTC clock (RTCCLK).
+ * @note As the RTC clock configuration bits are in the Backup domain and write
+ * access is denied to this domain after reset, you have to enable write
+ * access using the Power Backup Access macro before to configure
+ * the RTC clock source (to be done once after reset).
+ * @note Once the RTC clock is configured it cannot be changed unless the
+ * Backup domain is reset using @ref __HAL_RCC_BACKUPRESET_FORCE() macro, or by
+ * a Power On Reset (POR).
+ *
+ * @param __RTC_CLKSOURCE__ specifies the RTC clock source.
+ * This parameter can be one of the following values:
+ * @arg @ref RCC_RTCCLKSOURCE_NO_CLK No clock selected as RTC clock
+ * @arg @ref RCC_RTCCLKSOURCE_LSE LSE selected as RTC clock
+ * @arg @ref RCC_RTCCLKSOURCE_LSI LSI selected as RTC clock
+ * @arg @ref RCC_RTCCLKSOURCE_HSE_DIV32 HSE clock divided by 32
+ * @note If the LSE or LSI is used as RTC clock source, the RTC continues to
+ * work in STOP and STANDBY modes, and can be used as wakeup source.
+ * However, when the LSI clock and HSE clock divided by 32 is used as RTC clock source,
+ * the RTC cannot be used in STOP and STANDBY modes.
+ * @note The system must always be configured so as to get a PCLK frequency greater than or
+ * equal to the RTCCLK frequency for a proper operation of the RTC.
+ */
+#define __HAL_RCC_RTC_CONFIG(__RTC_CLKSOURCE__) MODIFY_REG(RCC->BDCR, RCC_BDCR_RTCSEL, (__RTC_CLKSOURCE__))
+
+/** @brief Macro to get the RTC clock source.
+ * @retval The clock source can be one of the following values:
+ * @arg @ref RCC_RTCCLKSOURCE_NO_CLK No clock selected as RTC clock
+ * @arg @ref RCC_RTCCLKSOURCE_LSE LSE selected as RTC clock
+ * @arg @ref RCC_RTCCLKSOURCE_LSI LSI selected as RTC clock
+ * @arg @ref RCC_RTCCLKSOURCE_HSE_DIV32 HSE clock divided by 32
+ */
+#define __HAL_RCC_GET_RTC_SOURCE() (READ_BIT(RCC->BDCR, RCC_BDCR_RTCSEL))
+
+/** @brief Macro to enable the the RTC clock.
+ * @note These macros must be used only after the RTC clock source was selected.
+ */
+#define __HAL_RCC_RTC_ENABLE() SET_BIT(RCC->BDCR, RCC_BDCR_RTCEN)
+
+/** @brief Macro to disable the the RTC clock.
+ * @note These macros must be used only after the RTC clock source was selected.
+ */
+#define __HAL_RCC_RTC_DISABLE() CLEAR_BIT(RCC->BDCR, RCC_BDCR_RTCEN)
+
+/** @brief Macro to force the Backup domain reset.
+ * @note This function resets the RTC peripheral (including the backup registers)
+ * and the RTC clock source selection in RCC_BDCR register.
+ */
+#define __HAL_RCC_BACKUPRESET_FORCE() SET_BIT(RCC->BDCR, RCC_BDCR_BDRST)
+
+/** @brief Macros to release the Backup domain reset.
+ */
+#define __HAL_RCC_BACKUPRESET_RELEASE() CLEAR_BIT(RCC->BDCR, RCC_BDCR_BDRST)
+
+/**
+ * @}
+ */
+
+/** @defgroup RCC_Flags_Interrupts_Management Flags Interrupts Management
+ * @brief macros to manage the specified RCC Flags and interrupts.
+ * @{
+ */
+
+/** @brief Enable RCC interrupt.
+ * @param __INTERRUPT__ specifies the RCC interrupt sources to be enabled.
+ * This parameter can be any combination of the following values:
+ * @arg @ref RCC_IT_LSIRDY LSI ready interrupt
+ * @arg @ref RCC_IT_LSERDY LSE ready interrupt
+ * @arg @ref RCC_IT_HSIRDY HSI ready interrupt
+ * @arg @ref RCC_IT_HSERDY HSE ready interrupt
+ * @arg @ref RCC_IT_PLLRDY main PLL ready interrupt
+ * @arg @ref RCC_IT_HSI14RDY HSI14 ready interrupt
+ @if STM32F042x6
+ * @arg @ref RCC_IT_HSI48RDY HSI48 ready interrupt
+ @elseif STM32F048xx
+ * @arg @ref RCC_IT_HSI48RDY HSI48 ready interrupt
+ @elseif STM32F071xB
+ * @arg @ref RCC_IT_HSI48RDY HSI48 ready interrupt
+ @elseif STM32F072xB
+ * @arg @ref RCC_IT_HSI48RDY HSI48 ready interrupt
+ @elseif STM32F078xx
+ * @arg @ref RCC_IT_HSI48RDY HSI48 ready interrupt
+ @elseif STM32F091xC
+ * @arg @ref RCC_IT_HSI48RDY HSI48 ready interrupt
+ @elseif STM32F098xx
+ * @arg @ref RCC_IT_HSI48RDY HSI48 ready interrupt
+ @endif
+ */
+#define __HAL_RCC_ENABLE_IT(__INTERRUPT__) (*(__IO uint8_t *) RCC_CIR_BYTE1_ADDRESS |= (__INTERRUPT__))
+
+/** @brief Disable RCC interrupt.
+ * @param __INTERRUPT__ specifies the RCC interrupt sources to be disabled.
+ * This parameter can be any combination of the following values:
+ * @arg @ref RCC_IT_LSIRDY LSI ready interrupt
+ * @arg @ref RCC_IT_LSERDY LSE ready interrupt
+ * @arg @ref RCC_IT_HSIRDY HSI ready interrupt
+ * @arg @ref RCC_IT_HSERDY HSE ready interrupt
+ * @arg @ref RCC_IT_PLLRDY main PLL ready interrupt
+ * @arg @ref RCC_IT_HSI14RDY HSI14 ready interrupt
+ @if STM32F042x6
+ * @arg @ref RCC_IT_HSI48RDY HSI48 ready interrupt
+ @elseif STM32F048xx
+ * @arg @ref RCC_IT_HSI48RDY HSI48 ready interrupt
+ @elseif STM32F071xB
+ * @arg @ref RCC_IT_HSI48RDY HSI48 ready interrupt
+ @elseif STM32F072xB
+ * @arg @ref RCC_IT_HSI48RDY HSI48 ready interrupt
+ @elseif STM32F078xx
+ * @arg @ref RCC_IT_HSI48RDY HSI48 ready interrupt
+ @elseif STM32F091xC
+ * @arg @ref RCC_IT_HSI48RDY HSI48 ready interrupt
+ @elseif STM32F098xx
+ * @arg @ref RCC_IT_HSI48RDY HSI48 ready interrupt
+ @endif
+ */
+#define __HAL_RCC_DISABLE_IT(__INTERRUPT__) (*(__IO uint8_t *) RCC_CIR_BYTE1_ADDRESS &= (uint8_t)(~(__INTERRUPT__)))
+
+/** @brief Clear the RCC's interrupt pending bits.
+ * @param __INTERRUPT__ specifies the interrupt pending bit to clear.
+ * This parameter can be any combination of the following values:
+ * @arg @ref RCC_IT_LSIRDY LSI ready interrupt.
+ * @arg @ref RCC_IT_LSERDY LSE ready interrupt.
+ * @arg @ref RCC_IT_HSIRDY HSI ready interrupt.
+ * @arg @ref RCC_IT_HSERDY HSE ready interrupt.
+ * @arg @ref RCC_IT_PLLRDY Main PLL ready interrupt.
+ * @arg @ref RCC_IT_CSS Clock Security System interrupt
+ * @arg @ref RCC_IT_HSI14RDY HSI14 ready interrupt
+ @if STM32F042x6
+ * @arg @ref RCC_IT_HSI48RDY HSI48 ready interrupt
+ @elseif STM32F048xx
+ * @arg @ref RCC_IT_HSI48RDY HSI48 ready interrupt
+ @elseif STM32F071xB
+ * @arg @ref RCC_IT_HSI48RDY HSI48 ready interrupt
+ @elseif STM32F072xB
+ * @arg @ref RCC_IT_HSI48RDY HSI48 ready interrupt
+ @elseif STM32F078xx
+ * @arg @ref RCC_IT_HSI48RDY HSI48 ready interrupt
+ @elseif STM32F091xC
+ * @arg @ref RCC_IT_HSI48RDY HSI48 ready interrupt
+ @elseif STM32F098xx
+ * @arg @ref RCC_IT_HSI48RDY HSI48 ready interrupt
+ @endif
+ */
+#define __HAL_RCC_CLEAR_IT(__INTERRUPT__) (*(__IO uint8_t *) RCC_CIR_BYTE2_ADDRESS = (__INTERRUPT__))
+
+/** @brief Check the RCC's interrupt has occurred or not.
+ * @param __INTERRUPT__ specifies the RCC interrupt source to check.
+ * This parameter can be one of the following values:
+ * @arg @ref RCC_IT_LSIRDY LSI ready interrupt.
+ * @arg @ref RCC_IT_LSERDY LSE ready interrupt.
+ * @arg @ref RCC_IT_HSIRDY HSI ready interrupt.
+ * @arg @ref RCC_IT_HSERDY HSE ready interrupt.
+ * @arg @ref RCC_IT_PLLRDY Main PLL ready interrupt.
+ * @arg @ref RCC_IT_CSS Clock Security System interrupt
+ * @arg @ref RCC_IT_HSI14RDY HSI14 ready interrupt enable
+ @if STM32F042x6
+ * @arg @ref RCC_IT_HSI48RDY HSI48 ready interrupt
+ @elseif STM32F048xx
+ * @arg @ref RCC_IT_HSI48RDY HSI48 ready interrupt
+ @elseif STM32F071xB
+ * @arg @ref RCC_IT_HSI48RDY HSI48 ready interrupt
+ @elseif STM32F072xB
+ * @arg @ref RCC_IT_HSI48RDY HSI48 ready interrupt
+ @elseif STM32F078xx
+ * @arg @ref RCC_IT_HSI48RDY HSI48 ready interrupt
+ @elseif STM32F091xC
+ * @arg @ref RCC_IT_HSI48RDY HSI48 ready interrupt
+ @elseif STM32F098xx
+ * @arg @ref RCC_IT_HSI48RDY HSI48 ready interrupt
+ @endif
+ * @retval The new state of __INTERRUPT__ (TRUE or FALSE).
+ */
+#define __HAL_RCC_GET_IT(__INTERRUPT__) ((RCC->CIR & (__INTERRUPT__)) == (__INTERRUPT__))
+
+/** @brief Set RMVF bit to clear the reset flags.
+ * The reset flags are RCC_FLAG_PINRST, RCC_FLAG_PORRST, RCC_FLAG_SFTRST,
+ * RCC_FLAG_OBLRST, RCC_FLAG_IWDGRST, RCC_FLAG_WWDGRST, RCC_FLAG_LPWRRST
+ */
+#define __HAL_RCC_CLEAR_RESET_FLAGS() (RCC->CSR |= RCC_CSR_RMVF)
+
+/** @brief Check RCC flag is set or not.
+ * @param __FLAG__ specifies the flag to check.
+ * This parameter can be one of the following values:
+ * @arg @ref RCC_FLAG_HSIRDY HSI oscillator clock ready.
+ * @arg @ref RCC_FLAG_HSERDY HSE oscillator clock ready.
+ * @arg @ref RCC_FLAG_PLLRDY Main PLL clock ready.
+ * @arg @ref RCC_FLAG_HSI14RDY HSI14 oscillator clock ready
+ @if STM32F038xx
+ * @arg @ref RCC_FLAG_V18PWRRST Reset flag of the 1.8 V domain
+ @elseif STM32F042x6
+ * @arg @ref RCC_FLAG_HSI48RDY HSI48 oscillator clock ready
+ @elseif STM32F048xx
+ * @arg @ref RCC_FLAG_HSI48RDY HSI48 oscillator clock ready
+ * @arg @ref RCC_FLAG_V18PWRRST Reset flag of the 1.8 V domain
+ @elseif STM32F058xx
+ * @arg @ref RCC_FLAG_V18PWRRST Reset flag of the 1.8 V domain
+ @elseif STM32F071xB
+ * @arg @ref RCC_FLAG_HSI48RDY HSI48 oscillator clock ready
+ @elseif STM32F072xB
+ * @arg @ref RCC_FLAG_HSI48RDY HSI48 oscillator clock ready
+ @elseif STM32F078xx
+ * @arg @ref RCC_FLAG_HSI48RDY HSI48 oscillator clock ready
+ * @arg @ref RCC_FLAG_V18PWRRST Reset flag of the 1.8 V domain
+ @elseif STM32F091xC
+ * @arg @ref RCC_FLAG_HSI48RDY HSI48 oscillator clock ready
+ @elseif STM32F098xx
+ * @arg @ref RCC_FLAG_HSI48RDY HSI48 oscillator clock ready
+ * @arg @ref RCC_FLAG_V18PWRRST Reset flag of the 1.8 V domain
+ @endif
+ * @arg @ref RCC_FLAG_LSERDY LSE oscillator clock ready.
+ * @arg @ref RCC_FLAG_LSIRDY LSI oscillator clock ready.
+ * @arg @ref RCC_FLAG_OBLRST Option Byte Load reset
+ * @arg @ref RCC_FLAG_PINRST Pin reset.
+ * @arg @ref RCC_FLAG_PORRST POR/PDR reset.
+ * @arg @ref RCC_FLAG_SFTRST Software reset.
+ * @arg @ref RCC_FLAG_IWDGRST Independent Watchdog reset.
+ * @arg @ref RCC_FLAG_WWDGRST Window Watchdog reset.
+ * @arg @ref RCC_FLAG_LPWRRST Low Power reset.
+ * @retval The new state of __FLAG__ (TRUE or FALSE).
+ */
+#define __HAL_RCC_GET_FLAG(__FLAG__) (((((__FLAG__) >> 5U) == CR_REG_INDEX)? RCC->CR : \
+ (((__FLAG__) >> 5U) == CR2_REG_INDEX)? RCC->CR2 : \
+ (((__FLAG__) >> 5U) == BDCR_REG_INDEX) ? RCC->BDCR : \
+ RCC->CSR) & (1U << ((__FLAG__) & RCC_FLAG_MASK)))
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/* Include RCC HAL Extension module */
+#include "stm32f0xx_hal_rcc_ex.h"
+
+/* Exported functions --------------------------------------------------------*/
+/** @addtogroup RCC_Exported_Functions
+ * @{
+ */
+
+/** @addtogroup RCC_Exported_Functions_Group1
+ * @{
+ */
+
+/* Initialization and de-initialization functions ******************************/
+HAL_StatusTypeDef HAL_RCC_DeInit(void);
+HAL_StatusTypeDef HAL_RCC_OscConfig(RCC_OscInitTypeDef *RCC_OscInitStruct);
+HAL_StatusTypeDef HAL_RCC_ClockConfig(RCC_ClkInitTypeDef *RCC_ClkInitStruct, uint32_t FLatency);
+
+/**
+ * @}
+ */
+
+/** @addtogroup RCC_Exported_Functions_Group2
+ * @{
+ */
+
+/* Peripheral Control functions ************************************************/
+void HAL_RCC_MCOConfig(uint32_t RCC_MCOx, uint32_t RCC_MCOSource, uint32_t RCC_MCODiv);
+void HAL_RCC_EnableCSS(void);
+/* CSS NMI IRQ handler */
+void HAL_RCC_NMI_IRQHandler(void);
+/* User Callbacks in non blocking mode (IT mode) */
+void HAL_RCC_CSSCallback(void);
+void HAL_RCC_DisableCSS(void);
+uint32_t HAL_RCC_GetSysClockFreq(void);
+uint32_t HAL_RCC_GetHCLKFreq(void);
+uint32_t HAL_RCC_GetPCLK1Freq(void);
+void HAL_RCC_GetOscConfig(RCC_OscInitTypeDef *RCC_OscInitStruct);
+void HAL_RCC_GetClockConfig(RCC_ClkInitTypeDef *RCC_ClkInitStruct, uint32_t *pFLatency);
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __STM32F0xx_HAL_RCC_H */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
+
diff --git a/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal_rcc_ex.h b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal_rcc_ex.h
new file mode 100644
index 0000000..cd83fd1
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal_rcc_ex.h
@@ -0,0 +1,2085 @@
+/**
+ ******************************************************************************
+ * @file stm32f0xx_hal_rcc_ex.h
+ * @author MCD Application Team
+ * @brief Header file of RCC HAL Extension module.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2016 STMicroelectronics.
+ * All rights reserved.
+ *
+ * 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 __STM32F0xx_HAL_RCC_EX_H
+#define __STM32F0xx_HAL_RCC_EX_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f0xx_hal_def.h"
+
+/** @addtogroup STM32F0xx_HAL_Driver
+ * @{
+ */
+
+/** @addtogroup RCC
+ * @{
+ */
+
+/** @addtogroup RCC_Private_Macros
+ * @{
+ */
+#if defined(RCC_HSI48_SUPPORT)
+#define IS_RCC_OSCILLATORTYPE(OSCILLATOR) (((OSCILLATOR) == RCC_OSCILLATORTYPE_NONE) || \
+ (((OSCILLATOR) & RCC_OSCILLATORTYPE_HSE) == RCC_OSCILLATORTYPE_HSE) || \
+ (((OSCILLATOR) & RCC_OSCILLATORTYPE_HSI) == RCC_OSCILLATORTYPE_HSI) || \
+ (((OSCILLATOR) & RCC_OSCILLATORTYPE_LSI) == RCC_OSCILLATORTYPE_LSI) || \
+ (((OSCILLATOR) & RCC_OSCILLATORTYPE_LSE) == RCC_OSCILLATORTYPE_LSE) || \
+ (((OSCILLATOR) & RCC_OSCILLATORTYPE_HSI14) == RCC_OSCILLATORTYPE_HSI14) || \
+ (((OSCILLATOR) & RCC_OSCILLATORTYPE_HSI48) == RCC_OSCILLATORTYPE_HSI48))
+
+#define IS_RCC_SYSCLKSOURCE(SOURCE) (((SOURCE) == RCC_SYSCLKSOURCE_HSI) || \
+ ((SOURCE) == RCC_SYSCLKSOURCE_HSE) || \
+ ((SOURCE) == RCC_SYSCLKSOURCE_PLLCLK) || \
+ ((SOURCE) == RCC_SYSCLKSOURCE_HSI48))
+
+#define IS_RCC_SYSCLKSOURCE_STATUS(SOURCE) (((SOURCE) == RCC_SYSCLKSOURCE_STATUS_HSI) || \
+ ((SOURCE) == RCC_SYSCLKSOURCE_STATUS_HSE) || \
+ ((SOURCE) == RCC_SYSCLKSOURCE_STATUS_PLLCLK) || \
+ ((SOURCE) == RCC_SYSCLKSOURCE_STATUS_HSI48))
+
+#define IS_RCC_PLLSOURCE(SOURCE) (((SOURCE) == RCC_PLLSOURCE_HSI) || \
+ ((SOURCE) == RCC_PLLSOURCE_HSI48) || \
+ ((SOURCE) == RCC_PLLSOURCE_HSE))
+
+#define IS_RCC_HSI48(HSI48) (((HSI48) == RCC_HSI48_OFF) || ((HSI48) == RCC_HSI48_ON))
+
+#else
+
+#define IS_RCC_OSCILLATORTYPE(OSCILLATOR) (((OSCILLATOR) == RCC_OSCILLATORTYPE_NONE) || \
+ (((OSCILLATOR) & RCC_OSCILLATORTYPE_HSE) == RCC_OSCILLATORTYPE_HSE) || \
+ (((OSCILLATOR) & RCC_OSCILLATORTYPE_HSI) == RCC_OSCILLATORTYPE_HSI) || \
+ (((OSCILLATOR) & RCC_OSCILLATORTYPE_LSI) == RCC_OSCILLATORTYPE_LSI) || \
+ (((OSCILLATOR) & RCC_OSCILLATORTYPE_LSE) == RCC_OSCILLATORTYPE_LSE) || \
+ (((OSCILLATOR) & RCC_OSCILLATORTYPE_HSI14) == RCC_OSCILLATORTYPE_HSI14))
+#define IS_RCC_SYSCLKSOURCE(SOURCE) (((SOURCE) == RCC_SYSCLKSOURCE_HSI) || \
+ ((SOURCE) == RCC_SYSCLKSOURCE_HSE) || \
+ ((SOURCE) == RCC_SYSCLKSOURCE_PLLCLK))
+
+#define IS_RCC_SYSCLKSOURCE_STATUS(SOURCE) (((SOURCE) == RCC_SYSCLKSOURCE_STATUS_HSI) || \
+ ((SOURCE) == RCC_SYSCLKSOURCE_STATUS_HSE) || \
+ ((SOURCE) == RCC_SYSCLKSOURCE_STATUS_PLLCLK))
+#define IS_RCC_PLLSOURCE(SOURCE) (((SOURCE) == RCC_PLLSOURCE_HSI) || \
+ ((SOURCE) == RCC_PLLSOURCE_HSE))
+
+#endif /* RCC_HSI48_SUPPORT */
+
+#if defined(RCC_CFGR_PLLNODIV) && !defined(RCC_CFGR_MCO_HSI48)
+
+#define IS_RCC_MCO1SOURCE(SOURCE) (((SOURCE) == RCC_MCO1SOURCE_NOCLOCK) || \
+ ((SOURCE) == RCC_MCO1SOURCE_LSI) || \
+ ((SOURCE) == RCC_MCO1SOURCE_LSE) || \
+ ((SOURCE) == RCC_MCO1SOURCE_SYSCLK) || \
+ ((SOURCE) == RCC_MCO1SOURCE_HSI) || \
+ ((SOURCE) == RCC_MCO1SOURCE_HSE) || \
+ ((SOURCE) == RCC_MCO1SOURCE_PLLCLK) || \
+ ((SOURCE) == RCC_MCO1SOURCE_PLLCLK_DIV2) || \
+ ((SOURCE) == RCC_MCO1SOURCE_HSI14))
+
+#elif defined(RCC_CFGR_PLLNODIV) && defined(RCC_CFGR_MCO_HSI48)
+
+#define IS_RCC_MCO1SOURCE(SOURCE) (((SOURCE) == RCC_MCO1SOURCE_NOCLOCK) || \
+ ((SOURCE) == RCC_MCO1SOURCE_LSI) || \
+ ((SOURCE) == RCC_MCO1SOURCE_LSE) || \
+ ((SOURCE) == RCC_MCO1SOURCE_SYSCLK) || \
+ ((SOURCE) == RCC_MCO1SOURCE_HSI) || \
+ ((SOURCE) == RCC_MCO1SOURCE_HSE) || \
+ ((SOURCE) == RCC_MCO1SOURCE_PLLCLK) || \
+ ((SOURCE) == RCC_MCO1SOURCE_PLLCLK_DIV2) || \
+ ((SOURCE) == RCC_MCO1SOURCE_HSI14) || \
+ ((SOURCE) == RCC_MCO1SOURCE_HSI48))
+
+#elif !defined(RCC_CFGR_PLLNODIV) && !defined(RCC_CFGR_MCO_HSI48)
+
+#define IS_RCC_MCO1SOURCE(SOURCE) (((SOURCE) == RCC_MCO1SOURCE_NOCLOCK) || \
+ ((SOURCE) == RCC_MCO1SOURCE_LSI) || \
+ ((SOURCE) == RCC_MCO1SOURCE_LSE) || \
+ ((SOURCE) == RCC_MCO1SOURCE_SYSCLK) || \
+ ((SOURCE) == RCC_MCO1SOURCE_HSI) || \
+ ((SOURCE) == RCC_MCO1SOURCE_HSE) || \
+ ((SOURCE) == RCC_MCO1SOURCE_PLLCLK_DIV2) || \
+ ((SOURCE) == RCC_MCO1SOURCE_HSI14))
+
+#endif /* RCC_CFGR_PLLNODIV && !RCC_CFGR_MCO_HSI48 */
+
+/**
+ * @}
+ */
+
+/** @addtogroup RCC_Exported_Constants
+ * @{
+ */
+#if defined(RCC_HSI48_SUPPORT)
+
+/** @addtogroup RCC_PLL_Clock_Source
+ * @{
+ */
+#define RCC_PLLSOURCE_HSI RCC_CFGR_PLLSRC_HSI_PREDIV
+#define RCC_PLLSOURCE_HSI48 RCC_CFGR_PLLSRC_HSI48_PREDIV
+
+/**
+ * @}
+ */
+
+/** @addtogroup RCC_Interrupt
+ * @{
+ */
+#define RCC_IT_HSI48 RCC_CIR_HSI48RDYF /*!< HSI48 Ready Interrupt flag */
+/**
+ * @}
+ */
+
+/** @addtogroup RCC_Flag
+ * @{
+ */
+#define RCC_FLAG_HSI48RDY ((uint8_t)((CR2_REG_INDEX << 5U) | RCC_CR2_HSI48RDY_BitNumber))
+/**
+ * @}
+ */
+
+/** @addtogroup RCC_System_Clock_Source
+ * @{
+ */
+#define RCC_SYSCLKSOURCE_HSI48 RCC_CFGR_SW_HSI48
+/**
+ * @}
+ */
+
+/** @addtogroup RCC_System_Clock_Source_Status
+ * @{
+ */
+#define RCC_SYSCLKSOURCE_STATUS_HSI48 RCC_CFGR_SWS_HSI48
+/**
+ * @}
+ */
+
+#else
+/** @addtogroup RCC_PLL_Clock_Source
+ * @{
+ */
+
+#if defined(STM32F070xB) || defined(STM32F070x6) || defined(STM32F030xC)
+#define RCC_PLLSOURCE_HSI RCC_CFGR_PLLSRC_HSI_PREDIV
+#else
+#define RCC_PLLSOURCE_HSI RCC_CFGR_PLLSRC_HSI_DIV2
+#endif
+
+/**
+ * @}
+ */
+
+#endif /* RCC_HSI48_SUPPORT */
+
+/** @addtogroup RCC_MCO_Clock_Source
+ * @{
+ */
+
+#if defined(RCC_CFGR_PLLNODIV)
+
+#define RCC_MCO1SOURCE_PLLCLK (RCC_CFGR_MCO_PLL | RCC_CFGR_PLLNODIV)
+
+#endif /* RCC_CFGR_PLLNODIV */
+
+#if defined(RCC_CFGR_MCO_HSI48)
+
+#define RCC_MCO1SOURCE_HSI48 RCC_CFGR_MCO_HSI48
+
+#endif /* SRCC_CFGR_MCO_HSI48 */
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/** @addtogroup RCCEx
+ * @{
+ */
+
+/* Private Constants -------------------------------------------------------------*/
+#if defined(CRS)
+/** @addtogroup RCCEx_Private_Constants
+ * @{
+ */
+
+/* CRS IT Error Mask */
+#define RCC_CRS_IT_ERROR_MASK ((uint32_t)(RCC_CRS_IT_TRIMOVF | RCC_CRS_IT_SYNCERR | RCC_CRS_IT_SYNCMISS))
+
+/* CRS Flag Error Mask */
+#define RCC_CRS_FLAG_ERROR_MASK ((uint32_t)(RCC_CRS_FLAG_TRIMOVF | RCC_CRS_FLAG_SYNCERR | RCC_CRS_FLAG_SYNCMISS))
+
+/**
+ * @}
+ */
+#endif /* CRS */
+
+/* Private macro -------------------------------------------------------------*/
+/** @defgroup RCCEx_Private_Macros RCCEx Private Macros
+ * @{
+ */
+#if defined(STM32F030x6) || defined(STM32F030x8) || defined(STM32F031x6) || defined(STM32F038xx)\
+ || defined(STM32F030xC)
+
+#define IS_RCC_PERIPHCLOCK(SELECTION) ((SELECTION) <= (RCC_PERIPHCLK_USART1 | RCC_PERIPHCLK_I2C1 | \
+ RCC_PERIPHCLK_RTC))
+#endif /* STM32F030x6 || STM32F030x8 || STM32F031x6 || STM32F038xx ||
+ STM32F030xC */
+
+#if defined(STM32F070x6) || defined(STM32F070xB)
+
+#define IS_RCC_PERIPHCLOCK(SELECTION) ((SELECTION) <= (RCC_PERIPHCLK_USART1 | RCC_PERIPHCLK_I2C1 | \
+ RCC_PERIPHCLK_RTC | RCC_PERIPHCLK_USB))
+#endif /* STM32F070x6 || STM32F070xB */
+
+#if defined(STM32F042x6) || defined(STM32F048xx)
+
+#define IS_RCC_PERIPHCLOCK(SELECTION) ((SELECTION) <= (RCC_PERIPHCLK_USART1 | RCC_PERIPHCLK_I2C1 | \
+ RCC_PERIPHCLK_CEC | RCC_PERIPHCLK_RTC | \
+ RCC_PERIPHCLK_USB))
+#endif /* STM32F042x6 || STM32F048xx */
+
+#if defined(STM32F051x8) || defined(STM32F058xx)
+
+#define IS_RCC_PERIPHCLOCK(SELECTION) ((SELECTION) <= (RCC_PERIPHCLK_USART1 | RCC_PERIPHCLK_I2C1 | \
+ RCC_PERIPHCLK_CEC | RCC_PERIPHCLK_RTC))
+#endif /* STM32F051x8 || STM32F058xx */
+
+#if defined(STM32F071xB)
+
+#define IS_RCC_PERIPHCLOCK(SELECTION) ((SELECTION) <= (RCC_PERIPHCLK_USART1 | RCC_PERIPHCLK_USART2 | \
+ RCC_PERIPHCLK_I2C1 | RCC_PERIPHCLK_CEC | \
+ RCC_PERIPHCLK_RTC))
+#endif /* STM32F071xB */
+
+#if defined(STM32F072xB) || defined(STM32F078xx)
+
+#define IS_RCC_PERIPHCLOCK(SELECTION) ((SELECTION) <= (RCC_PERIPHCLK_USART1 | RCC_PERIPHCLK_USART2 | \
+ RCC_PERIPHCLK_I2C1 | RCC_PERIPHCLK_CEC | \
+ RCC_PERIPHCLK_RTC | RCC_PERIPHCLK_USB))
+#endif /* STM32F072xB || STM32F078xx */
+
+#if defined(STM32F091xC) || defined(STM32F098xx)
+
+#define IS_RCC_PERIPHCLOCK(SELECTION) ((SELECTION) <= (RCC_PERIPHCLK_USART1 | RCC_PERIPHCLK_USART2 | \
+ RCC_PERIPHCLK_I2C1 | RCC_PERIPHCLK_CEC | \
+ RCC_PERIPHCLK_RTC | RCC_PERIPHCLK_USART3 ))
+#endif /* STM32F091xC || STM32F098xx */
+
+#if defined(STM32F042x6) || defined(STM32F048xx) || defined(STM32F072xB) || defined(STM32F078xx)
+
+#define IS_RCC_USBCLKSOURCE(SOURCE) (((SOURCE) == RCC_USBCLKSOURCE_HSI48) || \
+ ((SOURCE) == RCC_USBCLKSOURCE_PLL))
+
+#endif /* STM32F042x6 || STM32F048xx || STM32F072xB || STM32F078xx */
+
+#if defined(STM32F070x6) || defined(STM32F070xB)
+
+#define IS_RCC_USBCLKSOURCE(SOURCE) (((SOURCE) == RCC_USBCLKSOURCE_NONE) || \
+ ((SOURCE) == RCC_USBCLKSOURCE_PLL))
+
+#endif /* STM32F070x6 || STM32F070xB */
+
+#if defined(STM32F071xB) || defined(STM32F072xB) || defined(STM32F078xx)\
+ || defined(STM32F091xC) || defined(STM32F098xx)
+
+#define IS_RCC_USART2CLKSOURCE(SOURCE) (((SOURCE) == RCC_USART2CLKSOURCE_PCLK1) || \
+ ((SOURCE) == RCC_USART2CLKSOURCE_SYSCLK) || \
+ ((SOURCE) == RCC_USART2CLKSOURCE_LSE) || \
+ ((SOURCE) == RCC_USART2CLKSOURCE_HSI))
+
+#endif /* STM32F071xB || STM32F072xB || STM32F078xx || */
+ /* STM32F091xC || STM32F098xx */
+
+#if defined(STM32F091xC) || defined(STM32F098xx)
+
+#define IS_RCC_USART3CLKSOURCE(SOURCE) (((SOURCE) == RCC_USART3CLKSOURCE_PCLK1) || \
+ ((SOURCE) == RCC_USART3CLKSOURCE_SYSCLK) || \
+ ((SOURCE) == RCC_USART3CLKSOURCE_LSE) || \
+ ((SOURCE) == RCC_USART3CLKSOURCE_HSI))
+#endif /* STM32F091xC || STM32F098xx */
+
+
+#if defined(STM32F042x6) || defined(STM32F048xx)\
+ || defined(STM32F051x8) || defined(STM32F058xx)\
+ || defined(STM32F071xB) || defined(STM32F072xB) || defined(STM32F078xx)\
+ || defined(STM32F091xC) || defined(STM32F098xx)
+
+#define IS_RCC_CECCLKSOURCE(SOURCE) (((SOURCE) == RCC_CECCLKSOURCE_HSI) || \
+ ((SOURCE) == RCC_CECCLKSOURCE_LSE))
+#endif /* STM32F042x6 || STM32F048xx || */
+ /* STM32F051x8 || STM32F058xx || */
+ /* STM32F071xB || STM32F072xB || STM32F078xx || */
+ /* STM32F091xC || STM32F098xx */
+
+#if defined(RCC_CFGR_MCOPRE)
+
+#define IS_RCC_MCODIV(DIV) (((DIV) == RCC_MCODIV_1) || ((DIV) == RCC_MCODIV_2) || \
+ ((DIV) == RCC_MCODIV_4) || ((DIV) == RCC_MCODIV_8) || \
+ ((DIV) == RCC_MCODIV_16) || ((DIV) == RCC_MCODIV_32) || \
+ ((DIV) == RCC_MCODIV_64) || ((DIV) == RCC_MCODIV_128))
+#else
+
+#define IS_RCC_MCODIV(DIV) (((DIV) == RCC_MCODIV_1))
+
+#endif /* RCC_CFGR_MCOPRE */
+
+#define IS_RCC_LSE_DRIVE(__DRIVE__) (((__DRIVE__) == RCC_LSEDRIVE_LOW) || \
+ ((__DRIVE__) == RCC_LSEDRIVE_MEDIUMLOW) || \
+ ((__DRIVE__) == RCC_LSEDRIVE_MEDIUMHIGH) || \
+ ((__DRIVE__) == RCC_LSEDRIVE_HIGH))
+
+#if defined(CRS)
+
+#define IS_RCC_CRS_SYNC_SOURCE(_SOURCE_) (((_SOURCE_) == RCC_CRS_SYNC_SOURCE_GPIO) || \
+ ((_SOURCE_) == RCC_CRS_SYNC_SOURCE_LSE) || \
+ ((_SOURCE_) == RCC_CRS_SYNC_SOURCE_USB))
+#define IS_RCC_CRS_SYNC_DIV(_DIV_) (((_DIV_) == RCC_CRS_SYNC_DIV1) || ((_DIV_) == RCC_CRS_SYNC_DIV2) || \
+ ((_DIV_) == RCC_CRS_SYNC_DIV4) || ((_DIV_) == RCC_CRS_SYNC_DIV8) || \
+ ((_DIV_) == RCC_CRS_SYNC_DIV16) || ((_DIV_) == RCC_CRS_SYNC_DIV32) || \
+ ((_DIV_) == RCC_CRS_SYNC_DIV64) || ((_DIV_) == RCC_CRS_SYNC_DIV128))
+#define IS_RCC_CRS_SYNC_POLARITY(_POLARITY_) (((_POLARITY_) == RCC_CRS_SYNC_POLARITY_RISING) || \
+ ((_POLARITY_) == RCC_CRS_SYNC_POLARITY_FALLING))
+#define IS_RCC_CRS_RELOADVALUE(_VALUE_) (((_VALUE_) <= 0xFFFFU))
+#define IS_RCC_CRS_ERRORLIMIT(_VALUE_) (((_VALUE_) <= 0xFFU))
+#define IS_RCC_CRS_HSI48CALIBRATION(_VALUE_) (((_VALUE_) <= 0x3FU))
+#define IS_RCC_CRS_FREQERRORDIR(_DIR_) (((_DIR_) == RCC_CRS_FREQERRORDIR_UP) || \
+ ((_DIR_) == RCC_CRS_FREQERRORDIR_DOWN))
+#endif /* CRS */
+/**
+ * @}
+ */
+
+/* Exported types ------------------------------------------------------------*/
+
+/** @defgroup RCCEx_Exported_Types RCCEx Exported Types
+ * @{
+ */
+
+/**
+ * @brief RCC extended clocks structure definition
+ */
+#if defined(STM32F030x6) || defined(STM32F030x8) || defined(STM32F031x6) || defined(STM32F038xx)\
+ || defined(STM32F030xC)
+typedef struct
+{
+ uint32_t PeriphClockSelection; /*!< The Extended Clock to be configured.
+ This parameter can be a value of @ref RCCEx_Periph_Clock_Selection */
+
+ uint32_t RTCClockSelection; /*!< Specifies RTC Clock Prescalers Selection
+ This parameter can be a value of @ref RCC_RTC_Clock_Source */
+
+ uint32_t Usart1ClockSelection; /*!< USART1 clock source
+ This parameter can be a value of @ref RCC_USART1_Clock_Source */
+
+ uint32_t I2c1ClockSelection; /*!< I2C1 clock source
+ This parameter can be a value of @ref RCC_I2C1_Clock_Source */
+
+}RCC_PeriphCLKInitTypeDef;
+#endif /* STM32F030x6 || STM32F030x8 || STM32F031x6 || STM32F038xx ||
+ STM32F030xC */
+
+#if defined(STM32F070x6) || defined(STM32F070xB)
+typedef struct
+{
+ uint32_t PeriphClockSelection; /*!< The Extended Clock to be configured.
+ This parameter can be a value of @ref RCCEx_Periph_Clock_Selection */
+
+ uint32_t RTCClockSelection; /*!< Specifies RTC Clock Prescalers Selection
+ This parameter can be a value of @ref RCC_RTC_Clock_Source */
+
+ uint32_t Usart1ClockSelection; /*!< USART1 clock source
+ This parameter can be a value of @ref RCC_USART1_Clock_Source */
+
+ uint32_t I2c1ClockSelection; /*!< I2C1 clock source
+ This parameter can be a value of @ref RCC_I2C1_Clock_Source */
+
+ uint32_t UsbClockSelection; /*!< USB clock source
+ This parameter can be a value of @ref RCCEx_USB_Clock_Source */
+
+}RCC_PeriphCLKInitTypeDef;
+#endif /* STM32F070x6 || STM32F070xB */
+
+#if defined(STM32F042x6) || defined(STM32F048xx)
+typedef struct
+{
+ uint32_t PeriphClockSelection; /*!< The Extended Clock to be configured.
+ This parameter can be a value of @ref RCCEx_Periph_Clock_Selection */
+
+ uint32_t RTCClockSelection; /*!< Specifies RTC Clock Prescalers Selection
+ This parameter can be a value of @ref RCC_RTC_Clock_Source */
+
+ uint32_t Usart1ClockSelection; /*!< USART1 clock source
+ This parameter can be a value of @ref RCC_USART1_Clock_Source */
+
+ uint32_t I2c1ClockSelection; /*!< I2C1 clock source
+ This parameter can be a value of @ref RCC_I2C1_Clock_Source */
+
+ uint32_t CecClockSelection; /*!< HDMI CEC clock source
+ This parameter can be a value of @ref RCCEx_CEC_Clock_Source */
+
+ uint32_t UsbClockSelection; /*!< USB clock source
+ This parameter can be a value of @ref RCCEx_USB_Clock_Source */
+
+}RCC_PeriphCLKInitTypeDef;
+#endif /* STM32F042x6 || STM32F048xx */
+
+#if defined(STM32F051x8) || defined(STM32F058xx)
+typedef struct
+{
+ uint32_t PeriphClockSelection; /*!< The Extended Clock to be configured.
+ This parameter can be a value of @ref RCCEx_Periph_Clock_Selection */
+
+ uint32_t RTCClockSelection; /*!< Specifies RTC Clock Prescalers Selection
+ This parameter can be a value of @ref RCC_RTC_Clock_Source */
+
+ uint32_t Usart1ClockSelection; /*!< USART1 clock source
+ This parameter can be a value of @ref RCC_USART1_Clock_Source */
+
+ uint32_t I2c1ClockSelection; /*!< I2C1 clock source
+ This parameter can be a value of @ref RCC_I2C1_Clock_Source */
+
+ uint32_t CecClockSelection; /*!< HDMI CEC clock source
+ This parameter can be a value of @ref RCCEx_CEC_Clock_Source */
+
+}RCC_PeriphCLKInitTypeDef;
+#endif /* STM32F051x8 || STM32F058xx */
+
+#if defined(STM32F071xB)
+typedef struct
+{
+ uint32_t PeriphClockSelection; /*!< The Extended Clock to be configured.
+ This parameter can be a value of @ref RCCEx_Periph_Clock_Selection */
+
+ uint32_t RTCClockSelection; /*!< Specifies RTC Clock Prescalers Selection
+ This parameter can be a value of @ref RCC_RTC_Clock_Source */
+
+ uint32_t Usart1ClockSelection; /*!< USART1 clock source
+ This parameter can be a value of @ref RCC_USART1_Clock_Source */
+
+ uint32_t Usart2ClockSelection; /*!< USART2 clock source
+ This parameter can be a value of @ref RCCEx_USART2_Clock_Source */
+
+ uint32_t I2c1ClockSelection; /*!< I2C1 clock source
+ This parameter can be a value of @ref RCC_I2C1_Clock_Source */
+
+ uint32_t CecClockSelection; /*!< HDMI CEC clock source
+ This parameter can be a value of @ref RCCEx_CEC_Clock_Source */
+
+}RCC_PeriphCLKInitTypeDef;
+#endif /* STM32F071xB */
+
+#if defined(STM32F072xB) || defined(STM32F078xx)
+typedef struct
+{
+ uint32_t PeriphClockSelection; /*!< The Extended Clock to be configured.
+ This parameter can be a value of @ref RCCEx_Periph_Clock_Selection */
+
+ uint32_t RTCClockSelection; /*!< Specifies RTC Clock Prescalers Selection
+ This parameter can be a value of @ref RCC_RTC_Clock_Source */
+
+ uint32_t Usart1ClockSelection; /*!< USART1 clock source
+ This parameter can be a value of @ref RCC_USART1_Clock_Source */
+
+ uint32_t Usart2ClockSelection; /*!< USART2 clock source
+ This parameter can be a value of @ref RCCEx_USART2_Clock_Source */
+
+ uint32_t I2c1ClockSelection; /*!< I2C1 clock source
+ This parameter can be a value of @ref RCC_I2C1_Clock_Source */
+
+ uint32_t CecClockSelection; /*!< HDMI CEC clock source
+ This parameter can be a value of @ref RCCEx_CEC_Clock_Source */
+
+ uint32_t UsbClockSelection; /*!< USB clock source
+ This parameter can be a value of @ref RCCEx_USB_Clock_Source */
+
+}RCC_PeriphCLKInitTypeDef;
+#endif /* STM32F072xB || STM32F078xx */
+
+
+#if defined(STM32F091xC) || defined(STM32F098xx)
+typedef struct
+{
+ uint32_t PeriphClockSelection; /*!< The Extended Clock to be configured.
+ This parameter can be a value of @ref RCCEx_Periph_Clock_Selection */
+
+ uint32_t RTCClockSelection; /*!< Specifies RTC Clock Prescalers Selection
+ This parameter can be a value of @ref RCC_RTC_Clock_Source */
+
+ uint32_t Usart1ClockSelection; /*!< USART1 clock source
+ This parameter can be a value of @ref RCC_USART1_Clock_Source */
+
+ uint32_t Usart2ClockSelection; /*!< USART2 clock source
+ This parameter can be a value of @ref RCCEx_USART2_Clock_Source */
+
+ uint32_t Usart3ClockSelection; /*!< USART3 clock source
+ This parameter can be a value of @ref RCCEx_USART3_Clock_Source */
+
+ uint32_t I2c1ClockSelection; /*!< I2C1 clock source
+ This parameter can be a value of @ref RCC_I2C1_Clock_Source */
+
+ uint32_t CecClockSelection; /*!< HDMI CEC clock source
+ This parameter can be a value of @ref RCCEx_CEC_Clock_Source */
+
+}RCC_PeriphCLKInitTypeDef;
+#endif /* STM32F091xC || STM32F098xx */
+
+#if defined(CRS)
+
+/**
+ * @brief RCC_CRS Init structure definition
+ */
+typedef struct
+{
+ uint32_t Prescaler; /*!< Specifies the division factor of the SYNC signal.
+ This parameter can be a value of @ref RCCEx_CRS_SynchroDivider */
+
+ uint32_t Source; /*!< Specifies the SYNC signal source.
+ This parameter can be a value of @ref RCCEx_CRS_SynchroSource */
+
+ uint32_t Polarity; /*!< Specifies the input polarity for the SYNC signal source.
+ This parameter can be a value of @ref RCCEx_CRS_SynchroPolarity */
+
+ uint32_t ReloadValue; /*!< Specifies the value to be loaded in the frequency error counter with each SYNC event.
+ It can be calculated in using macro @ref __HAL_RCC_CRS_RELOADVALUE_CALCULATE(__FTARGET__, __FSYNC__)
+ This parameter must be a number between 0 and 0xFFFF or a value of @ref RCCEx_CRS_ReloadValueDefault .*/
+
+ uint32_t ErrorLimitValue; /*!< Specifies the value to be used to evaluate the captured frequency error value.
+ This parameter must be a number between 0 and 0xFF or a value of @ref RCCEx_CRS_ErrorLimitDefault */
+
+ uint32_t HSI48CalibrationValue; /*!< Specifies a user-programmable trimming value to the HSI48 oscillator.
+ This parameter must be a number between 0 and 0x3F or a value of @ref RCCEx_CRS_HSI48CalibrationDefault */
+
+}RCC_CRSInitTypeDef;
+
+/**
+ * @brief RCC_CRS Synchronization structure definition
+ */
+typedef struct
+{
+ uint32_t ReloadValue; /*!< Specifies the value loaded in the Counter reload value.
+ This parameter must be a number between 0 and 0xFFFFU */
+
+ uint32_t HSI48CalibrationValue; /*!< Specifies value loaded in HSI48 oscillator smooth trimming.
+ This parameter must be a number between 0 and 0x3FU */
+
+ uint32_t FreqErrorCapture; /*!< Specifies the value loaded in the .FECAP, the frequency error counter
+ value latched in the time of the last SYNC event.
+ This parameter must be a number between 0 and 0xFFFFU */
+
+ uint32_t FreqErrorDirection; /*!< Specifies the value loaded in the .FEDIR, the counting direction of the
+ frequency error counter latched in the time of the last SYNC event.
+ It shows whether the actual frequency is below or above the target.
+ This parameter must be a value of @ref RCCEx_CRS_FreqErrorDirection*/
+
+}RCC_CRSSynchroInfoTypeDef;
+
+#endif /* CRS */
+
+/**
+ * @}
+ */
+
+/* Exported constants --------------------------------------------------------*/
+
+/** @defgroup RCCEx_Exported_Constants RCCEx Exported Constants
+ * @{
+ */
+
+/** @defgroup RCCEx_Periph_Clock_Selection RCCEx Periph Clock Selection
+ * @{
+ */
+#if defined(STM32F030x6) || defined(STM32F030x8) || defined(STM32F031x6) || defined(STM32F038xx)\
+ || defined(STM32F030xC)
+#define RCC_PERIPHCLK_USART1 (0x00000001U)
+#define RCC_PERIPHCLK_I2C1 (0x00000020U)
+#define RCC_PERIPHCLK_RTC (0x00010000U)
+
+#endif /* STM32F030x6 || STM32F030x8 || STM32F031x6 || STM32F038xx ||
+ STM32F030xC */
+
+#if defined(STM32F070x6) || defined(STM32F070xB)
+#define RCC_PERIPHCLK_USART1 (0x00000001U)
+#define RCC_PERIPHCLK_I2C1 (0x00000020U)
+#define RCC_PERIPHCLK_RTC (0x00010000U)
+#define RCC_PERIPHCLK_USB (0x00020000U)
+
+#endif /* STM32F070x6 || STM32F070xB */
+
+#if defined(STM32F042x6) || defined(STM32F048xx)
+#define RCC_PERIPHCLK_USART1 (0x00000001U)
+#define RCC_PERIPHCLK_I2C1 (0x00000020U)
+#define RCC_PERIPHCLK_CEC (0x00000400U)
+#define RCC_PERIPHCLK_RTC (0x00010000U)
+#define RCC_PERIPHCLK_USB (0x00020000U)
+
+#endif /* STM32F042x6 || STM32F048xx */
+
+#if defined(STM32F051x8) || defined(STM32F058xx)
+#define RCC_PERIPHCLK_USART1 (0x00000001U)
+#define RCC_PERIPHCLK_I2C1 (0x00000020U)
+#define RCC_PERIPHCLK_CEC (0x00000400U)
+#define RCC_PERIPHCLK_RTC (0x00010000U)
+
+#endif /* STM32F051x8 || STM32F058xx */
+
+#if defined(STM32F071xB)
+#define RCC_PERIPHCLK_USART1 (0x00000001U)
+#define RCC_PERIPHCLK_USART2 (0x00000002U)
+#define RCC_PERIPHCLK_I2C1 (0x00000020U)
+#define RCC_PERIPHCLK_CEC (0x00000400U)
+#define RCC_PERIPHCLK_RTC (0x00010000U)
+
+#endif /* STM32F071xB */
+
+#if defined(STM32F072xB) || defined(STM32F078xx)
+#define RCC_PERIPHCLK_USART1 (0x00000001U)
+#define RCC_PERIPHCLK_USART2 (0x00000002U)
+#define RCC_PERIPHCLK_I2C1 (0x00000020U)
+#define RCC_PERIPHCLK_CEC (0x00000400U)
+#define RCC_PERIPHCLK_RTC (0x00010000U)
+#define RCC_PERIPHCLK_USB (0x00020000U)
+
+#endif /* STM32F072xB || STM32F078xx */
+
+#if defined(STM32F091xC) || defined(STM32F098xx)
+#define RCC_PERIPHCLK_USART1 (0x00000001U)
+#define RCC_PERIPHCLK_USART2 (0x00000002U)
+#define RCC_PERIPHCLK_I2C1 (0x00000020U)
+#define RCC_PERIPHCLK_CEC (0x00000400U)
+#define RCC_PERIPHCLK_RTC (0x00010000U)
+#define RCC_PERIPHCLK_USART3 (0x00040000U)
+
+#endif /* STM32F091xC || STM32F098xx */
+
+/**
+ * @}
+ */
+
+#if defined(STM32F042x6) || defined(STM32F048xx) || defined(STM32F072xB) || defined(STM32F078xx)
+
+/** @defgroup RCCEx_USB_Clock_Source RCCEx USB Clock Source
+ * @{
+ */
+#define RCC_USBCLKSOURCE_HSI48 RCC_CFGR3_USBSW_HSI48 /*!< HSI48 clock selected as USB clock source */
+#define RCC_USBCLKSOURCE_PLL RCC_CFGR3_USBSW_PLLCLK /*!< PLL clock (PLLCLK) selected as USB clock */
+
+/**
+ * @}
+ */
+
+#endif /* STM32F042x6 || STM32F048xx || STM32F072xB || STM32F078xx */
+
+#if defined(STM32F070x6) || defined(STM32F070xB)
+
+/** @defgroup RCCEx_USB_Clock_Source RCCEx USB Clock Source
+ * @{
+ */
+#define RCC_USBCLKSOURCE_NONE (0x00000000U) /*!< USB clock disabled */
+#define RCC_USBCLKSOURCE_PLL RCC_CFGR3_USBSW_PLLCLK /*!< PLL clock (PLLCLK) selected as USB clock */
+
+/**
+ * @}
+ */
+
+#endif /* STM32F070x6 || STM32F070xB */
+
+#if defined(STM32F071xB) || defined(STM32F072xB) || defined(STM32F078xx)\
+ || defined(STM32F091xC) || defined(STM32F098xx)
+
+/** @defgroup RCCEx_USART2_Clock_Source RCCEx USART2 Clock Source
+ * @{
+ */
+#define RCC_USART2CLKSOURCE_PCLK1 RCC_CFGR3_USART2SW_PCLK
+#define RCC_USART2CLKSOURCE_SYSCLK RCC_CFGR3_USART2SW_SYSCLK
+#define RCC_USART2CLKSOURCE_LSE RCC_CFGR3_USART2SW_LSE
+#define RCC_USART2CLKSOURCE_HSI RCC_CFGR3_USART2SW_HSI
+
+/**
+ * @}
+ */
+
+#endif /* STM32F071xB || STM32F072xB || STM32F078xx || */
+ /* STM32F091xC || STM32F098xx */
+
+#if defined(STM32F091xC) || defined(STM32F098xx)
+
+/** @defgroup RCCEx_USART3_Clock_Source RCCEx USART3 Clock Source
+ * @{
+ */
+#define RCC_USART3CLKSOURCE_PCLK1 RCC_CFGR3_USART3SW_PCLK
+#define RCC_USART3CLKSOURCE_SYSCLK RCC_CFGR3_USART3SW_SYSCLK
+#define RCC_USART3CLKSOURCE_LSE RCC_CFGR3_USART3SW_LSE
+#define RCC_USART3CLKSOURCE_HSI RCC_CFGR3_USART3SW_HSI
+
+/**
+ * @}
+ */
+
+#endif /* STM32F091xC || STM32F098xx */
+
+
+#if defined(STM32F042x6) || defined(STM32F048xx)\
+ || defined(STM32F051x8) || defined(STM32F058xx)\
+ || defined(STM32F071xB) || defined(STM32F072xB) || defined(STM32F078xx)\
+ || defined(STM32F091xC) || defined(STM32F098xx)
+
+/** @defgroup RCCEx_CEC_Clock_Source RCCEx CEC Clock Source
+ * @{
+ */
+#define RCC_CECCLKSOURCE_HSI RCC_CFGR3_CECSW_HSI_DIV244
+#define RCC_CECCLKSOURCE_LSE RCC_CFGR3_CECSW_LSE
+
+/**
+ * @}
+ */
+
+#endif /* STM32F042x6 || STM32F048xx || */
+ /* STM32F051x8 || STM32F058xx || */
+ /* STM32F071xB || STM32F072xB || STM32F078xx || */
+ /* STM32F091xC || STM32F098xx */
+
+/** @defgroup RCCEx_MCOx_Clock_Prescaler RCCEx MCOx Clock Prescaler
+ * @{
+ */
+
+#if defined(RCC_CFGR_MCOPRE)
+
+#define RCC_MCODIV_1 (0x00000000U)
+#define RCC_MCODIV_2 (0x10000000U)
+#define RCC_MCODIV_4 (0x20000000U)
+#define RCC_MCODIV_8 (0x30000000U)
+#define RCC_MCODIV_16 (0x40000000U)
+#define RCC_MCODIV_32 (0x50000000U)
+#define RCC_MCODIV_64 (0x60000000U)
+#define RCC_MCODIV_128 (0x70000000U)
+
+#else
+
+#define RCC_MCODIV_1 (0x00000000U)
+
+#endif /* RCC_CFGR_MCOPRE */
+
+/**
+ * @}
+ */
+
+/** @defgroup RCCEx_LSEDrive_Configuration RCC LSE Drive Configuration
+ * @{
+ */
+
+#define RCC_LSEDRIVE_LOW (0x00000000U) /*!< Xtal mode lower driving capability */
+#define RCC_LSEDRIVE_MEDIUMLOW RCC_BDCR_LSEDRV_1 /*!< Xtal mode medium low driving capability */
+#define RCC_LSEDRIVE_MEDIUMHIGH RCC_BDCR_LSEDRV_0 /*!< Xtal mode medium high driving capability */
+#define RCC_LSEDRIVE_HIGH RCC_BDCR_LSEDRV /*!< Xtal mode higher driving capability */
+
+/**
+ * @}
+ */
+
+#if defined(CRS)
+
+/** @defgroup RCCEx_CRS_Status RCCEx CRS Status
+ * @{
+ */
+#define RCC_CRS_NONE (0x00000000U)
+#define RCC_CRS_TIMEOUT (0x00000001U)
+#define RCC_CRS_SYNCOK (0x00000002U)
+#define RCC_CRS_SYNCWARN (0x00000004U)
+#define RCC_CRS_SYNCERR (0x00000008U)
+#define RCC_CRS_SYNCMISS (0x00000010U)
+#define RCC_CRS_TRIMOVF (0x00000020U)
+
+/**
+ * @}
+ */
+
+/** @defgroup RCCEx_CRS_SynchroSource RCCEx CRS Synchronization Source
+ * @{
+ */
+#define RCC_CRS_SYNC_SOURCE_GPIO (0x00000000U) /*!< Synchro Signal source GPIO */
+#define RCC_CRS_SYNC_SOURCE_LSE CRS_CFGR_SYNCSRC_0 /*!< Synchro Signal source LSE */
+#define RCC_CRS_SYNC_SOURCE_USB CRS_CFGR_SYNCSRC_1 /*!< Synchro Signal source USB SOF (default)*/
+/**
+ * @}
+ */
+
+/** @defgroup RCCEx_CRS_SynchroDivider RCCEx CRS Synchronization Divider
+ * @{
+ */
+#define RCC_CRS_SYNC_DIV1 (0x00000000U) /*!< Synchro Signal not divided (default) */
+#define RCC_CRS_SYNC_DIV2 CRS_CFGR_SYNCDIV_0 /*!< Synchro Signal divided by 2 */
+#define RCC_CRS_SYNC_DIV4 CRS_CFGR_SYNCDIV_1 /*!< Synchro Signal divided by 4 */
+#define RCC_CRS_SYNC_DIV8 (CRS_CFGR_SYNCDIV_1 | CRS_CFGR_SYNCDIV_0) /*!< Synchro Signal divided by 8 */
+#define RCC_CRS_SYNC_DIV16 CRS_CFGR_SYNCDIV_2 /*!< Synchro Signal divided by 16 */
+#define RCC_CRS_SYNC_DIV32 (CRS_CFGR_SYNCDIV_2 | CRS_CFGR_SYNCDIV_0) /*!< Synchro Signal divided by 32 */
+#define RCC_CRS_SYNC_DIV64 (CRS_CFGR_SYNCDIV_2 | CRS_CFGR_SYNCDIV_1) /*!< Synchro Signal divided by 64 */
+#define RCC_CRS_SYNC_DIV128 CRS_CFGR_SYNCDIV /*!< Synchro Signal divided by 128 */
+/**
+ * @}
+ */
+
+/** @defgroup RCCEx_CRS_SynchroPolarity RCCEx CRS Synchronization Polarity
+ * @{
+ */
+#define RCC_CRS_SYNC_POLARITY_RISING (0x00000000U) /*!< Synchro Active on rising edge (default) */
+#define RCC_CRS_SYNC_POLARITY_FALLING CRS_CFGR_SYNCPOL /*!< Synchro Active on falling edge */
+/**
+ * @}
+ */
+
+/** @defgroup RCCEx_CRS_ReloadValueDefault RCCEx CRS Default Reload Value
+ * @{
+ */
+#define RCC_CRS_RELOADVALUE_DEFAULT (0x0000BB7FU) /*!< The reset value of the RELOAD field corresponds
+ to a target frequency of 48 MHz and a synchronization signal frequency of 1 kHz (SOF signal from USB). */
+/**
+ * @}
+ */
+
+/** @defgroup RCCEx_CRS_ErrorLimitDefault RCCEx CRS Default Error Limit Value
+ * @{
+ */
+#define RCC_CRS_ERRORLIMIT_DEFAULT (0x00000022U) /*!< Default Frequency error limit */
+/**
+ * @}
+ */
+
+/** @defgroup RCCEx_CRS_HSI48CalibrationDefault RCCEx CRS Default HSI48 Calibration vakye
+ * @{
+ */
+#define RCC_CRS_HSI48CALIBRATION_DEFAULT (0x00000020U) /*!< The default value is 32, which corresponds to the middle of the trimming interval.
+ The trimming step is around 67 kHz between two consecutive TRIM steps. A higher TRIM value
+ corresponds to a higher output frequency */
+/**
+ * @}
+ */
+
+/** @defgroup RCCEx_CRS_FreqErrorDirection RCCEx CRS Frequency Error Direction
+ * @{
+ */
+#define RCC_CRS_FREQERRORDIR_UP (0x00000000U) /*!< Upcounting direction, the actual frequency is above the target */
+#define RCC_CRS_FREQERRORDIR_DOWN ((uint32_t)CRS_ISR_FEDIR) /*!< Downcounting direction, the actual frequency is below the target */
+/**
+ * @}
+ */
+
+/** @defgroup RCCEx_CRS_Interrupt_Sources RCCEx CRS Interrupt Sources
+ * @{
+ */
+#define RCC_CRS_IT_SYNCOK CRS_CR_SYNCOKIE /*!< SYNC event OK */
+#define RCC_CRS_IT_SYNCWARN CRS_CR_SYNCWARNIE /*!< SYNC warning */
+#define RCC_CRS_IT_ERR CRS_CR_ERRIE /*!< Error */
+#define RCC_CRS_IT_ESYNC CRS_CR_ESYNCIE /*!< Expected SYNC */
+#define RCC_CRS_IT_SYNCERR CRS_CR_ERRIE /*!< SYNC error */
+#define RCC_CRS_IT_SYNCMISS CRS_CR_ERRIE /*!< SYNC missed */
+#define RCC_CRS_IT_TRIMOVF CRS_CR_ERRIE /*!< Trimming overflow or underflow */
+
+/**
+ * @}
+ */
+
+/** @defgroup RCCEx_CRS_Flags RCCEx CRS Flags
+ * @{
+ */
+#define RCC_CRS_FLAG_SYNCOK CRS_ISR_SYNCOKF /*!< SYNC event OK flag */
+#define RCC_CRS_FLAG_SYNCWARN CRS_ISR_SYNCWARNF /*!< SYNC warning flag */
+#define RCC_CRS_FLAG_ERR CRS_ISR_ERRF /*!< Error flag */
+#define RCC_CRS_FLAG_ESYNC CRS_ISR_ESYNCF /*!< Expected SYNC flag */
+#define RCC_CRS_FLAG_SYNCERR CRS_ISR_SYNCERR /*!< SYNC error */
+#define RCC_CRS_FLAG_SYNCMISS CRS_ISR_SYNCMISS /*!< SYNC missed*/
+#define RCC_CRS_FLAG_TRIMOVF CRS_ISR_TRIMOVF /*!< Trimming overflow or underflow */
+
+/**
+ * @}
+ */
+
+#endif /* CRS */
+
+/**
+ * @}
+ */
+
+/* Exported macros ------------------------------------------------------------*/
+/** @defgroup RCCEx_Exported_Macros RCCEx Exported Macros
+ * @{
+ */
+
+/** @defgroup RCCEx_Peripheral_Clock_Enable_Disable RCCEx_Peripheral_Clock_Enable_Disable
+ * @brief Enables or disables the AHB1 peripheral clock.
+ * @note After reset, the peripheral clock (used for registers read/write access)
+ * is disabled and the application software has to enable this clock before
+ * using it.
+ * @{
+ */
+#if defined(GPIOD)
+
+#define __HAL_RCC_GPIOD_CLK_ENABLE() do { \
+ __IO uint32_t tmpreg; \
+ SET_BIT(RCC->AHBENR, RCC_AHBENR_GPIODEN);\
+ /* Delay after an RCC peripheral clock enabling */ \
+ tmpreg = READ_BIT(RCC->AHBENR, RCC_AHBENR_GPIODEN);\
+ UNUSED(tmpreg); \
+ } while(0U)
+
+#define __HAL_RCC_GPIOD_CLK_DISABLE() (RCC->AHBENR &= ~(RCC_AHBENR_GPIODEN))
+
+#endif /* GPIOD */
+
+#if defined(GPIOE)
+
+#define __HAL_RCC_GPIOE_CLK_ENABLE() do { \
+ __IO uint32_t tmpreg; \
+ SET_BIT(RCC->AHBENR, RCC_AHBENR_GPIOEEN);\
+ /* Delay after an RCC peripheral clock enabling */ \
+ tmpreg = READ_BIT(RCC->AHBENR, RCC_AHBENR_GPIOEEN);\
+ UNUSED(tmpreg); \
+ } while(0U)
+
+#define __HAL_RCC_GPIOE_CLK_DISABLE() (RCC->AHBENR &= ~(RCC_AHBENR_GPIOEEN))
+
+#endif /* GPIOE */
+
+#if defined(STM32F042x6) || defined(STM32F048xx)\
+ || defined(STM32F051x8) || defined(STM32F058xx)\
+ || defined(STM32F071xB) || defined(STM32F072xB) || defined(STM32F078xx)\
+ || defined(STM32F091xC) || defined(STM32F098xx)
+
+#define __HAL_RCC_TSC_CLK_ENABLE() do { \
+ __IO uint32_t tmpreg; \
+ SET_BIT(RCC->AHBENR, RCC_AHBENR_TSCEN);\
+ /* Delay after an RCC peripheral clock enabling */ \
+ tmpreg = READ_BIT(RCC->AHBENR, RCC_AHBENR_TSCEN);\
+ UNUSED(tmpreg); \
+ } while(0U)
+
+#define __HAL_RCC_TSC_CLK_DISABLE() (RCC->AHBENR &= ~(RCC_AHBENR_TSCEN))
+
+#endif /* STM32F042x6 || STM32F048xx || */
+ /* STM32F051x8 || STM32F058xx || */
+ /* STM32F071xB || STM32F072xB || STM32F078xx || */
+ /* STM32F091xC || STM32F098xx */
+
+#if defined(STM32F091xC) || defined(STM32F098xx)
+
+#define __HAL_RCC_DMA2_CLK_ENABLE() do { \
+ __IO uint32_t tmpreg; \
+ SET_BIT(RCC->AHBENR, RCC_AHBENR_DMA2EN);\
+ /* Delay after an RCC peripheral clock enabling */ \
+ tmpreg = READ_BIT(RCC->AHBENR, RCC_AHBENR_DMA2EN);\
+ UNUSED(tmpreg); \
+ } while(0U)
+
+#define __HAL_RCC_DMA2_CLK_DISABLE() (RCC->AHBENR &= ~(RCC_AHBENR_DMA2EN))
+
+#endif /* STM32F091xC || STM32F098xx */
+
+/** @brief Enable or disable the Low Speed APB (APB1) peripheral clock.
+ * @note After reset, the peripheral clock (used for registers read/write access)
+ * is disabled and the application software has to enable this clock before
+ * using it.
+ */
+#if defined(STM32F030x8)\
+ || defined(STM32F042x6) || defined(STM32F048xx) || defined(STM32F070x6)\
+ || defined(STM32F051x8) || defined(STM32F058xx)\
+ || defined(STM32F071xB) || defined(STM32F072xB) || defined(STM32F078xx) || defined(STM32F070xB)\
+ || defined(STM32F091xC) || defined(STM32F098xx) || defined(STM32F030xC)
+
+#define __HAL_RCC_USART2_CLK_ENABLE() do { \
+ __IO uint32_t tmpreg; \
+ SET_BIT(RCC->APB1ENR, RCC_APB1ENR_USART2EN);\
+ /* Delay after an RCC peripheral clock enabling */ \
+ tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_USART2EN);\
+ UNUSED(tmpreg); \
+ } while(0U)
+
+#define __HAL_RCC_USART2_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_USART2EN))
+
+#endif /* STM32F030x8 || STM32F042x6 || STM32F048xx || */
+ /* STM32F051x8 || STM32F058xx || STM32F070x6 || */
+ /* STM32F071xB || STM32F072xB || STM32F078xx || STM32F070xB || */
+ /* STM32F091xC || STM32F098xx || STM32F030xC */
+
+#if defined(STM32F030x8)\
+ || defined(STM32F042x6) || defined(STM32F048xx)\
+ || defined(STM32F051x8) || defined(STM32F058xx)\
+ || defined(STM32F071xB) || defined(STM32F072xB) || defined(STM32F078xx) || defined(STM32F070xB)\
+ || defined(STM32F091xC) || defined(STM32F098xx) || defined(STM32F030xC)
+
+#define __HAL_RCC_SPI2_CLK_ENABLE() do { \
+ __IO uint32_t tmpreg; \
+ SET_BIT(RCC->APB1ENR, RCC_APB1ENR_SPI2EN);\
+ /* Delay after an RCC peripheral clock enabling */ \
+ tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_SPI2EN);\
+ UNUSED(tmpreg); \
+ } while(0U)
+
+#define __HAL_RCC_SPI2_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_SPI2EN))
+
+#endif /* STM32F030x8 || STM32F042x6 || STM32F048xx || */
+ /* STM32F051x8 || STM32F058xx || */
+ /* STM32F071xB || STM32F072xB || STM32F078xx || STM32F070xB || */
+ /* STM32F091xC || STM32F098xx || STM32F030xC */
+
+#if defined(STM32F031x6) || defined(STM32F038xx)\
+ || defined(STM32F042x6) || defined(STM32F048xx)\
+ || defined(STM32F051x8) || defined(STM32F058xx)\
+ || defined(STM32F071xB) || defined(STM32F072xB) || defined(STM32F078xx)\
+ || defined(STM32F091xC) || defined(STM32F098xx)
+
+#define __HAL_RCC_TIM2_CLK_ENABLE() do { \
+ __IO uint32_t tmpreg; \
+ SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM2EN);\
+ /* Delay after an RCC peripheral clock enabling */ \
+ tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM2EN);\
+ UNUSED(tmpreg); \
+ } while(0U)
+
+#define __HAL_RCC_TIM2_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM2EN))
+
+#endif /* STM32F031x6 || STM32F038xx || */
+ /* STM32F042x6 || STM32F048xx || */
+ /* STM32F051x8 || STM32F058xx || */
+ /* STM32F071xB || STM32F072xB || STM32F078xx || */
+ /* STM32F091xC || STM32F098xx */
+
+#if defined(STM32F030x8) \
+ || defined(STM32F051x8) || defined(STM32F058xx)\
+ || defined(STM32F071xB) || defined(STM32F072xB) || defined(STM32F078xx) || defined(STM32F070xB)\
+ || defined(STM32F091xC) || defined(STM32F098xx) || defined(STM32F030xC)
+
+#define __HAL_RCC_TIM6_CLK_ENABLE() do { \
+ __IO uint32_t tmpreg; \
+ SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM6EN);\
+ /* Delay after an RCC peripheral clock enabling */ \
+ tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM6EN);\
+ UNUSED(tmpreg); \
+ } while(0U)
+#define __HAL_RCC_I2C2_CLK_ENABLE() do { \
+ __IO uint32_t tmpreg; \
+ SET_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C2EN);\
+ /* Delay after an RCC peripheral clock enabling */ \
+ tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C2EN);\
+ UNUSED(tmpreg); \
+ } while(0U)
+
+#define __HAL_RCC_TIM6_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM6EN))
+#define __HAL_RCC_I2C2_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_I2C2EN))
+
+#endif /* STM32F030x8 || */
+ /* STM32F051x8 || STM32F058xx || */
+ /* STM32F071xB || STM32F072xB || STM32F078xx || STM32F070xB || */
+ /* STM32F091xC || STM32F098xx || STM32F030xC */
+
+#if defined(STM32F051x8) || defined(STM32F058xx)\
+ || defined(STM32F071xB) || defined(STM32F072xB) || defined(STM32F078xx)\
+ || defined(STM32F091xC) || defined(STM32F098xx)
+
+#define __HAL_RCC_DAC1_CLK_ENABLE() do { \
+ __IO uint32_t tmpreg; \
+ SET_BIT(RCC->APB1ENR, RCC_APB1ENR_DACEN);\
+ /* Delay after an RCC peripheral clock enabling */ \
+ tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_DACEN);\
+ UNUSED(tmpreg); \
+ } while(0U)
+
+#define __HAL_RCC_DAC1_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_DACEN))
+
+#endif /* STM32F051x8 || STM32F058xx || */
+ /* STM32F071xB || STM32F072xB || STM32F078xx || */
+ /* STM32F091xC || STM32F098xx */
+
+#if defined(STM32F042x6) || defined(STM32F048xx)\
+ || defined(STM32F051x8) || defined(STM32F058xx)\
+ || defined(STM32F071xB) || defined(STM32F072xB) || defined(STM32F078xx)\
+ || defined(STM32F091xC) || defined(STM32F098xx)
+
+#define __HAL_RCC_CEC_CLK_ENABLE() do { \
+ __IO uint32_t tmpreg; \
+ SET_BIT(RCC->APB1ENR, RCC_APB1ENR_CECEN);\
+ /* Delay after an RCC peripheral clock enabling */ \
+ tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_CECEN);\
+ UNUSED(tmpreg); \
+ } while(0U)
+
+#define __HAL_RCC_CEC_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_CECEN))
+
+#endif /* STM32F042x6 || STM32F048xx || */
+ /* STM32F051x8 || STM32F058xx || */
+ /* STM32F071xB || STM32F072xB || STM32F078xx || */
+ /* STM32F091xC || STM32F098xx */
+
+#if defined(STM32F071xB) || defined(STM32F072xB) || defined(STM32F078xx) || defined(STM32F070xB)\
+ || defined(STM32F091xC) || defined(STM32F098xx) || defined(STM32F030xC)
+
+#define __HAL_RCC_TIM7_CLK_ENABLE() do { \
+ __IO uint32_t tmpreg; \
+ SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM7EN);\
+ /* Delay after an RCC peripheral clock enabling */ \
+ tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM7EN);\
+ UNUSED(tmpreg); \
+ } while(0U)
+#define __HAL_RCC_USART3_CLK_ENABLE() do { \
+ __IO uint32_t tmpreg; \
+ SET_BIT(RCC->APB1ENR, RCC_APB1ENR_USART3EN);\
+ /* Delay after an RCC peripheral clock enabling */ \
+ tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_USART3EN);\
+ UNUSED(tmpreg); \
+ } while(0U)
+#define __HAL_RCC_USART4_CLK_ENABLE() do { \
+ __IO uint32_t tmpreg; \
+ SET_BIT(RCC->APB1ENR, RCC_APB1ENR_USART4EN);\
+ /* Delay after an RCC peripheral clock enabling */ \
+ tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_USART4EN);\
+ UNUSED(tmpreg); \
+ } while(0U)
+
+#define __HAL_RCC_TIM7_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM7EN))
+#define __HAL_RCC_USART3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_USART3EN))
+#define __HAL_RCC_USART4_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_USART4EN))
+
+#endif /* STM32F071xB || STM32F072xB || STM32F078xx || STM32F070xB || */
+ /* STM32F091xC || STM32F098xx || STM32F030xC */
+
+#if defined(STM32F042x6) || defined(STM32F048xx) || defined(STM32F070x6)\
+ || defined(STM32F072xB) || defined(STM32F078xx) || defined(STM32F070xB)
+
+#define __HAL_RCC_USB_CLK_ENABLE() do { \
+ __IO uint32_t tmpreg; \
+ SET_BIT(RCC->APB1ENR, RCC_APB1ENR_USBEN);\
+ /* Delay after an RCC peripheral clock enabling */ \
+ tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_USBEN);\
+ UNUSED(tmpreg); \
+ } while(0U)
+
+#define __HAL_RCC_USB_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_USBEN))
+
+#endif /* STM32F042x6 || STM32F048xx || STM32F070x6 || */
+ /* STM32F072xB || STM32F078xx || STM32F070xB */
+
+#if defined(STM32F042x6) || defined(STM32F048xx) || defined(STM32F072xB)\
+ || defined(STM32F091xC) || defined(STM32F098xx)
+
+#define __HAL_RCC_CAN1_CLK_ENABLE() do { \
+ __IO uint32_t tmpreg; \
+ SET_BIT(RCC->APB1ENR, RCC_APB1ENR_CANEN);\
+ /* Delay after an RCC peripheral clock enabling */ \
+ tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_CANEN);\
+ UNUSED(tmpreg); \
+ } while(0U)
+#define __HAL_RCC_CAN1_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_CANEN))
+
+#endif /* STM32F042x6 || STM32F048xx || STM32F072xB || */
+ /* STM32F091xC || STM32F098xx */
+
+#if defined(CRS)
+
+#define __HAL_RCC_CRS_CLK_ENABLE() do { \
+ __IO uint32_t tmpreg; \
+ SET_BIT(RCC->APB1ENR, RCC_APB1ENR_CRSEN);\
+ /* Delay after an RCC peripheral clock enabling */ \
+ tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_CRSEN);\
+ UNUSED(tmpreg); \
+ } while(0U)
+
+#define __HAL_RCC_CRS_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_CRSEN))
+
+#endif /* CRS */
+
+#if defined(STM32F091xC) || defined(STM32F098xx) || defined(STM32F030xC)
+
+#define __HAL_RCC_USART5_CLK_ENABLE() do { \
+ __IO uint32_t tmpreg; \
+ SET_BIT(RCC->APB1ENR, RCC_APB1ENR_USART5EN);\
+ /* Delay after an RCC peripheral clock enabling */ \
+ tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_USART5EN);\
+ UNUSED(tmpreg); \
+ } while(0U)
+
+#define __HAL_RCC_USART5_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_USART5EN))
+
+#endif /* STM32F091xC || STM32F098xx || STM32F030xC */
+
+/** @brief Enable or disable the High Speed APB (APB2) peripheral clock.
+ * @note After reset, the peripheral clock (used for registers read/write access)
+ * is disabled and the application software has to enable this clock before
+ * using it.
+ */
+#if defined(STM32F030x8) || defined(STM32F042x6) || defined(STM32F048xx) || defined(STM32F070x6)\
+ || defined(STM32F051x8) || defined(STM32F058xx)\
+ || defined(STM32F071xB) || defined(STM32F072xB) || defined(STM32F078xx) || defined(STM32F070xB)\
+ || defined(STM32F091xC) || defined(STM32F098xx) || defined(STM32F030xC)
+
+#define __HAL_RCC_TIM15_CLK_ENABLE() do { \
+ __IO uint32_t tmpreg; \
+ SET_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM15EN);\
+ /* Delay after an RCC peripheral clock enabling */ \
+ tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM15EN);\
+ UNUSED(tmpreg); \
+ } while(0U)
+
+#define __HAL_RCC_TIM15_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_TIM15EN))
+
+#endif /* STM32F030x8 || STM32F042x6 || STM32F048xx || STM32F070x6 || */
+ /* STM32F051x8 || STM32F058xx || */
+ /* STM32F071xB || STM32F072xB || STM32F078xx || STM32F070xB || */
+ /* STM32F091xC || STM32F098xx || STM32F030xC */
+
+#if defined(STM32F091xC) || defined(STM32F098xx) || defined(STM32F030xC)
+
+#define __HAL_RCC_USART6_CLK_ENABLE() do { \
+ __IO uint32_t tmpreg; \
+ SET_BIT(RCC->APB2ENR, RCC_APB2ENR_USART6EN);\
+ /* Delay after an RCC peripheral clock enabling */ \
+ tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_USART6EN);\
+ UNUSED(tmpreg); \
+ } while(0U)
+
+#define __HAL_RCC_USART6_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_USART6EN))
+
+#endif /* STM32F091xC || STM32F098xx || STM32F030xC */
+
+#if defined(STM32F091xC) || defined(STM32F098xx)
+
+#define __HAL_RCC_USART7_CLK_ENABLE() do { \
+ __IO uint32_t tmpreg; \
+ SET_BIT(RCC->APB2ENR, RCC_APB2ENR_USART7EN);\
+ /* Delay after an RCC peripheral clock enabling */ \
+ tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_USART7EN);\
+ UNUSED(tmpreg); \
+ } while(0U)
+#define __HAL_RCC_USART8_CLK_ENABLE() do { \
+ __IO uint32_t tmpreg; \
+ SET_BIT(RCC->APB2ENR, RCC_APB2ENR_USART8EN);\
+ /* Delay after an RCC peripheral clock enabling */ \
+ tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_USART8EN);\
+ UNUSED(tmpreg); \
+ } while(0U)
+
+#define __HAL_RCC_USART7_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_USART7EN))
+#define __HAL_RCC_USART8_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_USART8EN))
+
+#endif /* STM32F091xC || STM32F098xx */
+
+/**
+ * @}
+ */
+
+
+/** @defgroup RCCEx_Force_Release_Peripheral_Reset RCCEx Force Release Peripheral Reset
+ * @brief Forces or releases peripheral reset.
+ * @{
+ */
+
+/** @brief Force or release AHB peripheral reset.
+ */
+#if defined(GPIOD)
+
+#define __HAL_RCC_GPIOD_FORCE_RESET() (RCC->AHBRSTR |= (RCC_AHBRSTR_GPIODRST))
+
+#define __HAL_RCC_GPIOD_RELEASE_RESET() (RCC->AHBRSTR &= ~(RCC_AHBRSTR_GPIODRST))
+
+#endif /* GPIOD */
+
+#if defined(GPIOE)
+
+#define __HAL_RCC_GPIOE_FORCE_RESET() (RCC->AHBRSTR |= (RCC_AHBRSTR_GPIOERST))
+
+#define __HAL_RCC_GPIOE_RELEASE_RESET() (RCC->AHBRSTR &= ~(RCC_AHBRSTR_GPIOERST))
+
+#endif /* GPIOE */
+
+#if defined(STM32F042x6) || defined(STM32F048xx)\
+ || defined(STM32F051x8) || defined(STM32F058xx)\
+ || defined(STM32F071xB) || defined(STM32F072xB) || defined(STM32F078xx)\
+ || defined(STM32F091xC) || defined(STM32F098xx)
+
+#define __HAL_RCC_TSC_FORCE_RESET() (RCC->AHBRSTR |= (RCC_AHBRSTR_TSCRST))
+
+#define __HAL_RCC_TSC_RELEASE_RESET() (RCC->AHBRSTR &= ~(RCC_AHBRSTR_TSCRST))
+
+#endif /* STM32F042x6 || STM32F048xx || */
+ /* STM32F051x8 || STM32F058xx || */
+ /* STM32F071xB || STM32F072xB || STM32F078xx || */
+ /* STM32F091xC || STM32F098xx */
+
+/** @brief Force or release APB1 peripheral reset.
+ */
+#if defined(STM32F030x8) \
+ || defined(STM32F042x6) || defined(STM32F048xx) || defined(STM32F070x6)\
+ || defined(STM32F051x8) || defined(STM32F058xx)\
+ || defined(STM32F071xB) || defined(STM32F072xB) || defined(STM32F078xx) || defined(STM32F070xB)\
+ || defined(STM32F091xC) || defined(STM32F098xx) || defined(STM32F030xC)
+
+#define __HAL_RCC_USART2_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_USART2RST))
+#define __HAL_RCC_SPI2_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_SPI2RST))
+
+#define __HAL_RCC_USART2_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_USART2RST))
+#define __HAL_RCC_SPI2_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_SPI2RST))
+
+#endif /* STM32F030x8 || STM32F042x6 || STM32F048xx || STM32F070x6 || */
+ /* STM32F051x8 || STM32F058xx || */
+ /* STM32F071xB || STM32F072xB || STM32F078xx || STM32F070xB || */
+ /* STM32F091xC || STM32F098xx || STM32F030xC */
+
+#if defined(STM32F031x6) || defined(STM32F038xx)\
+ || defined(STM32F042x6) || defined(STM32F048xx)\
+ || defined(STM32F051x8) || defined(STM32F058xx)\
+ || defined(STM32F071xB) || defined(STM32F072xB) || defined(STM32F078xx)\
+ || defined(STM32F091xC) || defined(STM32F098xx)
+
+#define __HAL_RCC_TIM2_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM2RST))
+
+#define __HAL_RCC_TIM2_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM2RST))
+
+#endif /* STM32F031x6 || STM32F038xx || */
+ /* STM32F042x6 || STM32F048xx || */
+ /* STM32F051x8 || STM32F058xx || */
+ /* STM32F071xB || STM32F072xB || STM32F078xx || */
+ /* STM32F091xC || STM32F098xx */
+
+#if defined(STM32F030x8) \
+ || defined(STM32F051x8) || defined(STM32F058xx)\
+ || defined(STM32F071xB) || defined(STM32F072xB) || defined(STM32F078xx) || defined(STM32F070xB)\
+ || defined(STM32F091xC) || defined(STM32F098xx) || defined(STM32F030xC)
+
+#define __HAL_RCC_TIM6_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM6RST))
+#define __HAL_RCC_I2C2_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_I2C2RST))
+
+#define __HAL_RCC_TIM6_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM6RST))
+#define __HAL_RCC_I2C2_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_I2C2RST))
+
+#endif /* STM32F030x8 || */
+ /* STM32F051x8 || STM32F058xx || */
+ /* STM32F071xB || STM32F072xB || STM32F078xx || STM32F070xB || */
+ /* STM32F091xC || STM32F098xx || STM32F030xC */
+
+#if defined(STM32F051x8) || defined(STM32F058xx)\
+ || defined(STM32F071xB) || defined(STM32F072xB) || defined(STM32F078xx)\
+ || defined(STM32F091xC) || defined(STM32F098xx)
+
+#define __HAL_RCC_DAC1_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_DACRST))
+
+#define __HAL_RCC_DAC1_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_DACRST))
+
+#endif /* STM32F051x8 || STM32F058xx || */
+ /* STM32F071xB || STM32F072xB || STM32F078xx || */
+ /* STM32F091xC || STM32F098xx */
+
+#if defined(STM32F042x6) || defined(STM32F048xx)\
+ || defined(STM32F051x8) || defined(STM32F058xx)\
+ || defined(STM32F071xB) || defined(STM32F072xB) || defined(STM32F078xx)\
+ || defined(STM32F091xC) || defined(STM32F098xx)
+
+#define __HAL_RCC_CEC_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_CECRST))
+
+#define __HAL_RCC_CEC_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_CECRST))
+
+#endif /* STM32F042x6 || STM32F048xx || */
+ /* STM32F051x8 || STM32F058xx || */
+ /* STM32F071xB || STM32F072xB || STM32F078xx || */
+ /* STM32F091xC || STM32F098xx */
+
+#if defined(STM32F071xB) || defined(STM32F072xB) || defined(STM32F078xx) || defined(STM32F070xB)\
+ || defined(STM32F091xC) || defined(STM32F098xx) || defined(STM32F030xC)
+
+#define __HAL_RCC_TIM7_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM7RST))
+#define __HAL_RCC_USART3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_USART3RST))
+#define __HAL_RCC_USART4_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_USART4RST))
+
+#define __HAL_RCC_TIM7_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM7RST))
+#define __HAL_RCC_USART3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_USART3RST))
+#define __HAL_RCC_USART4_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_USART4RST))
+
+#endif /* STM32F071xB || STM32F072xB || STM32F078xx || STM32F070xB || */
+ /* STM32F091xC || STM32F098xx || STM32F030xC */
+
+#if defined(STM32F042x6) || defined(STM32F048xx) || defined(STM32F070x6)\
+ || defined(STM32F072xB) || defined(STM32F078xx) || defined(STM32F070xB)
+
+#define __HAL_RCC_USB_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_USBRST))
+
+#define __HAL_RCC_USB_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_USBRST))
+
+#endif /* STM32F042x6 || STM32F048xx || STM32F070x6 || */
+ /* STM32F072xB || STM32F078xx || STM32F070xB */
+
+#if defined(STM32F042x6) || defined(STM32F048xx) || defined(STM32F072xB)\
+ || defined(STM32F091xC) || defined(STM32F098xx)
+
+#define __HAL_RCC_CAN1_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_CANRST))
+
+#define __HAL_RCC_CAN1_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_CANRST))
+
+#endif /* STM32F042x6 || STM32F048xx || STM32F072xB || */
+ /* STM32F091xC || STM32F098xx */
+
+#if defined(CRS)
+
+#define __HAL_RCC_CRS_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_CRSRST))
+
+#define __HAL_RCC_CRS_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_CRSRST))
+
+#endif /* CRS */
+
+#if defined(STM32F091xC) || defined(STM32F098xx) || defined(STM32F030xC)
+
+#define __HAL_RCC_USART5_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_USART5RST))
+
+#define __HAL_RCC_USART5_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_USART5RST))
+
+#endif /* STM32F091xC || STM32F098xx || STM32F030xC */
+
+
+/** @brief Force or release APB2 peripheral reset.
+ */
+#if defined(STM32F030x8) || defined(STM32F042x6) || defined(STM32F048xx) || defined(STM32F070x6)\
+ || defined(STM32F051x8) || defined(STM32F058xx)\
+ || defined(STM32F071xB) || defined(STM32F072xB) || defined(STM32F078xx) || defined(STM32F070xB)\
+ || defined(STM32F091xC) || defined(STM32F098xx) || defined(STM32F030xC)
+
+#define __HAL_RCC_TIM15_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_TIM15RST))
+
+#define __HAL_RCC_TIM15_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_TIM15RST))
+
+#endif /* STM32F030x8 || STM32F042x6 || STM32F048xx || STM32F070x6 || */
+ /* STM32F051x8 || STM32F058xx || */
+ /* STM32F071xB || STM32F072xB || STM32F078xx || STM32F070xB || */
+ /* STM32F091xC || STM32F098xx || STM32F030xC */
+
+#if defined(STM32F091xC) || defined(STM32F098xx) || defined(STM32F030xC)
+
+#define __HAL_RCC_USART6_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_USART6RST))
+
+#define __HAL_RCC_USART6_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_USART6RST))
+
+#endif /* STM32F091xC || STM32F098xx || STM32F030xC */
+
+#if defined(STM32F091xC) || defined(STM32F098xx)
+
+#define __HAL_RCC_USART7_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_USART7RST))
+#define __HAL_RCC_USART8_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_USART8RST))
+
+#define __HAL_RCC_USART7_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_USART7RST))
+#define __HAL_RCC_USART8_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_USART8RST))
+
+#endif /* STM32F091xC || STM32F098xx */
+
+/**
+ * @}
+ */
+
+/** @defgroup RCCEx_Peripheral_Clock_Enable_Disable_Status Peripheral Clock Enable Disable Status
+ * @brief Get the enable or disable status of peripheral clock.
+ * @note After reset, the peripheral clock (used for registers read/write access)
+ * is disabled and the application software has to enable this clock before
+ * using it.
+ * @{
+ */
+/** @brief AHB Peripheral Clock Enable Disable Status
+ */
+#if defined(GPIOD)
+
+#define __HAL_RCC_GPIOD_IS_CLK_ENABLED() ((RCC->AHBENR & (RCC_AHBENR_GPIODEN)) != RESET)
+#define __HAL_RCC_GPIOD_IS_CLK_DISABLED() ((RCC->AHBENR & (RCC_AHBENR_GPIODEN)) == RESET)
+
+#endif /* GPIOD */
+
+#if defined(GPIOE)
+
+#define __HAL_RCC_GPIOE_IS_CLK_ENABLED() ((RCC->AHBENR & (RCC_AHBENR_GPIOEEN)) != RESET)
+#define __HAL_RCC_GPIOE_IS_CLK_DISABLED() ((RCC->AHBENR & (RCC_AHBENR_GPIOEEN)) == RESET)
+
+#endif /* GPIOE */
+
+#if defined(STM32F042x6) || defined(STM32F048xx)\
+ || defined(STM32F051x8) || defined(STM32F058xx)\
+ || defined(STM32F071xB) || defined(STM32F072xB) || defined(STM32F078xx)\
+ || defined(STM32F091xC) || defined(STM32F098xx)
+
+#define __HAL_RCC_TSC_IS_CLK_ENABLED() ((RCC->AHBENR & (RCC_AHBENR_TSCEN)) != RESET)
+#define __HAL_RCC_TSC_IS_CLK_DISABLED() ((RCC->AHBENR & (RCC_AHBENR_TSCEN)) == RESET)
+
+#endif /* STM32F042x6 || STM32F048xx || */
+ /* STM32F051x8 || STM32F058xx || */
+ /* STM32F071xB || STM32F072xB || STM32F078xx || */
+ /* STM32F091xC || STM32F098xx */
+
+#if defined(STM32F091xC) || defined(STM32F098xx)
+
+#define __HAL_RCC_DMA2_IS_CLK_ENABLED() ((RCC->AHBENR & (RCC_AHBENR_DMA2EN)) != RESET)
+#define __HAL_RCC_DMA2_IS_CLK_DISABLED() ((RCC->AHBENR & (RCC_AHBENR_DMA2EN)) == RESET)
+
+#endif /* STM32F091xC || STM32F098xx */
+
+/** @brief APB1 Peripheral Clock Enable Disable Status
+ */
+#if defined(STM32F030x8)\
+ || defined(STM32F042x6) || defined(STM32F048xx) || defined(STM32F070x6)\
+ || defined(STM32F051x8) || defined(STM32F058xx)\
+ || defined(STM32F071xB) || defined(STM32F072xB) || defined(STM32F078xx) || defined(STM32F070xB)\
+ || defined(STM32F091xC) || defined(STM32F098xx) || defined(STM32F030xC)
+
+#define __HAL_RCC_USART2_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_USART2EN)) != RESET)
+#define __HAL_RCC_USART2_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_USART2EN)) == RESET)
+
+#endif /* STM32F030x8 || STM32F042x6 || STM32F048xx || */
+ /* STM32F051x8 || STM32F058xx || STM32F070x6 || */
+ /* STM32F071xB || STM32F072xB || STM32F078xx || STM32F070xB || */
+ /* STM32F091xC || STM32F098xx || STM32F030xC */
+
+#if defined(STM32F030x8)\
+ || defined(STM32F042x6) || defined(STM32F048xx)\
+ || defined(STM32F051x8) || defined(STM32F058xx)\
+ || defined(STM32F071xB) || defined(STM32F072xB) || defined(STM32F078xx) || defined(STM32F070xB)\
+ || defined(STM32F091xC) || defined(STM32F098xx) || defined(STM32F030xC)
+
+#define __HAL_RCC_SPI2_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPI2EN)) != RESET)
+#define __HAL_RCC_SPI2_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPI2EN)) == RESET)
+
+#endif /* STM32F030x8 || STM32F042x6 || STM32F048xx || */
+ /* STM32F051x8 || STM32F058xx || */
+ /* STM32F071xB || STM32F072xB || STM32F078xx || STM32F070xB || */
+ /* STM32F091xC || STM32F098xx || STM32F030xC */
+
+#if defined(STM32F031x6) || defined(STM32F038xx)\
+ || defined(STM32F042x6) || defined(STM32F048xx)\
+ || defined(STM32F051x8) || defined(STM32F058xx)\
+ || defined(STM32F071xB) || defined(STM32F072xB) || defined(STM32F078xx)\
+ || defined(STM32F091xC) || defined(STM32F098xx)
+
+#define __HAL_RCC_TIM2_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM2EN)) != RESET)
+#define __HAL_RCC_TIM2_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM2EN)) == RESET)
+
+#endif /* STM32F031x6 || STM32F038xx || */
+ /* STM32F042x6 || STM32F048xx || */
+ /* STM32F051x8 || STM32F058xx || */
+ /* STM32F071xB || STM32F072xB || STM32F078xx || */
+ /* STM32F091xC || STM32F098xx */
+
+#if defined(STM32F030x8) \
+ || defined(STM32F051x8) || defined(STM32F058xx)\
+ || defined(STM32F071xB) || defined(STM32F072xB) || defined(STM32F078xx) || defined(STM32F070xB)\
+ || defined(STM32F091xC) || defined(STM32F098xx) || defined(STM32F030xC)
+
+#define __HAL_RCC_TIM6_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM6EN)) != RESET)
+#define __HAL_RCC_I2C2_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C2EN)) != RESET)
+#define __HAL_RCC_TIM6_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM6EN)) == RESET)
+#define __HAL_RCC_I2C2_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C2EN)) == RESET)
+
+#endif /* STM32F030x8 || */
+ /* STM32F051x8 || STM32F058xx || */
+ /* STM32F071xB || STM32F072xB || STM32F078xx || STM32F070xB || */
+ /* STM32F091xC || STM32F098xx || STM32F030xC */
+
+#if defined(STM32F051x8) || defined(STM32F058xx)\
+ || defined(STM32F071xB) || defined(STM32F072xB) || defined(STM32F078xx)\
+ || defined(STM32F091xC) || defined(STM32F098xx)
+
+#define __HAL_RCC_DAC1_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_DAC1EN)) != RESET)
+#define __HAL_RCC_DAC1_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_DAC1EN)) == RESET)
+
+#endif /* STM32F051x8 || STM32F058xx || */
+ /* STM32F071xB || STM32F072xB || STM32F078xx || */
+ /* STM32F091xC || STM32F098xx */
+
+#if defined(STM32F042x6) || defined(STM32F048xx)\
+ || defined(STM32F051x8) || defined(STM32F058xx)\
+ || defined(STM32F071xB) || defined(STM32F072xB) || defined(STM32F078xx)\
+ || defined(STM32F091xC) || defined(STM32F098xx)
+
+#define __HAL_RCC_CEC_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CECEN)) != RESET)
+#define __HAL_RCC_CEC_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CECEN)) == RESET)
+
+#endif /* STM32F042x6 || STM32F048xx || */
+ /* STM32F051x8 || STM32F058xx || */
+ /* STM32F071xB || STM32F072xB || STM32F078xx || */
+ /* STM32F091xC || STM32F098xx */
+
+#if defined(STM32F071xB) || defined(STM32F072xB) || defined(STM32F078xx) || defined(STM32F070xB)\
+ || defined(STM32F091xC) || defined(STM32F098xx) || defined(STM32F030xC)
+
+#define __HAL_RCC_TIM7_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM7EN)) != RESET)
+#define __HAL_RCC_USART3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_USART3EN)) != RESET)
+#define __HAL_RCC_USART4_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_USART4EN)) != RESET)
+#define __HAL_RCC_TIM7_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM7EN)) == RESET)
+#define __HAL_RCC_USART3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_USART3EN)) == RESET)
+#define __HAL_RCC_USART4_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_USART4EN)) == RESET)
+
+#endif /* STM32F071xB || STM32F072xB || STM32F078xx || STM32F070xB || */
+ /* STM32F091xC || STM32F098xx || STM32F030xC */
+
+#if defined(STM32F042x6) || defined(STM32F048xx) || defined(STM32F070x6)\
+ || defined(STM32F072xB) || defined(STM32F078xx) || defined(STM32F070xB)
+
+#define __HAL_RCC_USB_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_USBEN)) != RESET)
+#define __HAL_RCC_USB_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_USBEN)) == RESET)
+
+#endif /* STM32F042x6 || STM32F048xx || STM32F070x6 || */
+ /* STM32F072xB || STM32F078xx || STM32F070xB */
+
+#if defined(STM32F042x6) || defined(STM32F048xx) || defined(STM32F072xB)\
+ || defined(STM32F091xC) || defined(STM32F098xx)
+
+#define __HAL_RCC_CAN1_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN1EN)) != RESET)
+#define __HAL_RCC_CAN1_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN1EN)) == RESET)
+
+#endif /* STM32F042x6 || STM32F048xx || STM32F072xB || */
+ /* STM32F091xC || STM32F098xx */
+
+#if defined(CRS)
+
+#define __HAL_RCC_CRS_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CRSEN)) != RESET)
+#define __HAL_RCC_CRS_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CRSEN)) == RESET)
+
+#endif /* CRS */
+
+#if defined(STM32F091xC) || defined(STM32F098xx) || defined(STM32F030xC)
+
+#define __HAL_RCC_USART5_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_USART5EN)) != RESET)
+#define __HAL_RCC_USART5_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_USART5EN)) == RESET)
+
+#endif /* STM32F091xC || STM32F098xx || STM32F030xC */
+
+/** @brief APB1 Peripheral Clock Enable Disable Status
+ */
+#if defined(STM32F030x8) || defined(STM32F042x6) || defined(STM32F048xx) || defined(STM32F070x6)\
+ || defined(STM32F051x8) || defined(STM32F058xx)\
+ || defined(STM32F071xB) || defined(STM32F072xB) || defined(STM32F078xx) || defined(STM32F070xB)\
+ || defined(STM32F091xC) || defined(STM32F098xx) || defined(STM32F030xC)
+
+#define __HAL_RCC_TIM15_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM15EN)) != RESET)
+#define __HAL_RCC_TIM15_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM15EN)) == RESET)
+
+#endif /* STM32F030x8 || STM32F042x6 || STM32F048xx || STM32F070x6 || */
+ /* STM32F051x8 || STM32F058xx || */
+ /* STM32F071xB || STM32F072xB || STM32F078xx || STM32F070xB || */
+ /* STM32F091xC || STM32F098xx || STM32F030xC */
+
+#if defined(STM32F091xC) || defined(STM32F098xx) || defined(STM32F030xC)
+
+#define __HAL_RCC_USART6_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_USART6EN)) != RESET)
+#define __HAL_RCC_USART6_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_USART6EN)) == RESET)
+
+#endif /* STM32F091xC || STM32F098xx || STM32F030xC */
+
+#if defined(STM32F091xC) || defined(STM32F098xx)
+
+#define __HAL_RCC_USART7_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_USART7EN)) != RESET)
+#define __HAL_RCC_USART8_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_USART8EN)) != RESET)
+#define __HAL_RCC_USART7_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_USART7EN)) == RESET)
+#define __HAL_RCC_USART8_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_USART8EN)) == RESET)
+
+#endif /* STM32F091xC || STM32F098xx */
+/**
+ * @}
+ */
+
+
+/** @defgroup RCCEx_HSI48_Enable_Disable RCCEx HSI48 Enable Disable
+ * @brief Macros to enable or disable the Internal 48Mhz High Speed oscillator (HSI48).
+ * @note The HSI48 is stopped by hardware when entering STOP and STANDBY modes.
+ * @note HSI48 can not be stopped if it is used as system clock source. In this case,
+ * you have to select another source of the system clock then stop the HSI14.
+ * @note After enabling the HSI48 with __HAL_RCC_HSI48_ENABLE(), the application software
+ * should wait on HSI48RDY flag to be set indicating that HSI48 clock is stable and can be
+ * used as system clock source. This is not necessary if HAL_RCC_OscConfig() is used.
+ * @note When the HSI48 is stopped, HSI48RDY flag goes low after 6 HSI48 oscillator
+ * clock cycles.
+ * @{
+ */
+#if defined(RCC_HSI48_SUPPORT)
+
+#define __HAL_RCC_HSI48_ENABLE() SET_BIT(RCC->CR2, RCC_CR2_HSI48ON)
+#define __HAL_RCC_HSI48_DISABLE() CLEAR_BIT(RCC->CR2, RCC_CR2_HSI48ON)
+
+/** @brief Macro to get the Internal 48Mhz High Speed oscillator (HSI48) state.
+ * @retval The clock source can be one of the following values:
+ * @arg @ref RCC_HSI48_ON HSI48 enabled
+ * @arg @ref RCC_HSI48_OFF HSI48 disabled
+ */
+#define __HAL_RCC_GET_HSI48_STATE() \
+ (((uint32_t)(READ_BIT(RCC->CR2, RCC_CR2_HSI48ON)) != RESET) ? RCC_HSI48_ON : RCC_HSI48_OFF)
+
+#endif /* RCC_HSI48_SUPPORT */
+
+/**
+ * @}
+ */
+
+/** @defgroup RCCEx_Peripheral_Clock_Source_Config RCCEx Peripheral Clock Source Config
+ * @{
+ */
+#if defined(STM32F042x6) || defined(STM32F048xx)\
+ || defined(STM32F072xB) || defined(STM32F078xx)\
+ || defined(STM32F070x6) || defined(STM32F070xB)
+
+/** @brief Macro to configure the USB clock (USBCLK).
+ * @param __USBCLKSOURCE__ specifies the USB clock source.
+ * This parameter can be one of the following values:
+@if STM32F070xB
+@elseif STM32F070x6
+@else
+ * @arg @ref RCC_USBCLKSOURCE_HSI48 HSI48 selected as USB clock
+@endif
+ * @arg @ref RCC_USBCLKSOURCE_PLL PLL Clock selected as USB clock
+ */
+#define __HAL_RCC_USB_CONFIG(__USBCLKSOURCE__) \
+ MODIFY_REG(RCC->CFGR3, RCC_CFGR3_USBSW, (uint32_t)(__USBCLKSOURCE__))
+
+/** @brief Macro to get the USB clock source.
+ * @retval The clock source can be one of the following values:
+@if STM32F070xB
+@elseif STM32F070x6
+@else
+ * @arg @ref RCC_USBCLKSOURCE_HSI48 HSI48 selected as USB clock
+@endif
+ * @arg @ref RCC_USBCLKSOURCE_PLL PLL Clock selected as USB clock
+ */
+#define __HAL_RCC_GET_USB_SOURCE() ((uint32_t)(READ_BIT(RCC->CFGR3, RCC_CFGR3_USBSW)))
+
+#endif /* STM32F042x6 || STM32F048xx || */
+ /* STM32F072xB || STM32F078xx || */
+ /* STM32F070x6 || STM32F070xB */
+
+#if defined(STM32F042x6) || defined(STM32F048xx)\
+ || defined(STM32F051x8) || defined(STM32F058xx)\
+ || defined(STM32F071xB) || defined(STM32F072xB) || defined(STM32F078xx)\
+ || defined(STM32F091xC) || defined(STM32F098xx)
+
+/** @brief Macro to configure the CEC clock.
+ * @param __CECCLKSOURCE__ specifies the CEC clock source.
+ * This parameter can be one of the following values:
+ * @arg @ref RCC_CECCLKSOURCE_HSI HSI selected as CEC clock
+ * @arg @ref RCC_CECCLKSOURCE_LSE LSE selected as CEC clock
+ */
+#define __HAL_RCC_CEC_CONFIG(__CECCLKSOURCE__) \
+ MODIFY_REG(RCC->CFGR3, RCC_CFGR3_CECSW, (uint32_t)(__CECCLKSOURCE__))
+
+/** @brief Macro to get the HDMI CEC clock source.
+ * @retval The clock source can be one of the following values:
+ * @arg @ref RCC_CECCLKSOURCE_HSI HSI selected as CEC clock
+ * @arg @ref RCC_CECCLKSOURCE_LSE LSE selected as CEC clock
+ */
+#define __HAL_RCC_GET_CEC_SOURCE() ((uint32_t)(READ_BIT(RCC->CFGR3, RCC_CFGR3_CECSW)))
+
+#endif /* STM32F042x6 || STM32F048xx || */
+ /* STM32F051x8 || STM32F058xx || */
+ /* STM32F071xB || STM32F072xB || STM32F078xx || */
+ /* STM32F091xC || defined(STM32F098xx) */
+
+#if defined(STM32F071xB) || defined(STM32F072xB) || defined(STM32F078xx)\
+ || defined(STM32F091xC) || defined(STM32F098xx)
+/** @brief Macro to configure the USART2 clock (USART2CLK).
+ * @param __USART2CLKSOURCE__ specifies the USART2 clock source.
+ * This parameter can be one of the following values:
+ * @arg @ref RCC_USART2CLKSOURCE_PCLK1 PCLK1 selected as USART2 clock
+ * @arg @ref RCC_USART2CLKSOURCE_HSI HSI selected as USART2 clock
+ * @arg @ref RCC_USART2CLKSOURCE_SYSCLK System Clock selected as USART2 clock
+ * @arg @ref RCC_USART2CLKSOURCE_LSE LSE selected as USART2 clock
+ */
+#define __HAL_RCC_USART2_CONFIG(__USART2CLKSOURCE__) \
+ MODIFY_REG(RCC->CFGR3, RCC_CFGR3_USART2SW, (uint32_t)(__USART2CLKSOURCE__))
+
+/** @brief Macro to get the USART2 clock source.
+ * @retval The clock source can be one of the following values:
+ * @arg @ref RCC_USART2CLKSOURCE_PCLK1 PCLK1 selected as USART2 clock
+ * @arg @ref RCC_USART2CLKSOURCE_HSI HSI selected as USART2 clock
+ * @arg @ref RCC_USART2CLKSOURCE_SYSCLK System Clock selected as USART2 clock
+ * @arg @ref RCC_USART2CLKSOURCE_LSE LSE selected as USART2 clock
+ */
+#define __HAL_RCC_GET_USART2_SOURCE() ((uint32_t)(READ_BIT(RCC->CFGR3, RCC_CFGR3_USART2SW)))
+#endif /* STM32F071xB || STM32F072xB || STM32F078xx || STM32F091xC || STM32F098xx*/
+
+#if defined(STM32F091xC) || defined(STM32F098xx)
+/** @brief Macro to configure the USART3 clock (USART3CLK).
+ * @param __USART3CLKSOURCE__ specifies the USART3 clock source.
+ * This parameter can be one of the following values:
+ * @arg @ref RCC_USART3CLKSOURCE_PCLK1 PCLK1 selected as USART3 clock
+ * @arg @ref RCC_USART3CLKSOURCE_HSI HSI selected as USART3 clock
+ * @arg @ref RCC_USART3CLKSOURCE_SYSCLK System Clock selected as USART3 clock
+ * @arg @ref RCC_USART3CLKSOURCE_LSE LSE selected as USART3 clock
+ */
+#define __HAL_RCC_USART3_CONFIG(__USART3CLKSOURCE__) \
+ MODIFY_REG(RCC->CFGR3, RCC_CFGR3_USART3SW, (uint32_t)(__USART3CLKSOURCE__))
+
+/** @brief Macro to get the USART3 clock source.
+ * @retval The clock source can be one of the following values:
+ * @arg @ref RCC_USART3CLKSOURCE_PCLK1 PCLK1 selected as USART3 clock
+ * @arg @ref RCC_USART3CLKSOURCE_HSI HSI selected as USART3 clock
+ * @arg @ref RCC_USART3CLKSOURCE_SYSCLK System Clock selected as USART3 clock
+ * @arg @ref RCC_USART3CLKSOURCE_LSE LSE selected as USART3 clock
+ */
+#define __HAL_RCC_GET_USART3_SOURCE() ((uint32_t)(READ_BIT(RCC->CFGR3, RCC_CFGR3_USART3SW)))
+
+#endif /* STM32F091xC || STM32F098xx */
+/**
+ * @}
+ */
+
+/** @defgroup RCCEx_LSE_Configuration LSE Drive Configuration
+ * @{
+ */
+
+/**
+ * @brief Macro to configure the External Low Speed oscillator (LSE) drive capability.
+ * @param __RCC_LSEDRIVE__ specifies the new state of the LSE drive capability.
+ * This parameter can be one of the following values:
+ * @arg @ref RCC_LSEDRIVE_LOW LSE oscillator low drive capability.
+ * @arg @ref RCC_LSEDRIVE_MEDIUMLOW LSE oscillator medium low drive capability.
+ * @arg @ref RCC_LSEDRIVE_MEDIUMHIGH LSE oscillator medium high drive capability.
+ * @arg @ref RCC_LSEDRIVE_HIGH LSE oscillator high drive capability.
+ * @retval None
+ */
+#define __HAL_RCC_LSEDRIVE_CONFIG(__RCC_LSEDRIVE__) (MODIFY_REG(RCC->BDCR,\
+ RCC_BDCR_LSEDRV, (uint32_t)(__RCC_LSEDRIVE__) ))
+
+/**
+ * @}
+ */
+
+#if defined(CRS)
+
+/** @defgroup RCCEx_IT_And_Flag RCCEx IT and Flag
+ * @{
+ */
+/* Interrupt & Flag management */
+
+/**
+ * @brief Enable the specified CRS interrupts.
+ * @param __INTERRUPT__ specifies the CRS interrupt sources to be enabled.
+ * This parameter can be any combination of the following values:
+ * @arg @ref RCC_CRS_IT_SYNCOK SYNC event OK interrupt
+ * @arg @ref RCC_CRS_IT_SYNCWARN SYNC warning interrupt
+ * @arg @ref RCC_CRS_IT_ERR Synchronization or trimming error interrupt
+ * @arg @ref RCC_CRS_IT_ESYNC Expected SYNC interrupt
+ * @retval None
+ */
+#define __HAL_RCC_CRS_ENABLE_IT(__INTERRUPT__) SET_BIT(CRS->CR, (__INTERRUPT__))
+
+/**
+ * @brief Disable the specified CRS interrupts.
+ * @param __INTERRUPT__ specifies the CRS interrupt sources to be disabled.
+ * This parameter can be any combination of the following values:
+ * @arg @ref RCC_CRS_IT_SYNCOK SYNC event OK interrupt
+ * @arg @ref RCC_CRS_IT_SYNCWARN SYNC warning interrupt
+ * @arg @ref RCC_CRS_IT_ERR Synchronization or trimming error interrupt
+ * @arg @ref RCC_CRS_IT_ESYNC Expected SYNC interrupt
+ * @retval None
+ */
+#define __HAL_RCC_CRS_DISABLE_IT(__INTERRUPT__) CLEAR_BIT(CRS->CR, (__INTERRUPT__))
+
+/** @brief Check whether the CRS interrupt has occurred or not.
+ * @param __INTERRUPT__ specifies the CRS interrupt source to check.
+ * This parameter can be one of the following values:
+ * @arg @ref RCC_CRS_IT_SYNCOK SYNC event OK interrupt
+ * @arg @ref RCC_CRS_IT_SYNCWARN SYNC warning interrupt
+ * @arg @ref RCC_CRS_IT_ERR Synchronization or trimming error interrupt
+ * @arg @ref RCC_CRS_IT_ESYNC Expected SYNC interrupt
+ * @retval The new state of __INTERRUPT__ (SET or RESET).
+ */
+#define __HAL_RCC_CRS_GET_IT_SOURCE(__INTERRUPT__) ((READ_BIT(CRS->CR, (__INTERRUPT__)) != RESET) ? SET : RESET)
+
+/** @brief Clear the CRS interrupt pending bits
+ * @param __INTERRUPT__ specifies the interrupt pending bit to clear.
+ * This parameter can be any combination of the following values:
+ * @arg @ref RCC_CRS_IT_SYNCOK SYNC event OK interrupt
+ * @arg @ref RCC_CRS_IT_SYNCWARN SYNC warning interrupt
+ * @arg @ref RCC_CRS_IT_ERR Synchronization or trimming error interrupt
+ * @arg @ref RCC_CRS_IT_ESYNC Expected SYNC interrupt
+ * @arg @ref RCC_CRS_IT_TRIMOVF Trimming overflow or underflow interrupt
+ * @arg @ref RCC_CRS_IT_SYNCERR SYNC error interrupt
+ * @arg @ref RCC_CRS_IT_SYNCMISS SYNC missed interrupt
+ */
+#define __HAL_RCC_CRS_CLEAR_IT(__INTERRUPT__) do { \
+ if(((__INTERRUPT__) & RCC_CRS_IT_ERROR_MASK) != RESET) \
+ { \
+ WRITE_REG(CRS->ICR, CRS_ICR_ERRC | ((__INTERRUPT__) & ~RCC_CRS_IT_ERROR_MASK)); \
+ } \
+ else \
+ { \
+ WRITE_REG(CRS->ICR, (__INTERRUPT__)); \
+ } \
+ } while(0U)
+
+/**
+ * @brief Check whether the specified CRS flag is set or not.
+ * @param __FLAG__ specifies the flag to check.
+ * This parameter can be one of the following values:
+ * @arg @ref RCC_CRS_FLAG_SYNCOK SYNC event OK
+ * @arg @ref RCC_CRS_FLAG_SYNCWARN SYNC warning
+ * @arg @ref RCC_CRS_FLAG_ERR Error
+ * @arg @ref RCC_CRS_FLAG_ESYNC Expected SYNC
+ * @arg @ref RCC_CRS_FLAG_TRIMOVF Trimming overflow or underflow
+ * @arg @ref RCC_CRS_FLAG_SYNCERR SYNC error
+ * @arg @ref RCC_CRS_FLAG_SYNCMISS SYNC missed
+ * @retval The new state of _FLAG_ (TRUE or FALSE).
+ */
+#define __HAL_RCC_CRS_GET_FLAG(__FLAG__) (READ_BIT(CRS->ISR, (__FLAG__)) == (__FLAG__))
+
+/**
+ * @brief Clear the CRS specified FLAG.
+ * @param __FLAG__ specifies the flag to clear.
+ * This parameter can be one of the following values:
+ * @arg @ref RCC_CRS_FLAG_SYNCOK SYNC event OK
+ * @arg @ref RCC_CRS_FLAG_SYNCWARN SYNC warning
+ * @arg @ref RCC_CRS_FLAG_ERR Error
+ * @arg @ref RCC_CRS_FLAG_ESYNC Expected SYNC
+ * @arg @ref RCC_CRS_FLAG_TRIMOVF Trimming overflow or underflow
+ * @arg @ref RCC_CRS_FLAG_SYNCERR SYNC error
+ * @arg @ref RCC_CRS_FLAG_SYNCMISS SYNC missed
+ * @note RCC_CRS_FLAG_ERR clears RCC_CRS_FLAG_TRIMOVF, RCC_CRS_FLAG_SYNCERR, RCC_CRS_FLAG_SYNCMISS and consequently RCC_CRS_FLAG_ERR
+ * @retval None
+ */
+#define __HAL_RCC_CRS_CLEAR_FLAG(__FLAG__) do { \
+ if(((__FLAG__) & RCC_CRS_FLAG_ERROR_MASK) != RESET) \
+ { \
+ WRITE_REG(CRS->ICR, CRS_ICR_ERRC | ((__FLAG__) & ~RCC_CRS_FLAG_ERROR_MASK)); \
+ } \
+ else \
+ { \
+ WRITE_REG(CRS->ICR, (__FLAG__)); \
+ } \
+ } while(0U)
+
+/**
+ * @}
+ */
+
+/** @defgroup RCCEx_CRS_Extended_Features RCCEx CRS Extended Features
+ * @{
+ */
+/**
+ * @brief Enable the oscillator clock for frequency error counter.
+ * @note when the CEN bit is set the CRS_CFGR register becomes write-protected.
+ * @retval None
+ */
+#define __HAL_RCC_CRS_FREQ_ERROR_COUNTER_ENABLE() SET_BIT(CRS->CR, CRS_CR_CEN)
+
+/**
+ * @brief Disable the oscillator clock for frequency error counter.
+ * @retval None
+ */
+#define __HAL_RCC_CRS_FREQ_ERROR_COUNTER_DISABLE() CLEAR_BIT(CRS->CR, CRS_CR_CEN)
+
+/**
+ * @brief Enable the automatic hardware adjustment of TRIM bits.
+ * @note When the AUTOTRIMEN bit is set the CRS_CFGR register becomes write-protected.
+ * @retval None
+ */
+#define __HAL_RCC_CRS_AUTOMATIC_CALIB_ENABLE() SET_BIT(CRS->CR, CRS_CR_AUTOTRIMEN)
+
+/**
+ * @brief Disable the automatic hardware adjustment of TRIM bits.
+ * @retval None
+ */
+#define __HAL_RCC_CRS_AUTOMATIC_CALIB_DISABLE() CLEAR_BIT(CRS->CR, CRS_CR_AUTOTRIMEN)
+
+/**
+ * @brief Macro to calculate reload value to be set in CRS register according to target and sync frequencies
+ * @note The RELOAD value should be selected according to the ratio between the target frequency and the frequency
+ * of the synchronization source after prescaling. It is then decreased by one in order to
+ * reach the expected synchronization on the zero value. The formula is the following:
+ * RELOAD = (fTARGET / fSYNC) -1
+ * @param __FTARGET__ Target frequency (value in Hz)
+ * @param __FSYNC__ Synchronization signal frequency (value in Hz)
+ * @retval None
+ */
+#define __HAL_RCC_CRS_RELOADVALUE_CALCULATE(__FTARGET__, __FSYNC__) (((__FTARGET__) / (__FSYNC__)) - 1U)
+
+/**
+ * @}
+ */
+
+#endif /* CRS */
+
+/**
+ * @}
+ */
+
+/* Exported functions --------------------------------------------------------*/
+/** @addtogroup RCCEx_Exported_Functions
+ * @{
+ */
+
+/** @addtogroup RCCEx_Exported_Functions_Group1
+ * @{
+ */
+
+HAL_StatusTypeDef HAL_RCCEx_PeriphCLKConfig(RCC_PeriphCLKInitTypeDef *PeriphClkInit);
+void HAL_RCCEx_GetPeriphCLKConfig(RCC_PeriphCLKInitTypeDef *PeriphClkInit);
+uint32_t HAL_RCCEx_GetPeriphCLKFreq(uint32_t PeriphClk);
+
+/**
+ * @}
+ */
+
+#if defined(CRS)
+
+/** @addtogroup RCCEx_Exported_Functions_Group3
+ * @{
+ */
+
+void HAL_RCCEx_CRSConfig(RCC_CRSInitTypeDef *pInit);
+void HAL_RCCEx_CRSSoftwareSynchronizationGenerate(void);
+void HAL_RCCEx_CRSGetSynchronizationInfo(RCC_CRSSynchroInfoTypeDef *pSynchroInfo);
+uint32_t HAL_RCCEx_CRSWaitSynchronization(uint32_t Timeout);
+void HAL_RCCEx_CRS_IRQHandler(void);
+void HAL_RCCEx_CRS_SyncOkCallback(void);
+void HAL_RCCEx_CRS_SyncWarnCallback(void);
+void HAL_RCCEx_CRS_ExpectedSyncCallback(void);
+void HAL_RCCEx_CRS_ErrorCallback(uint32_t Error);
+
+/**
+ * @}
+ */
+
+#endif /* CRS */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __STM32F0xx_HAL_RCC_EX_H */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal_spi.h b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal_spi.h
new file mode 100644
index 0000000..8f494b8
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal_spi.h
@@ -0,0 +1,852 @@
+/**
+ ******************************************************************************
+ * @file stm32f0xx_hal_spi.h
+ * @author MCD Application Team
+ * @brief Header file of SPI HAL module.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2016 STMicroelectronics.
+ * All rights reserved.
+ *
+ * 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 STM32F0xx_HAL_SPI_H
+#define STM32F0xx_HAL_SPI_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f0xx_hal_def.h"
+
+/** @addtogroup STM32F0xx_HAL_Driver
+ * @{
+ */
+
+/** @addtogroup SPI
+ * @{
+ */
+
+/* Exported types ------------------------------------------------------------*/
+/** @defgroup SPI_Exported_Types SPI Exported Types
+ * @{
+ */
+
+/**
+ * @brief SPI Configuration Structure definition
+ */
+typedef struct
+{
+ uint32_t Mode; /*!< Specifies the SPI operating mode.
+ This parameter can be a value of @ref SPI_Mode */
+
+ uint32_t Direction; /*!< Specifies the SPI bidirectional mode state.
+ This parameter can be a value of @ref SPI_Direction */
+
+ uint32_t DataSize; /*!< Specifies the SPI data size.
+ This parameter can be a value of @ref SPI_Data_Size */
+
+ uint32_t CLKPolarity; /*!< Specifies the serial clock steady state.
+ This parameter can be a value of @ref SPI_Clock_Polarity */
+
+ uint32_t CLKPhase; /*!< Specifies the clock active edge for the bit capture.
+ This parameter can be a value of @ref SPI_Clock_Phase */
+
+ uint32_t NSS; /*!< Specifies whether the NSS signal is managed by
+ hardware (NSS pin) or by software using the SSI bit.
+ This parameter can be a value of @ref SPI_Slave_Select_management */
+
+ uint32_t BaudRatePrescaler; /*!< Specifies the Baud Rate prescaler value which will be
+ used to configure the transmit and receive SCK clock.
+ This parameter can be a value of @ref SPI_BaudRate_Prescaler
+ @note The communication clock is derived from the master
+ clock. The slave clock does not need to be set. */
+
+ uint32_t FirstBit; /*!< Specifies whether data transfers start from MSB or LSB bit.
+ This parameter can be a value of @ref SPI_MSB_LSB_transmission */
+
+ uint32_t TIMode; /*!< Specifies if the TI mode is enabled or not.
+ This parameter can be a value of @ref SPI_TI_mode */
+
+ uint32_t CRCCalculation; /*!< Specifies if the CRC calculation is enabled or not.
+ This parameter can be a value of @ref SPI_CRC_Calculation */
+
+ uint32_t CRCPolynomial; /*!< Specifies the polynomial used for the CRC calculation.
+ This parameter must be an odd number between Min_Data = 1 and Max_Data = 65535 */
+
+ uint32_t CRCLength; /*!< Specifies the CRC Length used for the CRC calculation.
+ CRC Length is only used with Data8 and Data16, not other data size
+ This parameter can be a value of @ref SPI_CRC_length */
+
+ uint32_t NSSPMode; /*!< Specifies whether the NSSP signal is enabled or not .
+ This parameter can be a value of @ref SPI_NSSP_Mode
+ This mode is activated by the NSSP bit in the SPIx_CR2 register and
+ it takes effect only if the SPI interface is configured as Motorola SPI
+ master (FRF=0) with capture on the first edge (SPIx_CR1 CPHA = 0,
+ CPOL setting is ignored).. */
+} SPI_InitTypeDef;
+
+/**
+ * @brief HAL SPI State structure definition
+ */
+typedef enum
+{
+ HAL_SPI_STATE_RESET = 0x00U, /*!< Peripheral not Initialized */
+ HAL_SPI_STATE_READY = 0x01U, /*!< Peripheral Initialized and ready for use */
+ HAL_SPI_STATE_BUSY = 0x02U, /*!< an internal process is ongoing */
+ HAL_SPI_STATE_BUSY_TX = 0x03U, /*!< Data Transmission process is ongoing */
+ HAL_SPI_STATE_BUSY_RX = 0x04U, /*!< Data Reception process is ongoing */
+ HAL_SPI_STATE_BUSY_TX_RX = 0x05U, /*!< Data Transmission and Reception process is ongoing */
+ HAL_SPI_STATE_ERROR = 0x06U, /*!< SPI error state */
+ HAL_SPI_STATE_ABORT = 0x07U /*!< SPI abort is ongoing */
+} HAL_SPI_StateTypeDef;
+
+/**
+ * @brief SPI handle Structure definition
+ */
+typedef struct __SPI_HandleTypeDef
+{
+ SPI_TypeDef *Instance; /*!< SPI registers base address */
+
+ SPI_InitTypeDef Init; /*!< SPI communication parameters */
+
+ uint8_t *pTxBuffPtr; /*!< Pointer to SPI Tx transfer Buffer */
+
+ uint16_t TxXferSize; /*!< SPI Tx Transfer size */
+
+ __IO uint16_t TxXferCount; /*!< SPI Tx Transfer Counter */
+
+ uint8_t *pRxBuffPtr; /*!< Pointer to SPI Rx transfer Buffer */
+
+ uint16_t RxXferSize; /*!< SPI Rx Transfer size */
+
+ __IO uint16_t RxXferCount; /*!< SPI Rx Transfer Counter */
+
+ uint32_t CRCSize; /*!< SPI CRC size used for the transfer */
+
+ void (*RxISR)(struct __SPI_HandleTypeDef *hspi); /*!< function pointer on Rx ISR */
+
+ void (*TxISR)(struct __SPI_HandleTypeDef *hspi); /*!< function pointer on Tx ISR */
+
+ DMA_HandleTypeDef *hdmatx; /*!< SPI Tx DMA Handle parameters */
+
+ DMA_HandleTypeDef *hdmarx; /*!< SPI Rx DMA Handle parameters */
+
+ HAL_LockTypeDef Lock; /*!< Locking object */
+
+ __IO HAL_SPI_StateTypeDef State; /*!< SPI communication state */
+
+ __IO uint32_t ErrorCode; /*!< SPI Error code */
+
+#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U)
+ void (* TxCpltCallback)(struct __SPI_HandleTypeDef *hspi); /*!< SPI Tx Completed callback */
+ void (* RxCpltCallback)(struct __SPI_HandleTypeDef *hspi); /*!< SPI Rx Completed callback */
+ void (* TxRxCpltCallback)(struct __SPI_HandleTypeDef *hspi); /*!< SPI TxRx Completed callback */
+ void (* TxHalfCpltCallback)(struct __SPI_HandleTypeDef *hspi); /*!< SPI Tx Half Completed callback */
+ void (* RxHalfCpltCallback)(struct __SPI_HandleTypeDef *hspi); /*!< SPI Rx Half Completed callback */
+ void (* TxRxHalfCpltCallback)(struct __SPI_HandleTypeDef *hspi); /*!< SPI TxRx Half Completed callback */
+ void (* ErrorCallback)(struct __SPI_HandleTypeDef *hspi); /*!< SPI Error callback */
+ void (* AbortCpltCallback)(struct __SPI_HandleTypeDef *hspi); /*!< SPI Abort callback */
+ void (* MspInitCallback)(struct __SPI_HandleTypeDef *hspi); /*!< SPI Msp Init callback */
+ void (* MspDeInitCallback)(struct __SPI_HandleTypeDef *hspi); /*!< SPI Msp DeInit callback */
+
+#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */
+} SPI_HandleTypeDef;
+
+#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U)
+/**
+ * @brief HAL SPI Callback ID enumeration definition
+ */
+typedef enum
+{
+ HAL_SPI_TX_COMPLETE_CB_ID = 0x00U, /*!< SPI Tx Completed callback ID */
+ HAL_SPI_RX_COMPLETE_CB_ID = 0x01U, /*!< SPI Rx Completed callback ID */
+ HAL_SPI_TX_RX_COMPLETE_CB_ID = 0x02U, /*!< SPI TxRx Completed callback ID */
+ HAL_SPI_TX_HALF_COMPLETE_CB_ID = 0x03U, /*!< SPI Tx Half Completed callback ID */
+ HAL_SPI_RX_HALF_COMPLETE_CB_ID = 0x04U, /*!< SPI Rx Half Completed callback ID */
+ HAL_SPI_TX_RX_HALF_COMPLETE_CB_ID = 0x05U, /*!< SPI TxRx Half Completed callback ID */
+ HAL_SPI_ERROR_CB_ID = 0x06U, /*!< SPI Error callback ID */
+ HAL_SPI_ABORT_CB_ID = 0x07U, /*!< SPI Abort callback ID */
+ HAL_SPI_MSPINIT_CB_ID = 0x08U, /*!< SPI Msp Init callback ID */
+ HAL_SPI_MSPDEINIT_CB_ID = 0x09U /*!< SPI Msp DeInit callback ID */
+
+} HAL_SPI_CallbackIDTypeDef;
+
+/**
+ * @brief HAL SPI Callback pointer definition
+ */
+typedef void (*pSPI_CallbackTypeDef)(SPI_HandleTypeDef *hspi); /*!< pointer to an SPI callback function */
+
+#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */
+/**
+ * @}
+ */
+
+/* Exported constants --------------------------------------------------------*/
+/** @defgroup SPI_Exported_Constants SPI Exported Constants
+ * @{
+ */
+
+/** @defgroup SPI_Error_Code SPI Error Code
+ * @{
+ */
+#define HAL_SPI_ERROR_NONE (0x00000000U) /*!< No error */
+#define HAL_SPI_ERROR_MODF (0x00000001U) /*!< MODF error */
+#define HAL_SPI_ERROR_CRC (0x00000002U) /*!< CRC error */
+#define HAL_SPI_ERROR_OVR (0x00000004U) /*!< OVR error */
+#define HAL_SPI_ERROR_FRE (0x00000008U) /*!< FRE error */
+#define HAL_SPI_ERROR_DMA (0x00000010U) /*!< DMA transfer error */
+#define HAL_SPI_ERROR_FLAG (0x00000020U) /*!< Error on RXNE/TXE/BSY/FTLVL/FRLVL Flag */
+#define HAL_SPI_ERROR_ABORT (0x00000040U) /*!< Error during SPI Abort procedure */
+#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U)
+#define HAL_SPI_ERROR_INVALID_CALLBACK (0x00000080U) /*!< Invalid Callback error */
+#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */
+/**
+ * @}
+ */
+
+/** @defgroup SPI_Mode SPI Mode
+ * @{
+ */
+#define SPI_MODE_SLAVE (0x00000000U)
+#define SPI_MODE_MASTER (SPI_CR1_MSTR | SPI_CR1_SSI)
+/**
+ * @}
+ */
+
+/** @defgroup SPI_Direction SPI Direction Mode
+ * @{
+ */
+#define SPI_DIRECTION_2LINES (0x00000000U)
+#define SPI_DIRECTION_2LINES_RXONLY SPI_CR1_RXONLY
+#define SPI_DIRECTION_1LINE SPI_CR1_BIDIMODE
+/**
+ * @}
+ */
+
+/** @defgroup SPI_Data_Size SPI Data Size
+ * @{
+ */
+#define SPI_DATASIZE_4BIT (0x00000300U)
+#define SPI_DATASIZE_5BIT (0x00000400U)
+#define SPI_DATASIZE_6BIT (0x00000500U)
+#define SPI_DATASIZE_7BIT (0x00000600U)
+#define SPI_DATASIZE_8BIT (0x00000700U)
+#define SPI_DATASIZE_9BIT (0x00000800U)
+#define SPI_DATASIZE_10BIT (0x00000900U)
+#define SPI_DATASIZE_11BIT (0x00000A00U)
+#define SPI_DATASIZE_12BIT (0x00000B00U)
+#define SPI_DATASIZE_13BIT (0x00000C00U)
+#define SPI_DATASIZE_14BIT (0x00000D00U)
+#define SPI_DATASIZE_15BIT (0x00000E00U)
+#define SPI_DATASIZE_16BIT (0x00000F00U)
+/**
+ * @}
+ */
+
+/** @defgroup SPI_Clock_Polarity SPI Clock Polarity
+ * @{
+ */
+#define SPI_POLARITY_LOW (0x00000000U)
+#define SPI_POLARITY_HIGH SPI_CR1_CPOL
+/**
+ * @}
+ */
+
+/** @defgroup SPI_Clock_Phase SPI Clock Phase
+ * @{
+ */
+#define SPI_PHASE_1EDGE (0x00000000U)
+#define SPI_PHASE_2EDGE SPI_CR1_CPHA
+/**
+ * @}
+ */
+
+/** @defgroup SPI_Slave_Select_management SPI Slave Select Management
+ * @{
+ */
+#define SPI_NSS_SOFT SPI_CR1_SSM
+#define SPI_NSS_HARD_INPUT (0x00000000U)
+#define SPI_NSS_HARD_OUTPUT (SPI_CR2_SSOE << 16U)
+/**
+ * @}
+ */
+
+/** @defgroup SPI_NSSP_Mode SPI NSS Pulse Mode
+ * @{
+ */
+#define SPI_NSS_PULSE_ENABLE SPI_CR2_NSSP
+#define SPI_NSS_PULSE_DISABLE (0x00000000U)
+/**
+ * @}
+ */
+
+/** @defgroup SPI_BaudRate_Prescaler SPI BaudRate Prescaler
+ * @{
+ */
+#define SPI_BAUDRATEPRESCALER_2 (0x00000000U)
+#define SPI_BAUDRATEPRESCALER_4 (SPI_CR1_BR_0)
+#define SPI_BAUDRATEPRESCALER_8 (SPI_CR1_BR_1)
+#define SPI_BAUDRATEPRESCALER_16 (SPI_CR1_BR_1 | SPI_CR1_BR_0)
+#define SPI_BAUDRATEPRESCALER_32 (SPI_CR1_BR_2)
+#define SPI_BAUDRATEPRESCALER_64 (SPI_CR1_BR_2 | SPI_CR1_BR_0)
+#define SPI_BAUDRATEPRESCALER_128 (SPI_CR1_BR_2 | SPI_CR1_BR_1)
+#define SPI_BAUDRATEPRESCALER_256 (SPI_CR1_BR_2 | SPI_CR1_BR_1 | SPI_CR1_BR_0)
+/**
+ * @}
+ */
+
+/** @defgroup SPI_MSB_LSB_transmission SPI MSB LSB Transmission
+ * @{
+ */
+#define SPI_FIRSTBIT_MSB (0x00000000U)
+#define SPI_FIRSTBIT_LSB SPI_CR1_LSBFIRST
+/**
+ * @}
+ */
+
+/** @defgroup SPI_TI_mode SPI TI Mode
+ * @{
+ */
+#define SPI_TIMODE_DISABLE (0x00000000U)
+#define SPI_TIMODE_ENABLE SPI_CR2_FRF
+/**
+ * @}
+ */
+
+/** @defgroup SPI_CRC_Calculation SPI CRC Calculation
+ * @{
+ */
+#define SPI_CRCCALCULATION_DISABLE (0x00000000U)
+#define SPI_CRCCALCULATION_ENABLE SPI_CR1_CRCEN
+/**
+ * @}
+ */
+
+/** @defgroup SPI_CRC_length SPI CRC Length
+ * @{
+ * This parameter can be one of the following values:
+ * SPI_CRC_LENGTH_DATASIZE: aligned with the data size
+ * SPI_CRC_LENGTH_8BIT : CRC 8bit
+ * SPI_CRC_LENGTH_16BIT : CRC 16bit
+ */
+#define SPI_CRC_LENGTH_DATASIZE (0x00000000U)
+#define SPI_CRC_LENGTH_8BIT (0x00000001U)
+#define SPI_CRC_LENGTH_16BIT (0x00000002U)
+/**
+ * @}
+ */
+
+/** @defgroup SPI_FIFO_reception_threshold SPI FIFO Reception Threshold
+ * @{
+ * This parameter can be one of the following values:
+ * SPI_RXFIFO_THRESHOLD or SPI_RXFIFO_THRESHOLD_QF :
+ * RXNE event is generated if the FIFO
+ * level is greater or equal to 1/4(8-bits).
+ * SPI_RXFIFO_THRESHOLD_HF: RXNE event is generated if the FIFO
+ * level is greater or equal to 1/2(16 bits). */
+#define SPI_RXFIFO_THRESHOLD SPI_CR2_FRXTH
+#define SPI_RXFIFO_THRESHOLD_QF SPI_CR2_FRXTH
+#define SPI_RXFIFO_THRESHOLD_HF (0x00000000U)
+/**
+ * @}
+ */
+
+/** @defgroup SPI_Interrupt_definition SPI Interrupt Definition
+ * @{
+ */
+#define SPI_IT_TXE SPI_CR2_TXEIE
+#define SPI_IT_RXNE SPI_CR2_RXNEIE
+#define SPI_IT_ERR SPI_CR2_ERRIE
+/**
+ * @}
+ */
+
+/** @defgroup SPI_Flags_definition SPI Flags Definition
+ * @{
+ */
+#define SPI_FLAG_RXNE SPI_SR_RXNE /* SPI status flag: Rx buffer not empty flag */
+#define SPI_FLAG_TXE SPI_SR_TXE /* SPI status flag: Tx buffer empty flag */
+#define SPI_FLAG_BSY SPI_SR_BSY /* SPI status flag: Busy flag */
+#define SPI_FLAG_CRCERR SPI_SR_CRCERR /* SPI Error flag: CRC error flag */
+#define SPI_FLAG_MODF SPI_SR_MODF /* SPI Error flag: Mode fault flag */
+#define SPI_FLAG_OVR SPI_SR_OVR /* SPI Error flag: Overrun flag */
+#define SPI_FLAG_FRE SPI_SR_FRE /* SPI Error flag: TI mode frame format error flag */
+#define SPI_FLAG_FTLVL SPI_SR_FTLVL /* SPI fifo transmission level */
+#define SPI_FLAG_FRLVL SPI_SR_FRLVL /* SPI fifo reception level */
+#define SPI_FLAG_MASK (SPI_SR_RXNE | SPI_SR_TXE | SPI_SR_BSY | SPI_SR_CRCERR\
+ | SPI_SR_MODF | SPI_SR_OVR | SPI_SR_FRE | SPI_SR_FTLVL | SPI_SR_FRLVL)
+/**
+ * @}
+ */
+
+/** @defgroup SPI_transmission_fifo_status_level SPI Transmission FIFO Status Level
+ * @{
+ */
+#define SPI_FTLVL_EMPTY (0x00000000U)
+#define SPI_FTLVL_QUARTER_FULL (0x00000800U)
+#define SPI_FTLVL_HALF_FULL (0x00001000U)
+#define SPI_FTLVL_FULL (0x00001800U)
+
+/**
+ * @}
+ */
+
+/** @defgroup SPI_reception_fifo_status_level SPI Reception FIFO Status Level
+ * @{
+ */
+#define SPI_FRLVL_EMPTY (0x00000000U)
+#define SPI_FRLVL_QUARTER_FULL (0x00000200U)
+#define SPI_FRLVL_HALF_FULL (0x00000400U)
+#define SPI_FRLVL_FULL (0x00000600U)
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/* Exported macros -----------------------------------------------------------*/
+/** @defgroup SPI_Exported_Macros SPI Exported Macros
+ * @{
+ */
+
+/** @brief Reset SPI handle state.
+ * @param __HANDLE__ specifies the SPI Handle.
+ * This parameter can be SPI where x: 1, 2, or 3 to select the SPI peripheral.
+ * @retval None
+ */
+#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U)
+#define __HAL_SPI_RESET_HANDLE_STATE(__HANDLE__) do{ \
+ (__HANDLE__)->State = HAL_SPI_STATE_RESET; \
+ (__HANDLE__)->MspInitCallback = NULL; \
+ (__HANDLE__)->MspDeInitCallback = NULL; \
+ } while(0)
+#else
+#define __HAL_SPI_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_SPI_STATE_RESET)
+#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */
+
+/** @brief Enable the specified SPI interrupts.
+ * @param __HANDLE__ specifies the SPI Handle.
+ * This parameter can be SPI where x: 1, 2, or 3 to select the SPI peripheral.
+ * @param __INTERRUPT__ specifies the interrupt source to enable.
+ * This parameter can be one of the following values:
+ * @arg SPI_IT_TXE: Tx buffer empty interrupt enable
+ * @arg SPI_IT_RXNE: RX buffer not empty interrupt enable
+ * @arg SPI_IT_ERR: Error interrupt enable
+ * @retval None
+ */
+#define __HAL_SPI_ENABLE_IT(__HANDLE__, __INTERRUPT__) SET_BIT((__HANDLE__)->Instance->CR2, (__INTERRUPT__))
+
+/** @brief Disable the specified SPI interrupts.
+ * @param __HANDLE__ specifies the SPI handle.
+ * This parameter can be SPIx where x: 1, 2, or 3 to select the SPI peripheral.
+ * @param __INTERRUPT__ specifies the interrupt source to disable.
+ * This parameter can be one of the following values:
+ * @arg SPI_IT_TXE: Tx buffer empty interrupt enable
+ * @arg SPI_IT_RXNE: RX buffer not empty interrupt enable
+ * @arg SPI_IT_ERR: Error interrupt enable
+ * @retval None
+ */
+#define __HAL_SPI_DISABLE_IT(__HANDLE__, __INTERRUPT__) CLEAR_BIT((__HANDLE__)->Instance->CR2, (__INTERRUPT__))
+
+/** @brief Check whether the specified SPI interrupt source is enabled or not.
+ * @param __HANDLE__ specifies the SPI Handle.
+ * This parameter can be SPI where x: 1, 2, or 3 to select the SPI peripheral.
+ * @param __INTERRUPT__ specifies the SPI interrupt source to check.
+ * This parameter can be one of the following values:
+ * @arg SPI_IT_TXE: Tx buffer empty interrupt enable
+ * @arg SPI_IT_RXNE: RX buffer not empty interrupt enable
+ * @arg SPI_IT_ERR: Error interrupt enable
+ * @retval The new state of __IT__ (TRUE or FALSE).
+ */
+#define __HAL_SPI_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) ((((__HANDLE__)->Instance->CR2\
+ & (__INTERRUPT__)) == (__INTERRUPT__)) ? SET : RESET)
+
+/** @brief Check whether the specified SPI flag is set or not.
+ * @param __HANDLE__ specifies the SPI Handle.
+ * This parameter can be SPI where x: 1, 2, or 3 to select the SPI peripheral.
+ * @param __FLAG__ specifies the flag to check.
+ * This parameter can be one of the following values:
+ * @arg SPI_FLAG_RXNE: Receive buffer not empty flag
+ * @arg SPI_FLAG_TXE: Transmit buffer empty flag
+ * @arg SPI_FLAG_CRCERR: CRC error flag
+ * @arg SPI_FLAG_MODF: Mode fault flag
+ * @arg SPI_FLAG_OVR: Overrun flag
+ * @arg SPI_FLAG_BSY: Busy flag
+ * @arg SPI_FLAG_FRE: Frame format error flag
+ * @arg SPI_FLAG_FTLVL: SPI fifo transmission level
+ * @arg SPI_FLAG_FRLVL: SPI fifo reception level
+ * @retval The new state of __FLAG__ (TRUE or FALSE).
+ */
+#define __HAL_SPI_GET_FLAG(__HANDLE__, __FLAG__) ((((__HANDLE__)->Instance->SR) & (__FLAG__)) == (__FLAG__))
+
+/** @brief Clear the SPI CRCERR pending flag.
+ * @param __HANDLE__ specifies the SPI Handle.
+ * This parameter can be SPI where x: 1, 2, or 3 to select the SPI peripheral.
+ * @retval None
+ */
+#define __HAL_SPI_CLEAR_CRCERRFLAG(__HANDLE__) ((__HANDLE__)->Instance->SR = (uint16_t)(~SPI_FLAG_CRCERR))
+
+/** @brief Clear the SPI MODF pending flag.
+ * @param __HANDLE__ specifies the SPI Handle.
+ * This parameter can be SPI where x: 1, 2, or 3 to select the SPI peripheral.
+ * @retval None
+ */
+#define __HAL_SPI_CLEAR_MODFFLAG(__HANDLE__) \
+ do{ \
+ __IO uint32_t tmpreg_modf = 0x00U; \
+ tmpreg_modf = (__HANDLE__)->Instance->SR; \
+ CLEAR_BIT((__HANDLE__)->Instance->CR1, SPI_CR1_SPE); \
+ UNUSED(tmpreg_modf); \
+ } while(0U)
+
+/** @brief Clear the SPI OVR pending flag.
+ * @param __HANDLE__ specifies the SPI Handle.
+ * This parameter can be SPI where x: 1, 2, or 3 to select the SPI peripheral.
+ * @retval None
+ */
+#define __HAL_SPI_CLEAR_OVRFLAG(__HANDLE__) \
+ do{ \
+ __IO uint32_t tmpreg_ovr = 0x00U; \
+ tmpreg_ovr = (__HANDLE__)->Instance->DR; \
+ tmpreg_ovr = (__HANDLE__)->Instance->SR; \
+ UNUSED(tmpreg_ovr); \
+ } while(0U)
+
+/** @brief Clear the SPI FRE pending flag.
+ * @param __HANDLE__ specifies the SPI Handle.
+ * This parameter can be SPI where x: 1, 2, or 3 to select the SPI peripheral.
+ * @retval None
+ */
+#define __HAL_SPI_CLEAR_FREFLAG(__HANDLE__) \
+ do{ \
+ __IO uint32_t tmpreg_fre = 0x00U; \
+ tmpreg_fre = (__HANDLE__)->Instance->SR; \
+ UNUSED(tmpreg_fre); \
+ }while(0U)
+
+/** @brief Enable the SPI peripheral.
+ * @param __HANDLE__ specifies the SPI Handle.
+ * This parameter can be SPI where x: 1, 2, or 3 to select the SPI peripheral.
+ * @retval None
+ */
+#define __HAL_SPI_ENABLE(__HANDLE__) SET_BIT((__HANDLE__)->Instance->CR1, SPI_CR1_SPE)
+
+/** @brief Disable the SPI peripheral.
+ * @param __HANDLE__ specifies the SPI Handle.
+ * This parameter can be SPI where x: 1, 2, or 3 to select the SPI peripheral.
+ * @retval None
+ */
+#define __HAL_SPI_DISABLE(__HANDLE__) CLEAR_BIT((__HANDLE__)->Instance->CR1, SPI_CR1_SPE)
+
+/**
+ * @}
+ */
+
+/* Private macros ------------------------------------------------------------*/
+/** @defgroup SPI_Private_Macros SPI Private Macros
+ * @{
+ */
+
+/** @brief Set the SPI transmit-only mode.
+ * @param __HANDLE__ specifies the SPI Handle.
+ * This parameter can be SPI where x: 1, 2, or 3 to select the SPI peripheral.
+ * @retval None
+ */
+#define SPI_1LINE_TX(__HANDLE__) SET_BIT((__HANDLE__)->Instance->CR1, SPI_CR1_BIDIOE)
+
+/** @brief Set the SPI receive-only mode.
+ * @param __HANDLE__ specifies the SPI Handle.
+ * This parameter can be SPI where x: 1, 2, or 3 to select the SPI peripheral.
+ * @retval None
+ */
+#define SPI_1LINE_RX(__HANDLE__) CLEAR_BIT((__HANDLE__)->Instance->CR1, SPI_CR1_BIDIOE)
+
+/** @brief Reset the CRC calculation of the SPI.
+ * @param __HANDLE__ specifies the SPI Handle.
+ * This parameter can be SPI where x: 1, 2, or 3 to select the SPI peripheral.
+ * @retval None
+ */
+#define SPI_RESET_CRC(__HANDLE__) do{CLEAR_BIT((__HANDLE__)->Instance->CR1, SPI_CR1_CRCEN);\
+ SET_BIT((__HANDLE__)->Instance->CR1, SPI_CR1_CRCEN);}while(0U)
+
+/** @brief Check whether the specified SPI flag is set or not.
+ * @param __SR__ copy of SPI SR register.
+ * @param __FLAG__ specifies the flag to check.
+ * This parameter can be one of the following values:
+ * @arg SPI_FLAG_RXNE: Receive buffer not empty flag
+ * @arg SPI_FLAG_TXE: Transmit buffer empty flag
+ * @arg SPI_FLAG_CRCERR: CRC error flag
+ * @arg SPI_FLAG_MODF: Mode fault flag
+ * @arg SPI_FLAG_OVR: Overrun flag
+ * @arg SPI_FLAG_BSY: Busy flag
+ * @arg SPI_FLAG_FRE: Frame format error flag
+ * @arg SPI_FLAG_FTLVL: SPI fifo transmission level
+ * @arg SPI_FLAG_FRLVL: SPI fifo reception level
+ * @retval SET or RESET.
+ */
+#define SPI_CHECK_FLAG(__SR__, __FLAG__) ((((__SR__) & ((__FLAG__) & SPI_FLAG_MASK)) == \
+ ((__FLAG__) & SPI_FLAG_MASK)) ? SET : RESET)
+
+/** @brief Check whether the specified SPI Interrupt is set or not.
+ * @param __CR2__ copy of SPI CR2 register.
+ * @param __INTERRUPT__ specifies the SPI interrupt source to check.
+ * This parameter can be one of the following values:
+ * @arg SPI_IT_TXE: Tx buffer empty interrupt enable
+ * @arg SPI_IT_RXNE: RX buffer not empty interrupt enable
+ * @arg SPI_IT_ERR: Error interrupt enable
+ * @retval SET or RESET.
+ */
+#define SPI_CHECK_IT_SOURCE(__CR2__, __INTERRUPT__) ((((__CR2__) & (__INTERRUPT__)) == \
+ (__INTERRUPT__)) ? SET : RESET)
+
+/** @brief Checks if SPI Mode parameter is in allowed range.
+ * @param __MODE__ specifies the SPI Mode.
+ * This parameter can be a value of @ref SPI_Mode
+ * @retval None
+ */
+#define IS_SPI_MODE(__MODE__) (((__MODE__) == SPI_MODE_SLAVE) || \
+ ((__MODE__) == SPI_MODE_MASTER))
+
+/** @brief Checks if SPI Direction Mode parameter is in allowed range.
+ * @param __MODE__ specifies the SPI Direction Mode.
+ * This parameter can be a value of @ref SPI_Direction
+ * @retval None
+ */
+#define IS_SPI_DIRECTION(__MODE__) (((__MODE__) == SPI_DIRECTION_2LINES) || \
+ ((__MODE__) == SPI_DIRECTION_2LINES_RXONLY) || \
+ ((__MODE__) == SPI_DIRECTION_1LINE))
+
+/** @brief Checks if SPI Direction Mode parameter is 2 lines.
+ * @param __MODE__ specifies the SPI Direction Mode.
+ * @retval None
+ */
+#define IS_SPI_DIRECTION_2LINES(__MODE__) ((__MODE__) == SPI_DIRECTION_2LINES)
+
+/** @brief Checks if SPI Direction Mode parameter is 1 or 2 lines.
+ * @param __MODE__ specifies the SPI Direction Mode.
+ * @retval None
+ */
+#define IS_SPI_DIRECTION_2LINES_OR_1LINE(__MODE__) (((__MODE__) == SPI_DIRECTION_2LINES) || \
+ ((__MODE__) == SPI_DIRECTION_1LINE))
+
+/** @brief Checks if SPI Data Size parameter is in allowed range.
+ * @param __DATASIZE__ specifies the SPI Data Size.
+ * This parameter can be a value of @ref SPI_Data_Size
+ * @retval None
+ */
+#define IS_SPI_DATASIZE(__DATASIZE__) (((__DATASIZE__) == SPI_DATASIZE_16BIT) || \
+ ((__DATASIZE__) == SPI_DATASIZE_15BIT) || \
+ ((__DATASIZE__) == SPI_DATASIZE_14BIT) || \
+ ((__DATASIZE__) == SPI_DATASIZE_13BIT) || \
+ ((__DATASIZE__) == SPI_DATASIZE_12BIT) || \
+ ((__DATASIZE__) == SPI_DATASIZE_11BIT) || \
+ ((__DATASIZE__) == SPI_DATASIZE_10BIT) || \
+ ((__DATASIZE__) == SPI_DATASIZE_9BIT) || \
+ ((__DATASIZE__) == SPI_DATASIZE_8BIT) || \
+ ((__DATASIZE__) == SPI_DATASIZE_7BIT) || \
+ ((__DATASIZE__) == SPI_DATASIZE_6BIT) || \
+ ((__DATASIZE__) == SPI_DATASIZE_5BIT) || \
+ ((__DATASIZE__) == SPI_DATASIZE_4BIT))
+
+/** @brief Checks if SPI Serial clock steady state parameter is in allowed range.
+ * @param __CPOL__ specifies the SPI serial clock steady state.
+ * This parameter can be a value of @ref SPI_Clock_Polarity
+ * @retval None
+ */
+#define IS_SPI_CPOL(__CPOL__) (((__CPOL__) == SPI_POLARITY_LOW) || \
+ ((__CPOL__) == SPI_POLARITY_HIGH))
+
+/** @brief Checks if SPI Clock Phase parameter is in allowed range.
+ * @param __CPHA__ specifies the SPI Clock Phase.
+ * This parameter can be a value of @ref SPI_Clock_Phase
+ * @retval None
+ */
+#define IS_SPI_CPHA(__CPHA__) (((__CPHA__) == SPI_PHASE_1EDGE) || \
+ ((__CPHA__) == SPI_PHASE_2EDGE))
+
+/** @brief Checks if SPI Slave Select parameter is in allowed range.
+ * @param __NSS__ specifies the SPI Slave Select management parameter.
+ * This parameter can be a value of @ref SPI_Slave_Select_management
+ * @retval None
+ */
+#define IS_SPI_NSS(__NSS__) (((__NSS__) == SPI_NSS_SOFT) || \
+ ((__NSS__) == SPI_NSS_HARD_INPUT) || \
+ ((__NSS__) == SPI_NSS_HARD_OUTPUT))
+
+/** @brief Checks if SPI NSS Pulse parameter is in allowed range.
+ * @param __NSSP__ specifies the SPI NSS Pulse Mode parameter.
+ * This parameter can be a value of @ref SPI_NSSP_Mode
+ * @retval None
+ */
+#define IS_SPI_NSSP(__NSSP__) (((__NSSP__) == SPI_NSS_PULSE_ENABLE) || \
+ ((__NSSP__) == SPI_NSS_PULSE_DISABLE))
+
+/** @brief Checks if SPI Baudrate prescaler parameter is in allowed range.
+ * @param __PRESCALER__ specifies the SPI Baudrate prescaler.
+ * This parameter can be a value of @ref SPI_BaudRate_Prescaler
+ * @retval None
+ */
+#define IS_SPI_BAUDRATE_PRESCALER(__PRESCALER__) (((__PRESCALER__) == SPI_BAUDRATEPRESCALER_2) || \
+ ((__PRESCALER__) == SPI_BAUDRATEPRESCALER_4) || \
+ ((__PRESCALER__) == SPI_BAUDRATEPRESCALER_8) || \
+ ((__PRESCALER__) == SPI_BAUDRATEPRESCALER_16) || \
+ ((__PRESCALER__) == SPI_BAUDRATEPRESCALER_32) || \
+ ((__PRESCALER__) == SPI_BAUDRATEPRESCALER_64) || \
+ ((__PRESCALER__) == SPI_BAUDRATEPRESCALER_128) || \
+ ((__PRESCALER__) == SPI_BAUDRATEPRESCALER_256))
+
+/** @brief Checks if SPI MSB LSB transmission parameter is in allowed range.
+ * @param __BIT__ specifies the SPI MSB LSB transmission (whether data transfer starts from MSB or LSB bit).
+ * This parameter can be a value of @ref SPI_MSB_LSB_transmission
+ * @retval None
+ */
+#define IS_SPI_FIRST_BIT(__BIT__) (((__BIT__) == SPI_FIRSTBIT_MSB) || \
+ ((__BIT__) == SPI_FIRSTBIT_LSB))
+
+/** @brief Checks if SPI TI mode parameter is in allowed range.
+ * @param __MODE__ specifies the SPI TI mode.
+ * This parameter can be a value of @ref SPI_TI_mode
+ * @retval None
+ */
+#define IS_SPI_TIMODE(__MODE__) (((__MODE__) == SPI_TIMODE_DISABLE) || \
+ ((__MODE__) == SPI_TIMODE_ENABLE))
+
+/** @brief Checks if SPI CRC calculation enabled state is in allowed range.
+ * @param __CALCULATION__ specifies the SPI CRC calculation enable state.
+ * This parameter can be a value of @ref SPI_CRC_Calculation
+ * @retval None
+ */
+#define IS_SPI_CRC_CALCULATION(__CALCULATION__) (((__CALCULATION__) == SPI_CRCCALCULATION_DISABLE) || \
+ ((__CALCULATION__) == SPI_CRCCALCULATION_ENABLE))
+
+/** @brief Checks if SPI CRC length is in allowed range.
+ * @param __LENGTH__ specifies the SPI CRC length.
+ * This parameter can be a value of @ref SPI_CRC_length
+ * @retval None
+ */
+#define IS_SPI_CRC_LENGTH(__LENGTH__) (((__LENGTH__) == SPI_CRC_LENGTH_DATASIZE) || \
+ ((__LENGTH__) == SPI_CRC_LENGTH_8BIT) || \
+ ((__LENGTH__) == SPI_CRC_LENGTH_16BIT))
+
+/** @brief Checks if SPI polynomial value to be used for the CRC calculation, is in allowed range.
+ * @param __POLYNOMIAL__ specifies the SPI polynomial value to be used for the CRC calculation.
+ * This parameter must be a number between Min_Data = 0 and Max_Data = 65535
+ * @retval None
+ */
+#define IS_SPI_CRC_POLYNOMIAL(__POLYNOMIAL__) (((__POLYNOMIAL__) >= 0x1U) && \
+ ((__POLYNOMIAL__) <= 0xFFFFU) && \
+ (((__POLYNOMIAL__)&0x1U) != 0U))
+
+/** @brief Checks if DMA handle is valid.
+ * @param __HANDLE__ specifies a DMA Handle.
+ * @retval None
+ */
+#define IS_SPI_DMA_HANDLE(__HANDLE__) ((__HANDLE__) != NULL)
+
+/**
+ * @}
+ */
+
+/* Include SPI HAL Extended module */
+#include "stm32f0xx_hal_spi_ex.h"
+
+/* Exported functions --------------------------------------------------------*/
+/** @addtogroup SPI_Exported_Functions
+ * @{
+ */
+
+/** @addtogroup SPI_Exported_Functions_Group1
+ * @{
+ */
+/* Initialization/de-initialization functions ********************************/
+HAL_StatusTypeDef HAL_SPI_Init(SPI_HandleTypeDef *hspi);
+HAL_StatusTypeDef HAL_SPI_DeInit(SPI_HandleTypeDef *hspi);
+void HAL_SPI_MspInit(SPI_HandleTypeDef *hspi);
+void HAL_SPI_MspDeInit(SPI_HandleTypeDef *hspi);
+
+/* Callbacks Register/UnRegister functions ***********************************/
+#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U)
+HAL_StatusTypeDef HAL_SPI_RegisterCallback(SPI_HandleTypeDef *hspi, HAL_SPI_CallbackIDTypeDef CallbackID, pSPI_CallbackTypeDef pCallback);
+HAL_StatusTypeDef HAL_SPI_UnRegisterCallback(SPI_HandleTypeDef *hspi, HAL_SPI_CallbackIDTypeDef CallbackID);
+#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */
+/**
+ * @}
+ */
+
+/** @addtogroup SPI_Exported_Functions_Group2
+ * @{
+ */
+/* I/O operation functions ***************************************************/
+HAL_StatusTypeDef HAL_SPI_Transmit(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size, uint32_t Timeout);
+HAL_StatusTypeDef HAL_SPI_Receive(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size, uint32_t Timeout);
+HAL_StatusTypeDef HAL_SPI_TransmitReceive(SPI_HandleTypeDef *hspi, uint8_t *pTxData, uint8_t *pRxData, uint16_t Size,
+ uint32_t Timeout);
+HAL_StatusTypeDef HAL_SPI_Transmit_IT(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size);
+HAL_StatusTypeDef HAL_SPI_Receive_IT(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size);
+HAL_StatusTypeDef HAL_SPI_TransmitReceive_IT(SPI_HandleTypeDef *hspi, uint8_t *pTxData, uint8_t *pRxData,
+ uint16_t Size);
+HAL_StatusTypeDef HAL_SPI_Transmit_DMA(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size);
+HAL_StatusTypeDef HAL_SPI_Receive_DMA(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size);
+HAL_StatusTypeDef HAL_SPI_TransmitReceive_DMA(SPI_HandleTypeDef *hspi, uint8_t *pTxData, uint8_t *pRxData,
+ uint16_t Size);
+HAL_StatusTypeDef HAL_SPI_DMAPause(SPI_HandleTypeDef *hspi);
+HAL_StatusTypeDef HAL_SPI_DMAResume(SPI_HandleTypeDef *hspi);
+HAL_StatusTypeDef HAL_SPI_DMAStop(SPI_HandleTypeDef *hspi);
+/* Transfer Abort functions */
+HAL_StatusTypeDef HAL_SPI_Abort(SPI_HandleTypeDef *hspi);
+HAL_StatusTypeDef HAL_SPI_Abort_IT(SPI_HandleTypeDef *hspi);
+
+void HAL_SPI_IRQHandler(SPI_HandleTypeDef *hspi);
+void HAL_SPI_TxCpltCallback(SPI_HandleTypeDef *hspi);
+void HAL_SPI_RxCpltCallback(SPI_HandleTypeDef *hspi);
+void HAL_SPI_TxRxCpltCallback(SPI_HandleTypeDef *hspi);
+void HAL_SPI_TxHalfCpltCallback(SPI_HandleTypeDef *hspi);
+void HAL_SPI_RxHalfCpltCallback(SPI_HandleTypeDef *hspi);
+void HAL_SPI_TxRxHalfCpltCallback(SPI_HandleTypeDef *hspi);
+void HAL_SPI_ErrorCallback(SPI_HandleTypeDef *hspi);
+void HAL_SPI_AbortCpltCallback(SPI_HandleTypeDef *hspi);
+/**
+ * @}
+ */
+
+/** @addtogroup SPI_Exported_Functions_Group3
+ * @{
+ */
+/* Peripheral State and Error functions ***************************************/
+HAL_SPI_StateTypeDef HAL_SPI_GetState(SPI_HandleTypeDef *hspi);
+uint32_t HAL_SPI_GetError(SPI_HandleTypeDef *hspi);
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* STM32F0xx_HAL_SPI_H */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal_spi_ex.h b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal_spi_ex.h
new file mode 100644
index 0000000..b65c152
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal_spi_ex.h
@@ -0,0 +1,75 @@
+/**
+ ******************************************************************************
+ * @file stm32f0xx_hal_spi_ex.h
+ * @author MCD Application Team
+ * @brief Header file of SPI HAL Extended module.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2016 STMicroelectronics.
+ * All rights reserved.
+ *
+ * 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 STM32F0xx_HAL_SPI_EX_H
+#define STM32F0xx_HAL_SPI_EX_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f0xx_hal_def.h"
+
+/** @addtogroup STM32F0xx_HAL_Driver
+ * @{
+ */
+
+/** @addtogroup SPIEx
+ * @{
+ */
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macros -----------------------------------------------------------*/
+/* Exported functions --------------------------------------------------------*/
+/** @addtogroup SPIEx_Exported_Functions
+ * @{
+ */
+
+/* Initialization and de-initialization functions ****************************/
+/* IO operation functions *****************************************************/
+/** @addtogroup SPIEx_Exported_Functions_Group1
+ * @{
+ */
+HAL_StatusTypeDef HAL_SPIEx_FlushRxFifo(SPI_HandleTypeDef *hspi);
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* STM32F0xx_HAL_SPI_EX_H */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal_tim.h b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal_tim.h
new file mode 100644
index 0000000..f5fe905
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal_tim.h
@@ -0,0 +1,2131 @@
+/**
+ ******************************************************************************
+ * @file stm32f0xx_hal_tim.h
+ * @author MCD Application Team
+ * @brief Header file of TIM HAL module.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2016 STMicroelectronics.
+ * All rights reserved.
+ *
+ * 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 STM32F0xx_HAL_TIM_H
+#define STM32F0xx_HAL_TIM_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f0xx_hal_def.h"
+
+/** @addtogroup STM32F0xx_HAL_Driver
+ * @{
+ */
+
+/** @addtogroup TIM
+ * @{
+ */
+
+/* Exported types ------------------------------------------------------------*/
+/** @defgroup TIM_Exported_Types TIM Exported Types
+ * @{
+ */
+
+/**
+ * @brief TIM Time base Configuration Structure definition
+ */
+typedef struct
+{
+ uint32_t Prescaler; /*!< Specifies the prescaler value used to divide the TIM clock.
+ This parameter can be a number between Min_Data = 0x0000 and Max_Data = 0xFFFF */
+
+ uint32_t CounterMode; /*!< Specifies the counter mode.
+ This parameter can be a value of @ref TIM_Counter_Mode */
+
+ uint32_t Period; /*!< Specifies the period value to be loaded into the active
+ Auto-Reload Register at the next update event.
+ This parameter can be a number between Min_Data = 0x0000 and Max_Data = 0xFFFF. */
+
+ uint32_t ClockDivision; /*!< Specifies the clock division.
+ This parameter can be a value of @ref TIM_ClockDivision */
+
+ uint32_t RepetitionCounter; /*!< Specifies the repetition counter value. Each time the RCR downcounter
+ reaches zero, an update event is generated and counting restarts
+ from the RCR value (N).
+ This means in PWM mode that (N+1) corresponds to:
+ - the number of PWM periods in edge-aligned mode
+ - the number of half PWM period in center-aligned mode
+ GP timers: this parameter must be a number between Min_Data = 0x00 and
+ Max_Data = 0xFF.
+ Advanced timers: this parameter must be a number between Min_Data = 0x0000 and
+ Max_Data = 0xFFFF. */
+
+ uint32_t AutoReloadPreload; /*!< Specifies the auto-reload preload.
+ This parameter can be a value of @ref TIM_AutoReloadPreload */
+} TIM_Base_InitTypeDef;
+
+/**
+ * @brief TIM Output Compare Configuration Structure definition
+ */
+typedef struct
+{
+ uint32_t OCMode; /*!< Specifies the TIM mode.
+ This parameter can be a value of @ref TIM_Output_Compare_and_PWM_modes */
+
+ uint32_t Pulse; /*!< Specifies the pulse value to be loaded into the Capture Compare Register.
+ This parameter can be a number between Min_Data = 0x0000 and Max_Data = 0xFFFF */
+
+ uint32_t OCPolarity; /*!< Specifies the output polarity.
+ This parameter can be a value of @ref TIM_Output_Compare_Polarity */
+
+ uint32_t OCNPolarity; /*!< Specifies the complementary output polarity.
+ This parameter can be a value of @ref TIM_Output_Compare_N_Polarity
+ @note This parameter is valid only for timer instances supporting break feature. */
+
+ uint32_t OCFastMode; /*!< Specifies the Fast mode state.
+ This parameter can be a value of @ref TIM_Output_Fast_State
+ @note This parameter is valid only in PWM1 and PWM2 mode. */
+
+
+ uint32_t OCIdleState; /*!< Specifies the TIM Output Compare pin state during Idle state.
+ This parameter can be a value of @ref TIM_Output_Compare_Idle_State
+ @note This parameter is valid only for timer instances supporting break feature. */
+
+ uint32_t OCNIdleState; /*!< Specifies the TIM Output Compare pin state during Idle state.
+ This parameter can be a value of @ref TIM_Output_Compare_N_Idle_State
+ @note This parameter is valid only for timer instances supporting break feature. */
+} TIM_OC_InitTypeDef;
+
+/**
+ * @brief TIM One Pulse Mode Configuration Structure definition
+ */
+typedef struct
+{
+ uint32_t OCMode; /*!< Specifies the TIM mode.
+ This parameter can be a value of @ref TIM_Output_Compare_and_PWM_modes */
+
+ uint32_t Pulse; /*!< Specifies the pulse value to be loaded into the Capture Compare Register.
+ This parameter can be a number between Min_Data = 0x0000 and Max_Data = 0xFFFF */
+
+ uint32_t OCPolarity; /*!< Specifies the output polarity.
+ This parameter can be a value of @ref TIM_Output_Compare_Polarity */
+
+ uint32_t OCNPolarity; /*!< Specifies the complementary output polarity.
+ This parameter can be a value of @ref TIM_Output_Compare_N_Polarity
+ @note This parameter is valid only for timer instances supporting break feature. */
+
+ uint32_t OCIdleState; /*!< Specifies the TIM Output Compare pin state during Idle state.
+ This parameter can be a value of @ref TIM_Output_Compare_Idle_State
+ @note This parameter is valid only for timer instances supporting break feature. */
+
+ uint32_t OCNIdleState; /*!< Specifies the TIM Output Compare pin state during Idle state.
+ This parameter can be a value of @ref TIM_Output_Compare_N_Idle_State
+ @note This parameter is valid only for timer instances supporting break feature. */
+
+ uint32_t ICPolarity; /*!< Specifies the active edge of the input signal.
+ This parameter can be a value of @ref TIM_Input_Capture_Polarity */
+
+ uint32_t ICSelection; /*!< Specifies the input.
+ This parameter can be a value of @ref TIM_Input_Capture_Selection */
+
+ uint32_t ICFilter; /*!< Specifies the input capture filter.
+ This parameter can be a number between Min_Data = 0x0 and Max_Data = 0xF */
+} TIM_OnePulse_InitTypeDef;
+
+/**
+ * @brief TIM Input Capture Configuration Structure definition
+ */
+typedef struct
+{
+ uint32_t ICPolarity; /*!< Specifies the active edge of the input signal.
+ This parameter can be a value of @ref TIM_Input_Capture_Polarity */
+
+ uint32_t ICSelection; /*!< Specifies the input.
+ This parameter can be a value of @ref TIM_Input_Capture_Selection */
+
+ uint32_t ICPrescaler; /*!< Specifies the Input Capture Prescaler.
+ This parameter can be a value of @ref TIM_Input_Capture_Prescaler */
+
+ uint32_t ICFilter; /*!< Specifies the input capture filter.
+ This parameter can be a number between Min_Data = 0x0 and Max_Data = 0xF */
+} TIM_IC_InitTypeDef;
+
+/**
+ * @brief TIM Encoder Configuration Structure definition
+ */
+typedef struct
+{
+ uint32_t EncoderMode; /*!< Specifies the active edge of the input signal.
+ This parameter can be a value of @ref TIM_Encoder_Mode */
+
+ uint32_t IC1Polarity; /*!< Specifies the active edge of the input signal.
+ This parameter can be a value of @ref TIM_Encoder_Input_Polarity */
+
+ uint32_t IC1Selection; /*!< Specifies the input.
+ This parameter can be a value of @ref TIM_Input_Capture_Selection */
+
+ uint32_t IC1Prescaler; /*!< Specifies the Input Capture Prescaler.
+ This parameter can be a value of @ref TIM_Input_Capture_Prescaler */
+
+ uint32_t IC1Filter; /*!< Specifies the input capture filter.
+ This parameter can be a number between Min_Data = 0x0 and Max_Data = 0xF */
+
+ uint32_t IC2Polarity; /*!< Specifies the active edge of the input signal.
+ This parameter can be a value of @ref TIM_Encoder_Input_Polarity */
+
+ uint32_t IC2Selection; /*!< Specifies the input.
+ This parameter can be a value of @ref TIM_Input_Capture_Selection */
+
+ uint32_t IC2Prescaler; /*!< Specifies the Input Capture Prescaler.
+ This parameter can be a value of @ref TIM_Input_Capture_Prescaler */
+
+ uint32_t IC2Filter; /*!< Specifies the input capture filter.
+ This parameter can be a number between Min_Data = 0x0 and Max_Data = 0xF */
+} TIM_Encoder_InitTypeDef;
+
+/**
+ * @brief Clock Configuration Handle Structure definition
+ */
+typedef struct
+{
+ uint32_t ClockSource; /*!< TIM clock sources
+ This parameter can be a value of @ref TIM_Clock_Source */
+ uint32_t ClockPolarity; /*!< TIM clock polarity
+ This parameter can be a value of @ref TIM_Clock_Polarity */
+ uint32_t ClockPrescaler; /*!< TIM clock prescaler
+ This parameter can be a value of @ref TIM_Clock_Prescaler */
+ uint32_t ClockFilter; /*!< TIM clock filter
+ This parameter can be a number between Min_Data = 0x0 and Max_Data = 0xF */
+} TIM_ClockConfigTypeDef;
+
+/**
+ * @brief TIM Clear Input Configuration Handle Structure definition
+ */
+typedef struct
+{
+ uint32_t ClearInputState; /*!< TIM clear Input state
+ This parameter can be ENABLE or DISABLE */
+ uint32_t ClearInputSource; /*!< TIM clear Input sources
+ This parameter can be a value of @ref TIM_ClearInput_Source */
+ uint32_t ClearInputPolarity; /*!< TIM Clear Input polarity
+ This parameter can be a value of @ref TIM_ClearInput_Polarity */
+ uint32_t ClearInputPrescaler; /*!< TIM Clear Input prescaler
+ This parameter must be 0: When OCRef clear feature is used with ETR source,
+ ETR prescaler must be off */
+ uint32_t ClearInputFilter; /*!< TIM Clear Input filter
+ This parameter can be a number between Min_Data = 0x0 and Max_Data = 0xF */
+} TIM_ClearInputConfigTypeDef;
+
+/**
+ * @brief TIM Master configuration Structure definition
+ */
+typedef struct
+{
+ uint32_t MasterOutputTrigger; /*!< Trigger output (TRGO) selection
+ This parameter can be a value of @ref TIM_Master_Mode_Selection */
+ uint32_t MasterSlaveMode; /*!< Master/slave mode selection
+ This parameter can be a value of @ref TIM_Master_Slave_Mode
+ @note When the Master/slave mode is enabled, the effect of
+ an event on the trigger input (TRGI) is delayed to allow a
+ perfect synchronization between the current timer and its
+ slaves (through TRGO). It is not mandatory in case of timer
+ synchronization mode. */
+} TIM_MasterConfigTypeDef;
+
+/**
+ * @brief TIM Slave configuration Structure definition
+ */
+typedef struct
+{
+ uint32_t SlaveMode; /*!< Slave mode selection
+ This parameter can be a value of @ref TIM_Slave_Mode */
+ uint32_t InputTrigger; /*!< Input Trigger source
+ This parameter can be a value of @ref TIM_Trigger_Selection */
+ uint32_t TriggerPolarity; /*!< Input Trigger polarity
+ This parameter can be a value of @ref TIM_Trigger_Polarity */
+ uint32_t TriggerPrescaler; /*!< Input trigger prescaler
+ This parameter can be a value of @ref TIM_Trigger_Prescaler */
+ uint32_t TriggerFilter; /*!< Input trigger filter
+ This parameter can be a number between Min_Data = 0x0 and Max_Data = 0xF */
+
+} TIM_SlaveConfigTypeDef;
+
+/**
+ * @brief TIM Break input(s) and Dead time configuration Structure definition
+ * @note 2 break inputs can be configured (BKIN and BKIN2) with configurable
+ * filter and polarity.
+ */
+typedef struct
+{
+ uint32_t OffStateRunMode; /*!< TIM off state in run mode, This parameter can be a value of @ref TIM_OSSR_Off_State_Selection_for_Run_mode_state */
+
+ uint32_t OffStateIDLEMode; /*!< TIM off state in IDLE mode, This parameter can be a value of @ref TIM_OSSI_Off_State_Selection_for_Idle_mode_state */
+
+ uint32_t LockLevel; /*!< TIM Lock level, This parameter can be a value of @ref TIM_Lock_level */
+
+ uint32_t DeadTime; /*!< TIM dead Time, This parameter can be a number between Min_Data = 0x00 and Max_Data = 0xFF */
+
+ uint32_t BreakState; /*!< TIM Break State, This parameter can be a value of @ref TIM_Break_Input_enable_disable */
+
+ uint32_t BreakPolarity; /*!< TIM Break input polarity, This parameter can be a value of @ref TIM_Break_Polarity */
+
+ uint32_t BreakFilter; /*!< Specifies the break input filter.This parameter can be a number between Min_Data = 0x0 and Max_Data = 0xF */
+
+ uint32_t AutomaticOutput; /*!< TIM Automatic Output Enable state, This parameter can be a value of @ref TIM_AOE_Bit_Set_Reset */
+
+} TIM_BreakDeadTimeConfigTypeDef;
+
+/**
+ * @brief HAL State structures definition
+ */
+typedef enum
+{
+ HAL_TIM_STATE_RESET = 0x00U, /*!< Peripheral not yet initialized or disabled */
+ HAL_TIM_STATE_READY = 0x01U, /*!< Peripheral Initialized and ready for use */
+ HAL_TIM_STATE_BUSY = 0x02U, /*!< An internal process is ongoing */
+ HAL_TIM_STATE_TIMEOUT = 0x03U, /*!< Timeout state */
+ HAL_TIM_STATE_ERROR = 0x04U /*!< Reception process is ongoing */
+} HAL_TIM_StateTypeDef;
+
+/**
+ * @brief TIM Channel States definition
+ */
+typedef enum
+{
+ HAL_TIM_CHANNEL_STATE_RESET = 0x00U, /*!< TIM Channel initial state */
+ HAL_TIM_CHANNEL_STATE_READY = 0x01U, /*!< TIM Channel ready for use */
+ HAL_TIM_CHANNEL_STATE_BUSY = 0x02U, /*!< An internal process is ongoing on the TIM channel */
+} HAL_TIM_ChannelStateTypeDef;
+
+/**
+ * @brief DMA Burst States definition
+ */
+typedef enum
+{
+ HAL_DMA_BURST_STATE_RESET = 0x00U, /*!< DMA Burst initial state */
+ HAL_DMA_BURST_STATE_READY = 0x01U, /*!< DMA Burst ready for use */
+ HAL_DMA_BURST_STATE_BUSY = 0x02U, /*!< Ongoing DMA Burst */
+} HAL_TIM_DMABurstStateTypeDef;
+
+/**
+ * @brief HAL Active channel structures definition
+ */
+typedef enum
+{
+ HAL_TIM_ACTIVE_CHANNEL_1 = 0x01U, /*!< The active channel is 1 */
+ HAL_TIM_ACTIVE_CHANNEL_2 = 0x02U, /*!< The active channel is 2 */
+ HAL_TIM_ACTIVE_CHANNEL_3 = 0x04U, /*!< The active channel is 3 */
+ HAL_TIM_ACTIVE_CHANNEL_4 = 0x08U, /*!< The active channel is 4 */
+ HAL_TIM_ACTIVE_CHANNEL_CLEARED = 0x00U /*!< All active channels cleared */
+} HAL_TIM_ActiveChannel;
+
+/**
+ * @brief TIM Time Base Handle Structure definition
+ */
+#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1)
+typedef struct __TIM_HandleTypeDef
+#else
+typedef struct
+#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */
+{
+ TIM_TypeDef *Instance; /*!< Register base address */
+ TIM_Base_InitTypeDef Init; /*!< TIM Time Base required parameters */
+ HAL_TIM_ActiveChannel Channel; /*!< Active channel */
+ DMA_HandleTypeDef *hdma[7]; /*!< DMA Handlers array
+ This array is accessed by a @ref DMA_Handle_index */
+ HAL_LockTypeDef Lock; /*!< Locking object */
+ __IO HAL_TIM_StateTypeDef State; /*!< TIM operation state */
+ __IO HAL_TIM_ChannelStateTypeDef ChannelState[4]; /*!< TIM channel operation state */
+ __IO HAL_TIM_ChannelStateTypeDef ChannelNState[4]; /*!< TIM complementary channel operation state */
+ __IO HAL_TIM_DMABurstStateTypeDef DMABurstState; /*!< DMA burst operation state */
+
+#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1)
+ void (* Base_MspInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Base Msp Init Callback */
+ void (* Base_MspDeInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Base Msp DeInit Callback */
+ void (* IC_MspInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM IC Msp Init Callback */
+ void (* IC_MspDeInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM IC Msp DeInit Callback */
+ void (* OC_MspInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM OC Msp Init Callback */
+ void (* OC_MspDeInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM OC Msp DeInit Callback */
+ void (* PWM_MspInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM PWM Msp Init Callback */
+ void (* PWM_MspDeInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM PWM Msp DeInit Callback */
+ void (* OnePulse_MspInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM One Pulse Msp Init Callback */
+ void (* OnePulse_MspDeInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM One Pulse Msp DeInit Callback */
+ void (* Encoder_MspInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Encoder Msp Init Callback */
+ void (* Encoder_MspDeInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Encoder Msp DeInit Callback */
+ void (* HallSensor_MspInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Hall Sensor Msp Init Callback */
+ void (* HallSensor_MspDeInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Hall Sensor Msp DeInit Callback */
+ void (* PeriodElapsedCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Period Elapsed Callback */
+ void (* PeriodElapsedHalfCpltCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Period Elapsed half complete Callback */
+ void (* TriggerCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Trigger Callback */
+ void (* TriggerHalfCpltCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Trigger half complete Callback */
+ void (* IC_CaptureCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Input Capture Callback */
+ void (* IC_CaptureHalfCpltCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Input Capture half complete Callback */
+ void (* OC_DelayElapsedCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Output Compare Delay Elapsed Callback */
+ void (* PWM_PulseFinishedCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM PWM Pulse Finished Callback */
+ void (* PWM_PulseFinishedHalfCpltCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM PWM Pulse Finished half complete Callback */
+ void (* ErrorCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Error Callback */
+ void (* CommutationCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Commutation Callback */
+ void (* CommutationHalfCpltCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Commutation half complete Callback */
+ void (* BreakCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Break Callback */
+#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */
+} TIM_HandleTypeDef;
+
+#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1)
+/**
+ * @brief HAL TIM Callback ID enumeration definition
+ */
+typedef enum
+{
+ HAL_TIM_BASE_MSPINIT_CB_ID = 0x00U /*!< TIM Base MspInit Callback ID */
+ , HAL_TIM_BASE_MSPDEINIT_CB_ID = 0x01U /*!< TIM Base MspDeInit Callback ID */
+ , HAL_TIM_IC_MSPINIT_CB_ID = 0x02U /*!< TIM IC MspInit Callback ID */
+ , HAL_TIM_IC_MSPDEINIT_CB_ID = 0x03U /*!< TIM IC MspDeInit Callback ID */
+ , HAL_TIM_OC_MSPINIT_CB_ID = 0x04U /*!< TIM OC MspInit Callback ID */
+ , HAL_TIM_OC_MSPDEINIT_CB_ID = 0x05U /*!< TIM OC MspDeInit Callback ID */
+ , HAL_TIM_PWM_MSPINIT_CB_ID = 0x06U /*!< TIM PWM MspInit Callback ID */
+ , HAL_TIM_PWM_MSPDEINIT_CB_ID = 0x07U /*!< TIM PWM MspDeInit Callback ID */
+ , HAL_TIM_ONE_PULSE_MSPINIT_CB_ID = 0x08U /*!< TIM One Pulse MspInit Callback ID */
+ , HAL_TIM_ONE_PULSE_MSPDEINIT_CB_ID = 0x09U /*!< TIM One Pulse MspDeInit Callback ID */
+ , HAL_TIM_ENCODER_MSPINIT_CB_ID = 0x0AU /*!< TIM Encoder MspInit Callback ID */
+ , HAL_TIM_ENCODER_MSPDEINIT_CB_ID = 0x0BU /*!< TIM Encoder MspDeInit Callback ID */
+ , HAL_TIM_HALL_SENSOR_MSPINIT_CB_ID = 0x0CU /*!< TIM Hall Sensor MspDeInit Callback ID */
+ , HAL_TIM_HALL_SENSOR_MSPDEINIT_CB_ID = 0x0DU /*!< TIM Hall Sensor MspDeInit Callback ID */
+ , HAL_TIM_PERIOD_ELAPSED_CB_ID = 0x0EU /*!< TIM Period Elapsed Callback ID */
+ , HAL_TIM_PERIOD_ELAPSED_HALF_CB_ID = 0x0FU /*!< TIM Period Elapsed half complete Callback ID */
+ , HAL_TIM_TRIGGER_CB_ID = 0x10U /*!< TIM Trigger Callback ID */
+ , HAL_TIM_TRIGGER_HALF_CB_ID = 0x11U /*!< TIM Trigger half complete Callback ID */
+
+ , HAL_TIM_IC_CAPTURE_CB_ID = 0x12U /*!< TIM Input Capture Callback ID */
+ , HAL_TIM_IC_CAPTURE_HALF_CB_ID = 0x13U /*!< TIM Input Capture half complete Callback ID */
+ , HAL_TIM_OC_DELAY_ELAPSED_CB_ID = 0x14U /*!< TIM Output Compare Delay Elapsed Callback ID */
+ , HAL_TIM_PWM_PULSE_FINISHED_CB_ID = 0x15U /*!< TIM PWM Pulse Finished Callback ID */
+ , HAL_TIM_PWM_PULSE_FINISHED_HALF_CB_ID = 0x16U /*!< TIM PWM Pulse Finished half complete Callback ID */
+ , HAL_TIM_ERROR_CB_ID = 0x17U /*!< TIM Error Callback ID */
+ , HAL_TIM_COMMUTATION_CB_ID = 0x18U /*!< TIM Commutation Callback ID */
+ , HAL_TIM_COMMUTATION_HALF_CB_ID = 0x19U /*!< TIM Commutation half complete Callback ID */
+ , HAL_TIM_BREAK_CB_ID = 0x1AU /*!< TIM Break Callback ID */
+} HAL_TIM_CallbackIDTypeDef;
+
+/**
+ * @brief HAL TIM Callback pointer definition
+ */
+typedef void (*pTIM_CallbackTypeDef)(TIM_HandleTypeDef *htim); /*!< pointer to the TIM callback function */
+
+#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */
+
+/**
+ * @}
+ */
+/* End of exported types -----------------------------------------------------*/
+
+/* Exported constants --------------------------------------------------------*/
+/** @defgroup TIM_Exported_Constants TIM Exported Constants
+ * @{
+ */
+
+/** @defgroup TIM_ClearInput_Source TIM Clear Input Source
+ * @{
+ */
+#define TIM_CLEARINPUTSOURCE_NONE 0x00000000U /*!< OCREF_CLR is disabled */
+#define TIM_CLEARINPUTSOURCE_ETR 0x00000001U /*!< OCREF_CLR is connected to ETRF input */
+#define TIM_CLEARINPUTSOURCE_OCREFCLR 0x00000002U /*!< OCREF_CLR is connected to OCREF_CLR_INT */
+/**
+ * @}
+ */
+
+/** @defgroup TIM_DMA_Base_address TIM DMA Base Address
+ * @{
+ */
+#define TIM_DMABASE_CR1 0x00000000U
+#define TIM_DMABASE_CR2 0x00000001U
+#define TIM_DMABASE_SMCR 0x00000002U
+#define TIM_DMABASE_DIER 0x00000003U
+#define TIM_DMABASE_SR 0x00000004U
+#define TIM_DMABASE_EGR 0x00000005U
+#define TIM_DMABASE_CCMR1 0x00000006U
+#define TIM_DMABASE_CCMR2 0x00000007U
+#define TIM_DMABASE_CCER 0x00000008U
+#define TIM_DMABASE_CNT 0x00000009U
+#define TIM_DMABASE_PSC 0x0000000AU
+#define TIM_DMABASE_ARR 0x0000000BU
+#define TIM_DMABASE_RCR 0x0000000CU
+#define TIM_DMABASE_CCR1 0x0000000DU
+#define TIM_DMABASE_CCR2 0x0000000EU
+#define TIM_DMABASE_CCR3 0x0000000FU
+#define TIM_DMABASE_CCR4 0x00000010U
+#define TIM_DMABASE_BDTR 0x00000011U
+#define TIM_DMABASE_DCR 0x00000012U
+#define TIM_DMABASE_DMAR 0x00000013U
+/**
+ * @}
+ */
+
+/** @defgroup TIM_Event_Source TIM Event Source
+ * @{
+ */
+#define TIM_EVENTSOURCE_UPDATE TIM_EGR_UG /*!< Reinitialize the counter and generates an update of the registers */
+#define TIM_EVENTSOURCE_CC1 TIM_EGR_CC1G /*!< A capture/compare event is generated on channel 1 */
+#define TIM_EVENTSOURCE_CC2 TIM_EGR_CC2G /*!< A capture/compare event is generated on channel 2 */
+#define TIM_EVENTSOURCE_CC3 TIM_EGR_CC3G /*!< A capture/compare event is generated on channel 3 */
+#define TIM_EVENTSOURCE_CC4 TIM_EGR_CC4G /*!< A capture/compare event is generated on channel 4 */
+#define TIM_EVENTSOURCE_COM TIM_EGR_COMG /*!< A commutation event is generated */
+#define TIM_EVENTSOURCE_TRIGGER TIM_EGR_TG /*!< A trigger event is generated */
+#define TIM_EVENTSOURCE_BREAK TIM_EGR_BG /*!< A break event is generated */
+/**
+ * @}
+ */
+
+/** @defgroup TIM_Input_Channel_Polarity TIM Input Channel polarity
+ * @{
+ */
+#define TIM_INPUTCHANNELPOLARITY_RISING 0x00000000U /*!< Polarity for TIx source */
+#define TIM_INPUTCHANNELPOLARITY_FALLING TIM_CCER_CC1P /*!< Polarity for TIx source */
+#define TIM_INPUTCHANNELPOLARITY_BOTHEDGE (TIM_CCER_CC1P | TIM_CCER_CC1NP) /*!< Polarity for TIx source */
+/**
+ * @}
+ */
+
+/** @defgroup TIM_ETR_Polarity TIM ETR Polarity
+ * @{
+ */
+#define TIM_ETRPOLARITY_INVERTED TIM_SMCR_ETP /*!< Polarity for ETR source */
+#define TIM_ETRPOLARITY_NONINVERTED 0x00000000U /*!< Polarity for ETR source */
+/**
+ * @}
+ */
+
+/** @defgroup TIM_ETR_Prescaler TIM ETR Prescaler
+ * @{
+ */
+#define TIM_ETRPRESCALER_DIV1 0x00000000U /*!< No prescaler is used */
+#define TIM_ETRPRESCALER_DIV2 TIM_SMCR_ETPS_0 /*!< ETR input source is divided by 2 */
+#define TIM_ETRPRESCALER_DIV4 TIM_SMCR_ETPS_1 /*!< ETR input source is divided by 4 */
+#define TIM_ETRPRESCALER_DIV8 TIM_SMCR_ETPS /*!< ETR input source is divided by 8 */
+/**
+ * @}
+ */
+
+/** @defgroup TIM_Counter_Mode TIM Counter Mode
+ * @{
+ */
+#define TIM_COUNTERMODE_UP 0x00000000U /*!< Counter used as up-counter */
+#define TIM_COUNTERMODE_DOWN TIM_CR1_DIR /*!< Counter used as down-counter */
+#define TIM_COUNTERMODE_CENTERALIGNED1 TIM_CR1_CMS_0 /*!< Center-aligned mode 1 */
+#define TIM_COUNTERMODE_CENTERALIGNED2 TIM_CR1_CMS_1 /*!< Center-aligned mode 2 */
+#define TIM_COUNTERMODE_CENTERALIGNED3 TIM_CR1_CMS /*!< Center-aligned mode 3 */
+/**
+ * @}
+ */
+
+/** @defgroup TIM_ClockDivision TIM Clock Division
+ * @{
+ */
+#define TIM_CLOCKDIVISION_DIV1 0x00000000U /*!< Clock division: tDTS=tCK_INT */
+#define TIM_CLOCKDIVISION_DIV2 TIM_CR1_CKD_0 /*!< Clock division: tDTS=2*tCK_INT */
+#define TIM_CLOCKDIVISION_DIV4 TIM_CR1_CKD_1 /*!< Clock division: tDTS=4*tCK_INT */
+/**
+ * @}
+ */
+
+/** @defgroup TIM_Output_Compare_State TIM Output Compare State
+ * @{
+ */
+#define TIM_OUTPUTSTATE_DISABLE 0x00000000U /*!< Capture/Compare 1 output disabled */
+#define TIM_OUTPUTSTATE_ENABLE TIM_CCER_CC1E /*!< Capture/Compare 1 output enabled */
+/**
+ * @}
+ */
+
+/** @defgroup TIM_AutoReloadPreload TIM Auto-Reload Preload
+ * @{
+ */
+#define TIM_AUTORELOAD_PRELOAD_DISABLE 0x00000000U /*!< TIMx_ARR register is not buffered */
+#define TIM_AUTORELOAD_PRELOAD_ENABLE TIM_CR1_ARPE /*!< TIMx_ARR register is buffered */
+
+/**
+ * @}
+ */
+
+/** @defgroup TIM_Output_Fast_State TIM Output Fast State
+ * @{
+ */
+#define TIM_OCFAST_DISABLE 0x00000000U /*!< Output Compare fast disable */
+#define TIM_OCFAST_ENABLE TIM_CCMR1_OC1FE /*!< Output Compare fast enable */
+/**
+ * @}
+ */
+
+/** @defgroup TIM_Output_Compare_N_State TIM Complementary Output Compare State
+ * @{
+ */
+#define TIM_OUTPUTNSTATE_DISABLE 0x00000000U /*!< OCxN is disabled */
+#define TIM_OUTPUTNSTATE_ENABLE TIM_CCER_CC1NE /*!< OCxN is enabled */
+/**
+ * @}
+ */
+
+/** @defgroup TIM_Output_Compare_Polarity TIM Output Compare Polarity
+ * @{
+ */
+#define TIM_OCPOLARITY_HIGH 0x00000000U /*!< Capture/Compare output polarity */
+#define TIM_OCPOLARITY_LOW TIM_CCER_CC1P /*!< Capture/Compare output polarity */
+/**
+ * @}
+ */
+
+/** @defgroup TIM_Output_Compare_N_Polarity TIM Complementary Output Compare Polarity
+ * @{
+ */
+#define TIM_OCNPOLARITY_HIGH 0x00000000U /*!< Capture/Compare complementary output polarity */
+#define TIM_OCNPOLARITY_LOW TIM_CCER_CC1NP /*!< Capture/Compare complementary output polarity */
+/**
+ * @}
+ */
+
+/** @defgroup TIM_Output_Compare_Idle_State TIM Output Compare Idle State
+ * @{
+ */
+#define TIM_OCIDLESTATE_SET TIM_CR2_OIS1 /*!< Output Idle state: OCx=1 when MOE=0 */
+#define TIM_OCIDLESTATE_RESET 0x00000000U /*!< Output Idle state: OCx=0 when MOE=0 */
+/**
+ * @}
+ */
+
+/** @defgroup TIM_Output_Compare_N_Idle_State TIM Complementary Output Compare Idle State
+ * @{
+ */
+#define TIM_OCNIDLESTATE_SET TIM_CR2_OIS1N /*!< Complementary output Idle state: OCxN=1 when MOE=0 */
+#define TIM_OCNIDLESTATE_RESET 0x00000000U /*!< Complementary output Idle state: OCxN=0 when MOE=0 */
+/**
+ * @}
+ */
+
+/** @defgroup TIM_Input_Capture_Polarity TIM Input Capture Polarity
+ * @{
+ */
+#define TIM_ICPOLARITY_RISING TIM_INPUTCHANNELPOLARITY_RISING /*!< Capture triggered by rising edge on timer input */
+#define TIM_ICPOLARITY_FALLING TIM_INPUTCHANNELPOLARITY_FALLING /*!< Capture triggered by falling edge on timer input */
+#define TIM_ICPOLARITY_BOTHEDGE TIM_INPUTCHANNELPOLARITY_BOTHEDGE /*!< Capture triggered by both rising and falling edges on timer input*/
+/**
+ * @}
+ */
+
+/** @defgroup TIM_Encoder_Input_Polarity TIM Encoder Input Polarity
+ * @{
+ */
+#define TIM_ENCODERINPUTPOLARITY_RISING TIM_INPUTCHANNELPOLARITY_RISING /*!< Encoder input with rising edge polarity */
+#define TIM_ENCODERINPUTPOLARITY_FALLING TIM_INPUTCHANNELPOLARITY_FALLING /*!< Encoder input with falling edge polarity */
+/**
+ * @}
+ */
+
+/** @defgroup TIM_Input_Capture_Selection TIM Input Capture Selection
+ * @{
+ */
+#define TIM_ICSELECTION_DIRECTTI TIM_CCMR1_CC1S_0 /*!< TIM Input 1, 2, 3 or 4 is selected to be connected to IC1, IC2, IC3 or IC4, respectively */
+#define TIM_ICSELECTION_INDIRECTTI TIM_CCMR1_CC1S_1 /*!< TIM Input 1, 2, 3 or 4 is selected to be connected to IC2, IC1, IC4 or IC3, respectively */
+#define TIM_ICSELECTION_TRC TIM_CCMR1_CC1S /*!< TIM Input 1, 2, 3 or 4 is selected to be connected to TRC */
+/**
+ * @}
+ */
+
+/** @defgroup TIM_Input_Capture_Prescaler TIM Input Capture Prescaler
+ * @{
+ */
+#define TIM_ICPSC_DIV1 0x00000000U /*!< Capture performed each time an edge is detected on the capture input */
+#define TIM_ICPSC_DIV2 TIM_CCMR1_IC1PSC_0 /*!< Capture performed once every 2 events */
+#define TIM_ICPSC_DIV4 TIM_CCMR1_IC1PSC_1 /*!< Capture performed once every 4 events */
+#define TIM_ICPSC_DIV8 TIM_CCMR1_IC1PSC /*!< Capture performed once every 8 events */
+/**
+ * @}
+ */
+
+/** @defgroup TIM_One_Pulse_Mode TIM One Pulse Mode
+ * @{
+ */
+#define TIM_OPMODE_SINGLE TIM_CR1_OPM /*!< Counter stops counting at the next update event */
+#define TIM_OPMODE_REPETITIVE 0x00000000U /*!< Counter is not stopped at update event */
+/**
+ * @}
+ */
+
+/** @defgroup TIM_Encoder_Mode TIM Encoder Mode
+ * @{
+ */
+#define TIM_ENCODERMODE_TI1 TIM_SMCR_SMS_0 /*!< Quadrature encoder mode 1, x2 mode, counts up/down on TI1FP1 edge depending on TI2FP2 level */
+#define TIM_ENCODERMODE_TI2 TIM_SMCR_SMS_1 /*!< Quadrature encoder mode 2, x2 mode, counts up/down on TI2FP2 edge depending on TI1FP1 level. */
+#define TIM_ENCODERMODE_TI12 (TIM_SMCR_SMS_1 | TIM_SMCR_SMS_0) /*!< Quadrature encoder mode 3, x4 mode, counts up/down on both TI1FP1 and TI2FP2 edges depending on the level of the other input. */
+/**
+ * @}
+ */
+
+/** @defgroup TIM_Interrupt_definition TIM interrupt Definition
+ * @{
+ */
+#define TIM_IT_UPDATE TIM_DIER_UIE /*!< Update interrupt */
+#define TIM_IT_CC1 TIM_DIER_CC1IE /*!< Capture/Compare 1 interrupt */
+#define TIM_IT_CC2 TIM_DIER_CC2IE /*!< Capture/Compare 2 interrupt */
+#define TIM_IT_CC3 TIM_DIER_CC3IE /*!< Capture/Compare 3 interrupt */
+#define TIM_IT_CC4 TIM_DIER_CC4IE /*!< Capture/Compare 4 interrupt */
+#define TIM_IT_COM TIM_DIER_COMIE /*!< Commutation interrupt */
+#define TIM_IT_TRIGGER TIM_DIER_TIE /*!< Trigger interrupt */
+#define TIM_IT_BREAK TIM_DIER_BIE /*!< Break interrupt */
+/**
+ * @}
+ */
+
+/** @defgroup TIM_Commutation_Source TIM Commutation Source
+ * @{
+ */
+#define TIM_COMMUTATION_TRGI TIM_CR2_CCUS /*!< When Capture/compare control bits are preloaded, they are updated by setting the COMG bit or when an rising edge occurs on trigger input */
+#define TIM_COMMUTATION_SOFTWARE 0x00000000U /*!< When Capture/compare control bits are preloaded, they are updated by setting the COMG bit */
+/**
+ * @}
+ */
+
+/** @defgroup TIM_DMA_sources TIM DMA Sources
+ * @{
+ */
+#define TIM_DMA_UPDATE TIM_DIER_UDE /*!< DMA request is triggered by the update event */
+#define TIM_DMA_CC1 TIM_DIER_CC1DE /*!< DMA request is triggered by the capture/compare macth 1 event */
+#define TIM_DMA_CC2 TIM_DIER_CC2DE /*!< DMA request is triggered by the capture/compare macth 2 event event */
+#define TIM_DMA_CC3 TIM_DIER_CC3DE /*!< DMA request is triggered by the capture/compare macth 3 event event */
+#define TIM_DMA_CC4 TIM_DIER_CC4DE /*!< DMA request is triggered by the capture/compare macth 4 event event */
+#define TIM_DMA_COM TIM_DIER_COMDE /*!< DMA request is triggered by the commutation event */
+#define TIM_DMA_TRIGGER TIM_DIER_TDE /*!< DMA request is triggered by the trigger event */
+/**
+ * @}
+ */
+
+/** @defgroup TIM_Flag_definition TIM Flag Definition
+ * @{
+ */
+#define TIM_FLAG_UPDATE TIM_SR_UIF /*!< Update interrupt flag */
+#define TIM_FLAG_CC1 TIM_SR_CC1IF /*!< Capture/Compare 1 interrupt flag */
+#define TIM_FLAG_CC2 TIM_SR_CC2IF /*!< Capture/Compare 2 interrupt flag */
+#define TIM_FLAG_CC3 TIM_SR_CC3IF /*!< Capture/Compare 3 interrupt flag */
+#define TIM_FLAG_CC4 TIM_SR_CC4IF /*!< Capture/Compare 4 interrupt flag */
+#define TIM_FLAG_COM TIM_SR_COMIF /*!< Commutation interrupt flag */
+#define TIM_FLAG_TRIGGER TIM_SR_TIF /*!< Trigger interrupt flag */
+#define TIM_FLAG_BREAK TIM_SR_BIF /*!< Break interrupt flag */
+#define TIM_FLAG_CC1OF TIM_SR_CC1OF /*!< Capture 1 overcapture flag */
+#define TIM_FLAG_CC2OF TIM_SR_CC2OF /*!< Capture 2 overcapture flag */
+#define TIM_FLAG_CC3OF TIM_SR_CC3OF /*!< Capture 3 overcapture flag */
+#define TIM_FLAG_CC4OF TIM_SR_CC4OF /*!< Capture 4 overcapture flag */
+/**
+ * @}
+ */
+
+/** @defgroup TIM_Channel TIM Channel
+ * @{
+ */
+#define TIM_CHANNEL_1 0x00000000U /*!< Capture/compare channel 1 identifier */
+#define TIM_CHANNEL_2 0x00000004U /*!< Capture/compare channel 2 identifier */
+#define TIM_CHANNEL_3 0x00000008U /*!< Capture/compare channel 3 identifier */
+#define TIM_CHANNEL_4 0x0000000CU /*!< Capture/compare channel 4 identifier */
+#define TIM_CHANNEL_ALL 0x0000003CU /*!< Global Capture/compare channel identifier */
+/**
+ * @}
+ */
+
+/** @defgroup TIM_Clock_Source TIM Clock Source
+ * @{
+ */
+#define TIM_CLOCKSOURCE_ETRMODE2 TIM_SMCR_ETPS_1 /*!< External clock source mode 2 */
+#define TIM_CLOCKSOURCE_INTERNAL TIM_SMCR_ETPS_0 /*!< Internal clock source */
+#define TIM_CLOCKSOURCE_ITR0 TIM_TS_ITR0 /*!< External clock source mode 1 (ITR0) */
+#define TIM_CLOCKSOURCE_ITR1 TIM_TS_ITR1 /*!< External clock source mode 1 (ITR1) */
+#define TIM_CLOCKSOURCE_ITR2 TIM_TS_ITR2 /*!< External clock source mode 1 (ITR2) */
+#define TIM_CLOCKSOURCE_ITR3 TIM_TS_ITR3 /*!< External clock source mode 1 (ITR3) */
+#define TIM_CLOCKSOURCE_TI1ED TIM_TS_TI1F_ED /*!< External clock source mode 1 (TTI1FP1 + edge detect.) */
+#define TIM_CLOCKSOURCE_TI1 TIM_TS_TI1FP1 /*!< External clock source mode 1 (TTI1FP1) */
+#define TIM_CLOCKSOURCE_TI2 TIM_TS_TI2FP2 /*!< External clock source mode 1 (TTI2FP2) */
+#define TIM_CLOCKSOURCE_ETRMODE1 TIM_TS_ETRF /*!< External clock source mode 1 (ETRF) */
+/**
+ * @}
+ */
+
+/** @defgroup TIM_Clock_Polarity TIM Clock Polarity
+ * @{
+ */
+#define TIM_CLOCKPOLARITY_INVERTED TIM_ETRPOLARITY_INVERTED /*!< Polarity for ETRx clock sources */
+#define TIM_CLOCKPOLARITY_NONINVERTED TIM_ETRPOLARITY_NONINVERTED /*!< Polarity for ETRx clock sources */
+#define TIM_CLOCKPOLARITY_RISING TIM_INPUTCHANNELPOLARITY_RISING /*!< Polarity for TIx clock sources */
+#define TIM_CLOCKPOLARITY_FALLING TIM_INPUTCHANNELPOLARITY_FALLING /*!< Polarity for TIx clock sources */
+#define TIM_CLOCKPOLARITY_BOTHEDGE TIM_INPUTCHANNELPOLARITY_BOTHEDGE /*!< Polarity for TIx clock sources */
+/**
+ * @}
+ */
+
+/** @defgroup TIM_Clock_Prescaler TIM Clock Prescaler
+ * @{
+ */
+#define TIM_CLOCKPRESCALER_DIV1 TIM_ETRPRESCALER_DIV1 /*!< No prescaler is used */
+#define TIM_CLOCKPRESCALER_DIV2 TIM_ETRPRESCALER_DIV2 /*!< Prescaler for External ETR Clock: Capture performed once every 2 events. */
+#define TIM_CLOCKPRESCALER_DIV4 TIM_ETRPRESCALER_DIV4 /*!< Prescaler for External ETR Clock: Capture performed once every 4 events. */
+#define TIM_CLOCKPRESCALER_DIV8 TIM_ETRPRESCALER_DIV8 /*!< Prescaler for External ETR Clock: Capture performed once every 8 events. */
+/**
+ * @}
+ */
+
+/** @defgroup TIM_ClearInput_Polarity TIM Clear Input Polarity
+ * @{
+ */
+#define TIM_CLEARINPUTPOLARITY_INVERTED TIM_ETRPOLARITY_INVERTED /*!< Polarity for ETRx pin */
+#define TIM_CLEARINPUTPOLARITY_NONINVERTED TIM_ETRPOLARITY_NONINVERTED /*!< Polarity for ETRx pin */
+/**
+ * @}
+ */
+
+/** @defgroup TIM_ClearInput_Prescaler TIM Clear Input Prescaler
+ * @{
+ */
+#define TIM_CLEARINPUTPRESCALER_DIV1 TIM_ETRPRESCALER_DIV1 /*!< No prescaler is used */
+#define TIM_CLEARINPUTPRESCALER_DIV2 TIM_ETRPRESCALER_DIV2 /*!< Prescaler for External ETR pin: Capture performed once every 2 events. */
+#define TIM_CLEARINPUTPRESCALER_DIV4 TIM_ETRPRESCALER_DIV4 /*!< Prescaler for External ETR pin: Capture performed once every 4 events. */
+#define TIM_CLEARINPUTPRESCALER_DIV8 TIM_ETRPRESCALER_DIV8 /*!< Prescaler for External ETR pin: Capture performed once every 8 events. */
+/**
+ * @}
+ */
+
+/** @defgroup TIM_OSSR_Off_State_Selection_for_Run_mode_state TIM OSSR OffState Selection for Run mode state
+ * @{
+ */
+#define TIM_OSSR_ENABLE TIM_BDTR_OSSR /*!< When inactive, OC/OCN outputs are enabled (still controlled by the timer) */
+#define TIM_OSSR_DISABLE 0x00000000U /*!< When inactive, OC/OCN outputs are disabled (not controlled any longer by the timer) */
+/**
+ * @}
+ */
+
+/** @defgroup TIM_OSSI_Off_State_Selection_for_Idle_mode_state TIM OSSI OffState Selection for Idle mode state
+ * @{
+ */
+#define TIM_OSSI_ENABLE TIM_BDTR_OSSI /*!< When inactive, OC/OCN outputs are enabled (still controlled by the timer) */
+#define TIM_OSSI_DISABLE 0x00000000U /*!< When inactive, OC/OCN outputs are disabled (not controlled any longer by the timer) */
+/**
+ * @}
+ */
+/** @defgroup TIM_Lock_level TIM Lock level
+ * @{
+ */
+#define TIM_LOCKLEVEL_OFF 0x00000000U /*!< LOCK OFF */
+#define TIM_LOCKLEVEL_1 TIM_BDTR_LOCK_0 /*!< LOCK Level 1 */
+#define TIM_LOCKLEVEL_2 TIM_BDTR_LOCK_1 /*!< LOCK Level 2 */
+#define TIM_LOCKLEVEL_3 TIM_BDTR_LOCK /*!< LOCK Level 3 */
+/**
+ * @}
+ */
+
+/** @defgroup TIM_Break_Input_enable_disable TIM Break Input Enable
+ * @{
+ */
+#define TIM_BREAK_ENABLE TIM_BDTR_BKE /*!< Break input BRK is enabled */
+#define TIM_BREAK_DISABLE 0x00000000U /*!< Break input BRK is disabled */
+/**
+ * @}
+ */
+
+/** @defgroup TIM_Break_Polarity TIM Break Input Polarity
+ * @{
+ */
+#define TIM_BREAKPOLARITY_LOW 0x00000000U /*!< Break input BRK is active low */
+#define TIM_BREAKPOLARITY_HIGH TIM_BDTR_BKP /*!< Break input BRK is active high */
+/**
+ * @}
+ */
+
+/** @defgroup TIM_AOE_Bit_Set_Reset TIM Automatic Output Enable
+ * @{
+ */
+#define TIM_AUTOMATICOUTPUT_DISABLE 0x00000000U /*!< MOE can be set only by software */
+#define TIM_AUTOMATICOUTPUT_ENABLE TIM_BDTR_AOE /*!< MOE can be set by software or automatically at the next update event (if none of the break inputs BRK and BRK2 is active) */
+/**
+ * @}
+ */
+
+/** @defgroup TIM_Master_Mode_Selection TIM Master Mode Selection
+ * @{
+ */
+#define TIM_TRGO_RESET 0x00000000U /*!< TIMx_EGR.UG bit is used as trigger output (TRGO) */
+#define TIM_TRGO_ENABLE TIM_CR2_MMS_0 /*!< TIMx_CR1.CEN bit is used as trigger output (TRGO) */
+#define TIM_TRGO_UPDATE TIM_CR2_MMS_1 /*!< Update event is used as trigger output (TRGO) */
+#define TIM_TRGO_OC1 (TIM_CR2_MMS_1 | TIM_CR2_MMS_0) /*!< Capture or a compare match 1 is used as trigger output (TRGO) */
+#define TIM_TRGO_OC1REF TIM_CR2_MMS_2 /*!< OC1REF signal is used as trigger output (TRGO) */
+#define TIM_TRGO_OC2REF (TIM_CR2_MMS_2 | TIM_CR2_MMS_0) /*!< OC2REF signal is used as trigger output(TRGO) */
+#define TIM_TRGO_OC3REF (TIM_CR2_MMS_2 | TIM_CR2_MMS_1) /*!< OC3REF signal is used as trigger output(TRGO) */
+#define TIM_TRGO_OC4REF (TIM_CR2_MMS_2 | TIM_CR2_MMS_1 | TIM_CR2_MMS_0) /*!< OC4REF signal is used as trigger output(TRGO) */
+/**
+ * @}
+ */
+
+/** @defgroup TIM_Master_Slave_Mode TIM Master/Slave Mode
+ * @{
+ */
+#define TIM_MASTERSLAVEMODE_ENABLE TIM_SMCR_MSM /*!< No action */
+#define TIM_MASTERSLAVEMODE_DISABLE 0x00000000U /*!< Master/slave mode is selected */
+/**
+ * @}
+ */
+
+/** @defgroup TIM_Slave_Mode TIM Slave mode
+ * @{
+ */
+#define TIM_SLAVEMODE_DISABLE 0x00000000U /*!< Slave mode disabled */
+#define TIM_SLAVEMODE_RESET TIM_SMCR_SMS_2 /*!< Reset Mode */
+#define TIM_SLAVEMODE_GATED (TIM_SMCR_SMS_2 | TIM_SMCR_SMS_0) /*!< Gated Mode */
+#define TIM_SLAVEMODE_TRIGGER (TIM_SMCR_SMS_2 | TIM_SMCR_SMS_1) /*!< Trigger Mode */
+#define TIM_SLAVEMODE_EXTERNAL1 (TIM_SMCR_SMS_2 | TIM_SMCR_SMS_1 | TIM_SMCR_SMS_0) /*!< External Clock Mode 1 */
+/**
+ * @}
+ */
+
+/** @defgroup TIM_Output_Compare_and_PWM_modes TIM Output Compare and PWM Modes
+ * @{
+ */
+#define TIM_OCMODE_TIMING 0x00000000U /*!< Frozen */
+#define TIM_OCMODE_ACTIVE TIM_CCMR1_OC1M_0 /*!< Set channel to active level on match */
+#define TIM_OCMODE_INACTIVE TIM_CCMR1_OC1M_1 /*!< Set channel to inactive level on match */
+#define TIM_OCMODE_TOGGLE (TIM_CCMR1_OC1M_1 | TIM_CCMR1_OC1M_0) /*!< Toggle */
+#define TIM_OCMODE_PWM1 (TIM_CCMR1_OC1M_2 | TIM_CCMR1_OC1M_1) /*!< PWM mode 1 */
+#define TIM_OCMODE_PWM2 (TIM_CCMR1_OC1M_2 | TIM_CCMR1_OC1M_1 | TIM_CCMR1_OC1M_0) /*!< PWM mode 2 */
+#define TIM_OCMODE_FORCED_ACTIVE (TIM_CCMR1_OC1M_2 | TIM_CCMR1_OC1M_0) /*!< Force active level */
+#define TIM_OCMODE_FORCED_INACTIVE TIM_CCMR1_OC1M_2 /*!< Force inactive level */
+/**
+ * @}
+ */
+
+/** @defgroup TIM_Trigger_Selection TIM Trigger Selection
+ * @{
+ */
+#define TIM_TS_ITR0 0x00000000U /*!< Internal Trigger 0 (ITR0) */
+#define TIM_TS_ITR1 TIM_SMCR_TS_0 /*!< Internal Trigger 1 (ITR1) */
+#define TIM_TS_ITR2 TIM_SMCR_TS_1 /*!< Internal Trigger 2 (ITR2) */
+#define TIM_TS_ITR3 (TIM_SMCR_TS_0 | TIM_SMCR_TS_1) /*!< Internal Trigger 3 (ITR3) */
+#define TIM_TS_TI1F_ED TIM_SMCR_TS_2 /*!< TI1 Edge Detector (TI1F_ED) */
+#define TIM_TS_TI1FP1 (TIM_SMCR_TS_0 | TIM_SMCR_TS_2) /*!< Filtered Timer Input 1 (TI1FP1) */
+#define TIM_TS_TI2FP2 (TIM_SMCR_TS_1 | TIM_SMCR_TS_2) /*!< Filtered Timer Input 2 (TI2FP2) */
+#define TIM_TS_ETRF (TIM_SMCR_TS_0 | TIM_SMCR_TS_1 | TIM_SMCR_TS_2) /*!< Filtered External Trigger input (ETRF) */
+#define TIM_TS_NONE 0x0000FFFFU /*!< No trigger selected */
+/**
+ * @}
+ */
+
+/** @defgroup TIM_Trigger_Polarity TIM Trigger Polarity
+ * @{
+ */
+#define TIM_TRIGGERPOLARITY_INVERTED TIM_ETRPOLARITY_INVERTED /*!< Polarity for ETRx trigger sources */
+#define TIM_TRIGGERPOLARITY_NONINVERTED TIM_ETRPOLARITY_NONINVERTED /*!< Polarity for ETRx trigger sources */
+#define TIM_TRIGGERPOLARITY_RISING TIM_INPUTCHANNELPOLARITY_RISING /*!< Polarity for TIxFPx or TI1_ED trigger sources */
+#define TIM_TRIGGERPOLARITY_FALLING TIM_INPUTCHANNELPOLARITY_FALLING /*!< Polarity for TIxFPx or TI1_ED trigger sources */
+#define TIM_TRIGGERPOLARITY_BOTHEDGE TIM_INPUTCHANNELPOLARITY_BOTHEDGE /*!< Polarity for TIxFPx or TI1_ED trigger sources */
+/**
+ * @}
+ */
+
+/** @defgroup TIM_Trigger_Prescaler TIM Trigger Prescaler
+ * @{
+ */
+#define TIM_TRIGGERPRESCALER_DIV1 TIM_ETRPRESCALER_DIV1 /*!< No prescaler is used */
+#define TIM_TRIGGERPRESCALER_DIV2 TIM_ETRPRESCALER_DIV2 /*!< Prescaler for External ETR Trigger: Capture performed once every 2 events. */
+#define TIM_TRIGGERPRESCALER_DIV4 TIM_ETRPRESCALER_DIV4 /*!< Prescaler for External ETR Trigger: Capture performed once every 4 events. */
+#define TIM_TRIGGERPRESCALER_DIV8 TIM_ETRPRESCALER_DIV8 /*!< Prescaler for External ETR Trigger: Capture performed once every 8 events. */
+/**
+ * @}
+ */
+
+/** @defgroup TIM_TI1_Selection TIM TI1 Input Selection
+ * @{
+ */
+#define TIM_TI1SELECTION_CH1 0x00000000U /*!< The TIMx_CH1 pin is connected to TI1 input */
+#define TIM_TI1SELECTION_XORCOMBINATION TIM_CR2_TI1S /*!< The TIMx_CH1, CH2 and CH3 pins are connected to the TI1 input (XOR combination) */
+/**
+ * @}
+ */
+
+/** @defgroup TIM_DMA_Burst_Length TIM DMA Burst Length
+ * @{
+ */
+#define TIM_DMABURSTLENGTH_1TRANSFER 0x00000000U /*!< The transfer is done to 1 register starting from TIMx_CR1 + TIMx_DCR.DBA */
+#define TIM_DMABURSTLENGTH_2TRANSFERS 0x00000100U /*!< The transfer is done to 2 registers starting from TIMx_CR1 + TIMx_DCR.DBA */
+#define TIM_DMABURSTLENGTH_3TRANSFERS 0x00000200U /*!< The transfer is done to 3 registers starting from TIMx_CR1 + TIMx_DCR.DBA */
+#define TIM_DMABURSTLENGTH_4TRANSFERS 0x00000300U /*!< The transfer is done to 4 registers starting from TIMx_CR1 + TIMx_DCR.DBA */
+#define TIM_DMABURSTLENGTH_5TRANSFERS 0x00000400U /*!< The transfer is done to 5 registers starting from TIMx_CR1 + TIMx_DCR.DBA */
+#define TIM_DMABURSTLENGTH_6TRANSFERS 0x00000500U /*!< The transfer is done to 6 registers starting from TIMx_CR1 + TIMx_DCR.DBA */
+#define TIM_DMABURSTLENGTH_7TRANSFERS 0x00000600U /*!< The transfer is done to 7 registers starting from TIMx_CR1 + TIMx_DCR.DBA */
+#define TIM_DMABURSTLENGTH_8TRANSFERS 0x00000700U /*!< The transfer is done to 8 registers starting from TIMx_CR1 + TIMx_DCR.DBA */
+#define TIM_DMABURSTLENGTH_9TRANSFERS 0x00000800U /*!< The transfer is done to 9 registers starting from TIMx_CR1 + TIMx_DCR.DBA */
+#define TIM_DMABURSTLENGTH_10TRANSFERS 0x00000900U /*!< The transfer is done to 10 registers starting from TIMx_CR1 + TIMx_DCR.DBA */
+#define TIM_DMABURSTLENGTH_11TRANSFERS 0x00000A00U /*!< The transfer is done to 11 registers starting from TIMx_CR1 + TIMx_DCR.DBA */
+#define TIM_DMABURSTLENGTH_12TRANSFERS 0x00000B00U /*!< The transfer is done to 12 registers starting from TIMx_CR1 + TIMx_DCR.DBA */
+#define TIM_DMABURSTLENGTH_13TRANSFERS 0x00000C00U /*!< The transfer is done to 13 registers starting from TIMx_CR1 + TIMx_DCR.DBA */
+#define TIM_DMABURSTLENGTH_14TRANSFERS 0x00000D00U /*!< The transfer is done to 14 registers starting from TIMx_CR1 + TIMx_DCR.DBA */
+#define TIM_DMABURSTLENGTH_15TRANSFERS 0x00000E00U /*!< The transfer is done to 15 registers starting from TIMx_CR1 + TIMx_DCR.DBA */
+#define TIM_DMABURSTLENGTH_16TRANSFERS 0x00000F00U /*!< The transfer is done to 16 registers starting from TIMx_CR1 + TIMx_DCR.DBA */
+#define TIM_DMABURSTLENGTH_17TRANSFERS 0x00001000U /*!< The transfer is done to 17 registers starting from TIMx_CR1 + TIMx_DCR.DBA */
+#define TIM_DMABURSTLENGTH_18TRANSFERS 0x00001100U /*!< The transfer is done to 18 registers starting from TIMx_CR1 + TIMx_DCR.DBA */
+/**
+ * @}
+ */
+
+/** @defgroup DMA_Handle_index TIM DMA Handle Index
+ * @{
+ */
+#define TIM_DMA_ID_UPDATE ((uint16_t) 0x0000) /*!< Index of the DMA handle used for Update DMA requests */
+#define TIM_DMA_ID_CC1 ((uint16_t) 0x0001) /*!< Index of the DMA handle used for Capture/Compare 1 DMA requests */
+#define TIM_DMA_ID_CC2 ((uint16_t) 0x0002) /*!< Index of the DMA handle used for Capture/Compare 2 DMA requests */
+#define TIM_DMA_ID_CC3 ((uint16_t) 0x0003) /*!< Index of the DMA handle used for Capture/Compare 3 DMA requests */
+#define TIM_DMA_ID_CC4 ((uint16_t) 0x0004) /*!< Index of the DMA handle used for Capture/Compare 4 DMA requests */
+#define TIM_DMA_ID_COMMUTATION ((uint16_t) 0x0005) /*!< Index of the DMA handle used for Commutation DMA requests */
+#define TIM_DMA_ID_TRIGGER ((uint16_t) 0x0006) /*!< Index of the DMA handle used for Trigger DMA requests */
+/**
+ * @}
+ */
+
+/** @defgroup Channel_CC_State TIM Capture/Compare Channel State
+ * @{
+ */
+#define TIM_CCx_ENABLE 0x00000001U /*!< Input or output channel is enabled */
+#define TIM_CCx_DISABLE 0x00000000U /*!< Input or output channel is disabled */
+#define TIM_CCxN_ENABLE 0x00000004U /*!< Complementary output channel is enabled */
+#define TIM_CCxN_DISABLE 0x00000000U /*!< Complementary output channel is enabled */
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+/* End of exported constants -------------------------------------------------*/
+
+/* Exported macros -----------------------------------------------------------*/
+/** @defgroup TIM_Exported_Macros TIM Exported Macros
+ * @{
+ */
+
+/** @brief Reset TIM handle state.
+ * @param __HANDLE__ TIM handle.
+ * @retval None
+ */
+#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1)
+#define __HAL_TIM_RESET_HANDLE_STATE(__HANDLE__) do { \
+ (__HANDLE__)->State = HAL_TIM_STATE_RESET; \
+ (__HANDLE__)->ChannelState[0] = HAL_TIM_CHANNEL_STATE_RESET; \
+ (__HANDLE__)->ChannelState[1] = HAL_TIM_CHANNEL_STATE_RESET; \
+ (__HANDLE__)->ChannelState[2] = HAL_TIM_CHANNEL_STATE_RESET; \
+ (__HANDLE__)->ChannelState[3] = HAL_TIM_CHANNEL_STATE_RESET; \
+ (__HANDLE__)->ChannelNState[0] = HAL_TIM_CHANNEL_STATE_RESET; \
+ (__HANDLE__)->ChannelNState[1] = HAL_TIM_CHANNEL_STATE_RESET; \
+ (__HANDLE__)->ChannelNState[2] = HAL_TIM_CHANNEL_STATE_RESET; \
+ (__HANDLE__)->ChannelNState[3] = HAL_TIM_CHANNEL_STATE_RESET; \
+ (__HANDLE__)->DMABurstState = HAL_DMA_BURST_STATE_RESET; \
+ (__HANDLE__)->Base_MspInitCallback = NULL; \
+ (__HANDLE__)->Base_MspDeInitCallback = NULL; \
+ (__HANDLE__)->IC_MspInitCallback = NULL; \
+ (__HANDLE__)->IC_MspDeInitCallback = NULL; \
+ (__HANDLE__)->OC_MspInitCallback = NULL; \
+ (__HANDLE__)->OC_MspDeInitCallback = NULL; \
+ (__HANDLE__)->PWM_MspInitCallback = NULL; \
+ (__HANDLE__)->PWM_MspDeInitCallback = NULL; \
+ (__HANDLE__)->OnePulse_MspInitCallback = NULL; \
+ (__HANDLE__)->OnePulse_MspDeInitCallback = NULL; \
+ (__HANDLE__)->Encoder_MspInitCallback = NULL; \
+ (__HANDLE__)->Encoder_MspDeInitCallback = NULL; \
+ (__HANDLE__)->HallSensor_MspInitCallback = NULL; \
+ (__HANDLE__)->HallSensor_MspDeInitCallback = NULL; \
+ } while(0)
+#else
+#define __HAL_TIM_RESET_HANDLE_STATE(__HANDLE__) do { \
+ (__HANDLE__)->State = HAL_TIM_STATE_RESET; \
+ (__HANDLE__)->ChannelState[0] = HAL_TIM_CHANNEL_STATE_RESET; \
+ (__HANDLE__)->ChannelState[1] = HAL_TIM_CHANNEL_STATE_RESET; \
+ (__HANDLE__)->ChannelState[2] = HAL_TIM_CHANNEL_STATE_RESET; \
+ (__HANDLE__)->ChannelState[3] = HAL_TIM_CHANNEL_STATE_RESET; \
+ (__HANDLE__)->ChannelNState[0] = HAL_TIM_CHANNEL_STATE_RESET; \
+ (__HANDLE__)->ChannelNState[1] = HAL_TIM_CHANNEL_STATE_RESET; \
+ (__HANDLE__)->ChannelNState[2] = HAL_TIM_CHANNEL_STATE_RESET; \
+ (__HANDLE__)->ChannelNState[3] = HAL_TIM_CHANNEL_STATE_RESET; \
+ (__HANDLE__)->DMABurstState = HAL_DMA_BURST_STATE_RESET; \
+ } while(0)
+#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */
+
+/**
+ * @brief Enable the TIM peripheral.
+ * @param __HANDLE__ TIM handle
+ * @retval None
+ */
+#define __HAL_TIM_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR1|=(TIM_CR1_CEN))
+
+/**
+ * @brief Enable the TIM main Output.
+ * @param __HANDLE__ TIM handle
+ * @retval None
+ */
+#define __HAL_TIM_MOE_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->BDTR|=(TIM_BDTR_MOE))
+
+/**
+ * @brief Disable the TIM peripheral.
+ * @param __HANDLE__ TIM handle
+ * @retval None
+ */
+#define __HAL_TIM_DISABLE(__HANDLE__) \
+ do { \
+ if (((__HANDLE__)->Instance->CCER & TIM_CCER_CCxE_MASK) == 0UL) \
+ { \
+ if(((__HANDLE__)->Instance->CCER & TIM_CCER_CCxNE_MASK) == 0UL) \
+ { \
+ (__HANDLE__)->Instance->CR1 &= ~(TIM_CR1_CEN); \
+ } \
+ } \
+ } while(0)
+
+/**
+ * @brief Disable the TIM main Output.
+ * @param __HANDLE__ TIM handle
+ * @retval None
+ * @note The Main Output Enable of a timer instance is disabled only if all the CCx and CCxN channels have been
+ * disabled
+ */
+#define __HAL_TIM_MOE_DISABLE(__HANDLE__) \
+ do { \
+ if (((__HANDLE__)->Instance->CCER & TIM_CCER_CCxE_MASK) == 0UL) \
+ { \
+ if(((__HANDLE__)->Instance->CCER & TIM_CCER_CCxNE_MASK) == 0UL) \
+ { \
+ (__HANDLE__)->Instance->BDTR &= ~(TIM_BDTR_MOE); \
+ } \
+ } \
+ } while(0)
+
+/**
+ * @brief Disable the TIM main Output.
+ * @param __HANDLE__ TIM handle
+ * @retval None
+ * @note The Main Output Enable of a timer instance is disabled unconditionally
+ */
+#define __HAL_TIM_MOE_DISABLE_UNCONDITIONALLY(__HANDLE__) (__HANDLE__)->Instance->BDTR &= ~(TIM_BDTR_MOE)
+
+/** @brief Enable the specified TIM interrupt.
+ * @param __HANDLE__ specifies the TIM Handle.
+ * @param __INTERRUPT__ specifies the TIM interrupt source to enable.
+ * This parameter can be one of the following values:
+ * @arg TIM_IT_UPDATE: Update interrupt
+ * @arg TIM_IT_CC1: Capture/Compare 1 interrupt
+ * @arg TIM_IT_CC2: Capture/Compare 2 interrupt
+ * @arg TIM_IT_CC3: Capture/Compare 3 interrupt
+ * @arg TIM_IT_CC4: Capture/Compare 4 interrupt
+ * @arg TIM_IT_COM: Commutation interrupt
+ * @arg TIM_IT_TRIGGER: Trigger interrupt
+ * @arg TIM_IT_BREAK: Break interrupt
+ * @retval None
+ */
+#define __HAL_TIM_ENABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->DIER |= (__INTERRUPT__))
+
+/** @brief Disable the specified TIM interrupt.
+ * @param __HANDLE__ specifies the TIM Handle.
+ * @param __INTERRUPT__ specifies the TIM interrupt source to disable.
+ * This parameter can be one of the following values:
+ * @arg TIM_IT_UPDATE: Update interrupt
+ * @arg TIM_IT_CC1: Capture/Compare 1 interrupt
+ * @arg TIM_IT_CC2: Capture/Compare 2 interrupt
+ * @arg TIM_IT_CC3: Capture/Compare 3 interrupt
+ * @arg TIM_IT_CC4: Capture/Compare 4 interrupt
+ * @arg TIM_IT_COM: Commutation interrupt
+ * @arg TIM_IT_TRIGGER: Trigger interrupt
+ * @arg TIM_IT_BREAK: Break interrupt
+ * @retval None
+ */
+#define __HAL_TIM_DISABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->DIER &= ~(__INTERRUPT__))
+
+/** @brief Enable the specified DMA request.
+ * @param __HANDLE__ specifies the TIM Handle.
+ * @param __DMA__ specifies the TIM DMA request to enable.
+ * This parameter can be one of the following values:
+ * @arg TIM_DMA_UPDATE: Update DMA request
+ * @arg TIM_DMA_CC1: Capture/Compare 1 DMA request
+ * @arg TIM_DMA_CC2: Capture/Compare 2 DMA request
+ * @arg TIM_DMA_CC3: Capture/Compare 3 DMA request
+ * @arg TIM_DMA_CC4: Capture/Compare 4 DMA request
+ * @arg TIM_DMA_COM: Commutation DMA request
+ * @arg TIM_DMA_TRIGGER: Trigger DMA request
+ * @retval None
+ */
+#define __HAL_TIM_ENABLE_DMA(__HANDLE__, __DMA__) ((__HANDLE__)->Instance->DIER |= (__DMA__))
+
+/** @brief Disable the specified DMA request.
+ * @param __HANDLE__ specifies the TIM Handle.
+ * @param __DMA__ specifies the TIM DMA request to disable.
+ * This parameter can be one of the following values:
+ * @arg TIM_DMA_UPDATE: Update DMA request
+ * @arg TIM_DMA_CC1: Capture/Compare 1 DMA request
+ * @arg TIM_DMA_CC2: Capture/Compare 2 DMA request
+ * @arg TIM_DMA_CC3: Capture/Compare 3 DMA request
+ * @arg TIM_DMA_CC4: Capture/Compare 4 DMA request
+ * @arg TIM_DMA_COM: Commutation DMA request
+ * @arg TIM_DMA_TRIGGER: Trigger DMA request
+ * @retval None
+ */
+#define __HAL_TIM_DISABLE_DMA(__HANDLE__, __DMA__) ((__HANDLE__)->Instance->DIER &= ~(__DMA__))
+
+/** @brief Check whether the specified TIM interrupt flag is set or not.
+ * @param __HANDLE__ specifies the TIM Handle.
+ * @param __FLAG__ specifies the TIM interrupt flag to check.
+ * This parameter can be one of the following values:
+ * @arg TIM_FLAG_UPDATE: Update interrupt flag
+ * @arg TIM_FLAG_CC1: Capture/Compare 1 interrupt flag
+ * @arg TIM_FLAG_CC2: Capture/Compare 2 interrupt flag
+ * @arg TIM_FLAG_CC3: Capture/Compare 3 interrupt flag
+ * @arg TIM_FLAG_CC4: Capture/Compare 4 interrupt flag
+ * @arg TIM_FLAG_COM: Commutation interrupt flag
+ * @arg TIM_FLAG_TRIGGER: Trigger interrupt flag
+ * @arg TIM_FLAG_BREAK: Break interrupt flag
+ * @arg TIM_FLAG_CC1OF: Capture/Compare 1 overcapture flag
+ * @arg TIM_FLAG_CC2OF: Capture/Compare 2 overcapture flag
+ * @arg TIM_FLAG_CC3OF: Capture/Compare 3 overcapture flag
+ * @arg TIM_FLAG_CC4OF: Capture/Compare 4 overcapture flag
+ * @retval The new state of __FLAG__ (TRUE or FALSE).
+ */
+#define __HAL_TIM_GET_FLAG(__HANDLE__, __FLAG__) (((__HANDLE__)->Instance->SR &(__FLAG__)) == (__FLAG__))
+
+/** @brief Clear the specified TIM interrupt flag.
+ * @param __HANDLE__ specifies the TIM Handle.
+ * @param __FLAG__ specifies the TIM interrupt flag to clear.
+ * This parameter can be one of the following values:
+ * @arg TIM_FLAG_UPDATE: Update interrupt flag
+ * @arg TIM_FLAG_CC1: Capture/Compare 1 interrupt flag
+ * @arg TIM_FLAG_CC2: Capture/Compare 2 interrupt flag
+ * @arg TIM_FLAG_CC3: Capture/Compare 3 interrupt flag
+ * @arg TIM_FLAG_CC4: Capture/Compare 4 interrupt flag
+ * @arg TIM_FLAG_COM: Commutation interrupt flag
+ * @arg TIM_FLAG_TRIGGER: Trigger interrupt flag
+ * @arg TIM_FLAG_BREAK: Break interrupt flag
+ * @arg TIM_FLAG_CC1OF: Capture/Compare 1 overcapture flag
+ * @arg TIM_FLAG_CC2OF: Capture/Compare 2 overcapture flag
+ * @arg TIM_FLAG_CC3OF: Capture/Compare 3 overcapture flag
+ * @arg TIM_FLAG_CC4OF: Capture/Compare 4 overcapture flag
+ * @retval The new state of __FLAG__ (TRUE or FALSE).
+ */
+#define __HAL_TIM_CLEAR_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->SR = ~(__FLAG__))
+
+/**
+ * @brief Check whether the specified TIM interrupt source is enabled or not.
+ * @param __HANDLE__ TIM handle
+ * @param __INTERRUPT__ specifies the TIM interrupt source to check.
+ * This parameter can be one of the following values:
+ * @arg TIM_IT_UPDATE: Update interrupt
+ * @arg TIM_IT_CC1: Capture/Compare 1 interrupt
+ * @arg TIM_IT_CC2: Capture/Compare 2 interrupt
+ * @arg TIM_IT_CC3: Capture/Compare 3 interrupt
+ * @arg TIM_IT_CC4: Capture/Compare 4 interrupt
+ * @arg TIM_IT_COM: Commutation interrupt
+ * @arg TIM_IT_TRIGGER: Trigger interrupt
+ * @arg TIM_IT_BREAK: Break interrupt
+ * @retval The state of TIM_IT (SET or RESET).
+ */
+#define __HAL_TIM_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) ((((__HANDLE__)->Instance->DIER & (__INTERRUPT__)) \
+ == (__INTERRUPT__)) ? SET : RESET)
+
+/** @brief Clear the TIM interrupt pending bits.
+ * @param __HANDLE__ TIM handle
+ * @param __INTERRUPT__ specifies the interrupt pending bit to clear.
+ * This parameter can be one of the following values:
+ * @arg TIM_IT_UPDATE: Update interrupt
+ * @arg TIM_IT_CC1: Capture/Compare 1 interrupt
+ * @arg TIM_IT_CC2: Capture/Compare 2 interrupt
+ * @arg TIM_IT_CC3: Capture/Compare 3 interrupt
+ * @arg TIM_IT_CC4: Capture/Compare 4 interrupt
+ * @arg TIM_IT_COM: Commutation interrupt
+ * @arg TIM_IT_TRIGGER: Trigger interrupt
+ * @arg TIM_IT_BREAK: Break interrupt
+ * @retval None
+ */
+#define __HAL_TIM_CLEAR_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->SR = ~(__INTERRUPT__))
+
+/**
+ * @brief Indicates whether or not the TIM Counter is used as downcounter.
+ * @param __HANDLE__ TIM handle.
+ * @retval False (Counter used as upcounter) or True (Counter used as downcounter)
+ * @note This macro is particularly useful to get the counting mode when the timer operates in Center-aligned mode
+ * or Encoder mode.
+ */
+#define __HAL_TIM_IS_TIM_COUNTING_DOWN(__HANDLE__) (((__HANDLE__)->Instance->CR1 &(TIM_CR1_DIR)) == (TIM_CR1_DIR))
+
+/**
+ * @brief Set the TIM Prescaler on runtime.
+ * @param __HANDLE__ TIM handle.
+ * @param __PRESC__ specifies the Prescaler new value.
+ * @retval None
+ */
+#define __HAL_TIM_SET_PRESCALER(__HANDLE__, __PRESC__) ((__HANDLE__)->Instance->PSC = (__PRESC__))
+
+/**
+ * @brief Set the TIM Counter Register value on runtime.
+ * @param __HANDLE__ TIM handle.
+ * @param __COUNTER__ specifies the Counter register new value.
+ * @retval None
+ */
+#define __HAL_TIM_SET_COUNTER(__HANDLE__, __COUNTER__) ((__HANDLE__)->Instance->CNT = (__COUNTER__))
+
+/**
+ * @brief Get the TIM Counter Register value on runtime.
+ * @param __HANDLE__ TIM handle.
+ * @retval 16-bit or 32-bit value of the timer counter register (TIMx_CNT)
+ */
+#define __HAL_TIM_GET_COUNTER(__HANDLE__) ((__HANDLE__)->Instance->CNT)
+
+/**
+ * @brief Set the TIM Autoreload Register value on runtime without calling another time any Init function.
+ * @param __HANDLE__ TIM handle.
+ * @param __AUTORELOAD__ specifies the Counter register new value.
+ * @retval None
+ */
+#define __HAL_TIM_SET_AUTORELOAD(__HANDLE__, __AUTORELOAD__) \
+ do{ \
+ (__HANDLE__)->Instance->ARR = (__AUTORELOAD__); \
+ (__HANDLE__)->Init.Period = (__AUTORELOAD__); \
+ } while(0)
+
+/**
+ * @brief Get the TIM Autoreload Register value on runtime.
+ * @param __HANDLE__ TIM handle.
+ * @retval 16-bit or 32-bit value of the timer auto-reload register(TIMx_ARR)
+ */
+#define __HAL_TIM_GET_AUTORELOAD(__HANDLE__) ((__HANDLE__)->Instance->ARR)
+
+/**
+ * @brief Set the TIM Clock Division value on runtime without calling another time any Init function.
+ * @param __HANDLE__ TIM handle.
+ * @param __CKD__ specifies the clock division value.
+ * This parameter can be one of the following value:
+ * @arg TIM_CLOCKDIVISION_DIV1: tDTS=tCK_INT
+ * @arg TIM_CLOCKDIVISION_DIV2: tDTS=2*tCK_INT
+ * @arg TIM_CLOCKDIVISION_DIV4: tDTS=4*tCK_INT
+ * @retval None
+ */
+#define __HAL_TIM_SET_CLOCKDIVISION(__HANDLE__, __CKD__) \
+ do{ \
+ (__HANDLE__)->Instance->CR1 &= (~TIM_CR1_CKD); \
+ (__HANDLE__)->Instance->CR1 |= (__CKD__); \
+ (__HANDLE__)->Init.ClockDivision = (__CKD__); \
+ } while(0)
+
+/**
+ * @brief Get the TIM Clock Division value on runtime.
+ * @param __HANDLE__ TIM handle.
+ * @retval The clock division can be one of the following values:
+ * @arg TIM_CLOCKDIVISION_DIV1: tDTS=tCK_INT
+ * @arg TIM_CLOCKDIVISION_DIV2: tDTS=2*tCK_INT
+ * @arg TIM_CLOCKDIVISION_DIV4: tDTS=4*tCK_INT
+ */
+#define __HAL_TIM_GET_CLOCKDIVISION(__HANDLE__) ((__HANDLE__)->Instance->CR1 & TIM_CR1_CKD)
+
+/**
+ * @brief Set the TIM Input Capture prescaler on runtime without calling another time HAL_TIM_IC_ConfigChannel()
+ * function.
+ * @param __HANDLE__ TIM handle.
+ * @param __CHANNEL__ TIM Channels to be configured.
+ * This parameter can be one of the following values:
+ * @arg TIM_CHANNEL_1: TIM Channel 1 selected
+ * @arg TIM_CHANNEL_2: TIM Channel 2 selected
+ * @arg TIM_CHANNEL_3: TIM Channel 3 selected
+ * @arg TIM_CHANNEL_4: TIM Channel 4 selected
+ * @param __ICPSC__ specifies the Input Capture4 prescaler new value.
+ * This parameter can be one of the following values:
+ * @arg TIM_ICPSC_DIV1: no prescaler
+ * @arg TIM_ICPSC_DIV2: capture is done once every 2 events
+ * @arg TIM_ICPSC_DIV4: capture is done once every 4 events
+ * @arg TIM_ICPSC_DIV8: capture is done once every 8 events
+ * @retval None
+ */
+#define __HAL_TIM_SET_ICPRESCALER(__HANDLE__, __CHANNEL__, __ICPSC__) \
+ do{ \
+ TIM_RESET_ICPRESCALERVALUE((__HANDLE__), (__CHANNEL__)); \
+ TIM_SET_ICPRESCALERVALUE((__HANDLE__), (__CHANNEL__), (__ICPSC__)); \
+ } while(0)
+
+/**
+ * @brief Get the TIM Input Capture prescaler on runtime.
+ * @param __HANDLE__ TIM handle.
+ * @param __CHANNEL__ TIM Channels to be configured.
+ * This parameter can be one of the following values:
+ * @arg TIM_CHANNEL_1: get input capture 1 prescaler value
+ * @arg TIM_CHANNEL_2: get input capture 2 prescaler value
+ * @arg TIM_CHANNEL_3: get input capture 3 prescaler value
+ * @arg TIM_CHANNEL_4: get input capture 4 prescaler value
+ * @retval The input capture prescaler can be one of the following values:
+ * @arg TIM_ICPSC_DIV1: no prescaler
+ * @arg TIM_ICPSC_DIV2: capture is done once every 2 events
+ * @arg TIM_ICPSC_DIV4: capture is done once every 4 events
+ * @arg TIM_ICPSC_DIV8: capture is done once every 8 events
+ */
+#define __HAL_TIM_GET_ICPRESCALER(__HANDLE__, __CHANNEL__) \
+ (((__CHANNEL__) == TIM_CHANNEL_1) ? ((__HANDLE__)->Instance->CCMR1 & TIM_CCMR1_IC1PSC) :\
+ ((__CHANNEL__) == TIM_CHANNEL_2) ? (((__HANDLE__)->Instance->CCMR1 & TIM_CCMR1_IC2PSC) >> 8U) :\
+ ((__CHANNEL__) == TIM_CHANNEL_3) ? ((__HANDLE__)->Instance->CCMR2 & TIM_CCMR2_IC3PSC) :\
+ (((__HANDLE__)->Instance->CCMR2 & TIM_CCMR2_IC4PSC)) >> 8U)
+
+/**
+ * @brief Set the TIM Capture Compare Register value on runtime without calling another time ConfigChannel function.
+ * @param __HANDLE__ TIM handle.
+ * @param __CHANNEL__ TIM Channels to be configured.
+ * This parameter can be one of the following values:
+ * @arg TIM_CHANNEL_1: TIM Channel 1 selected
+ * @arg TIM_CHANNEL_2: TIM Channel 2 selected
+ * @arg TIM_CHANNEL_3: TIM Channel 3 selected
+ * @arg TIM_CHANNEL_4: TIM Channel 4 selected
+ * @param __COMPARE__ specifies the Capture Compare register new value.
+ * @retval None
+ */
+#define __HAL_TIM_SET_COMPARE(__HANDLE__, __CHANNEL__, __COMPARE__) \
+ (((__CHANNEL__) == TIM_CHANNEL_1) ? ((__HANDLE__)->Instance->CCR1 = (__COMPARE__)) :\
+ ((__CHANNEL__) == TIM_CHANNEL_2) ? ((__HANDLE__)->Instance->CCR2 = (__COMPARE__)) :\
+ ((__CHANNEL__) == TIM_CHANNEL_3) ? ((__HANDLE__)->Instance->CCR3 = (__COMPARE__)) :\
+ ((__HANDLE__)->Instance->CCR4 = (__COMPARE__)))
+
+/**
+ * @brief Get the TIM Capture Compare Register value on runtime.
+ * @param __HANDLE__ TIM handle.
+ * @param __CHANNEL__ TIM Channel associated with the capture compare register
+ * This parameter can be one of the following values:
+ * @arg TIM_CHANNEL_1: get capture/compare 1 register value
+ * @arg TIM_CHANNEL_2: get capture/compare 2 register value
+ * @arg TIM_CHANNEL_3: get capture/compare 3 register value
+ * @arg TIM_CHANNEL_4: get capture/compare 4 register value
+ * @retval 16-bit or 32-bit value of the capture/compare register (TIMx_CCRy)
+ */
+#define __HAL_TIM_GET_COMPARE(__HANDLE__, __CHANNEL__) \
+ (((__CHANNEL__) == TIM_CHANNEL_1) ? ((__HANDLE__)->Instance->CCR1) :\
+ ((__CHANNEL__) == TIM_CHANNEL_2) ? ((__HANDLE__)->Instance->CCR2) :\
+ ((__CHANNEL__) == TIM_CHANNEL_3) ? ((__HANDLE__)->Instance->CCR3) :\
+ ((__HANDLE__)->Instance->CCR4))
+
+/**
+ * @brief Set the TIM Output compare preload.
+ * @param __HANDLE__ TIM handle.
+ * @param __CHANNEL__ TIM Channels to be configured.
+ * This parameter can be one of the following values:
+ * @arg TIM_CHANNEL_1: TIM Channel 1 selected
+ * @arg TIM_CHANNEL_2: TIM Channel 2 selected
+ * @arg TIM_CHANNEL_3: TIM Channel 3 selected
+ * @arg TIM_CHANNEL_4: TIM Channel 4 selected
+ * @retval None
+ */
+#define __HAL_TIM_ENABLE_OCxPRELOAD(__HANDLE__, __CHANNEL__) \
+ (((__CHANNEL__) == TIM_CHANNEL_1) ? ((__HANDLE__)->Instance->CCMR1 |= TIM_CCMR1_OC1PE) :\
+ ((__CHANNEL__) == TIM_CHANNEL_2) ? ((__HANDLE__)->Instance->CCMR1 |= TIM_CCMR1_OC2PE) :\
+ ((__CHANNEL__) == TIM_CHANNEL_3) ? ((__HANDLE__)->Instance->CCMR2 |= TIM_CCMR2_OC3PE) :\
+ ((__HANDLE__)->Instance->CCMR2 |= TIM_CCMR2_OC4PE))
+
+/**
+ * @brief Reset the TIM Output compare preload.
+ * @param __HANDLE__ TIM handle.
+ * @param __CHANNEL__ TIM Channels to be configured.
+ * This parameter can be one of the following values:
+ * @arg TIM_CHANNEL_1: TIM Channel 1 selected
+ * @arg TIM_CHANNEL_2: TIM Channel 2 selected
+ * @arg TIM_CHANNEL_3: TIM Channel 3 selected
+ * @arg TIM_CHANNEL_4: TIM Channel 4 selected
+ * @retval None
+ */
+#define __HAL_TIM_DISABLE_OCxPRELOAD(__HANDLE__, __CHANNEL__) \
+ (((__CHANNEL__) == TIM_CHANNEL_1) ? ((__HANDLE__)->Instance->CCMR1 &= ~TIM_CCMR1_OC1PE) :\
+ ((__CHANNEL__) == TIM_CHANNEL_2) ? ((__HANDLE__)->Instance->CCMR1 &= ~TIM_CCMR1_OC2PE) :\
+ ((__CHANNEL__) == TIM_CHANNEL_3) ? ((__HANDLE__)->Instance->CCMR2 &= ~TIM_CCMR2_OC3PE) :\
+ ((__HANDLE__)->Instance->CCMR2 &= ~TIM_CCMR2_OC4PE))
+
+/**
+ * @brief Enable fast mode for a given channel.
+ * @param __HANDLE__ TIM handle.
+ * @param __CHANNEL__ TIM Channels to be configured.
+ * This parameter can be one of the following values:
+ * @arg TIM_CHANNEL_1: TIM Channel 1 selected
+ * @arg TIM_CHANNEL_2: TIM Channel 2 selected
+ * @arg TIM_CHANNEL_3: TIM Channel 3 selected
+ * @arg TIM_CHANNEL_4: TIM Channel 4 selected
+ * @note When fast mode is enabled an active edge on the trigger input acts
+ * like a compare match on CCx output. Delay to sample the trigger
+ * input and to activate CCx output is reduced to 3 clock cycles.
+ * @note Fast mode acts only if the channel is configured in PWM1 or PWM2 mode.
+ * @retval None
+ */
+#define __HAL_TIM_ENABLE_OCxFAST(__HANDLE__, __CHANNEL__) \
+ (((__CHANNEL__) == TIM_CHANNEL_1) ? ((__HANDLE__)->Instance->CCMR1 |= TIM_CCMR1_OC1FE) :\
+ ((__CHANNEL__) == TIM_CHANNEL_2) ? ((__HANDLE__)->Instance->CCMR1 |= TIM_CCMR1_OC2FE) :\
+ ((__CHANNEL__) == TIM_CHANNEL_3) ? ((__HANDLE__)->Instance->CCMR2 |= TIM_CCMR2_OC3FE) :\
+ ((__HANDLE__)->Instance->CCMR2 |= TIM_CCMR2_OC4FE))
+
+/**
+ * @brief Disable fast mode for a given channel.
+ * @param __HANDLE__ TIM handle.
+ * @param __CHANNEL__ TIM Channels to be configured.
+ * This parameter can be one of the following values:
+ * @arg TIM_CHANNEL_1: TIM Channel 1 selected
+ * @arg TIM_CHANNEL_2: TIM Channel 2 selected
+ * @arg TIM_CHANNEL_3: TIM Channel 3 selected
+ * @arg TIM_CHANNEL_4: TIM Channel 4 selected
+ * @note When fast mode is disabled CCx output behaves normally depending
+ * on counter and CCRx values even when the trigger is ON. The minimum
+ * delay to activate CCx output when an active edge occurs on the
+ * trigger input is 5 clock cycles.
+ * @retval None
+ */
+#define __HAL_TIM_DISABLE_OCxFAST(__HANDLE__, __CHANNEL__) \
+ (((__CHANNEL__) == TIM_CHANNEL_1) ? ((__HANDLE__)->Instance->CCMR1 &= ~TIM_CCMR1_OC1FE) :\
+ ((__CHANNEL__) == TIM_CHANNEL_2) ? ((__HANDLE__)->Instance->CCMR1 &= ~TIM_CCMR1_OC2FE) :\
+ ((__CHANNEL__) == TIM_CHANNEL_3) ? ((__HANDLE__)->Instance->CCMR2 &= ~TIM_CCMR2_OC3FE) :\
+ ((__HANDLE__)->Instance->CCMR2 &= ~TIM_CCMR2_OC4FE))
+
+/**
+ * @brief Set the Update Request Source (URS) bit of the TIMx_CR1 register.
+ * @param __HANDLE__ TIM handle.
+ * @note When the URS bit of the TIMx_CR1 register is set, only counter
+ * overflow/underflow generates an update interrupt or DMA request (if
+ * enabled)
+ * @retval None
+ */
+#define __HAL_TIM_URS_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR1|= TIM_CR1_URS)
+
+/**
+ * @brief Reset the Update Request Source (URS) bit of the TIMx_CR1 register.
+ * @param __HANDLE__ TIM handle.
+ * @note When the URS bit of the TIMx_CR1 register is reset, any of the
+ * following events generate an update interrupt or DMA request (if
+ * enabled):
+ * _ Counter overflow underflow
+ * _ Setting the UG bit
+ * _ Update generation through the slave mode controller
+ * @retval None
+ */
+#define __HAL_TIM_URS_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR1&=~TIM_CR1_URS)
+
+/**
+ * @brief Set the TIM Capture x input polarity on runtime.
+ * @param __HANDLE__ TIM handle.
+ * @param __CHANNEL__ TIM Channels to be configured.
+ * This parameter can be one of the following values:
+ * @arg TIM_CHANNEL_1: TIM Channel 1 selected
+ * @arg TIM_CHANNEL_2: TIM Channel 2 selected
+ * @arg TIM_CHANNEL_3: TIM Channel 3 selected
+ * @arg TIM_CHANNEL_4: TIM Channel 4 selected
+ * @param __POLARITY__ Polarity for TIx source
+ * @arg TIM_INPUTCHANNELPOLARITY_RISING: Rising Edge
+ * @arg TIM_INPUTCHANNELPOLARITY_FALLING: Falling Edge
+ * @arg TIM_INPUTCHANNELPOLARITY_BOTHEDGE: Rising and Falling Edge
+ * @retval None
+ */
+#define __HAL_TIM_SET_CAPTUREPOLARITY(__HANDLE__, __CHANNEL__, __POLARITY__) \
+ do{ \
+ TIM_RESET_CAPTUREPOLARITY((__HANDLE__), (__CHANNEL__)); \
+ TIM_SET_CAPTUREPOLARITY((__HANDLE__), (__CHANNEL__), (__POLARITY__)); \
+ }while(0)
+
+/**
+ * @}
+ */
+/* End of exported macros ----------------------------------------------------*/
+
+/* Private constants ---------------------------------------------------------*/
+/** @defgroup TIM_Private_Constants TIM Private Constants
+ * @{
+ */
+/* The counter of a timer instance is disabled only if all the CCx and CCxN
+ channels have been disabled */
+#define TIM_CCER_CCxE_MASK ((uint32_t)(TIM_CCER_CC1E | TIM_CCER_CC2E | TIM_CCER_CC3E | TIM_CCER_CC4E))
+#define TIM_CCER_CCxNE_MASK ((uint32_t)(TIM_CCER_CC1NE | TIM_CCER_CC2NE | TIM_CCER_CC3NE))
+/**
+ * @}
+ */
+/* End of private constants --------------------------------------------------*/
+
+/* Private macros ------------------------------------------------------------*/
+/** @defgroup TIM_Private_Macros TIM Private Macros
+ * @{
+ */
+#define IS_TIM_CLEARINPUT_SOURCE(__MODE__) (((__MODE__) == TIM_CLEARINPUTSOURCE_NONE) || \
+ ((__MODE__) == TIM_CLEARINPUTSOURCE_ETR) || \
+ ((__MODE__) == TIM_CLEARINPUTSOURCE_OCREFCLR))
+
+#define IS_TIM_DMA_BASE(__BASE__) (((__BASE__) == TIM_DMABASE_CR1) || \
+ ((__BASE__) == TIM_DMABASE_CR2) || \
+ ((__BASE__) == TIM_DMABASE_SMCR) || \
+ ((__BASE__) == TIM_DMABASE_DIER) || \
+ ((__BASE__) == TIM_DMABASE_SR) || \
+ ((__BASE__) == TIM_DMABASE_EGR) || \
+ ((__BASE__) == TIM_DMABASE_CCMR1) || \
+ ((__BASE__) == TIM_DMABASE_CCMR2) || \
+ ((__BASE__) == TIM_DMABASE_CCER) || \
+ ((__BASE__) == TIM_DMABASE_CNT) || \
+ ((__BASE__) == TIM_DMABASE_PSC) || \
+ ((__BASE__) == TIM_DMABASE_ARR) || \
+ ((__BASE__) == TIM_DMABASE_RCR) || \
+ ((__BASE__) == TIM_DMABASE_CCR1) || \
+ ((__BASE__) == TIM_DMABASE_CCR2) || \
+ ((__BASE__) == TIM_DMABASE_CCR3) || \
+ ((__BASE__) == TIM_DMABASE_CCR4) || \
+ ((__BASE__) == TIM_DMABASE_BDTR))
+
+#define IS_TIM_EVENT_SOURCE(__SOURCE__) ((((__SOURCE__) & 0xFFFFFF00U) == 0x00000000U) && ((__SOURCE__) != 0x00000000U))
+
+#define IS_TIM_COUNTER_MODE(__MODE__) (((__MODE__) == TIM_COUNTERMODE_UP) || \
+ ((__MODE__) == TIM_COUNTERMODE_DOWN) || \
+ ((__MODE__) == TIM_COUNTERMODE_CENTERALIGNED1) || \
+ ((__MODE__) == TIM_COUNTERMODE_CENTERALIGNED2) || \
+ ((__MODE__) == TIM_COUNTERMODE_CENTERALIGNED3))
+
+#define IS_TIM_CLOCKDIVISION_DIV(__DIV__) (((__DIV__) == TIM_CLOCKDIVISION_DIV1) || \
+ ((__DIV__) == TIM_CLOCKDIVISION_DIV2) || \
+ ((__DIV__) == TIM_CLOCKDIVISION_DIV4))
+
+#define IS_TIM_AUTORELOAD_PRELOAD(PRELOAD) (((PRELOAD) == TIM_AUTORELOAD_PRELOAD_DISABLE) || \
+ ((PRELOAD) == TIM_AUTORELOAD_PRELOAD_ENABLE))
+
+#define IS_TIM_FAST_STATE(__STATE__) (((__STATE__) == TIM_OCFAST_DISABLE) || \
+ ((__STATE__) == TIM_OCFAST_ENABLE))
+
+#define IS_TIM_OC_POLARITY(__POLARITY__) (((__POLARITY__) == TIM_OCPOLARITY_HIGH) || \
+ ((__POLARITY__) == TIM_OCPOLARITY_LOW))
+
+#define IS_TIM_OCN_POLARITY(__POLARITY__) (((__POLARITY__) == TIM_OCNPOLARITY_HIGH) || \
+ ((__POLARITY__) == TIM_OCNPOLARITY_LOW))
+
+#define IS_TIM_OCIDLE_STATE(__STATE__) (((__STATE__) == TIM_OCIDLESTATE_SET) || \
+ ((__STATE__) == TIM_OCIDLESTATE_RESET))
+
+#define IS_TIM_OCNIDLE_STATE(__STATE__) (((__STATE__) == TIM_OCNIDLESTATE_SET) || \
+ ((__STATE__) == TIM_OCNIDLESTATE_RESET))
+
+#define IS_TIM_ENCODERINPUT_POLARITY(__POLARITY__) (((__POLARITY__) == TIM_ENCODERINPUTPOLARITY_RISING) || \
+ ((__POLARITY__) == TIM_ENCODERINPUTPOLARITY_FALLING))
+
+#define IS_TIM_IC_POLARITY(__POLARITY__) (((__POLARITY__) == TIM_ICPOLARITY_RISING) || \
+ ((__POLARITY__) == TIM_ICPOLARITY_FALLING) || \
+ ((__POLARITY__) == TIM_ICPOLARITY_BOTHEDGE))
+
+#define IS_TIM_IC_SELECTION(__SELECTION__) (((__SELECTION__) == TIM_ICSELECTION_DIRECTTI) || \
+ ((__SELECTION__) == TIM_ICSELECTION_INDIRECTTI) || \
+ ((__SELECTION__) == TIM_ICSELECTION_TRC))
+
+#define IS_TIM_IC_PRESCALER(__PRESCALER__) (((__PRESCALER__) == TIM_ICPSC_DIV1) || \
+ ((__PRESCALER__) == TIM_ICPSC_DIV2) || \
+ ((__PRESCALER__) == TIM_ICPSC_DIV4) || \
+ ((__PRESCALER__) == TIM_ICPSC_DIV8))
+
+#define IS_TIM_OPM_MODE(__MODE__) (((__MODE__) == TIM_OPMODE_SINGLE) || \
+ ((__MODE__) == TIM_OPMODE_REPETITIVE))
+
+#define IS_TIM_ENCODER_MODE(__MODE__) (((__MODE__) == TIM_ENCODERMODE_TI1) || \
+ ((__MODE__) == TIM_ENCODERMODE_TI2) || \
+ ((__MODE__) == TIM_ENCODERMODE_TI12))
+
+#define IS_TIM_DMA_SOURCE(__SOURCE__) ((((__SOURCE__) & 0xFFFF80FFU) == 0x00000000U) && ((__SOURCE__) != 0x00000000U))
+
+#define IS_TIM_CHANNELS(__CHANNEL__) (((__CHANNEL__) == TIM_CHANNEL_1) || \
+ ((__CHANNEL__) == TIM_CHANNEL_2) || \
+ ((__CHANNEL__) == TIM_CHANNEL_3) || \
+ ((__CHANNEL__) == TIM_CHANNEL_4) || \
+ ((__CHANNEL__) == TIM_CHANNEL_ALL))
+
+#define IS_TIM_OPM_CHANNELS(__CHANNEL__) (((__CHANNEL__) == TIM_CHANNEL_1) || \
+ ((__CHANNEL__) == TIM_CHANNEL_2))
+
+#define IS_TIM_COMPLEMENTARY_CHANNELS(__CHANNEL__) (((__CHANNEL__) == TIM_CHANNEL_1) || \
+ ((__CHANNEL__) == TIM_CHANNEL_2) || \
+ ((__CHANNEL__) == TIM_CHANNEL_3))
+
+#define IS_TIM_CLOCKSOURCE(__CLOCK__) (((__CLOCK__) == TIM_CLOCKSOURCE_INTERNAL) || \
+ ((__CLOCK__) == TIM_CLOCKSOURCE_ETRMODE2) || \
+ ((__CLOCK__) == TIM_CLOCKSOURCE_ITR0) || \
+ ((__CLOCK__) == TIM_CLOCKSOURCE_ITR1) || \
+ ((__CLOCK__) == TIM_CLOCKSOURCE_ITR2) || \
+ ((__CLOCK__) == TIM_CLOCKSOURCE_ITR3) || \
+ ((__CLOCK__) == TIM_CLOCKSOURCE_TI1ED) || \
+ ((__CLOCK__) == TIM_CLOCKSOURCE_TI1) || \
+ ((__CLOCK__) == TIM_CLOCKSOURCE_TI2) || \
+ ((__CLOCK__) == TIM_CLOCKSOURCE_ETRMODE1))
+
+#define IS_TIM_CLOCKPOLARITY(__POLARITY__) (((__POLARITY__) == TIM_CLOCKPOLARITY_INVERTED) || \
+ ((__POLARITY__) == TIM_CLOCKPOLARITY_NONINVERTED) || \
+ ((__POLARITY__) == TIM_CLOCKPOLARITY_RISING) || \
+ ((__POLARITY__) == TIM_CLOCKPOLARITY_FALLING) || \
+ ((__POLARITY__) == TIM_CLOCKPOLARITY_BOTHEDGE))
+
+#define IS_TIM_CLOCKPRESCALER(__PRESCALER__) (((__PRESCALER__) == TIM_CLOCKPRESCALER_DIV1) || \
+ ((__PRESCALER__) == TIM_CLOCKPRESCALER_DIV2) || \
+ ((__PRESCALER__) == TIM_CLOCKPRESCALER_DIV4) || \
+ ((__PRESCALER__) == TIM_CLOCKPRESCALER_DIV8))
+
+#define IS_TIM_CLOCKFILTER(__ICFILTER__) ((__ICFILTER__) <= 0xFU)
+
+#define IS_TIM_CLEARINPUT_POLARITY(__POLARITY__) (((__POLARITY__) == TIM_CLEARINPUTPOLARITY_INVERTED) || \
+ ((__POLARITY__) == TIM_CLEARINPUTPOLARITY_NONINVERTED))
+
+#define IS_TIM_CLEARINPUT_PRESCALER(__PRESCALER__) (((__PRESCALER__) == TIM_CLEARINPUTPRESCALER_DIV1) || \
+ ((__PRESCALER__) == TIM_CLEARINPUTPRESCALER_DIV2) || \
+ ((__PRESCALER__) == TIM_CLEARINPUTPRESCALER_DIV4) || \
+ ((__PRESCALER__) == TIM_CLEARINPUTPRESCALER_DIV8))
+
+#define IS_TIM_CLEARINPUT_FILTER(__ICFILTER__) ((__ICFILTER__) <= 0xFU)
+
+#define IS_TIM_OSSR_STATE(__STATE__) (((__STATE__) == TIM_OSSR_ENABLE) || \
+ ((__STATE__) == TIM_OSSR_DISABLE))
+
+#define IS_TIM_OSSI_STATE(__STATE__) (((__STATE__) == TIM_OSSI_ENABLE) || \
+ ((__STATE__) == TIM_OSSI_DISABLE))
+
+#define IS_TIM_LOCK_LEVEL(__LEVEL__) (((__LEVEL__) == TIM_LOCKLEVEL_OFF) || \
+ ((__LEVEL__) == TIM_LOCKLEVEL_1) || \
+ ((__LEVEL__) == TIM_LOCKLEVEL_2) || \
+ ((__LEVEL__) == TIM_LOCKLEVEL_3))
+
+#define IS_TIM_BREAK_FILTER(__BRKFILTER__) ((__BRKFILTER__) <= 0xFUL)
+
+
+#define IS_TIM_BREAK_STATE(__STATE__) (((__STATE__) == TIM_BREAK_ENABLE) || \
+ ((__STATE__) == TIM_BREAK_DISABLE))
+
+#define IS_TIM_BREAK_POLARITY(__POLARITY__) (((__POLARITY__) == TIM_BREAKPOLARITY_LOW) || \
+ ((__POLARITY__) == TIM_BREAKPOLARITY_HIGH))
+
+#define IS_TIM_AUTOMATIC_OUTPUT_STATE(__STATE__) (((__STATE__) == TIM_AUTOMATICOUTPUT_ENABLE) || \
+ ((__STATE__) == TIM_AUTOMATICOUTPUT_DISABLE))
+
+#define IS_TIM_TRGO_SOURCE(__SOURCE__) (((__SOURCE__) == TIM_TRGO_RESET) || \
+ ((__SOURCE__) == TIM_TRGO_ENABLE) || \
+ ((__SOURCE__) == TIM_TRGO_UPDATE) || \
+ ((__SOURCE__) == TIM_TRGO_OC1) || \
+ ((__SOURCE__) == TIM_TRGO_OC1REF) || \
+ ((__SOURCE__) == TIM_TRGO_OC2REF) || \
+ ((__SOURCE__) == TIM_TRGO_OC3REF) || \
+ ((__SOURCE__) == TIM_TRGO_OC4REF))
+
+#define IS_TIM_MSM_STATE(__STATE__) (((__STATE__) == TIM_MASTERSLAVEMODE_ENABLE) || \
+ ((__STATE__) == TIM_MASTERSLAVEMODE_DISABLE))
+
+#define IS_TIM_SLAVE_MODE(__MODE__) (((__MODE__) == TIM_SLAVEMODE_DISABLE) || \
+ ((__MODE__) == TIM_SLAVEMODE_RESET) || \
+ ((__MODE__) == TIM_SLAVEMODE_GATED) || \
+ ((__MODE__) == TIM_SLAVEMODE_TRIGGER) || \
+ ((__MODE__) == TIM_SLAVEMODE_EXTERNAL1))
+
+#define IS_TIM_PWM_MODE(__MODE__) (((__MODE__) == TIM_OCMODE_PWM1) || \
+ ((__MODE__) == TIM_OCMODE_PWM2))
+
+#define IS_TIM_OC_MODE(__MODE__) (((__MODE__) == TIM_OCMODE_TIMING) || \
+ ((__MODE__) == TIM_OCMODE_ACTIVE) || \
+ ((__MODE__) == TIM_OCMODE_INACTIVE) || \
+ ((__MODE__) == TIM_OCMODE_TOGGLE) || \
+ ((__MODE__) == TIM_OCMODE_FORCED_ACTIVE) || \
+ ((__MODE__) == TIM_OCMODE_FORCED_INACTIVE))
+
+#define IS_TIM_TRIGGER_SELECTION(__SELECTION__) (((__SELECTION__) == TIM_TS_ITR0) || \
+ ((__SELECTION__) == TIM_TS_ITR1) || \
+ ((__SELECTION__) == TIM_TS_ITR2) || \
+ ((__SELECTION__) == TIM_TS_ITR3) || \
+ ((__SELECTION__) == TIM_TS_TI1F_ED) || \
+ ((__SELECTION__) == TIM_TS_TI1FP1) || \
+ ((__SELECTION__) == TIM_TS_TI2FP2) || \
+ ((__SELECTION__) == TIM_TS_ETRF))
+
+#define IS_TIM_INTERNAL_TRIGGEREVENT_SELECTION(__SELECTION__) (((__SELECTION__) == TIM_TS_ITR0) || \
+ ((__SELECTION__) == TIM_TS_ITR1) || \
+ ((__SELECTION__) == TIM_TS_ITR2) || \
+ ((__SELECTION__) == TIM_TS_ITR3) || \
+ ((__SELECTION__) == TIM_TS_NONE))
+
+#define IS_TIM_TRIGGERPOLARITY(__POLARITY__) (((__POLARITY__) == TIM_TRIGGERPOLARITY_INVERTED ) || \
+ ((__POLARITY__) == TIM_TRIGGERPOLARITY_NONINVERTED) || \
+ ((__POLARITY__) == TIM_TRIGGERPOLARITY_RISING ) || \
+ ((__POLARITY__) == TIM_TRIGGERPOLARITY_FALLING ) || \
+ ((__POLARITY__) == TIM_TRIGGERPOLARITY_BOTHEDGE ))
+
+#define IS_TIM_TRIGGERPRESCALER(__PRESCALER__) (((__PRESCALER__) == TIM_TRIGGERPRESCALER_DIV1) || \
+ ((__PRESCALER__) == TIM_TRIGGERPRESCALER_DIV2) || \
+ ((__PRESCALER__) == TIM_TRIGGERPRESCALER_DIV4) || \
+ ((__PRESCALER__) == TIM_TRIGGERPRESCALER_DIV8))
+
+#define IS_TIM_TRIGGERFILTER(__ICFILTER__) ((__ICFILTER__) <= 0xFU)
+
+#define IS_TIM_TI1SELECTION(__TI1SELECTION__) (((__TI1SELECTION__) == TIM_TI1SELECTION_CH1) || \
+ ((__TI1SELECTION__) == TIM_TI1SELECTION_XORCOMBINATION))
+
+#define IS_TIM_DMA_LENGTH(__LENGTH__) (((__LENGTH__) == TIM_DMABURSTLENGTH_1TRANSFER) || \
+ ((__LENGTH__) == TIM_DMABURSTLENGTH_2TRANSFERS) || \
+ ((__LENGTH__) == TIM_DMABURSTLENGTH_3TRANSFERS) || \
+ ((__LENGTH__) == TIM_DMABURSTLENGTH_4TRANSFERS) || \
+ ((__LENGTH__) == TIM_DMABURSTLENGTH_5TRANSFERS) || \
+ ((__LENGTH__) == TIM_DMABURSTLENGTH_6TRANSFERS) || \
+ ((__LENGTH__) == TIM_DMABURSTLENGTH_7TRANSFERS) || \
+ ((__LENGTH__) == TIM_DMABURSTLENGTH_8TRANSFERS) || \
+ ((__LENGTH__) == TIM_DMABURSTLENGTH_9TRANSFERS) || \
+ ((__LENGTH__) == TIM_DMABURSTLENGTH_10TRANSFERS) || \
+ ((__LENGTH__) == TIM_DMABURSTLENGTH_11TRANSFERS) || \
+ ((__LENGTH__) == TIM_DMABURSTLENGTH_12TRANSFERS) || \
+ ((__LENGTH__) == TIM_DMABURSTLENGTH_13TRANSFERS) || \
+ ((__LENGTH__) == TIM_DMABURSTLENGTH_14TRANSFERS) || \
+ ((__LENGTH__) == TIM_DMABURSTLENGTH_15TRANSFERS) || \
+ ((__LENGTH__) == TIM_DMABURSTLENGTH_16TRANSFERS) || \
+ ((__LENGTH__) == TIM_DMABURSTLENGTH_17TRANSFERS) || \
+ ((__LENGTH__) == TIM_DMABURSTLENGTH_18TRANSFERS))
+
+#define IS_TIM_DMA_DATA_LENGTH(LENGTH) (((LENGTH) >= 0x1U) && ((LENGTH) < 0x10000U))
+
+#define IS_TIM_IC_FILTER(__ICFILTER__) ((__ICFILTER__) <= 0xFU)
+
+#define IS_TIM_DEADTIME(__DEADTIME__) ((__DEADTIME__) <= 0xFFU)
+
+#define IS_TIM_SLAVEMODE_TRIGGER_ENABLED(__TRIGGER__) ((__TRIGGER__) == TIM_SLAVEMODE_TRIGGER)
+
+#define TIM_SET_ICPRESCALERVALUE(__HANDLE__, __CHANNEL__, __ICPSC__) \
+ (((__CHANNEL__) == TIM_CHANNEL_1) ? ((__HANDLE__)->Instance->CCMR1 |= (__ICPSC__)) :\
+ ((__CHANNEL__) == TIM_CHANNEL_2) ? ((__HANDLE__)->Instance->CCMR1 |= ((__ICPSC__) << 8U)) :\
+ ((__CHANNEL__) == TIM_CHANNEL_3) ? ((__HANDLE__)->Instance->CCMR2 |= (__ICPSC__)) :\
+ ((__HANDLE__)->Instance->CCMR2 |= ((__ICPSC__) << 8U)))
+
+#define TIM_RESET_ICPRESCALERVALUE(__HANDLE__, __CHANNEL__) \
+ (((__CHANNEL__) == TIM_CHANNEL_1) ? ((__HANDLE__)->Instance->CCMR1 &= ~TIM_CCMR1_IC1PSC) :\
+ ((__CHANNEL__) == TIM_CHANNEL_2) ? ((__HANDLE__)->Instance->CCMR1 &= ~TIM_CCMR1_IC2PSC) :\
+ ((__CHANNEL__) == TIM_CHANNEL_3) ? ((__HANDLE__)->Instance->CCMR2 &= ~TIM_CCMR2_IC3PSC) :\
+ ((__HANDLE__)->Instance->CCMR2 &= ~TIM_CCMR2_IC4PSC))
+
+#define TIM_SET_CAPTUREPOLARITY(__HANDLE__, __CHANNEL__, __POLARITY__) \
+ (((__CHANNEL__) == TIM_CHANNEL_1) ? ((__HANDLE__)->Instance->CCER |= (__POLARITY__)) :\
+ ((__CHANNEL__) == TIM_CHANNEL_2) ? ((__HANDLE__)->Instance->CCER |= ((__POLARITY__) << 4U)) :\
+ ((__CHANNEL__) == TIM_CHANNEL_3) ? ((__HANDLE__)->Instance->CCER |= ((__POLARITY__) << 8U)) :\
+ ((__HANDLE__)->Instance->CCER |= (((__POLARITY__) << 12U))))
+
+#define TIM_RESET_CAPTUREPOLARITY(__HANDLE__, __CHANNEL__) \
+ (((__CHANNEL__) == TIM_CHANNEL_1) ? ((__HANDLE__)->Instance->CCER &= ~(TIM_CCER_CC1P | TIM_CCER_CC1NP)) :\
+ ((__CHANNEL__) == TIM_CHANNEL_2) ? ((__HANDLE__)->Instance->CCER &= ~(TIM_CCER_CC2P | TIM_CCER_CC2NP)) :\
+ ((__CHANNEL__) == TIM_CHANNEL_3) ? ((__HANDLE__)->Instance->CCER &= ~(TIM_CCER_CC3P | TIM_CCER_CC3NP)) :\
+ ((__HANDLE__)->Instance->CCER &= ~(TIM_CCER_CC4P | TIM_CCER_CC4NP)))
+
+#define TIM_CHANNEL_STATE_GET(__HANDLE__, __CHANNEL__)\
+ (((__CHANNEL__) == TIM_CHANNEL_1) ? (__HANDLE__)->ChannelState[0] :\
+ ((__CHANNEL__) == TIM_CHANNEL_2) ? (__HANDLE__)->ChannelState[1] :\
+ ((__CHANNEL__) == TIM_CHANNEL_3) ? (__HANDLE__)->ChannelState[2] :\
+ (__HANDLE__)->ChannelState[3])
+
+#define TIM_CHANNEL_STATE_SET(__HANDLE__, __CHANNEL__, __CHANNEL_STATE__) \
+ (((__CHANNEL__) == TIM_CHANNEL_1) ? ((__HANDLE__)->ChannelState[0] = (__CHANNEL_STATE__)) :\
+ ((__CHANNEL__) == TIM_CHANNEL_2) ? ((__HANDLE__)->ChannelState[1] = (__CHANNEL_STATE__)) :\
+ ((__CHANNEL__) == TIM_CHANNEL_3) ? ((__HANDLE__)->ChannelState[2] = (__CHANNEL_STATE__)) :\
+ ((__HANDLE__)->ChannelState[3] = (__CHANNEL_STATE__)))
+
+#define TIM_CHANNEL_STATE_SET_ALL(__HANDLE__, __CHANNEL_STATE__) do { \
+ (__HANDLE__)->ChannelState[0] = (__CHANNEL_STATE__); \
+ (__HANDLE__)->ChannelState[1] = (__CHANNEL_STATE__); \
+ (__HANDLE__)->ChannelState[2] = (__CHANNEL_STATE__); \
+ (__HANDLE__)->ChannelState[3] = (__CHANNEL_STATE__); \
+ } while(0)
+
+#define TIM_CHANNEL_N_STATE_GET(__HANDLE__, __CHANNEL__)\
+ (((__CHANNEL__) == TIM_CHANNEL_1) ? (__HANDLE__)->ChannelNState[0] :\
+ ((__CHANNEL__) == TIM_CHANNEL_2) ? (__HANDLE__)->ChannelNState[1] :\
+ ((__CHANNEL__) == TIM_CHANNEL_3) ? (__HANDLE__)->ChannelNState[2] :\
+ (__HANDLE__)->ChannelNState[3])
+
+#define TIM_CHANNEL_N_STATE_SET(__HANDLE__, __CHANNEL__, __CHANNEL_STATE__) \
+ (((__CHANNEL__) == TIM_CHANNEL_1) ? ((__HANDLE__)->ChannelNState[0] = (__CHANNEL_STATE__)) :\
+ ((__CHANNEL__) == TIM_CHANNEL_2) ? ((__HANDLE__)->ChannelNState[1] = (__CHANNEL_STATE__)) :\
+ ((__CHANNEL__) == TIM_CHANNEL_3) ? ((__HANDLE__)->ChannelNState[2] = (__CHANNEL_STATE__)) :\
+ ((__HANDLE__)->ChannelNState[3] = (__CHANNEL_STATE__)))
+
+#define TIM_CHANNEL_N_STATE_SET_ALL(__HANDLE__, __CHANNEL_STATE__) do { \
+ (__HANDLE__)->ChannelNState[0] = \
+ (__CHANNEL_STATE__); \
+ (__HANDLE__)->ChannelNState[1] = \
+ (__CHANNEL_STATE__); \
+ (__HANDLE__)->ChannelNState[2] = \
+ (__CHANNEL_STATE__); \
+ (__HANDLE__)->ChannelNState[3] = \
+ (__CHANNEL_STATE__); \
+ } while(0)
+
+/**
+ * @}
+ */
+/* End of private macros -----------------------------------------------------*/
+
+/* Include TIM HAL Extended module */
+#include "stm32f0xx_hal_tim_ex.h"
+
+/* Exported functions --------------------------------------------------------*/
+/** @addtogroup TIM_Exported_Functions TIM Exported Functions
+ * @{
+ */
+
+/** @addtogroup TIM_Exported_Functions_Group1 TIM Time Base functions
+ * @brief Time Base functions
+ * @{
+ */
+/* Time Base functions ********************************************************/
+HAL_StatusTypeDef HAL_TIM_Base_Init(TIM_HandleTypeDef *htim);
+HAL_StatusTypeDef HAL_TIM_Base_DeInit(TIM_HandleTypeDef *htim);
+void HAL_TIM_Base_MspInit(TIM_HandleTypeDef *htim);
+void HAL_TIM_Base_MspDeInit(TIM_HandleTypeDef *htim);
+/* Blocking mode: Polling */
+HAL_StatusTypeDef HAL_TIM_Base_Start(TIM_HandleTypeDef *htim);
+HAL_StatusTypeDef HAL_TIM_Base_Stop(TIM_HandleTypeDef *htim);
+/* Non-Blocking mode: Interrupt */
+HAL_StatusTypeDef HAL_TIM_Base_Start_IT(TIM_HandleTypeDef *htim);
+HAL_StatusTypeDef HAL_TIM_Base_Stop_IT(TIM_HandleTypeDef *htim);
+/* Non-Blocking mode: DMA */
+HAL_StatusTypeDef HAL_TIM_Base_Start_DMA(TIM_HandleTypeDef *htim, uint32_t *pData, uint16_t Length);
+HAL_StatusTypeDef HAL_TIM_Base_Stop_DMA(TIM_HandleTypeDef *htim);
+/**
+ * @}
+ */
+
+/** @addtogroup TIM_Exported_Functions_Group2 TIM Output Compare functions
+ * @brief TIM Output Compare functions
+ * @{
+ */
+/* Timer Output Compare functions *********************************************/
+HAL_StatusTypeDef HAL_TIM_OC_Init(TIM_HandleTypeDef *htim);
+HAL_StatusTypeDef HAL_TIM_OC_DeInit(TIM_HandleTypeDef *htim);
+void HAL_TIM_OC_MspInit(TIM_HandleTypeDef *htim);
+void HAL_TIM_OC_MspDeInit(TIM_HandleTypeDef *htim);
+/* Blocking mode: Polling */
+HAL_StatusTypeDef HAL_TIM_OC_Start(TIM_HandleTypeDef *htim, uint32_t Channel);
+HAL_StatusTypeDef HAL_TIM_OC_Stop(TIM_HandleTypeDef *htim, uint32_t Channel);
+/* Non-Blocking mode: Interrupt */
+HAL_StatusTypeDef HAL_TIM_OC_Start_IT(TIM_HandleTypeDef *htim, uint32_t Channel);
+HAL_StatusTypeDef HAL_TIM_OC_Stop_IT(TIM_HandleTypeDef *htim, uint32_t Channel);
+/* Non-Blocking mode: DMA */
+HAL_StatusTypeDef HAL_TIM_OC_Start_DMA(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pData, uint16_t Length);
+HAL_StatusTypeDef HAL_TIM_OC_Stop_DMA(TIM_HandleTypeDef *htim, uint32_t Channel);
+/**
+ * @}
+ */
+
+/** @addtogroup TIM_Exported_Functions_Group3 TIM PWM functions
+ * @brief TIM PWM functions
+ * @{
+ */
+/* Timer PWM functions ********************************************************/
+HAL_StatusTypeDef HAL_TIM_PWM_Init(TIM_HandleTypeDef *htim);
+HAL_StatusTypeDef HAL_TIM_PWM_DeInit(TIM_HandleTypeDef *htim);
+void HAL_TIM_PWM_MspInit(TIM_HandleTypeDef *htim);
+void HAL_TIM_PWM_MspDeInit(TIM_HandleTypeDef *htim);
+/* Blocking mode: Polling */
+HAL_StatusTypeDef HAL_TIM_PWM_Start(TIM_HandleTypeDef *htim, uint32_t Channel);
+HAL_StatusTypeDef HAL_TIM_PWM_Stop(TIM_HandleTypeDef *htim, uint32_t Channel);
+/* Non-Blocking mode: Interrupt */
+HAL_StatusTypeDef HAL_TIM_PWM_Start_IT(TIM_HandleTypeDef *htim, uint32_t Channel);
+HAL_StatusTypeDef HAL_TIM_PWM_Stop_IT(TIM_HandleTypeDef *htim, uint32_t Channel);
+/* Non-Blocking mode: DMA */
+HAL_StatusTypeDef HAL_TIM_PWM_Start_DMA(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pData, uint16_t Length);
+HAL_StatusTypeDef HAL_TIM_PWM_Stop_DMA(TIM_HandleTypeDef *htim, uint32_t Channel);
+/**
+ * @}
+ */
+
+/** @addtogroup TIM_Exported_Functions_Group4 TIM Input Capture functions
+ * @brief TIM Input Capture functions
+ * @{
+ */
+/* Timer Input Capture functions **********************************************/
+HAL_StatusTypeDef HAL_TIM_IC_Init(TIM_HandleTypeDef *htim);
+HAL_StatusTypeDef HAL_TIM_IC_DeInit(TIM_HandleTypeDef *htim);
+void HAL_TIM_IC_MspInit(TIM_HandleTypeDef *htim);
+void HAL_TIM_IC_MspDeInit(TIM_HandleTypeDef *htim);
+/* Blocking mode: Polling */
+HAL_StatusTypeDef HAL_TIM_IC_Start(TIM_HandleTypeDef *htim, uint32_t Channel);
+HAL_StatusTypeDef HAL_TIM_IC_Stop(TIM_HandleTypeDef *htim, uint32_t Channel);
+/* Non-Blocking mode: Interrupt */
+HAL_StatusTypeDef HAL_TIM_IC_Start_IT(TIM_HandleTypeDef *htim, uint32_t Channel);
+HAL_StatusTypeDef HAL_TIM_IC_Stop_IT(TIM_HandleTypeDef *htim, uint32_t Channel);
+/* Non-Blocking mode: DMA */
+HAL_StatusTypeDef HAL_TIM_IC_Start_DMA(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pData, uint16_t Length);
+HAL_StatusTypeDef HAL_TIM_IC_Stop_DMA(TIM_HandleTypeDef *htim, uint32_t Channel);
+/**
+ * @}
+ */
+
+/** @addtogroup TIM_Exported_Functions_Group5 TIM One Pulse functions
+ * @brief TIM One Pulse functions
+ * @{
+ */
+/* Timer One Pulse functions **************************************************/
+HAL_StatusTypeDef HAL_TIM_OnePulse_Init(TIM_HandleTypeDef *htim, uint32_t OnePulseMode);
+HAL_StatusTypeDef HAL_TIM_OnePulse_DeInit(TIM_HandleTypeDef *htim);
+void HAL_TIM_OnePulse_MspInit(TIM_HandleTypeDef *htim);
+void HAL_TIM_OnePulse_MspDeInit(TIM_HandleTypeDef *htim);
+/* Blocking mode: Polling */
+HAL_StatusTypeDef HAL_TIM_OnePulse_Start(TIM_HandleTypeDef *htim, uint32_t OutputChannel);
+HAL_StatusTypeDef HAL_TIM_OnePulse_Stop(TIM_HandleTypeDef *htim, uint32_t OutputChannel);
+/* Non-Blocking mode: Interrupt */
+HAL_StatusTypeDef HAL_TIM_OnePulse_Start_IT(TIM_HandleTypeDef *htim, uint32_t OutputChannel);
+HAL_StatusTypeDef HAL_TIM_OnePulse_Stop_IT(TIM_HandleTypeDef *htim, uint32_t OutputChannel);
+/**
+ * @}
+ */
+
+/** @addtogroup TIM_Exported_Functions_Group6 TIM Encoder functions
+ * @brief TIM Encoder functions
+ * @{
+ */
+/* Timer Encoder functions ****************************************************/
+HAL_StatusTypeDef HAL_TIM_Encoder_Init(TIM_HandleTypeDef *htim, TIM_Encoder_InitTypeDef *sConfig);
+HAL_StatusTypeDef HAL_TIM_Encoder_DeInit(TIM_HandleTypeDef *htim);
+void HAL_TIM_Encoder_MspInit(TIM_HandleTypeDef *htim);
+void HAL_TIM_Encoder_MspDeInit(TIM_HandleTypeDef *htim);
+/* Blocking mode: Polling */
+HAL_StatusTypeDef HAL_TIM_Encoder_Start(TIM_HandleTypeDef *htim, uint32_t Channel);
+HAL_StatusTypeDef HAL_TIM_Encoder_Stop(TIM_HandleTypeDef *htim, uint32_t Channel);
+/* Non-Blocking mode: Interrupt */
+HAL_StatusTypeDef HAL_TIM_Encoder_Start_IT(TIM_HandleTypeDef *htim, uint32_t Channel);
+HAL_StatusTypeDef HAL_TIM_Encoder_Stop_IT(TIM_HandleTypeDef *htim, uint32_t Channel);
+/* Non-Blocking mode: DMA */
+HAL_StatusTypeDef HAL_TIM_Encoder_Start_DMA(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pData1,
+ uint32_t *pData2, uint16_t Length);
+HAL_StatusTypeDef HAL_TIM_Encoder_Stop_DMA(TIM_HandleTypeDef *htim, uint32_t Channel);
+/**
+ * @}
+ */
+
+/** @addtogroup TIM_Exported_Functions_Group7 TIM IRQ handler management
+ * @brief IRQ handler management
+ * @{
+ */
+/* Interrupt Handler functions ***********************************************/
+void HAL_TIM_IRQHandler(TIM_HandleTypeDef *htim);
+/**
+ * @}
+ */
+
+/** @defgroup TIM_Exported_Functions_Group8 TIM Peripheral Control functions
+ * @brief Peripheral Control functions
+ * @{
+ */
+/* Control functions *********************************************************/
+HAL_StatusTypeDef HAL_TIM_OC_ConfigChannel(TIM_HandleTypeDef *htim, TIM_OC_InitTypeDef *sConfig, uint32_t Channel);
+HAL_StatusTypeDef HAL_TIM_PWM_ConfigChannel(TIM_HandleTypeDef *htim, TIM_OC_InitTypeDef *sConfig, uint32_t Channel);
+HAL_StatusTypeDef HAL_TIM_IC_ConfigChannel(TIM_HandleTypeDef *htim, TIM_IC_InitTypeDef *sConfig, uint32_t Channel);
+HAL_StatusTypeDef HAL_TIM_OnePulse_ConfigChannel(TIM_HandleTypeDef *htim, TIM_OnePulse_InitTypeDef *sConfig,
+ uint32_t OutputChannel, uint32_t InputChannel);
+HAL_StatusTypeDef HAL_TIM_ConfigOCrefClear(TIM_HandleTypeDef *htim, TIM_ClearInputConfigTypeDef *sClearInputConfig,
+ uint32_t Channel);
+HAL_StatusTypeDef HAL_TIM_ConfigClockSource(TIM_HandleTypeDef *htim, TIM_ClockConfigTypeDef *sClockSourceConfig);
+HAL_StatusTypeDef HAL_TIM_ConfigTI1Input(TIM_HandleTypeDef *htim, uint32_t TI1_Selection);
+HAL_StatusTypeDef HAL_TIM_SlaveConfigSynchro(TIM_HandleTypeDef *htim, TIM_SlaveConfigTypeDef *sSlaveConfig);
+HAL_StatusTypeDef HAL_TIM_SlaveConfigSynchro_IT(TIM_HandleTypeDef *htim, TIM_SlaveConfigTypeDef *sSlaveConfig);
+HAL_StatusTypeDef HAL_TIM_DMABurst_WriteStart(TIM_HandleTypeDef *htim, uint32_t BurstBaseAddress,
+ uint32_t BurstRequestSrc, uint32_t *BurstBuffer, uint32_t BurstLength);
+HAL_StatusTypeDef HAL_TIM_DMABurst_MultiWriteStart(TIM_HandleTypeDef *htim, uint32_t BurstBaseAddress,
+ uint32_t BurstRequestSrc, uint32_t *BurstBuffer,
+ uint32_t BurstLength, uint32_t DataLength);
+HAL_StatusTypeDef HAL_TIM_DMABurst_WriteStop(TIM_HandleTypeDef *htim, uint32_t BurstRequestSrc);
+HAL_StatusTypeDef HAL_TIM_DMABurst_ReadStart(TIM_HandleTypeDef *htim, uint32_t BurstBaseAddress,
+ uint32_t BurstRequestSrc, uint32_t *BurstBuffer, uint32_t BurstLength);
+HAL_StatusTypeDef HAL_TIM_DMABurst_MultiReadStart(TIM_HandleTypeDef *htim, uint32_t BurstBaseAddress,
+ uint32_t BurstRequestSrc, uint32_t *BurstBuffer,
+ uint32_t BurstLength, uint32_t DataLength);
+HAL_StatusTypeDef HAL_TIM_DMABurst_ReadStop(TIM_HandleTypeDef *htim, uint32_t BurstRequestSrc);
+HAL_StatusTypeDef HAL_TIM_GenerateEvent(TIM_HandleTypeDef *htim, uint32_t EventSource);
+uint32_t HAL_TIM_ReadCapturedValue(TIM_HandleTypeDef *htim, uint32_t Channel);
+/**
+ * @}
+ */
+
+/** @defgroup TIM_Exported_Functions_Group9 TIM Callbacks functions
+ * @brief TIM Callbacks functions
+ * @{
+ */
+/* Callback in non blocking modes (Interrupt and DMA) *************************/
+void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim);
+void HAL_TIM_PeriodElapsedHalfCpltCallback(TIM_HandleTypeDef *htim);
+void HAL_TIM_OC_DelayElapsedCallback(TIM_HandleTypeDef *htim);
+void HAL_TIM_IC_CaptureCallback(TIM_HandleTypeDef *htim);
+void HAL_TIM_IC_CaptureHalfCpltCallback(TIM_HandleTypeDef *htim);
+void HAL_TIM_PWM_PulseFinishedCallback(TIM_HandleTypeDef *htim);
+void HAL_TIM_PWM_PulseFinishedHalfCpltCallback(TIM_HandleTypeDef *htim);
+void HAL_TIM_TriggerCallback(TIM_HandleTypeDef *htim);
+void HAL_TIM_TriggerHalfCpltCallback(TIM_HandleTypeDef *htim);
+void HAL_TIM_ErrorCallback(TIM_HandleTypeDef *htim);
+
+/* Callbacks Register/UnRegister functions ***********************************/
+#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1)
+HAL_StatusTypeDef HAL_TIM_RegisterCallback(TIM_HandleTypeDef *htim, HAL_TIM_CallbackIDTypeDef CallbackID,
+ pTIM_CallbackTypeDef pCallback);
+HAL_StatusTypeDef HAL_TIM_UnRegisterCallback(TIM_HandleTypeDef *htim, HAL_TIM_CallbackIDTypeDef CallbackID);
+#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */
+
+/**
+ * @}
+ */
+
+/** @defgroup TIM_Exported_Functions_Group10 TIM Peripheral State functions
+ * @brief Peripheral State functions
+ * @{
+ */
+/* Peripheral State functions ************************************************/
+HAL_TIM_StateTypeDef HAL_TIM_Base_GetState(TIM_HandleTypeDef *htim);
+HAL_TIM_StateTypeDef HAL_TIM_OC_GetState(TIM_HandleTypeDef *htim);
+HAL_TIM_StateTypeDef HAL_TIM_PWM_GetState(TIM_HandleTypeDef *htim);
+HAL_TIM_StateTypeDef HAL_TIM_IC_GetState(TIM_HandleTypeDef *htim);
+HAL_TIM_StateTypeDef HAL_TIM_OnePulse_GetState(TIM_HandleTypeDef *htim);
+HAL_TIM_StateTypeDef HAL_TIM_Encoder_GetState(TIM_HandleTypeDef *htim);
+
+/* Peripheral Channel state functions ************************************************/
+HAL_TIM_ActiveChannel HAL_TIM_GetActiveChannel(TIM_HandleTypeDef *htim);
+HAL_TIM_ChannelStateTypeDef HAL_TIM_GetChannelState(TIM_HandleTypeDef *htim, uint32_t Channel);
+HAL_TIM_DMABurstStateTypeDef HAL_TIM_DMABurstState(TIM_HandleTypeDef *htim);
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+/* End of exported functions -------------------------------------------------*/
+
+/* Private functions----------------------------------------------------------*/
+/** @defgroup TIM_Private_Functions TIM Private Functions
+ * @{
+ */
+void TIM_Base_SetConfig(TIM_TypeDef *TIMx, TIM_Base_InitTypeDef *Structure);
+void TIM_TI1_SetConfig(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32_t TIM_ICSelection, uint32_t TIM_ICFilter);
+void TIM_OC2_SetConfig(TIM_TypeDef *TIMx, TIM_OC_InitTypeDef *OC_Config);
+void TIM_ETR_SetConfig(TIM_TypeDef *TIMx, uint32_t TIM_ExtTRGPrescaler,
+ uint32_t TIM_ExtTRGPolarity, uint32_t ExtTRGFilter);
+
+void TIM_DMADelayPulseHalfCplt(DMA_HandleTypeDef *hdma);
+void TIM_DMAError(DMA_HandleTypeDef *hdma);
+void TIM_DMACaptureCplt(DMA_HandleTypeDef *hdma);
+void TIM_DMACaptureHalfCplt(DMA_HandleTypeDef *hdma);
+void TIM_CCxChannelCmd(TIM_TypeDef *TIMx, uint32_t Channel, uint32_t ChannelState);
+
+#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1)
+void TIM_ResetCallback(TIM_HandleTypeDef *htim);
+#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */
+
+/**
+ * @}
+ */
+/* End of private functions --------------------------------------------------*/
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* STM32F0xx_HAL_TIM_H */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal_tim_ex.h b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal_tim_ex.h
new file mode 100644
index 0000000..e3098b2
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal_tim_ex.h
@@ -0,0 +1,268 @@
+/**
+ ******************************************************************************
+ * @file stm32f0xx_hal_tim_ex.h
+ * @author MCD Application Team
+ * @brief Header file of TIM HAL Extended module.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2016 STMicroelectronics.
+ * All rights reserved.
+ *
+ * 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 STM32F0xx_HAL_TIM_EX_H
+#define STM32F0xx_HAL_TIM_EX_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f0xx_hal_def.h"
+
+/** @addtogroup STM32F0xx_HAL_Driver
+ * @{
+ */
+
+/** @addtogroup TIMEx
+ * @{
+ */
+
+/* Exported types ------------------------------------------------------------*/
+/** @defgroup TIMEx_Exported_Types TIM Extended Exported Types
+ * @{
+ */
+
+/**
+ * @brief TIM Hall sensor Configuration Structure definition
+ */
+
+typedef struct
+{
+ uint32_t IC1Polarity; /*!< Specifies the active edge of the input signal.
+ This parameter can be a value of @ref TIM_Input_Capture_Polarity */
+
+ uint32_t IC1Prescaler; /*!< Specifies the Input Capture Prescaler.
+ This parameter can be a value of @ref TIM_Input_Capture_Prescaler */
+
+ uint32_t IC1Filter; /*!< Specifies the input capture filter.
+ This parameter can be a number between Min_Data = 0x0 and Max_Data = 0xF */
+
+ uint32_t Commutation_Delay; /*!< Specifies the pulse value to be loaded into the Capture Compare Register.
+ This parameter can be a number between Min_Data = 0x0000 and Max_Data = 0xFFFF */
+} TIM_HallSensor_InitTypeDef;
+/**
+ * @}
+ */
+/* End of exported types -----------------------------------------------------*/
+
+/* Exported constants --------------------------------------------------------*/
+/** @defgroup TIMEx_Exported_Constants TIM Extended Exported Constants
+ * @{
+ */
+
+/** @defgroup TIMEx_Remap TIM Extended Remapping
+ * @{
+ */
+#define TIM_TIM14_GPIO (0x00000000U) /*!< TIM14 TI1 is connected to GPIO */
+#define TIM_TIM14_RTC (0x00000001U) /*!< TIM14 TI1 is connected to RTC_clock */
+#define TIM_TIM14_HSE (0x00000002U) /*!< TIM14 TI1 is connected to HSE/32U */
+#define TIM_TIM14_MCO (0x00000003U) /*!< TIM14 TI1 is connected to MCO */
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+/* End of exported constants -------------------------------------------------*/
+
+/* Exported macro ------------------------------------------------------------*/
+/** @defgroup TIMEx_Exported_Macros TIM Extended Exported Macros
+ * @{
+ */
+
+/**
+ * @}
+ */
+/* End of exported macro -----------------------------------------------------*/
+
+/* Private macro -------------------------------------------------------------*/
+/** @defgroup TIMEx_Private_Macros TIM Extended Private Macros
+ * @{
+ */
+#define IS_TIM_REMAP(__INSTANCE__, __REMAP__) \
+ (((__INSTANCE__) == TIM14) && (((__REMAP__) & 0xFFFFFFFCU) == 0x00000000U))
+
+/**
+ * @}
+ */
+/* End of private macro ------------------------------------------------------*/
+
+/* Exported functions --------------------------------------------------------*/
+/** @addtogroup TIMEx_Exported_Functions TIM Extended Exported Functions
+ * @{
+ */
+
+/** @addtogroup TIMEx_Exported_Functions_Group1 Extended Timer Hall Sensor functions
+ * @brief Timer Hall Sensor functions
+ * @{
+ */
+/* Timer Hall Sensor functions **********************************************/
+HAL_StatusTypeDef HAL_TIMEx_HallSensor_Init(TIM_HandleTypeDef *htim, TIM_HallSensor_InitTypeDef *sConfig);
+HAL_StatusTypeDef HAL_TIMEx_HallSensor_DeInit(TIM_HandleTypeDef *htim);
+
+void HAL_TIMEx_HallSensor_MspInit(TIM_HandleTypeDef *htim);
+void HAL_TIMEx_HallSensor_MspDeInit(TIM_HandleTypeDef *htim);
+
+/* Blocking mode: Polling */
+HAL_StatusTypeDef HAL_TIMEx_HallSensor_Start(TIM_HandleTypeDef *htim);
+HAL_StatusTypeDef HAL_TIMEx_HallSensor_Stop(TIM_HandleTypeDef *htim);
+/* Non-Blocking mode: Interrupt */
+HAL_StatusTypeDef HAL_TIMEx_HallSensor_Start_IT(TIM_HandleTypeDef *htim);
+HAL_StatusTypeDef HAL_TIMEx_HallSensor_Stop_IT(TIM_HandleTypeDef *htim);
+/* Non-Blocking mode: DMA */
+HAL_StatusTypeDef HAL_TIMEx_HallSensor_Start_DMA(TIM_HandleTypeDef *htim, uint32_t *pData, uint16_t Length);
+HAL_StatusTypeDef HAL_TIMEx_HallSensor_Stop_DMA(TIM_HandleTypeDef *htim);
+/**
+ * @}
+ */
+
+/** @addtogroup TIMEx_Exported_Functions_Group2 Extended Timer Complementary Output Compare functions
+ * @brief Timer Complementary Output Compare functions
+ * @{
+ */
+/* Timer Complementary Output Compare functions *****************************/
+/* Blocking mode: Polling */
+HAL_StatusTypeDef HAL_TIMEx_OCN_Start(TIM_HandleTypeDef *htim, uint32_t Channel);
+HAL_StatusTypeDef HAL_TIMEx_OCN_Stop(TIM_HandleTypeDef *htim, uint32_t Channel);
+
+/* Non-Blocking mode: Interrupt */
+HAL_StatusTypeDef HAL_TIMEx_OCN_Start_IT(TIM_HandleTypeDef *htim, uint32_t Channel);
+HAL_StatusTypeDef HAL_TIMEx_OCN_Stop_IT(TIM_HandleTypeDef *htim, uint32_t Channel);
+
+/* Non-Blocking mode: DMA */
+HAL_StatusTypeDef HAL_TIMEx_OCN_Start_DMA(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pData, uint16_t Length);
+HAL_StatusTypeDef HAL_TIMEx_OCN_Stop_DMA(TIM_HandleTypeDef *htim, uint32_t Channel);
+/**
+ * @}
+ */
+
+/** @addtogroup TIMEx_Exported_Functions_Group3 Extended Timer Complementary PWM functions
+ * @brief Timer Complementary PWM functions
+ * @{
+ */
+/* Timer Complementary PWM functions ****************************************/
+/* Blocking mode: Polling */
+HAL_StatusTypeDef HAL_TIMEx_PWMN_Start(TIM_HandleTypeDef *htim, uint32_t Channel);
+HAL_StatusTypeDef HAL_TIMEx_PWMN_Stop(TIM_HandleTypeDef *htim, uint32_t Channel);
+
+/* Non-Blocking mode: Interrupt */
+HAL_StatusTypeDef HAL_TIMEx_PWMN_Start_IT(TIM_HandleTypeDef *htim, uint32_t Channel);
+HAL_StatusTypeDef HAL_TIMEx_PWMN_Stop_IT(TIM_HandleTypeDef *htim, uint32_t Channel);
+/* Non-Blocking mode: DMA */
+HAL_StatusTypeDef HAL_TIMEx_PWMN_Start_DMA(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pData, uint16_t Length);
+HAL_StatusTypeDef HAL_TIMEx_PWMN_Stop_DMA(TIM_HandleTypeDef *htim, uint32_t Channel);
+/**
+ * @}
+ */
+
+/** @addtogroup TIMEx_Exported_Functions_Group4 Extended Timer Complementary One Pulse functions
+ * @brief Timer Complementary One Pulse functions
+ * @{
+ */
+/* Timer Complementary One Pulse functions **********************************/
+/* Blocking mode: Polling */
+HAL_StatusTypeDef HAL_TIMEx_OnePulseN_Start(TIM_HandleTypeDef *htim, uint32_t OutputChannel);
+HAL_StatusTypeDef HAL_TIMEx_OnePulseN_Stop(TIM_HandleTypeDef *htim, uint32_t OutputChannel);
+
+/* Non-Blocking mode: Interrupt */
+HAL_StatusTypeDef HAL_TIMEx_OnePulseN_Start_IT(TIM_HandleTypeDef *htim, uint32_t OutputChannel);
+HAL_StatusTypeDef HAL_TIMEx_OnePulseN_Stop_IT(TIM_HandleTypeDef *htim, uint32_t OutputChannel);
+/**
+ * @}
+ */
+
+/** @addtogroup TIMEx_Exported_Functions_Group5 Extended Peripheral Control functions
+ * @brief Peripheral Control functions
+ * @{
+ */
+/* Extended Control functions ************************************************/
+HAL_StatusTypeDef HAL_TIMEx_ConfigCommutEvent(TIM_HandleTypeDef *htim, uint32_t InputTrigger,
+ uint32_t CommutationSource);
+HAL_StatusTypeDef HAL_TIMEx_ConfigCommutEvent_IT(TIM_HandleTypeDef *htim, uint32_t InputTrigger,
+ uint32_t CommutationSource);
+HAL_StatusTypeDef HAL_TIMEx_ConfigCommutEvent_DMA(TIM_HandleTypeDef *htim, uint32_t InputTrigger,
+ uint32_t CommutationSource);
+HAL_StatusTypeDef HAL_TIMEx_MasterConfigSynchronization(TIM_HandleTypeDef *htim,
+ TIM_MasterConfigTypeDef *sMasterConfig);
+HAL_StatusTypeDef HAL_TIMEx_ConfigBreakDeadTime(TIM_HandleTypeDef *htim,
+ TIM_BreakDeadTimeConfigTypeDef *sBreakDeadTimeConfig);
+HAL_StatusTypeDef HAL_TIMEx_RemapConfig(TIM_HandleTypeDef *htim, uint32_t Remap);
+/**
+ * @}
+ */
+
+/** @addtogroup TIMEx_Exported_Functions_Group6 Extended Callbacks functions
+ * @brief Extended Callbacks functions
+ * @{
+ */
+/* Extended Callback **********************************************************/
+void HAL_TIMEx_CommutCallback(TIM_HandleTypeDef *htim);
+void HAL_TIMEx_CommutHalfCpltCallback(TIM_HandleTypeDef *htim);
+void HAL_TIMEx_BreakCallback(TIM_HandleTypeDef *htim);
+/**
+ * @}
+ */
+
+/** @addtogroup TIMEx_Exported_Functions_Group7 Extended Peripheral State functions
+ * @brief Extended Peripheral State functions
+ * @{
+ */
+/* Extended Peripheral State functions ***************************************/
+HAL_TIM_StateTypeDef HAL_TIMEx_HallSensor_GetState(TIM_HandleTypeDef *htim);
+HAL_TIM_ChannelStateTypeDef HAL_TIMEx_GetChannelNState(TIM_HandleTypeDef *htim, uint32_t ChannelN);
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+/* End of exported functions -------------------------------------------------*/
+
+/* Private functions----------------------------------------------------------*/
+/** @addtogroup TIMEx_Private_Functions TIMEx Private Functions
+ * @{
+ */
+void TIMEx_DMACommutationCplt(DMA_HandleTypeDef *hdma);
+void TIMEx_DMACommutationHalfCplt(DMA_HandleTypeDef *hdma);
+/**
+ * @}
+ */
+/* End of private functions --------------------------------------------------*/
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+#ifdef __cplusplus
+}
+#endif
+
+
+#endif /* STM32F0xx_HAL_TIM_EX_H */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_ll_rcc.h b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_ll_rcc.h
new file mode 100644
index 0000000..0206b9d
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_ll_rcc.h
@@ -0,0 +1,2261 @@
+/**
+ ******************************************************************************
+ * @file stm32f0xx_ll_rcc.h
+ * @author MCD Application Team
+ * @brief Header file of RCC LL module.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2016 STMicroelectronics.
+ * All rights reserved.
+ *
+ * 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 __STM32F0xx_LL_RCC_H
+#define __STM32F0xx_LL_RCC_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f0xx.h"
+
+/** @addtogroup STM32F0xx_LL_Driver
+ * @{
+ */
+
+#if defined(RCC)
+
+/** @defgroup RCC_LL RCC
+ * @{
+ */
+
+/* Private types -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private constants ---------------------------------------------------------*/
+/** @defgroup RCC_LL_Private_Constants RCC Private Constants
+ * @{
+ */
+/* Defines used for the bit position in the register and perform offsets*/
+#define RCC_POSITION_HPRE (uint32_t)4U /*!< field position in register RCC_CFGR */
+#define RCC_POSITION_PPRE1 (uint32_t)8U /*!< field position in register RCC_CFGR */
+#define RCC_POSITION_PLLMUL (uint32_t)18U /*!< field position in register RCC_CFGR */
+#define RCC_POSITION_HSICAL (uint32_t)8U /*!< field position in register RCC_CR */
+#define RCC_POSITION_HSITRIM (uint32_t)3U /*!< field position in register RCC_CR */
+#define RCC_POSITION_HSI14TRIM (uint32_t)3U /*!< field position in register RCC_CR2 */
+#define RCC_POSITION_HSI14CAL (uint32_t)8U /*!< field position in register RCC_CR2 */
+#if defined(RCC_HSI48_SUPPORT)
+#define RCC_POSITION_HSI48CAL (uint32_t)24U /*!< field position in register RCC_CR2 */
+#endif /* RCC_HSI48_SUPPORT */
+#define RCC_POSITION_USART1SW (uint32_t)0U /*!< field position in register RCC_CFGR3 */
+#define RCC_POSITION_USART2SW (uint32_t)16U /*!< field position in register RCC_CFGR3 */
+#define RCC_POSITION_USART3SW (uint32_t)18U /*!< field position in register RCC_CFGR3 */
+
+/**
+ * @}
+ */
+
+/* Private macros ------------------------------------------------------------*/
+#if defined(USE_FULL_LL_DRIVER)
+/** @defgroup RCC_LL_Private_Macros RCC Private Macros
+ * @{
+ */
+/**
+ * @}
+ */
+#endif /*USE_FULL_LL_DRIVER*/
+/* Exported types ------------------------------------------------------------*/
+#if defined(USE_FULL_LL_DRIVER)
+/** @defgroup RCC_LL_Exported_Types RCC Exported Types
+ * @{
+ */
+
+/** @defgroup LL_ES_CLOCK_FREQ Clocks Frequency Structure
+ * @{
+ */
+
+/**
+ * @brief RCC Clocks Frequency Structure
+ */
+typedef struct
+{
+ uint32_t SYSCLK_Frequency; /*!< SYSCLK clock frequency */
+ uint32_t HCLK_Frequency; /*!< HCLK clock frequency */
+ uint32_t PCLK1_Frequency; /*!< PCLK1 clock frequency */
+} LL_RCC_ClocksTypeDef;
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+#endif /* USE_FULL_LL_DRIVER */
+
+/* Exported constants --------------------------------------------------------*/
+/** @defgroup RCC_LL_Exported_Constants RCC Exported Constants
+ * @{
+ */
+
+/** @defgroup RCC_LL_EC_OSC_VALUES Oscillator Values adaptation
+ * @brief Defines used to adapt values of different oscillators
+ * @note These values could be modified in the user environment according to
+ * HW set-up.
+ * @{
+ */
+#if !defined (HSE_VALUE)
+#define HSE_VALUE 8000000U /*!< Value of the HSE oscillator in Hz */
+#endif /* HSE_VALUE */
+
+#if !defined (HSI_VALUE)
+#define HSI_VALUE 8000000U /*!< Value of the HSI oscillator in Hz */
+#endif /* HSI_VALUE */
+
+#if !defined (LSE_VALUE)
+#define LSE_VALUE 32768U /*!< Value of the LSE oscillator in Hz */
+#endif /* LSE_VALUE */
+
+#if !defined (LSI_VALUE)
+#define LSI_VALUE 32000U /*!< Value of the LSI oscillator in Hz */
+#endif /* LSI_VALUE */
+#if defined(RCC_HSI48_SUPPORT)
+
+#if !defined (HSI48_VALUE)
+#define HSI48_VALUE 48000000U /*!< Value of the HSI48 oscillator in Hz */
+#endif /* HSI48_VALUE */
+#endif /* RCC_HSI48_SUPPORT */
+/**
+ * @}
+ */
+
+/** @defgroup RCC_LL_EC_CLEAR_FLAG Clear Flags Defines
+ * @brief Flags defines which can be used with LL_RCC_WriteReg function
+ * @{
+ */
+#define LL_RCC_CIR_LSIRDYC RCC_CIR_LSIRDYC /*!< LSI Ready Interrupt Clear */
+#define LL_RCC_CIR_LSERDYC RCC_CIR_LSERDYC /*!< LSE Ready Interrupt Clear */
+#define LL_RCC_CIR_HSIRDYC RCC_CIR_HSIRDYC /*!< HSI Ready Interrupt Clear */
+#define LL_RCC_CIR_HSERDYC RCC_CIR_HSERDYC /*!< HSE Ready Interrupt Clear */
+#define LL_RCC_CIR_PLLRDYC RCC_CIR_PLLRDYC /*!< PLL Ready Interrupt Clear */
+#define LL_RCC_CIR_HSI14RDYC RCC_CIR_HSI14RDYC /*!< HSI14 Ready Interrupt Clear */
+#if defined(RCC_HSI48_SUPPORT)
+#define LL_RCC_CIR_HSI48RDYC RCC_CIR_HSI48RDYC /*!< HSI48 Ready Interrupt Clear */
+#endif /* RCC_HSI48_SUPPORT */
+#define LL_RCC_CIR_CSSC RCC_CIR_CSSC /*!< Clock Security System Interrupt Clear */
+/**
+ * @}
+ */
+
+/** @defgroup RCC_LL_EC_GET_FLAG Get Flags Defines
+ * @brief Flags defines which can be used with LL_RCC_ReadReg function
+ * @{
+ */
+#define LL_RCC_CIR_LSIRDYF RCC_CIR_LSIRDYF /*!< LSI Ready Interrupt flag */
+#define LL_RCC_CIR_LSERDYF RCC_CIR_LSERDYF /*!< LSE Ready Interrupt flag */
+#define LL_RCC_CIR_HSIRDYF RCC_CIR_HSIRDYF /*!< HSI Ready Interrupt flag */
+#define LL_RCC_CIR_HSERDYF RCC_CIR_HSERDYF /*!< HSE Ready Interrupt flag */
+#define LL_RCC_CIR_PLLRDYF RCC_CIR_PLLRDYF /*!< PLL Ready Interrupt flag */
+#define LL_RCC_CIR_HSI14RDYF RCC_CIR_HSI14RDYF /*!< HSI14 Ready Interrupt flag */
+#if defined(RCC_HSI48_SUPPORT)
+#define LL_RCC_CIR_HSI48RDYF RCC_CIR_HSI48RDYF /*!< HSI48 Ready Interrupt flag */
+#endif /* RCC_HSI48_SUPPORT */
+#define LL_RCC_CIR_CSSF RCC_CIR_CSSF /*!< Clock Security System Interrupt flag */
+#define LL_RCC_CSR_OBLRSTF RCC_CSR_OBLRSTF /*!< OBL reset flag */
+#define LL_RCC_CSR_PINRSTF RCC_CSR_PINRSTF /*!< PIN reset flag */
+#define LL_RCC_CSR_PORRSTF RCC_CSR_PORRSTF /*!< POR/PDR reset flag */
+#define LL_RCC_CSR_SFTRSTF RCC_CSR_SFTRSTF /*!< Software Reset flag */
+#define LL_RCC_CSR_IWDGRSTF RCC_CSR_IWDGRSTF /*!< Independent Watchdog reset flag */
+#define LL_RCC_CSR_WWDGRSTF RCC_CSR_WWDGRSTF /*!< Window watchdog reset flag */
+#define LL_RCC_CSR_LPWRRSTF RCC_CSR_LPWRRSTF /*!< Low-Power reset flag */
+#if defined(RCC_CSR_V18PWRRSTF)
+#define LL_RCC_CSR_V18PWRRSTF RCC_CSR_V18PWRRSTF /*!< Reset flag of the 1.8 V domain. */
+#endif /* RCC_CSR_V18PWRRSTF */
+/**
+ * @}
+ */
+
+/** @defgroup RCC_LL_EC_IT IT Defines
+ * @brief IT defines which can be used with LL_RCC_ReadReg and LL_RCC_WriteReg functions
+ * @{
+ */
+#define LL_RCC_CIR_LSIRDYIE RCC_CIR_LSIRDYIE /*!< LSI Ready Interrupt Enable */
+#define LL_RCC_CIR_LSERDYIE RCC_CIR_LSERDYIE /*!< LSE Ready Interrupt Enable */
+#define LL_RCC_CIR_HSIRDYIE RCC_CIR_HSIRDYIE /*!< HSI Ready Interrupt Enable */
+#define LL_RCC_CIR_HSERDYIE RCC_CIR_HSERDYIE /*!< HSE Ready Interrupt Enable */
+#define LL_RCC_CIR_PLLRDYIE RCC_CIR_PLLRDYIE /*!< PLL Ready Interrupt Enable */
+#define LL_RCC_CIR_HSI14RDYIE RCC_CIR_HSI14RDYIE /*!< HSI14 Ready Interrupt Enable */
+#if defined(RCC_HSI48_SUPPORT)
+#define LL_RCC_CIR_HSI48RDYIE RCC_CIR_HSI48RDYIE /*!< HSI48 Ready Interrupt Enable */
+#endif /* RCC_HSI48_SUPPORT */
+/**
+ * @}
+ */
+
+/** @defgroup RCC_LL_EC_LSEDRIVE LSE oscillator drive capability
+ * @{
+ */
+#define LL_RCC_LSEDRIVE_LOW ((uint32_t)0x00000000U) /*!< Xtal mode lower driving capability */
+#define LL_RCC_LSEDRIVE_MEDIUMLOW RCC_BDCR_LSEDRV_1 /*!< Xtal mode medium low driving capability */
+#define LL_RCC_LSEDRIVE_MEDIUMHIGH RCC_BDCR_LSEDRV_0 /*!< Xtal mode medium high driving capability */
+#define LL_RCC_LSEDRIVE_HIGH RCC_BDCR_LSEDRV /*!< Xtal mode higher driving capability */
+/**
+ * @}
+ */
+
+/** @defgroup RCC_LL_EC_SYS_CLKSOURCE System clock switch
+ * @{
+ */
+#define LL_RCC_SYS_CLKSOURCE_HSI RCC_CFGR_SW_HSI /*!< HSI selection as system clock */
+#define LL_RCC_SYS_CLKSOURCE_HSE RCC_CFGR_SW_HSE /*!< HSE selection as system clock */
+#define LL_RCC_SYS_CLKSOURCE_PLL RCC_CFGR_SW_PLL /*!< PLL selection as system clock */
+#if defined(RCC_CFGR_SW_HSI48)
+#define LL_RCC_SYS_CLKSOURCE_HSI48 RCC_CFGR_SW_HSI48 /*!< HSI48 selection as system clock */
+#endif /* RCC_CFGR_SW_HSI48 */
+/**
+ * @}
+ */
+
+/** @defgroup RCC_LL_EC_SYS_CLKSOURCE_STATUS System clock switch status
+ * @{
+ */
+#define LL_RCC_SYS_CLKSOURCE_STATUS_HSI RCC_CFGR_SWS_HSI /*!< HSI used as system clock */
+#define LL_RCC_SYS_CLKSOURCE_STATUS_HSE RCC_CFGR_SWS_HSE /*!< HSE used as system clock */
+#define LL_RCC_SYS_CLKSOURCE_STATUS_PLL RCC_CFGR_SWS_PLL /*!< PLL used as system clock */
+#if defined(RCC_CFGR_SWS_HSI48)
+#define LL_RCC_SYS_CLKSOURCE_STATUS_HSI48 RCC_CFGR_SWS_HSI48 /*!< HSI48 used as system clock */
+#endif /* RCC_CFGR_SWS_HSI48 */
+/**
+ * @}
+ */
+
+/** @defgroup RCC_LL_EC_SYSCLK_DIV AHB prescaler
+ * @{
+ */
+#define LL_RCC_SYSCLK_DIV_1 RCC_CFGR_HPRE_DIV1 /*!< SYSCLK not divided */
+#define LL_RCC_SYSCLK_DIV_2 RCC_CFGR_HPRE_DIV2 /*!< SYSCLK divided by 2 */
+#define LL_RCC_SYSCLK_DIV_4 RCC_CFGR_HPRE_DIV4 /*!< SYSCLK divided by 4 */
+#define LL_RCC_SYSCLK_DIV_8 RCC_CFGR_HPRE_DIV8 /*!< SYSCLK divided by 8 */
+#define LL_RCC_SYSCLK_DIV_16 RCC_CFGR_HPRE_DIV16 /*!< SYSCLK divided by 16 */
+#define LL_RCC_SYSCLK_DIV_64 RCC_CFGR_HPRE_DIV64 /*!< SYSCLK divided by 64 */
+#define LL_RCC_SYSCLK_DIV_128 RCC_CFGR_HPRE_DIV128 /*!< SYSCLK divided by 128 */
+#define LL_RCC_SYSCLK_DIV_256 RCC_CFGR_HPRE_DIV256 /*!< SYSCLK divided by 256 */
+#define LL_RCC_SYSCLK_DIV_512 RCC_CFGR_HPRE_DIV512 /*!< SYSCLK divided by 512 */
+/**
+ * @}
+ */
+
+/** @defgroup RCC_LL_EC_APB1_DIV APB low-speed prescaler (APB1)
+ * @{
+ */
+#define LL_RCC_APB1_DIV_1 RCC_CFGR_PPRE_DIV1 /*!< HCLK not divided */
+#define LL_RCC_APB1_DIV_2 RCC_CFGR_PPRE_DIV2 /*!< HCLK divided by 2 */
+#define LL_RCC_APB1_DIV_4 RCC_CFGR_PPRE_DIV4 /*!< HCLK divided by 4 */
+#define LL_RCC_APB1_DIV_8 RCC_CFGR_PPRE_DIV8 /*!< HCLK divided by 8 */
+#define LL_RCC_APB1_DIV_16 RCC_CFGR_PPRE_DIV16 /*!< HCLK divided by 16 */
+/**
+ * @}
+ */
+
+/** @defgroup RCC_LL_EC_MCO1SOURCE MCO1 SOURCE selection
+ * @{
+ */
+#define LL_RCC_MCO1SOURCE_NOCLOCK RCC_CFGR_MCOSEL_NOCLOCK /*!< MCO output disabled, no clock on MCO */
+#define LL_RCC_MCO1SOURCE_HSI14 RCC_CFGR_MCOSEL_HSI14 /*!< HSI14 oscillator clock selected */
+#define LL_RCC_MCO1SOURCE_SYSCLK RCC_CFGR_MCOSEL_SYSCLK /*!< SYSCLK selection as MCO source */
+#define LL_RCC_MCO1SOURCE_HSI RCC_CFGR_MCOSEL_HSI /*!< HSI selection as MCO source */
+#define LL_RCC_MCO1SOURCE_HSE RCC_CFGR_MCOSEL_HSE /*!< HSE selection as MCO source */
+#define LL_RCC_MCO1SOURCE_LSI RCC_CFGR_MCOSEL_LSI /*!< LSI selection as MCO source */
+#define LL_RCC_MCO1SOURCE_LSE RCC_CFGR_MCOSEL_LSE /*!< LSE selection as MCO source */
+#if defined(RCC_CFGR_MCOSEL_HSI48)
+#define LL_RCC_MCO1SOURCE_HSI48 RCC_CFGR_MCOSEL_HSI48 /*!< HSI48 selection as MCO source */
+#endif /* RCC_CFGR_MCOSEL_HSI48 */
+#define LL_RCC_MCO1SOURCE_PLLCLK_DIV_2 RCC_CFGR_MCOSEL_PLL_DIV2 /*!< PLL clock divided by 2*/
+#if defined(RCC_CFGR_PLLNODIV)
+#define LL_RCC_MCO1SOURCE_PLLCLK (RCC_CFGR_MCOSEL_PLL_DIV2 | RCC_CFGR_PLLNODIV) /*!< PLL clock selected*/
+#endif /* RCC_CFGR_PLLNODIV */
+/**
+ * @}
+ */
+
+/** @defgroup RCC_LL_EC_MCO1_DIV MCO1 prescaler
+ * @{
+ */
+#define LL_RCC_MCO1_DIV_1 ((uint32_t)0x00000000U)/*!< MCO Clock divided by 1 */
+#if defined(RCC_CFGR_MCOPRE)
+#define LL_RCC_MCO1_DIV_2 RCC_CFGR_MCOPRE_DIV2 /*!< MCO Clock divided by 2 */
+#define LL_RCC_MCO1_DIV_4 RCC_CFGR_MCOPRE_DIV4 /*!< MCO Clock divided by 4 */
+#define LL_RCC_MCO1_DIV_8 RCC_CFGR_MCOPRE_DIV8 /*!< MCO Clock divided by 8 */
+#define LL_RCC_MCO1_DIV_16 RCC_CFGR_MCOPRE_DIV16 /*!< MCO Clock divided by 16 */
+#define LL_RCC_MCO1_DIV_32 RCC_CFGR_MCOPRE_DIV32 /*!< MCO Clock divided by 32 */
+#define LL_RCC_MCO1_DIV_64 RCC_CFGR_MCOPRE_DIV64 /*!< MCO Clock divided by 64 */
+#define LL_RCC_MCO1_DIV_128 RCC_CFGR_MCOPRE_DIV128 /*!< MCO Clock divided by 128 */
+#endif /* RCC_CFGR_MCOPRE */
+/**
+ * @}
+ */
+
+#if defined(USE_FULL_LL_DRIVER)
+/** @defgroup RCC_LL_EC_PERIPH_FREQUENCY Peripheral clock frequency
+ * @{
+ */
+#define LL_RCC_PERIPH_FREQUENCY_NO 0x00000000U /*!< No clock enabled for the peripheral */
+#define LL_RCC_PERIPH_FREQUENCY_NA 0xFFFFFFFFU /*!< Frequency cannot be provided as external clock */
+/**
+ * @}
+ */
+#endif /* USE_FULL_LL_DRIVER */
+
+/** @defgroup RCC_LL_EC_USART1_CLKSOURCE Peripheral USART clock source selection
+ * @{
+ */
+#define LL_RCC_USART1_CLKSOURCE_PCLK1 (uint32_t)((RCC_POSITION_USART1SW << 24) | RCC_CFGR3_USART1SW_PCLK) /*!< PCLK1 clock used as USART1 clock source */
+#define LL_RCC_USART1_CLKSOURCE_SYSCLK (uint32_t)((RCC_POSITION_USART1SW << 24) | RCC_CFGR3_USART1SW_SYSCLK) /*!< System clock selected as USART1 clock source */
+#define LL_RCC_USART1_CLKSOURCE_LSE (uint32_t)((RCC_POSITION_USART1SW << 24) | RCC_CFGR3_USART1SW_LSE) /*!< LSE oscillator clock used as USART1 clock source */
+#define LL_RCC_USART1_CLKSOURCE_HSI (uint32_t)((RCC_POSITION_USART1SW << 24) | RCC_CFGR3_USART1SW_HSI) /*!< HSI oscillator clock used as USART1 clock source */
+#if defined(RCC_CFGR3_USART2SW)
+#define LL_RCC_USART2_CLKSOURCE_PCLK1 (uint32_t)((RCC_POSITION_USART2SW << 24) | RCC_CFGR3_USART2SW_PCLK) /*!< PCLK1 clock used as USART2 clock source */
+#define LL_RCC_USART2_CLKSOURCE_SYSCLK (uint32_t)((RCC_POSITION_USART2SW << 24) | RCC_CFGR3_USART2SW_SYSCLK) /*!< System clock selected as USART2 clock source */
+#define LL_RCC_USART2_CLKSOURCE_LSE (uint32_t)((RCC_POSITION_USART2SW << 24) | RCC_CFGR3_USART2SW_LSE) /*!< LSE oscillator clock used as USART2 clock source */
+#define LL_RCC_USART2_CLKSOURCE_HSI (uint32_t)((RCC_POSITION_USART2SW << 24) | RCC_CFGR3_USART2SW_HSI) /*!< HSI oscillator clock used as USART2 clock source */
+#endif /* RCC_CFGR3_USART2SW */
+#if defined(RCC_CFGR3_USART3SW)
+#define LL_RCC_USART3_CLKSOURCE_PCLK1 (uint32_t)((RCC_POSITION_USART3SW << 24) | RCC_CFGR3_USART3SW_PCLK) /*!< PCLK1 clock used as USART3 clock source */
+#define LL_RCC_USART3_CLKSOURCE_SYSCLK (uint32_t)((RCC_POSITION_USART3SW << 24) | RCC_CFGR3_USART3SW_SYSCLK) /*!< System clock selected as USART3 clock source */
+#define LL_RCC_USART3_CLKSOURCE_LSE (uint32_t)((RCC_POSITION_USART3SW << 24) | RCC_CFGR3_USART3SW_LSE) /*!< LSE oscillator clock used as USART3 clock source */
+#define LL_RCC_USART3_CLKSOURCE_HSI (uint32_t)((RCC_POSITION_USART3SW << 24) | RCC_CFGR3_USART3SW_HSI) /*!< HSI oscillator clock used as USART3 clock source */
+#endif /* RCC_CFGR3_USART3SW */
+/**
+ * @}
+ */
+
+/** @defgroup RCC_LL_EC_I2C1_CLKSOURCE Peripheral I2C clock source selection
+ * @{
+ */
+#define LL_RCC_I2C1_CLKSOURCE_HSI RCC_CFGR3_I2C1SW_HSI /*!< HSI oscillator clock used as I2C1 clock source */
+#define LL_RCC_I2C1_CLKSOURCE_SYSCLK RCC_CFGR3_I2C1SW_SYSCLK /*!< System clock selected as I2C1 clock source */
+/**
+ * @}
+ */
+
+#if defined(CEC)
+/** @defgroup RCC_LL_EC_CEC_CLKSOURCE Peripheral CEC clock source selection
+ * @{
+ */
+#define LL_RCC_CEC_CLKSOURCE_HSI_DIV244 RCC_CFGR3_CECSW_HSI_DIV244 /*!< HSI clock divided by 244 selected as HDMI CEC entry clock source */
+#define LL_RCC_CEC_CLKSOURCE_LSE RCC_CFGR3_CECSW_LSE /*!< LSE clock selected as HDMI CEC entry clock source */
+/**
+ * @}
+ */
+
+#endif /* CEC */
+
+#if defined(USB)
+/** @defgroup RCC_LL_EC_USB_CLKSOURCE Peripheral USB clock source selection
+ * @{
+ */
+#if defined(RCC_CFGR3_USBSW_HSI48)
+#define LL_RCC_USB_CLKSOURCE_HSI48 RCC_CFGR3_USBSW_HSI48 /*!< HSI48 oscillator clock used as USB clock source */
+#else
+#define LL_RCC_USB_CLKSOURCE_NONE ((uint32_t)0x00000000) /*!< USB Clock disabled */
+#endif /*RCC_CFGR3_USBSW_HSI48*/
+#define LL_RCC_USB_CLKSOURCE_PLL RCC_CFGR3_USBSW_PLLCLK /*!< PLL selected as USB clock source */
+/**
+ * @}
+ */
+
+#endif /* USB */
+
+/** @defgroup RCC_LL_EC_USART1 Peripheral USART get clock source
+ * @{
+ */
+#define LL_RCC_USART1_CLKSOURCE RCC_POSITION_USART1SW /*!< USART1 Clock source selection */
+#if defined(RCC_CFGR3_USART2SW)
+#define LL_RCC_USART2_CLKSOURCE RCC_POSITION_USART2SW /*!< USART2 Clock source selection */
+#endif /* RCC_CFGR3_USART2SW */
+#if defined(RCC_CFGR3_USART3SW)
+#define LL_RCC_USART3_CLKSOURCE RCC_POSITION_USART3SW /*!< USART3 Clock source selection */
+#endif /* RCC_CFGR3_USART3SW */
+/**
+ * @}
+ */
+
+/** @defgroup RCC_LL_EC_I2C1 Peripheral I2C get clock source
+ * @{
+ */
+#define LL_RCC_I2C1_CLKSOURCE RCC_CFGR3_I2C1SW /*!< I2C1 Clock source selection */
+/**
+ * @}
+ */
+
+#if defined(CEC)
+/** @defgroup RCC_LL_EC_CEC Peripheral CEC get clock source
+ * @{
+ */
+#define LL_RCC_CEC_CLKSOURCE RCC_CFGR3_CECSW /*!< CEC Clock source selection */
+/**
+ * @}
+ */
+#endif /* CEC */
+
+#if defined(USB)
+/** @defgroup RCC_LL_EC_USB Peripheral USB get clock source
+ * @{
+ */
+#define LL_RCC_USB_CLKSOURCE RCC_CFGR3_USBSW /*!< USB Clock source selection */
+/**
+ * @}
+ */
+#endif /* USB */
+
+/** @defgroup RCC_LL_EC_RTC_CLKSOURCE RTC clock source selection
+ * @{
+ */
+#define LL_RCC_RTC_CLKSOURCE_NONE 0x00000000U /*!< No clock used as RTC clock */
+#define LL_RCC_RTC_CLKSOURCE_LSE RCC_BDCR_RTCSEL_0 /*!< LSE oscillator clock used as RTC clock */
+#define LL_RCC_RTC_CLKSOURCE_LSI RCC_BDCR_RTCSEL_1 /*!< LSI oscillator clock used as RTC clock */
+#define LL_RCC_RTC_CLKSOURCE_HSE_DIV32 RCC_BDCR_RTCSEL /*!< HSE oscillator clock divided by 32 used as RTC clock */
+/**
+ * @}
+ */
+
+/** @defgroup RCC_LL_EC_PLL_MUL PLL Multiplicator factor
+ * @{
+ */
+#define LL_RCC_PLL_MUL_2 RCC_CFGR_PLLMUL2 /*!< PLL input clock*2 */
+#define LL_RCC_PLL_MUL_3 RCC_CFGR_PLLMUL3 /*!< PLL input clock*3 */
+#define LL_RCC_PLL_MUL_4 RCC_CFGR_PLLMUL4 /*!< PLL input clock*4 */
+#define LL_RCC_PLL_MUL_5 RCC_CFGR_PLLMUL5 /*!< PLL input clock*5 */
+#define LL_RCC_PLL_MUL_6 RCC_CFGR_PLLMUL6 /*!< PLL input clock*6 */
+#define LL_RCC_PLL_MUL_7 RCC_CFGR_PLLMUL7 /*!< PLL input clock*7 */
+#define LL_RCC_PLL_MUL_8 RCC_CFGR_PLLMUL8 /*!< PLL input clock*8 */
+#define LL_RCC_PLL_MUL_9 RCC_CFGR_PLLMUL9 /*!< PLL input clock*9 */
+#define LL_RCC_PLL_MUL_10 RCC_CFGR_PLLMUL10 /*!< PLL input clock*10 */
+#define LL_RCC_PLL_MUL_11 RCC_CFGR_PLLMUL11 /*!< PLL input clock*11 */
+#define LL_RCC_PLL_MUL_12 RCC_CFGR_PLLMUL12 /*!< PLL input clock*12 */
+#define LL_RCC_PLL_MUL_13 RCC_CFGR_PLLMUL13 /*!< PLL input clock*13 */
+#define LL_RCC_PLL_MUL_14 RCC_CFGR_PLLMUL14 /*!< PLL input clock*14 */
+#define LL_RCC_PLL_MUL_15 RCC_CFGR_PLLMUL15 /*!< PLL input clock*15 */
+#define LL_RCC_PLL_MUL_16 RCC_CFGR_PLLMUL16 /*!< PLL input clock*16 */
+/**
+ * @}
+ */
+
+/** @defgroup RCC_LL_EC_PLLSOURCE PLL SOURCE
+ * @{
+ */
+#define LL_RCC_PLLSOURCE_NONE 0x00000000U /*!< No clock selected as main PLL entry clock source */
+#define LL_RCC_PLLSOURCE_HSE RCC_CFGR_PLLSRC_HSE_PREDIV /*!< HSE/PREDIV clock selected as PLL entry clock source */
+#if defined(RCC_PLLSRC_PREDIV1_SUPPORT)
+#define LL_RCC_PLLSOURCE_HSI RCC_CFGR_PLLSRC_HSI_PREDIV /*!< HSI/PREDIV clock selected as PLL entry clock source */
+#if defined(RCC_CFGR_SW_HSI48)
+#define LL_RCC_PLLSOURCE_HSI48 RCC_CFGR_PLLSRC_HSI48_PREDIV /*!< HSI48/PREDIV clock selected as PLL entry clock source */
+#endif /* RCC_CFGR_SW_HSI48 */
+#else
+#define LL_RCC_PLLSOURCE_HSI_DIV_2 RCC_CFGR_PLLSRC_HSI_DIV2 /*!< HSI clock divided by 2 selected as PLL entry clock source */
+#define LL_RCC_PLLSOURCE_HSE_DIV_1 (RCC_CFGR_PLLSRC_HSE_PREDIV | RCC_CFGR2_PREDIV_DIV1) /*!< HSE clock selected as PLL entry clock source */
+#define LL_RCC_PLLSOURCE_HSE_DIV_2 (RCC_CFGR_PLLSRC_HSE_PREDIV | RCC_CFGR2_PREDIV_DIV2) /*!< HSE/2 clock selected as PLL entry clock source */
+#define LL_RCC_PLLSOURCE_HSE_DIV_3 (RCC_CFGR_PLLSRC_HSE_PREDIV | RCC_CFGR2_PREDIV_DIV3) /*!< HSE/3 clock selected as PLL entry clock source */
+#define LL_RCC_PLLSOURCE_HSE_DIV_4 (RCC_CFGR_PLLSRC_HSE_PREDIV | RCC_CFGR2_PREDIV_DIV4) /*!< HSE/4 clock selected as PLL entry clock source */
+#define LL_RCC_PLLSOURCE_HSE_DIV_5 (RCC_CFGR_PLLSRC_HSE_PREDIV | RCC_CFGR2_PREDIV_DIV5) /*!< HSE/5 clock selected as PLL entry clock source */
+#define LL_RCC_PLLSOURCE_HSE_DIV_6 (RCC_CFGR_PLLSRC_HSE_PREDIV | RCC_CFGR2_PREDIV_DIV6) /*!< HSE/6 clock selected as PLL entry clock source */
+#define LL_RCC_PLLSOURCE_HSE_DIV_7 (RCC_CFGR_PLLSRC_HSE_PREDIV | RCC_CFGR2_PREDIV_DIV7) /*!< HSE/7 clock selected as PLL entry clock source */
+#define LL_RCC_PLLSOURCE_HSE_DIV_8 (RCC_CFGR_PLLSRC_HSE_PREDIV | RCC_CFGR2_PREDIV_DIV8) /*!< HSE/8 clock selected as PLL entry clock source */
+#define LL_RCC_PLLSOURCE_HSE_DIV_9 (RCC_CFGR_PLLSRC_HSE_PREDIV | RCC_CFGR2_PREDIV_DIV9) /*!< HSE/9 clock selected as PLL entry clock source */
+#define LL_RCC_PLLSOURCE_HSE_DIV_10 (RCC_CFGR_PLLSRC_HSE_PREDIV | RCC_CFGR2_PREDIV_DIV10) /*!< HSE/10 clock selected as PLL entry clock source */
+#define LL_RCC_PLLSOURCE_HSE_DIV_11 (RCC_CFGR_PLLSRC_HSE_PREDIV | RCC_CFGR2_PREDIV_DIV11) /*!< HSE/11 clock selected as PLL entry clock source */
+#define LL_RCC_PLLSOURCE_HSE_DIV_12 (RCC_CFGR_PLLSRC_HSE_PREDIV | RCC_CFGR2_PREDIV_DIV12) /*!< HSE/12 clock selected as PLL entry clock source */
+#define LL_RCC_PLLSOURCE_HSE_DIV_13 (RCC_CFGR_PLLSRC_HSE_PREDIV | RCC_CFGR2_PREDIV_DIV13) /*!< HSE/13 clock selected as PLL entry clock source */
+#define LL_RCC_PLLSOURCE_HSE_DIV_14 (RCC_CFGR_PLLSRC_HSE_PREDIV | RCC_CFGR2_PREDIV_DIV14) /*!< HSE/14 clock selected as PLL entry clock source */
+#define LL_RCC_PLLSOURCE_HSE_DIV_15 (RCC_CFGR_PLLSRC_HSE_PREDIV | RCC_CFGR2_PREDIV_DIV15) /*!< HSE/15 clock selected as PLL entry clock source */
+#define LL_RCC_PLLSOURCE_HSE_DIV_16 (RCC_CFGR_PLLSRC_HSE_PREDIV | RCC_CFGR2_PREDIV_DIV16) /*!< HSE/16 clock selected as PLL entry clock source */
+#endif /* RCC_PLLSRC_PREDIV1_SUPPORT */
+/**
+ * @}
+ */
+
+/** @defgroup RCC_LL_EC_PREDIV_DIV PREDIV Division factor
+ * @{
+ */
+#define LL_RCC_PREDIV_DIV_1 RCC_CFGR2_PREDIV_DIV1 /*!< PREDIV input clock not divided */
+#define LL_RCC_PREDIV_DIV_2 RCC_CFGR2_PREDIV_DIV2 /*!< PREDIV input clock divided by 2 */
+#define LL_RCC_PREDIV_DIV_3 RCC_CFGR2_PREDIV_DIV3 /*!< PREDIV input clock divided by 3 */
+#define LL_RCC_PREDIV_DIV_4 RCC_CFGR2_PREDIV_DIV4 /*!< PREDIV input clock divided by 4 */
+#define LL_RCC_PREDIV_DIV_5 RCC_CFGR2_PREDIV_DIV5 /*!< PREDIV input clock divided by 5 */
+#define LL_RCC_PREDIV_DIV_6 RCC_CFGR2_PREDIV_DIV6 /*!< PREDIV input clock divided by 6 */
+#define LL_RCC_PREDIV_DIV_7 RCC_CFGR2_PREDIV_DIV7 /*!< PREDIV input clock divided by 7 */
+#define LL_RCC_PREDIV_DIV_8 RCC_CFGR2_PREDIV_DIV8 /*!< PREDIV input clock divided by 8 */
+#define LL_RCC_PREDIV_DIV_9 RCC_CFGR2_PREDIV_DIV9 /*!< PREDIV input clock divided by 9 */
+#define LL_RCC_PREDIV_DIV_10 RCC_CFGR2_PREDIV_DIV10 /*!< PREDIV input clock divided by 10 */
+#define LL_RCC_PREDIV_DIV_11 RCC_CFGR2_PREDIV_DIV11 /*!< PREDIV input clock divided by 11 */
+#define LL_RCC_PREDIV_DIV_12 RCC_CFGR2_PREDIV_DIV12 /*!< PREDIV input clock divided by 12 */
+#define LL_RCC_PREDIV_DIV_13 RCC_CFGR2_PREDIV_DIV13 /*!< PREDIV input clock divided by 13 */
+#define LL_RCC_PREDIV_DIV_14 RCC_CFGR2_PREDIV_DIV14 /*!< PREDIV input clock divided by 14 */
+#define LL_RCC_PREDIV_DIV_15 RCC_CFGR2_PREDIV_DIV15 /*!< PREDIV input clock divided by 15 */
+#define LL_RCC_PREDIV_DIV_16 RCC_CFGR2_PREDIV_DIV16 /*!< PREDIV input clock divided by 16 */
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/* Exported macro ------------------------------------------------------------*/
+/** @defgroup RCC_LL_Exported_Macros RCC Exported Macros
+ * @{
+ */
+
+/** @defgroup RCC_LL_EM_WRITE_READ Common Write and read registers Macros
+ * @{
+ */
+
+/**
+ * @brief Write a value in RCC register
+ * @param __REG__ Register to be written
+ * @param __VALUE__ Value to be written in the register
+ * @retval None
+ */
+#define LL_RCC_WriteReg(__REG__, __VALUE__) WRITE_REG(RCC->__REG__, (__VALUE__))
+
+/**
+ * @brief Read a value in RCC register
+ * @param __REG__ Register to be read
+ * @retval Register value
+ */
+#define LL_RCC_ReadReg(__REG__) READ_REG(RCC->__REG__)
+/**
+ * @}
+ */
+
+/** @defgroup RCC_LL_EM_CALC_FREQ Calculate frequencies
+ * @{
+ */
+
+#if defined(RCC_PLLSRC_PREDIV1_SUPPORT)
+/**
+ * @brief Helper macro to calculate the PLLCLK frequency
+ * @note ex: @ref __LL_RCC_CALC_PLLCLK_FREQ (HSE_VALUE, @ref LL_RCC_PLL_GetMultiplicator()
+ * , @ref LL_RCC_PLL_GetPrediv());
+ * @param __INPUTFREQ__ PLL Input frequency (based on HSE/HSI/HSI48)
+ * @param __PLLMUL__ This parameter can be one of the following values:
+ * @arg @ref LL_RCC_PLL_MUL_2
+ * @arg @ref LL_RCC_PLL_MUL_3
+ * @arg @ref LL_RCC_PLL_MUL_4
+ * @arg @ref LL_RCC_PLL_MUL_5
+ * @arg @ref LL_RCC_PLL_MUL_6
+ * @arg @ref LL_RCC_PLL_MUL_7
+ * @arg @ref LL_RCC_PLL_MUL_8
+ * @arg @ref LL_RCC_PLL_MUL_9
+ * @arg @ref LL_RCC_PLL_MUL_10
+ * @arg @ref LL_RCC_PLL_MUL_11
+ * @arg @ref LL_RCC_PLL_MUL_12
+ * @arg @ref LL_RCC_PLL_MUL_13
+ * @arg @ref LL_RCC_PLL_MUL_14
+ * @arg @ref LL_RCC_PLL_MUL_15
+ * @arg @ref LL_RCC_PLL_MUL_16
+ * @param __PLLPREDIV__ This parameter can be one of the following values:
+ * @arg @ref LL_RCC_PREDIV_DIV_1
+ * @arg @ref LL_RCC_PREDIV_DIV_2
+ * @arg @ref LL_RCC_PREDIV_DIV_3
+ * @arg @ref LL_RCC_PREDIV_DIV_4
+ * @arg @ref LL_RCC_PREDIV_DIV_5
+ * @arg @ref LL_RCC_PREDIV_DIV_6
+ * @arg @ref LL_RCC_PREDIV_DIV_7
+ * @arg @ref LL_RCC_PREDIV_DIV_8
+ * @arg @ref LL_RCC_PREDIV_DIV_9
+ * @arg @ref LL_RCC_PREDIV_DIV_10
+ * @arg @ref LL_RCC_PREDIV_DIV_11
+ * @arg @ref LL_RCC_PREDIV_DIV_12
+ * @arg @ref LL_RCC_PREDIV_DIV_13
+ * @arg @ref LL_RCC_PREDIV_DIV_14
+ * @arg @ref LL_RCC_PREDIV_DIV_15
+ * @arg @ref LL_RCC_PREDIV_DIV_16
+ * @retval PLL clock frequency (in Hz)
+ */
+#define __LL_RCC_CALC_PLLCLK_FREQ(__INPUTFREQ__, __PLLMUL__, __PLLPREDIV__) \
+ (((__INPUTFREQ__) / ((((__PLLPREDIV__) & RCC_CFGR2_PREDIV) + 1U))) * ((((__PLLMUL__) & RCC_CFGR_PLLMUL) >> RCC_POSITION_PLLMUL) + 2U))
+
+#else
+/**
+ * @brief Helper macro to calculate the PLLCLK frequency
+ * @note ex: @ref __LL_RCC_CALC_PLLCLK_FREQ (HSE_VALUE / (@ref LL_RCC_PLL_GetPrediv () + 1), @ref LL_RCC_PLL_GetMultiplicator());
+ * @param __INPUTFREQ__ PLL Input frequency (based on HSE div Prediv / HSI div 2)
+ * @param __PLLMUL__ This parameter can be one of the following values:
+ * @arg @ref LL_RCC_PLL_MUL_2
+ * @arg @ref LL_RCC_PLL_MUL_3
+ * @arg @ref LL_RCC_PLL_MUL_4
+ * @arg @ref LL_RCC_PLL_MUL_5
+ * @arg @ref LL_RCC_PLL_MUL_6
+ * @arg @ref LL_RCC_PLL_MUL_7
+ * @arg @ref LL_RCC_PLL_MUL_8
+ * @arg @ref LL_RCC_PLL_MUL_9
+ * @arg @ref LL_RCC_PLL_MUL_10
+ * @arg @ref LL_RCC_PLL_MUL_11
+ * @arg @ref LL_RCC_PLL_MUL_12
+ * @arg @ref LL_RCC_PLL_MUL_13
+ * @arg @ref LL_RCC_PLL_MUL_14
+ * @arg @ref LL_RCC_PLL_MUL_15
+ * @arg @ref LL_RCC_PLL_MUL_16
+ * @retval PLL clock frequency (in Hz)
+ */
+#define __LL_RCC_CALC_PLLCLK_FREQ(__INPUTFREQ__, __PLLMUL__) \
+ ((__INPUTFREQ__) * ((((__PLLMUL__) & RCC_CFGR_PLLMUL) >> RCC_POSITION_PLLMUL) + 2U))
+#endif /* RCC_PLLSRC_PREDIV1_SUPPORT */
+/**
+ * @brief Helper macro to calculate the HCLK frequency
+ * @note: __AHBPRESCALER__ be retrieved by @ref LL_RCC_GetAHBPrescaler
+ * ex: __LL_RCC_CALC_HCLK_FREQ(LL_RCC_GetAHBPrescaler())
+ * @param __SYSCLKFREQ__ SYSCLK frequency (based on HSE/HSI/PLLCLK)
+ * @param __AHBPRESCALER__ This parameter can be one of the following values:
+ * @arg @ref LL_RCC_SYSCLK_DIV_1
+ * @arg @ref LL_RCC_SYSCLK_DIV_2
+ * @arg @ref LL_RCC_SYSCLK_DIV_4
+ * @arg @ref LL_RCC_SYSCLK_DIV_8
+ * @arg @ref LL_RCC_SYSCLK_DIV_16
+ * @arg @ref LL_RCC_SYSCLK_DIV_64
+ * @arg @ref LL_RCC_SYSCLK_DIV_128
+ * @arg @ref LL_RCC_SYSCLK_DIV_256
+ * @arg @ref LL_RCC_SYSCLK_DIV_512
+ * @retval HCLK clock frequency (in Hz)
+ */
+#define __LL_RCC_CALC_HCLK_FREQ(__SYSCLKFREQ__, __AHBPRESCALER__) ((__SYSCLKFREQ__) >> AHBPrescTable[((__AHBPRESCALER__) & RCC_CFGR_HPRE) >> RCC_CFGR_HPRE_Pos])
+
+/**
+ * @brief Helper macro to calculate the PCLK1 frequency (ABP1)
+ * @note: __APB1PRESCALER__ be retrieved by @ref LL_RCC_GetAPB1Prescaler
+ * ex: __LL_RCC_CALC_PCLK1_FREQ(LL_RCC_GetAPB1Prescaler())
+ * @param __HCLKFREQ__ HCLK frequency
+ * @param __APB1PRESCALER__ This parameter can be one of the following values:
+ * @arg @ref LL_RCC_APB1_DIV_1
+ * @arg @ref LL_RCC_APB1_DIV_2
+ * @arg @ref LL_RCC_APB1_DIV_4
+ * @arg @ref LL_RCC_APB1_DIV_8
+ * @arg @ref LL_RCC_APB1_DIV_16
+ * @retval PCLK1 clock frequency (in Hz)
+ */
+#define __LL_RCC_CALC_PCLK1_FREQ(__HCLKFREQ__, __APB1PRESCALER__) ((__HCLKFREQ__) >> APBPrescTable[(__APB1PRESCALER__) >> RCC_CFGR_PPRE_Pos])
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/* Exported functions --------------------------------------------------------*/
+/** @defgroup RCC_LL_Exported_Functions RCC Exported Functions
+ * @{
+ */
+
+/** @defgroup RCC_LL_EF_HSE HSE
+ * @{
+ */
+
+/**
+ * @brief Enable the Clock Security System.
+ * @rmtoll CR CSSON LL_RCC_HSE_EnableCSS
+ * @retval None
+ */
+__STATIC_INLINE void LL_RCC_HSE_EnableCSS(void)
+{
+ SET_BIT(RCC->CR, RCC_CR_CSSON);
+}
+
+/**
+ * @brief Disable the Clock Security System.
+ * @note Cannot be disabled in HSE is ready (only by hardware)
+ * @rmtoll CR CSSON LL_RCC_HSE_DisableCSS
+ * @retval None
+ */
+__STATIC_INLINE void LL_RCC_HSE_DisableCSS(void)
+{
+ CLEAR_BIT(RCC->CR, RCC_CR_CSSON);
+}
+
+/**
+ * @brief Enable HSE external oscillator (HSE Bypass)
+ * @rmtoll CR HSEBYP LL_RCC_HSE_EnableBypass
+ * @retval None
+ */
+__STATIC_INLINE void LL_RCC_HSE_EnableBypass(void)
+{
+ SET_BIT(RCC->CR, RCC_CR_HSEBYP);
+}
+
+/**
+ * @brief Disable HSE external oscillator (HSE Bypass)
+ * @rmtoll CR HSEBYP LL_RCC_HSE_DisableBypass
+ * @retval None
+ */
+__STATIC_INLINE void LL_RCC_HSE_DisableBypass(void)
+{
+ CLEAR_BIT(RCC->CR, RCC_CR_HSEBYP);
+}
+
+/**
+ * @brief Enable HSE crystal oscillator (HSE ON)
+ * @rmtoll CR HSEON LL_RCC_HSE_Enable
+ * @retval None
+ */
+__STATIC_INLINE void LL_RCC_HSE_Enable(void)
+{
+ SET_BIT(RCC->CR, RCC_CR_HSEON);
+}
+
+/**
+ * @brief Disable HSE crystal oscillator (HSE ON)
+ * @rmtoll CR HSEON LL_RCC_HSE_Disable
+ * @retval None
+ */
+__STATIC_INLINE void LL_RCC_HSE_Disable(void)
+{
+ CLEAR_BIT(RCC->CR, RCC_CR_HSEON);
+}
+
+/**
+ * @brief Check if HSE oscillator Ready
+ * @rmtoll CR HSERDY LL_RCC_HSE_IsReady
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_RCC_HSE_IsReady(void)
+{
+ return (READ_BIT(RCC->CR, RCC_CR_HSERDY) == (RCC_CR_HSERDY));
+}
+
+/**
+ * @}
+ */
+
+/** @defgroup RCC_LL_EF_HSI HSI
+ * @{
+ */
+
+/**
+ * @brief Enable HSI oscillator
+ * @rmtoll CR HSION LL_RCC_HSI_Enable
+ * @retval None
+ */
+__STATIC_INLINE void LL_RCC_HSI_Enable(void)
+{
+ SET_BIT(RCC->CR, RCC_CR_HSION);
+}
+
+/**
+ * @brief Disable HSI oscillator
+ * @rmtoll CR HSION LL_RCC_HSI_Disable
+ * @retval None
+ */
+__STATIC_INLINE void LL_RCC_HSI_Disable(void)
+{
+ CLEAR_BIT(RCC->CR, RCC_CR_HSION);
+}
+
+/**
+ * @brief Check if HSI clock is ready
+ * @rmtoll CR HSIRDY LL_RCC_HSI_IsReady
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_RCC_HSI_IsReady(void)
+{
+ return (READ_BIT(RCC->CR, RCC_CR_HSIRDY) == (RCC_CR_HSIRDY));
+}
+
+/**
+ * @brief Get HSI Calibration value
+ * @note When HSITRIM is written, HSICAL is updated with the sum of
+ * HSITRIM and the factory trim value
+ * @rmtoll CR HSICAL LL_RCC_HSI_GetCalibration
+ * @retval Between Min_Data = 0x00 and Max_Data = 0xFF
+ */
+__STATIC_INLINE uint32_t LL_RCC_HSI_GetCalibration(void)
+{
+ return (uint32_t)(READ_BIT(RCC->CR, RCC_CR_HSICAL) >> RCC_CR_HSICAL_Pos);
+}
+
+/**
+ * @brief Set HSI Calibration trimming
+ * @note user-programmable trimming value that is added to the HSICAL
+ * @note Default value is 16, which, when added to the HSICAL value,
+ * should trim the HSI to 16 MHz +/- 1 %
+ * @rmtoll CR HSITRIM LL_RCC_HSI_SetCalibTrimming
+ * @param Value between Min_Data = 0x00 and Max_Data = 0x1F
+ * @retval None
+ */
+__STATIC_INLINE void LL_RCC_HSI_SetCalibTrimming(uint32_t Value)
+{
+ MODIFY_REG(RCC->CR, RCC_CR_HSITRIM, Value << RCC_CR_HSITRIM_Pos);
+}
+
+/**
+ * @brief Get HSI Calibration trimming
+ * @rmtoll CR HSITRIM LL_RCC_HSI_GetCalibTrimming
+ * @retval Between Min_Data = 0x00 and Max_Data = 0x1F
+ */
+__STATIC_INLINE uint32_t LL_RCC_HSI_GetCalibTrimming(void)
+{
+ return (uint32_t)(READ_BIT(RCC->CR, RCC_CR_HSITRIM) >> RCC_CR_HSITRIM_Pos);
+}
+
+/**
+ * @}
+ */
+
+#if defined(RCC_HSI48_SUPPORT)
+/** @defgroup RCC_LL_EF_HSI48 HSI48
+ * @{
+ */
+
+/**
+ * @brief Enable HSI48
+ * @rmtoll CR2 HSI48ON LL_RCC_HSI48_Enable
+ * @retval None
+ */
+__STATIC_INLINE void LL_RCC_HSI48_Enable(void)
+{
+ SET_BIT(RCC->CR2, RCC_CR2_HSI48ON);
+}
+
+/**
+ * @brief Disable HSI48
+ * @rmtoll CR2 HSI48ON LL_RCC_HSI48_Disable
+ * @retval None
+ */
+__STATIC_INLINE void LL_RCC_HSI48_Disable(void)
+{
+ CLEAR_BIT(RCC->CR2, RCC_CR2_HSI48ON);
+}
+
+/**
+ * @brief Check if HSI48 oscillator Ready
+ * @rmtoll CR2 HSI48RDY LL_RCC_HSI48_IsReady
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_RCC_HSI48_IsReady(void)
+{
+ return (READ_BIT(RCC->CR2, RCC_CR2_HSI48RDY) == (RCC_CR2_HSI48RDY));
+}
+
+/**
+ * @brief Get HSI48 Calibration value
+ * @rmtoll CR2 HSI48CAL LL_RCC_HSI48_GetCalibration
+ * @retval Between Min_Data = 0x00 and Max_Data = 0xFF
+ */
+__STATIC_INLINE uint32_t LL_RCC_HSI48_GetCalibration(void)
+{
+ return (uint32_t)(READ_BIT(RCC->CR2, RCC_CR2_HSI48CAL) >> RCC_POSITION_HSI48CAL);
+}
+
+/**
+ * @}
+ */
+
+#endif /* RCC_HSI48_SUPPORT */
+
+/** @defgroup RCC_LL_EF_HSI14 HSI14
+ * @{
+ */
+
+/**
+ * @brief Enable HSI14
+ * @rmtoll CR2 HSI14ON LL_RCC_HSI14_Enable
+ * @retval None
+ */
+__STATIC_INLINE void LL_RCC_HSI14_Enable(void)
+{
+ SET_BIT(RCC->CR2, RCC_CR2_HSI14ON);
+}
+
+/**
+ * @brief Disable HSI14
+ * @rmtoll CR2 HSI14ON LL_RCC_HSI14_Disable
+ * @retval None
+ */
+__STATIC_INLINE void LL_RCC_HSI14_Disable(void)
+{
+ CLEAR_BIT(RCC->CR2, RCC_CR2_HSI14ON);
+}
+
+/**
+ * @brief Check if HSI14 oscillator Ready
+ * @rmtoll CR2 HSI14RDY LL_RCC_HSI14_IsReady
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_RCC_HSI14_IsReady(void)
+{
+ return (READ_BIT(RCC->CR2, RCC_CR2_HSI14RDY) == (RCC_CR2_HSI14RDY));
+}
+
+/**
+ * @brief ADC interface can turn on the HSI14 oscillator
+ * @rmtoll CR2 HSI14DIS LL_RCC_HSI14_EnableADCControl
+ * @retval None
+ */
+__STATIC_INLINE void LL_RCC_HSI14_EnableADCControl(void)
+{
+ CLEAR_BIT(RCC->CR2, RCC_CR2_HSI14DIS);
+}
+
+/**
+ * @brief ADC interface can not turn on the HSI14 oscillator
+ * @rmtoll CR2 HSI14DIS LL_RCC_HSI14_DisableADCControl
+ * @retval None
+ */
+__STATIC_INLINE void LL_RCC_HSI14_DisableADCControl(void)
+{
+ SET_BIT(RCC->CR2, RCC_CR2_HSI14DIS);
+}
+
+/**
+ * @brief Set HSI14 Calibration trimming
+ * @note user-programmable trimming value that is added to the HSI14CAL
+ * @note Default value is 16, which, when added to the HSI14CAL value,
+ * should trim the HSI14 to 14 MHz +/- 1 %
+ * @rmtoll CR2 HSI14TRIM LL_RCC_HSI14_SetCalibTrimming
+ * @param Value between Min_Data = 0x00 and Max_Data = 0xFF
+ * @retval None
+ */
+__STATIC_INLINE void LL_RCC_HSI14_SetCalibTrimming(uint32_t Value)
+{
+ MODIFY_REG(RCC->CR2, RCC_CR2_HSI14TRIM, Value << RCC_POSITION_HSI14TRIM);
+}
+
+/**
+ * @brief Get HSI14 Calibration value
+ * @note When HSI14TRIM is written, HSI14CAL is updated with the sum of
+ * HSI14TRIM and the factory trim value
+ * @rmtoll CR2 HSI14TRIM LL_RCC_HSI14_GetCalibTrimming
+ * @retval Between Min_Data = 0x00 and Max_Data = 0x1F
+ */
+__STATIC_INLINE uint32_t LL_RCC_HSI14_GetCalibTrimming(void)
+{
+ return (uint32_t)(READ_BIT(RCC->CR2, RCC_CR2_HSI14TRIM) >> RCC_POSITION_HSI14TRIM);
+}
+
+/**
+ * @brief Get HSI14 Calibration trimming
+ * @rmtoll CR2 HSI14CAL LL_RCC_HSI14_GetCalibration
+ * @retval Between Min_Data = 0x00 and Max_Data = 0x1F
+ */
+__STATIC_INLINE uint32_t LL_RCC_HSI14_GetCalibration(void)
+{
+ return (uint32_t)(READ_BIT(RCC->CR2, RCC_CR2_HSI14CAL) >> RCC_POSITION_HSI14CAL);
+}
+
+/**
+ * @}
+ */
+
+/** @defgroup RCC_LL_EF_LSE LSE
+ * @{
+ */
+
+/**
+ * @brief Enable Low Speed External (LSE) crystal.
+ * @rmtoll BDCR LSEON LL_RCC_LSE_Enable
+ * @retval None
+ */
+__STATIC_INLINE void LL_RCC_LSE_Enable(void)
+{
+ SET_BIT(RCC->BDCR, RCC_BDCR_LSEON);
+}
+
+/**
+ * @brief Disable Low Speed External (LSE) crystal.
+ * @rmtoll BDCR LSEON LL_RCC_LSE_Disable
+ * @retval None
+ */
+__STATIC_INLINE void LL_RCC_LSE_Disable(void)
+{
+ CLEAR_BIT(RCC->BDCR, RCC_BDCR_LSEON);
+}
+
+/**
+ * @brief Enable external clock source (LSE bypass).
+ * @rmtoll BDCR LSEBYP LL_RCC_LSE_EnableBypass
+ * @retval None
+ */
+__STATIC_INLINE void LL_RCC_LSE_EnableBypass(void)
+{
+ SET_BIT(RCC->BDCR, RCC_BDCR_LSEBYP);
+}
+
+/**
+ * @brief Disable external clock source (LSE bypass).
+ * @rmtoll BDCR LSEBYP LL_RCC_LSE_DisableBypass
+ * @retval None
+ */
+__STATIC_INLINE void LL_RCC_LSE_DisableBypass(void)
+{
+ CLEAR_BIT(RCC->BDCR, RCC_BDCR_LSEBYP);
+}
+
+/**
+ * @brief Set LSE oscillator drive capability
+ * @note The oscillator is in Xtal mode when it is not in bypass mode.
+ * @rmtoll BDCR LSEDRV LL_RCC_LSE_SetDriveCapability
+ * @param LSEDrive This parameter can be one of the following values:
+ * @arg @ref LL_RCC_LSEDRIVE_LOW
+ * @arg @ref LL_RCC_LSEDRIVE_MEDIUMLOW
+ * @arg @ref LL_RCC_LSEDRIVE_MEDIUMHIGH
+ * @arg @ref LL_RCC_LSEDRIVE_HIGH
+ * @retval None
+ */
+__STATIC_INLINE void LL_RCC_LSE_SetDriveCapability(uint32_t LSEDrive)
+{
+ MODIFY_REG(RCC->BDCR, RCC_BDCR_LSEDRV, LSEDrive);
+}
+
+/**
+ * @brief Get LSE oscillator drive capability
+ * @rmtoll BDCR LSEDRV LL_RCC_LSE_GetDriveCapability
+ * @retval Returned value can be one of the following values:
+ * @arg @ref LL_RCC_LSEDRIVE_LOW
+ * @arg @ref LL_RCC_LSEDRIVE_MEDIUMLOW
+ * @arg @ref LL_RCC_LSEDRIVE_MEDIUMHIGH
+ * @arg @ref LL_RCC_LSEDRIVE_HIGH
+ */
+__STATIC_INLINE uint32_t LL_RCC_LSE_GetDriveCapability(void)
+{
+ return (uint32_t)(READ_BIT(RCC->BDCR, RCC_BDCR_LSEDRV));
+}
+
+/**
+ * @brief Check if LSE oscillator Ready
+ * @rmtoll BDCR LSERDY LL_RCC_LSE_IsReady
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_RCC_LSE_IsReady(void)
+{
+ return (READ_BIT(RCC->BDCR, RCC_BDCR_LSERDY) == (RCC_BDCR_LSERDY));
+}
+
+/**
+ * @}
+ */
+
+/** @defgroup RCC_LL_EF_LSI LSI
+ * @{
+ */
+
+/**
+ * @brief Enable LSI Oscillator
+ * @rmtoll CSR LSION LL_RCC_LSI_Enable
+ * @retval None
+ */
+__STATIC_INLINE void LL_RCC_LSI_Enable(void)
+{
+ SET_BIT(RCC->CSR, RCC_CSR_LSION);
+}
+
+/**
+ * @brief Disable LSI Oscillator
+ * @rmtoll CSR LSION LL_RCC_LSI_Disable
+ * @retval None
+ */
+__STATIC_INLINE void LL_RCC_LSI_Disable(void)
+{
+ CLEAR_BIT(RCC->CSR, RCC_CSR_LSION);
+}
+
+/**
+ * @brief Check if LSI is Ready
+ * @rmtoll CSR LSIRDY LL_RCC_LSI_IsReady
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_RCC_LSI_IsReady(void)
+{
+ return (READ_BIT(RCC->CSR, RCC_CSR_LSIRDY) == (RCC_CSR_LSIRDY));
+}
+
+/**
+ * @}
+ */
+
+/** @defgroup RCC_LL_EF_System System
+ * @{
+ */
+
+/**
+ * @brief Configure the system clock source
+ * @rmtoll CFGR SW LL_RCC_SetSysClkSource
+ * @param Source This parameter can be one of the following values:
+ * @arg @ref LL_RCC_SYS_CLKSOURCE_HSI
+ * @arg @ref LL_RCC_SYS_CLKSOURCE_HSE
+ * @arg @ref LL_RCC_SYS_CLKSOURCE_PLL
+ * @arg @ref LL_RCC_SYS_CLKSOURCE_HSI48 (*)
+ *
+ * (*) value not defined in all devices
+ * @retval None
+ */
+__STATIC_INLINE void LL_RCC_SetSysClkSource(uint32_t Source)
+{
+ MODIFY_REG(RCC->CFGR, RCC_CFGR_SW, Source);
+}
+
+/**
+ * @brief Get the system clock source
+ * @rmtoll CFGR SWS LL_RCC_GetSysClkSource
+ * @retval Returned value can be one of the following values:
+ * @arg @ref LL_RCC_SYS_CLKSOURCE_STATUS_HSI
+ * @arg @ref LL_RCC_SYS_CLKSOURCE_STATUS_HSE
+ * @arg @ref LL_RCC_SYS_CLKSOURCE_STATUS_PLL
+ * @arg @ref LL_RCC_SYS_CLKSOURCE_STATUS_HSI48 (*)
+ *
+ * (*) value not defined in all devices
+ */
+__STATIC_INLINE uint32_t LL_RCC_GetSysClkSource(void)
+{
+ return (uint32_t)(READ_BIT(RCC->CFGR, RCC_CFGR_SWS));
+}
+
+/**
+ * @brief Set AHB prescaler
+ * @rmtoll CFGR HPRE LL_RCC_SetAHBPrescaler
+ * @param Prescaler This parameter can be one of the following values:
+ * @arg @ref LL_RCC_SYSCLK_DIV_1
+ * @arg @ref LL_RCC_SYSCLK_DIV_2
+ * @arg @ref LL_RCC_SYSCLK_DIV_4
+ * @arg @ref LL_RCC_SYSCLK_DIV_8
+ * @arg @ref LL_RCC_SYSCLK_DIV_16
+ * @arg @ref LL_RCC_SYSCLK_DIV_64
+ * @arg @ref LL_RCC_SYSCLK_DIV_128
+ * @arg @ref LL_RCC_SYSCLK_DIV_256
+ * @arg @ref LL_RCC_SYSCLK_DIV_512
+ * @retval None
+ */
+__STATIC_INLINE void LL_RCC_SetAHBPrescaler(uint32_t Prescaler)
+{
+ MODIFY_REG(RCC->CFGR, RCC_CFGR_HPRE, Prescaler);
+}
+
+/**
+ * @brief Set APB1 prescaler
+ * @rmtoll CFGR PPRE LL_RCC_SetAPB1Prescaler
+ * @param Prescaler This parameter can be one of the following values:
+ * @arg @ref LL_RCC_APB1_DIV_1
+ * @arg @ref LL_RCC_APB1_DIV_2
+ * @arg @ref LL_RCC_APB1_DIV_4
+ * @arg @ref LL_RCC_APB1_DIV_8
+ * @arg @ref LL_RCC_APB1_DIV_16
+ * @retval None
+ */
+__STATIC_INLINE void LL_RCC_SetAPB1Prescaler(uint32_t Prescaler)
+{
+ MODIFY_REG(RCC->CFGR, RCC_CFGR_PPRE, Prescaler);
+}
+
+/**
+ * @brief Get AHB prescaler
+ * @rmtoll CFGR HPRE LL_RCC_GetAHBPrescaler
+ * @retval Returned value can be one of the following values:
+ * @arg @ref LL_RCC_SYSCLK_DIV_1
+ * @arg @ref LL_RCC_SYSCLK_DIV_2
+ * @arg @ref LL_RCC_SYSCLK_DIV_4
+ * @arg @ref LL_RCC_SYSCLK_DIV_8
+ * @arg @ref LL_RCC_SYSCLK_DIV_16
+ * @arg @ref LL_RCC_SYSCLK_DIV_64
+ * @arg @ref LL_RCC_SYSCLK_DIV_128
+ * @arg @ref LL_RCC_SYSCLK_DIV_256
+ * @arg @ref LL_RCC_SYSCLK_DIV_512
+ */
+__STATIC_INLINE uint32_t LL_RCC_GetAHBPrescaler(void)
+{
+ return (uint32_t)(READ_BIT(RCC->CFGR, RCC_CFGR_HPRE));
+}
+
+/**
+ * @brief Get APB1 prescaler
+ * @rmtoll CFGR PPRE LL_RCC_GetAPB1Prescaler
+ * @retval Returned value can be one of the following values:
+ * @arg @ref LL_RCC_APB1_DIV_1
+ * @arg @ref LL_RCC_APB1_DIV_2
+ * @arg @ref LL_RCC_APB1_DIV_4
+ * @arg @ref LL_RCC_APB1_DIV_8
+ * @arg @ref LL_RCC_APB1_DIV_16
+ */
+__STATIC_INLINE uint32_t LL_RCC_GetAPB1Prescaler(void)
+{
+ return (uint32_t)(READ_BIT(RCC->CFGR, RCC_CFGR_PPRE));
+}
+
+/**
+ * @}
+ */
+
+/** @defgroup RCC_LL_EF_MCO MCO
+ * @{
+ */
+
+/**
+ * @brief Configure MCOx
+ * @rmtoll CFGR MCO LL_RCC_ConfigMCO\n
+ * CFGR MCOPRE LL_RCC_ConfigMCO\n
+ * CFGR PLLNODIV LL_RCC_ConfigMCO
+ * @param MCOxSource This parameter can be one of the following values:
+ * @arg @ref LL_RCC_MCO1SOURCE_NOCLOCK
+ * @arg @ref LL_RCC_MCO1SOURCE_HSI14
+ * @arg @ref LL_RCC_MCO1SOURCE_SYSCLK
+ * @arg @ref LL_RCC_MCO1SOURCE_HSI
+ * @arg @ref LL_RCC_MCO1SOURCE_HSE
+ * @arg @ref LL_RCC_MCO1SOURCE_LSI
+ * @arg @ref LL_RCC_MCO1SOURCE_LSE
+ * @arg @ref LL_RCC_MCO1SOURCE_HSI48 (*)
+ * @arg @ref LL_RCC_MCO1SOURCE_PLLCLK (*)
+ * @arg @ref LL_RCC_MCO1SOURCE_PLLCLK_DIV_2
+ *
+ * (*) value not defined in all devices
+ * @param MCOxPrescaler This parameter can be one of the following values:
+ * @arg @ref LL_RCC_MCO1_DIV_1
+ * @arg @ref LL_RCC_MCO1_DIV_2 (*)
+ * @arg @ref LL_RCC_MCO1_DIV_4 (*)
+ * @arg @ref LL_RCC_MCO1_DIV_8 (*)
+ * @arg @ref LL_RCC_MCO1_DIV_16 (*)
+ * @arg @ref LL_RCC_MCO1_DIV_32 (*)
+ * @arg @ref LL_RCC_MCO1_DIV_64 (*)
+ * @arg @ref LL_RCC_MCO1_DIV_128 (*)
+ *
+ * (*) value not defined in all devices
+ * @retval None
+ */
+__STATIC_INLINE void LL_RCC_ConfigMCO(uint32_t MCOxSource, uint32_t MCOxPrescaler)
+{
+#if defined(RCC_CFGR_MCOPRE)
+#if defined(RCC_CFGR_PLLNODIV)
+ MODIFY_REG(RCC->CFGR, RCC_CFGR_MCOSEL | RCC_CFGR_MCOPRE | RCC_CFGR_PLLNODIV, MCOxSource | MCOxPrescaler);
+#else
+ MODIFY_REG(RCC->CFGR, RCC_CFGR_MCOSEL | RCC_CFGR_MCOPRE, MCOxSource | MCOxPrescaler);
+#endif /* RCC_CFGR_PLLNODIV */
+#else
+ MODIFY_REG(RCC->CFGR, RCC_CFGR_MCOSEL, MCOxSource);
+#endif /* RCC_CFGR_MCOPRE */
+}
+
+/**
+ * @}
+ */
+
+/** @defgroup RCC_LL_EF_Peripheral_Clock_Source Peripheral Clock Source
+ * @{
+ */
+
+/**
+ * @brief Configure USARTx clock source
+ * @rmtoll CFGR3 USART1SW LL_RCC_SetUSARTClockSource\n
+ * CFGR3 USART2SW LL_RCC_SetUSARTClockSource\n
+ * CFGR3 USART3SW LL_RCC_SetUSARTClockSource
+ * @param USARTxSource This parameter can be one of the following values:
+ * @arg @ref LL_RCC_USART1_CLKSOURCE_PCLK1
+ * @arg @ref LL_RCC_USART1_CLKSOURCE_SYSCLK
+ * @arg @ref LL_RCC_USART1_CLKSOURCE_LSE
+ * @arg @ref LL_RCC_USART1_CLKSOURCE_HSI
+ * @arg @ref LL_RCC_USART2_CLKSOURCE_PCLK1 (*)
+ * @arg @ref LL_RCC_USART2_CLKSOURCE_SYSCLK (*)
+ * @arg @ref LL_RCC_USART2_CLKSOURCE_LSE (*)
+ * @arg @ref LL_RCC_USART2_CLKSOURCE_HSI (*)
+ * @arg @ref LL_RCC_USART3_CLKSOURCE_PCLK1 (*)
+ * @arg @ref LL_RCC_USART3_CLKSOURCE_SYSCLK (*)
+ * @arg @ref LL_RCC_USART3_CLKSOURCE_LSE (*)
+ * @arg @ref LL_RCC_USART3_CLKSOURCE_HSI (*)
+ *
+ * (*) value not defined in all devices.
+ * @retval None
+ */
+__STATIC_INLINE void LL_RCC_SetUSARTClockSource(uint32_t USARTxSource)
+{
+ MODIFY_REG(RCC->CFGR3, (RCC_CFGR3_USART1SW << ((USARTxSource & 0xFF000000U) >> 24U)), (USARTxSource & 0x00FFFFFFU));
+}
+
+/**
+ * @brief Configure I2Cx clock source
+ * @rmtoll CFGR3 I2C1SW LL_RCC_SetI2CClockSource
+ * @param I2CxSource This parameter can be one of the following values:
+ * @arg @ref LL_RCC_I2C1_CLKSOURCE_HSI
+ * @arg @ref LL_RCC_I2C1_CLKSOURCE_SYSCLK
+ * @retval None
+ */
+__STATIC_INLINE void LL_RCC_SetI2CClockSource(uint32_t I2CxSource)
+{
+ MODIFY_REG(RCC->CFGR3, RCC_CFGR3_I2C1SW, I2CxSource);
+}
+
+#if defined(CEC)
+/**
+ * @brief Configure CEC clock source
+ * @rmtoll CFGR3 CECSW LL_RCC_SetCECClockSource
+ * @param CECxSource This parameter can be one of the following values:
+ * @arg @ref LL_RCC_CEC_CLKSOURCE_HSI_DIV244
+ * @arg @ref LL_RCC_CEC_CLKSOURCE_LSE
+ * @retval None
+ */
+__STATIC_INLINE void LL_RCC_SetCECClockSource(uint32_t CECxSource)
+{
+ MODIFY_REG(RCC->CFGR3, RCC_CFGR3_CECSW, CECxSource);
+}
+#endif /* CEC */
+
+#if defined(USB)
+/**
+ * @brief Configure USB clock source
+ * @rmtoll CFGR3 USBSW LL_RCC_SetUSBClockSource
+ * @param USBxSource This parameter can be one of the following values:
+ * @arg @ref LL_RCC_USB_CLKSOURCE_HSI48 (*)
+ * @arg @ref LL_RCC_USB_CLKSOURCE_NONE (*)
+ * @arg @ref LL_RCC_USB_CLKSOURCE_PLL
+ *
+ * (*) value not defined in all devices.
+ * @retval None
+ */
+__STATIC_INLINE void LL_RCC_SetUSBClockSource(uint32_t USBxSource)
+{
+ MODIFY_REG(RCC->CFGR3, RCC_CFGR3_USBSW, USBxSource);
+}
+#endif /* USB */
+
+/**
+ * @brief Get USARTx clock source
+ * @rmtoll CFGR3 USART1SW LL_RCC_GetUSARTClockSource\n
+ * CFGR3 USART2SW LL_RCC_GetUSARTClockSource\n
+ * CFGR3 USART3SW LL_RCC_GetUSARTClockSource
+ * @param USARTx This parameter can be one of the following values:
+ * @arg @ref LL_RCC_USART1_CLKSOURCE
+ * @arg @ref LL_RCC_USART2_CLKSOURCE (*)
+ * @arg @ref LL_RCC_USART3_CLKSOURCE (*)
+ *
+ * (*) value not defined in all devices.
+ * @retval Returned value can be one of the following values:
+ * @arg @ref LL_RCC_USART1_CLKSOURCE_PCLK1
+ * @arg @ref LL_RCC_USART1_CLKSOURCE_SYSCLK
+ * @arg @ref LL_RCC_USART1_CLKSOURCE_LSE
+ * @arg @ref LL_RCC_USART1_CLKSOURCE_HSI
+ * @arg @ref LL_RCC_USART2_CLKSOURCE_PCLK1 (*)
+ * @arg @ref LL_RCC_USART2_CLKSOURCE_SYSCLK (*)
+ * @arg @ref LL_RCC_USART2_CLKSOURCE_LSE (*)
+ * @arg @ref LL_RCC_USART2_CLKSOURCE_HSI (*)
+ * @arg @ref LL_RCC_USART3_CLKSOURCE_PCLK1 (*)
+ * @arg @ref LL_RCC_USART3_CLKSOURCE_SYSCLK (*)
+ * @arg @ref LL_RCC_USART3_CLKSOURCE_LSE (*)
+ * @arg @ref LL_RCC_USART3_CLKSOURCE_HSI (*)
+ *
+ * (*) value not defined in all devices.
+ */
+__STATIC_INLINE uint32_t LL_RCC_GetUSARTClockSource(uint32_t USARTx)
+{
+ return (uint32_t)(READ_BIT(RCC->CFGR3, (RCC_CFGR3_USART1SW << USARTx)) | (USARTx << 24U));
+}
+
+/**
+ * @brief Get I2Cx clock source
+ * @rmtoll CFGR3 I2C1SW LL_RCC_GetI2CClockSource
+ * @param I2Cx This parameter can be one of the following values:
+ * @arg @ref LL_RCC_I2C1_CLKSOURCE
+ * @retval Returned value can be one of the following values:
+ * @arg @ref LL_RCC_I2C1_CLKSOURCE_HSI
+ * @arg @ref LL_RCC_I2C1_CLKSOURCE_SYSCLK
+ */
+__STATIC_INLINE uint32_t LL_RCC_GetI2CClockSource(uint32_t I2Cx)
+{
+ return (uint32_t)(READ_BIT(RCC->CFGR3, I2Cx));
+}
+
+#if defined(CEC)
+/**
+ * @brief Get CEC clock source
+ * @rmtoll CFGR3 CECSW LL_RCC_GetCECClockSource
+ * @param CECx This parameter can be one of the following values:
+ * @arg @ref LL_RCC_CEC_CLKSOURCE
+ * @retval Returned value can be one of the following values:
+ * @arg @ref LL_RCC_CEC_CLKSOURCE_HSI_DIV244
+ * @arg @ref LL_RCC_CEC_CLKSOURCE_LSE
+ */
+__STATIC_INLINE uint32_t LL_RCC_GetCECClockSource(uint32_t CECx)
+{
+ return (uint32_t)(READ_BIT(RCC->CFGR3, CECx));
+}
+#endif /* CEC */
+
+#if defined(USB)
+/**
+ * @brief Get USBx clock source
+ * @rmtoll CFGR3 USBSW LL_RCC_GetUSBClockSource
+ * @param USBx This parameter can be one of the following values:
+ * @arg @ref LL_RCC_USB_CLKSOURCE
+ * @retval Returned value can be one of the following values:
+ * @arg @ref LL_RCC_USB_CLKSOURCE_HSI48 (*)
+ * @arg @ref LL_RCC_USB_CLKSOURCE_NONE (*)
+ * @arg @ref LL_RCC_USB_CLKSOURCE_PLL
+ *
+ * (*) value not defined in all devices.
+ */
+__STATIC_INLINE uint32_t LL_RCC_GetUSBClockSource(uint32_t USBx)
+{
+ return (uint32_t)(READ_BIT(RCC->CFGR3, USBx));
+}
+#endif /* USB */
+
+/**
+ * @}
+ */
+
+/** @defgroup RCC_LL_EF_RTC RTC
+ * @{
+ */
+
+/**
+ * @brief Set RTC Clock Source
+ * @note Once the RTC clock source has been selected, it cannot be changed any more unless
+ * the Backup domain is reset. The BDRST bit can be used to reset them.
+ * @rmtoll BDCR RTCSEL LL_RCC_SetRTCClockSource
+ * @param Source This parameter can be one of the following values:
+ * @arg @ref LL_RCC_RTC_CLKSOURCE_NONE
+ * @arg @ref LL_RCC_RTC_CLKSOURCE_LSE
+ * @arg @ref LL_RCC_RTC_CLKSOURCE_LSI
+ * @arg @ref LL_RCC_RTC_CLKSOURCE_HSE_DIV32
+ * @retval None
+ */
+__STATIC_INLINE void LL_RCC_SetRTCClockSource(uint32_t Source)
+{
+ MODIFY_REG(RCC->BDCR, RCC_BDCR_RTCSEL, Source);
+}
+
+/**
+ * @brief Get RTC Clock Source
+ * @rmtoll BDCR RTCSEL LL_RCC_GetRTCClockSource
+ * @retval Returned value can be one of the following values:
+ * @arg @ref LL_RCC_RTC_CLKSOURCE_NONE
+ * @arg @ref LL_RCC_RTC_CLKSOURCE_LSE
+ * @arg @ref LL_RCC_RTC_CLKSOURCE_LSI
+ * @arg @ref LL_RCC_RTC_CLKSOURCE_HSE_DIV32
+ */
+__STATIC_INLINE uint32_t LL_RCC_GetRTCClockSource(void)
+{
+ return (uint32_t)(READ_BIT(RCC->BDCR, RCC_BDCR_RTCSEL));
+}
+
+/**
+ * @brief Enable RTC
+ * @rmtoll BDCR RTCEN LL_RCC_EnableRTC
+ * @retval None
+ */
+__STATIC_INLINE void LL_RCC_EnableRTC(void)
+{
+ SET_BIT(RCC->BDCR, RCC_BDCR_RTCEN);
+}
+
+/**
+ * @brief Disable RTC
+ * @rmtoll BDCR RTCEN LL_RCC_DisableRTC
+ * @retval None
+ */
+__STATIC_INLINE void LL_RCC_DisableRTC(void)
+{
+ CLEAR_BIT(RCC->BDCR, RCC_BDCR_RTCEN);
+}
+
+/**
+ * @brief Check if RTC has been enabled or not
+ * @rmtoll BDCR RTCEN LL_RCC_IsEnabledRTC
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_RCC_IsEnabledRTC(void)
+{
+ return (READ_BIT(RCC->BDCR, RCC_BDCR_RTCEN) == (RCC_BDCR_RTCEN));
+}
+
+/**
+ * @brief Force the Backup domain reset
+ * @rmtoll BDCR BDRST LL_RCC_ForceBackupDomainReset
+ * @retval None
+ */
+__STATIC_INLINE void LL_RCC_ForceBackupDomainReset(void)
+{
+ SET_BIT(RCC->BDCR, RCC_BDCR_BDRST);
+}
+
+/**
+ * @brief Release the Backup domain reset
+ * @rmtoll BDCR BDRST LL_RCC_ReleaseBackupDomainReset
+ * @retval None
+ */
+__STATIC_INLINE void LL_RCC_ReleaseBackupDomainReset(void)
+{
+ CLEAR_BIT(RCC->BDCR, RCC_BDCR_BDRST);
+}
+
+/**
+ * @}
+ */
+
+/** @defgroup RCC_LL_EF_PLL PLL
+ * @{
+ */
+
+/**
+ * @brief Enable PLL
+ * @rmtoll CR PLLON LL_RCC_PLL_Enable
+ * @retval None
+ */
+__STATIC_INLINE void LL_RCC_PLL_Enable(void)
+{
+ SET_BIT(RCC->CR, RCC_CR_PLLON);
+}
+
+/**
+ * @brief Disable PLL
+ * @note Cannot be disabled if the PLL clock is used as the system clock
+ * @rmtoll CR PLLON LL_RCC_PLL_Disable
+ * @retval None
+ */
+__STATIC_INLINE void LL_RCC_PLL_Disable(void)
+{
+ CLEAR_BIT(RCC->CR, RCC_CR_PLLON);
+}
+
+/**
+ * @brief Check if PLL Ready
+ * @rmtoll CR PLLRDY LL_RCC_PLL_IsReady
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_RCC_PLL_IsReady(void)
+{
+ return (READ_BIT(RCC->CR, RCC_CR_PLLRDY) == (RCC_CR_PLLRDY));
+}
+
+#if defined(RCC_PLLSRC_PREDIV1_SUPPORT)
+/**
+ * @brief Configure PLL used for SYSCLK Domain
+ * @rmtoll CFGR PLLSRC LL_RCC_PLL_ConfigDomain_SYS\n
+ * CFGR PLLMUL LL_RCC_PLL_ConfigDomain_SYS\n
+ * CFGR2 PREDIV LL_RCC_PLL_ConfigDomain_SYS
+ * @param Source This parameter can be one of the following values:
+ * @arg @ref LL_RCC_PLLSOURCE_HSI
+ * @arg @ref LL_RCC_PLLSOURCE_HSE
+ * @arg @ref LL_RCC_PLLSOURCE_HSI48 (*)
+ *
+ * (*) value not defined in all devices
+ * @param PLLMul This parameter can be one of the following values:
+ * @arg @ref LL_RCC_PLL_MUL_2
+ * @arg @ref LL_RCC_PLL_MUL_3
+ * @arg @ref LL_RCC_PLL_MUL_4
+ * @arg @ref LL_RCC_PLL_MUL_5
+ * @arg @ref LL_RCC_PLL_MUL_6
+ * @arg @ref LL_RCC_PLL_MUL_7
+ * @arg @ref LL_RCC_PLL_MUL_8
+ * @arg @ref LL_RCC_PLL_MUL_9
+ * @arg @ref LL_RCC_PLL_MUL_10
+ * @arg @ref LL_RCC_PLL_MUL_11
+ * @arg @ref LL_RCC_PLL_MUL_12
+ * @arg @ref LL_RCC_PLL_MUL_13
+ * @arg @ref LL_RCC_PLL_MUL_14
+ * @arg @ref LL_RCC_PLL_MUL_15
+ * @arg @ref LL_RCC_PLL_MUL_16
+ * @param PLLDiv This parameter can be one of the following values:
+ * @arg @ref LL_RCC_PREDIV_DIV_1
+ * @arg @ref LL_RCC_PREDIV_DIV_2
+ * @arg @ref LL_RCC_PREDIV_DIV_3
+ * @arg @ref LL_RCC_PREDIV_DIV_4
+ * @arg @ref LL_RCC_PREDIV_DIV_5
+ * @arg @ref LL_RCC_PREDIV_DIV_6
+ * @arg @ref LL_RCC_PREDIV_DIV_7
+ * @arg @ref LL_RCC_PREDIV_DIV_8
+ * @arg @ref LL_RCC_PREDIV_DIV_9
+ * @arg @ref LL_RCC_PREDIV_DIV_10
+ * @arg @ref LL_RCC_PREDIV_DIV_11
+ * @arg @ref LL_RCC_PREDIV_DIV_12
+ * @arg @ref LL_RCC_PREDIV_DIV_13
+ * @arg @ref LL_RCC_PREDIV_DIV_14
+ * @arg @ref LL_RCC_PREDIV_DIV_15
+ * @arg @ref LL_RCC_PREDIV_DIV_16
+ * @retval None
+ */
+__STATIC_INLINE void LL_RCC_PLL_ConfigDomain_SYS(uint32_t Source, uint32_t PLLMul, uint32_t PLLDiv)
+{
+ MODIFY_REG(RCC->CFGR, RCC_CFGR_PLLSRC | RCC_CFGR_PLLMUL, Source | PLLMul);
+ MODIFY_REG(RCC->CFGR2, RCC_CFGR2_PREDIV, PLLDiv);
+}
+
+#else
+
+/**
+ * @brief Configure PLL used for SYSCLK Domain
+ * @rmtoll CFGR PLLSRC LL_RCC_PLL_ConfigDomain_SYS\n
+ * CFGR PLLMUL LL_RCC_PLL_ConfigDomain_SYS\n
+ * CFGR2 PREDIV LL_RCC_PLL_ConfigDomain_SYS
+ * @param Source This parameter can be one of the following values:
+ * @arg @ref LL_RCC_PLLSOURCE_HSI_DIV_2
+ * @arg @ref LL_RCC_PLLSOURCE_HSE_DIV_1
+ * @arg @ref LL_RCC_PLLSOURCE_HSE_DIV_2
+ * @arg @ref LL_RCC_PLLSOURCE_HSE_DIV_3
+ * @arg @ref LL_RCC_PLLSOURCE_HSE_DIV_4
+ * @arg @ref LL_RCC_PLLSOURCE_HSE_DIV_5
+ * @arg @ref LL_RCC_PLLSOURCE_HSE_DIV_6
+ * @arg @ref LL_RCC_PLLSOURCE_HSE_DIV_7
+ * @arg @ref LL_RCC_PLLSOURCE_HSE_DIV_8
+ * @arg @ref LL_RCC_PLLSOURCE_HSE_DIV_9
+ * @arg @ref LL_RCC_PLLSOURCE_HSE_DIV_10
+ * @arg @ref LL_RCC_PLLSOURCE_HSE_DIV_11
+ * @arg @ref LL_RCC_PLLSOURCE_HSE_DIV_12
+ * @arg @ref LL_RCC_PLLSOURCE_HSE_DIV_13
+ * @arg @ref LL_RCC_PLLSOURCE_HSE_DIV_14
+ * @arg @ref LL_RCC_PLLSOURCE_HSE_DIV_15
+ * @arg @ref LL_RCC_PLLSOURCE_HSE_DIV_16
+ * @param PLLMul This parameter can be one of the following values:
+ * @arg @ref LL_RCC_PLL_MUL_2
+ * @arg @ref LL_RCC_PLL_MUL_3
+ * @arg @ref LL_RCC_PLL_MUL_4
+ * @arg @ref LL_RCC_PLL_MUL_5
+ * @arg @ref LL_RCC_PLL_MUL_6
+ * @arg @ref LL_RCC_PLL_MUL_7
+ * @arg @ref LL_RCC_PLL_MUL_8
+ * @arg @ref LL_RCC_PLL_MUL_9
+ * @arg @ref LL_RCC_PLL_MUL_10
+ * @arg @ref LL_RCC_PLL_MUL_11
+ * @arg @ref LL_RCC_PLL_MUL_12
+ * @arg @ref LL_RCC_PLL_MUL_13
+ * @arg @ref LL_RCC_PLL_MUL_14
+ * @arg @ref LL_RCC_PLL_MUL_15
+ * @arg @ref LL_RCC_PLL_MUL_16
+ * @retval None
+ */
+__STATIC_INLINE void LL_RCC_PLL_ConfigDomain_SYS(uint32_t Source, uint32_t PLLMul)
+{
+ MODIFY_REG(RCC->CFGR, RCC_CFGR_PLLSRC | RCC_CFGR_PLLMUL, (Source & RCC_CFGR_PLLSRC) | PLLMul);
+ MODIFY_REG(RCC->CFGR2, RCC_CFGR2_PREDIV, (Source & RCC_CFGR2_PREDIV));
+}
+#endif /* RCC_PLLSRC_PREDIV1_SUPPORT */
+
+/**
+ * @brief Configure PLL clock source
+ * @rmtoll CFGR PLLSRC LL_RCC_PLL_SetMainSource
+ * @param PLLSource This parameter can be one of the following values:
+ * @arg @ref LL_RCC_PLLSOURCE_NONE
+ * @arg @ref LL_RCC_PLLSOURCE_HSI (*)
+ * @arg @ref LL_RCC_PLLSOURCE_HSI_DIV_2 (*)
+ * @arg @ref LL_RCC_PLLSOURCE_HSE
+ * @arg @ref LL_RCC_PLLSOURCE_HSI48 (*)
+ *
+ * (*) value not defined in all devices
+ * @retval None
+ */
+__STATIC_INLINE void LL_RCC_PLL_SetMainSource(uint32_t PLLSource)
+{
+ MODIFY_REG(RCC->CFGR, RCC_CFGR_PLLSRC, PLLSource);
+}
+
+/**
+ * @brief Get the oscillator used as PLL clock source.
+ * @rmtoll CFGR PLLSRC LL_RCC_PLL_GetMainSource
+ * @retval Returned value can be one of the following values:
+ * @arg @ref LL_RCC_PLLSOURCE_NONE
+ * @arg @ref LL_RCC_PLLSOURCE_HSI (*)
+ * @arg @ref LL_RCC_PLLSOURCE_HSI_DIV_2 (*)
+ * @arg @ref LL_RCC_PLLSOURCE_HSE
+ * @arg @ref LL_RCC_PLLSOURCE_HSI48 (*)
+ *
+ * (*) value not defined in all devices
+ */
+__STATIC_INLINE uint32_t LL_RCC_PLL_GetMainSource(void)
+{
+ return (uint32_t)(READ_BIT(RCC->CFGR, RCC_CFGR_PLLSRC));
+}
+
+/**
+ * @brief Get PLL multiplication Factor
+ * @rmtoll CFGR PLLMUL LL_RCC_PLL_GetMultiplicator
+ * @retval Returned value can be one of the following values:
+ * @arg @ref LL_RCC_PLL_MUL_2
+ * @arg @ref LL_RCC_PLL_MUL_3
+ * @arg @ref LL_RCC_PLL_MUL_4
+ * @arg @ref LL_RCC_PLL_MUL_5
+ * @arg @ref LL_RCC_PLL_MUL_6
+ * @arg @ref LL_RCC_PLL_MUL_7
+ * @arg @ref LL_RCC_PLL_MUL_8
+ * @arg @ref LL_RCC_PLL_MUL_9
+ * @arg @ref LL_RCC_PLL_MUL_10
+ * @arg @ref LL_RCC_PLL_MUL_11
+ * @arg @ref LL_RCC_PLL_MUL_12
+ * @arg @ref LL_RCC_PLL_MUL_13
+ * @arg @ref LL_RCC_PLL_MUL_14
+ * @arg @ref LL_RCC_PLL_MUL_15
+ * @arg @ref LL_RCC_PLL_MUL_16
+ */
+__STATIC_INLINE uint32_t LL_RCC_PLL_GetMultiplicator(void)
+{
+ return (uint32_t)(READ_BIT(RCC->CFGR, RCC_CFGR_PLLMUL));
+}
+
+/**
+ * @brief Get PREDIV division factor for the main PLL
+ * @note They can be written only when the PLL is disabled
+ * @rmtoll CFGR2 PREDIV LL_RCC_PLL_GetPrediv
+ * @retval Returned value can be one of the following values:
+ * @arg @ref LL_RCC_PREDIV_DIV_1
+ * @arg @ref LL_RCC_PREDIV_DIV_2
+ * @arg @ref LL_RCC_PREDIV_DIV_3
+ * @arg @ref LL_RCC_PREDIV_DIV_4
+ * @arg @ref LL_RCC_PREDIV_DIV_5
+ * @arg @ref LL_RCC_PREDIV_DIV_6
+ * @arg @ref LL_RCC_PREDIV_DIV_7
+ * @arg @ref LL_RCC_PREDIV_DIV_8
+ * @arg @ref LL_RCC_PREDIV_DIV_9
+ * @arg @ref LL_RCC_PREDIV_DIV_10
+ * @arg @ref LL_RCC_PREDIV_DIV_11
+ * @arg @ref LL_RCC_PREDIV_DIV_12
+ * @arg @ref LL_RCC_PREDIV_DIV_13
+ * @arg @ref LL_RCC_PREDIV_DIV_14
+ * @arg @ref LL_RCC_PREDIV_DIV_15
+ * @arg @ref LL_RCC_PREDIV_DIV_16
+ */
+__STATIC_INLINE uint32_t LL_RCC_PLL_GetPrediv(void)
+{
+ return (uint32_t)(READ_BIT(RCC->CFGR2, RCC_CFGR2_PREDIV));
+}
+
+/**
+ * @}
+ */
+
+/** @defgroup RCC_LL_EF_FLAG_Management FLAG Management
+ * @{
+ */
+
+/**
+ * @brief Clear LSI ready interrupt flag
+ * @rmtoll CIR LSIRDYC LL_RCC_ClearFlag_LSIRDY
+ * @retval None
+ */
+__STATIC_INLINE void LL_RCC_ClearFlag_LSIRDY(void)
+{
+ SET_BIT(RCC->CIR, RCC_CIR_LSIRDYC);
+}
+
+/**
+ * @brief Clear LSE ready interrupt flag
+ * @rmtoll CIR LSERDYC LL_RCC_ClearFlag_LSERDY
+ * @retval None
+ */
+__STATIC_INLINE void LL_RCC_ClearFlag_LSERDY(void)
+{
+ SET_BIT(RCC->CIR, RCC_CIR_LSERDYC);
+}
+
+/**
+ * @brief Clear HSI ready interrupt flag
+ * @rmtoll CIR HSIRDYC LL_RCC_ClearFlag_HSIRDY
+ * @retval None
+ */
+__STATIC_INLINE void LL_RCC_ClearFlag_HSIRDY(void)
+{
+ SET_BIT(RCC->CIR, RCC_CIR_HSIRDYC);
+}
+
+/**
+ * @brief Clear HSE ready interrupt flag
+ * @rmtoll CIR HSERDYC LL_RCC_ClearFlag_HSERDY
+ * @retval None
+ */
+__STATIC_INLINE void LL_RCC_ClearFlag_HSERDY(void)
+{
+ SET_BIT(RCC->CIR, RCC_CIR_HSERDYC);
+}
+
+/**
+ * @brief Clear PLL ready interrupt flag
+ * @rmtoll CIR PLLRDYC LL_RCC_ClearFlag_PLLRDY
+ * @retval None
+ */
+__STATIC_INLINE void LL_RCC_ClearFlag_PLLRDY(void)
+{
+ SET_BIT(RCC->CIR, RCC_CIR_PLLRDYC);
+}
+
+/**
+ * @brief Clear HSI14 ready interrupt flag
+ * @rmtoll CIR HSI14RDYC LL_RCC_ClearFlag_HSI14RDY
+ * @retval None
+ */
+__STATIC_INLINE void LL_RCC_ClearFlag_HSI14RDY(void)
+{
+ SET_BIT(RCC->CIR, RCC_CIR_HSI14RDYC);
+}
+
+#if defined(RCC_HSI48_SUPPORT)
+/**
+ * @brief Clear HSI48 ready interrupt flag
+ * @rmtoll CIR HSI48RDYC LL_RCC_ClearFlag_HSI48RDY
+ * @retval None
+ */
+__STATIC_INLINE void LL_RCC_ClearFlag_HSI48RDY(void)
+{
+ SET_BIT(RCC->CIR, RCC_CIR_HSI48RDYC);
+}
+#endif /* RCC_HSI48_SUPPORT */
+
+/**
+ * @brief Clear Clock security system interrupt flag
+ * @rmtoll CIR CSSC LL_RCC_ClearFlag_HSECSS
+ * @retval None
+ */
+__STATIC_INLINE void LL_RCC_ClearFlag_HSECSS(void)
+{
+ SET_BIT(RCC->CIR, RCC_CIR_CSSC);
+}
+
+/**
+ * @brief Check if LSI ready interrupt occurred or not
+ * @rmtoll CIR LSIRDYF LL_RCC_IsActiveFlag_LSIRDY
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_LSIRDY(void)
+{
+ return (READ_BIT(RCC->CIR, RCC_CIR_LSIRDYF) == (RCC_CIR_LSIRDYF));
+}
+
+/**
+ * @brief Check if LSE ready interrupt occurred or not
+ * @rmtoll CIR LSERDYF LL_RCC_IsActiveFlag_LSERDY
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_LSERDY(void)
+{
+ return (READ_BIT(RCC->CIR, RCC_CIR_LSERDYF) == (RCC_CIR_LSERDYF));
+}
+
+/**
+ * @brief Check if HSI ready interrupt occurred or not
+ * @rmtoll CIR HSIRDYF LL_RCC_IsActiveFlag_HSIRDY
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_HSIRDY(void)
+{
+ return (READ_BIT(RCC->CIR, RCC_CIR_HSIRDYF) == (RCC_CIR_HSIRDYF));
+}
+
+/**
+ * @brief Check if HSE ready interrupt occurred or not
+ * @rmtoll CIR HSERDYF LL_RCC_IsActiveFlag_HSERDY
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_HSERDY(void)
+{
+ return (READ_BIT(RCC->CIR, RCC_CIR_HSERDYF) == (RCC_CIR_HSERDYF));
+}
+
+/**
+ * @brief Check if PLL ready interrupt occurred or not
+ * @rmtoll CIR PLLRDYF LL_RCC_IsActiveFlag_PLLRDY
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_PLLRDY(void)
+{
+ return (READ_BIT(RCC->CIR, RCC_CIR_PLLRDYF) == (RCC_CIR_PLLRDYF));
+}
+
+/**
+ * @brief Check if HSI14 ready interrupt occurred or not
+ * @rmtoll CIR HSI14RDYF LL_RCC_IsActiveFlag_HSI14RDY
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_HSI14RDY(void)
+{
+ return (READ_BIT(RCC->CIR, RCC_CIR_HSI14RDYF) == (RCC_CIR_HSI14RDYF));
+}
+
+#if defined(RCC_HSI48_SUPPORT)
+/**
+ * @brief Check if HSI48 ready interrupt occurred or not
+ * @rmtoll CIR HSI48RDYF LL_RCC_IsActiveFlag_HSI48RDY
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_HSI48RDY(void)
+{
+ return (READ_BIT(RCC->CIR, RCC_CIR_HSI48RDYF) == (RCC_CIR_HSI48RDYF));
+}
+#endif /* RCC_HSI48_SUPPORT */
+
+/**
+ * @brief Check if Clock security system interrupt occurred or not
+ * @rmtoll CIR CSSF LL_RCC_IsActiveFlag_HSECSS
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_HSECSS(void)
+{
+ return (READ_BIT(RCC->CIR, RCC_CIR_CSSF) == (RCC_CIR_CSSF));
+}
+
+/**
+ * @brief Check if RCC flag Independent Watchdog reset is set or not.
+ * @rmtoll CSR IWDGRSTF LL_RCC_IsActiveFlag_IWDGRST
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_IWDGRST(void)
+{
+ return (READ_BIT(RCC->CSR, RCC_CSR_IWDGRSTF) == (RCC_CSR_IWDGRSTF));
+}
+
+/**
+ * @brief Check if RCC flag Low Power reset is set or not.
+ * @rmtoll CSR LPWRRSTF LL_RCC_IsActiveFlag_LPWRRST
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_LPWRRST(void)
+{
+ return (READ_BIT(RCC->CSR, RCC_CSR_LPWRRSTF) == (RCC_CSR_LPWRRSTF));
+}
+
+/**
+ * @brief Check if RCC flag is set or not.
+ * @rmtoll CSR OBLRSTF LL_RCC_IsActiveFlag_OBLRST
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_OBLRST(void)
+{
+ return (READ_BIT(RCC->CSR, RCC_CSR_OBLRSTF) == (RCC_CSR_OBLRSTF));
+}
+
+/**
+ * @brief Check if RCC flag Pin reset is set or not.
+ * @rmtoll CSR PINRSTF LL_RCC_IsActiveFlag_PINRST
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_PINRST(void)
+{
+ return (READ_BIT(RCC->CSR, RCC_CSR_PINRSTF) == (RCC_CSR_PINRSTF));
+}
+
+/**
+ * @brief Check if RCC flag POR/PDR reset is set or not.
+ * @rmtoll CSR PORRSTF LL_RCC_IsActiveFlag_PORRST
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_PORRST(void)
+{
+ return (READ_BIT(RCC->CSR, RCC_CSR_PORRSTF) == (RCC_CSR_PORRSTF));
+}
+
+/**
+ * @brief Check if RCC flag Software reset is set or not.
+ * @rmtoll CSR SFTRSTF LL_RCC_IsActiveFlag_SFTRST
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_SFTRST(void)
+{
+ return (READ_BIT(RCC->CSR, RCC_CSR_SFTRSTF) == (RCC_CSR_SFTRSTF));
+}
+
+/**
+ * @brief Check if RCC flag Window Watchdog reset is set or not.
+ * @rmtoll CSR WWDGRSTF LL_RCC_IsActiveFlag_WWDGRST
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_WWDGRST(void)
+{
+ return (READ_BIT(RCC->CSR, RCC_CSR_WWDGRSTF) == (RCC_CSR_WWDGRSTF));
+}
+
+#if defined(RCC_CSR_V18PWRRSTF)
+/**
+ * @brief Check if RCC Reset flag of the 1.8 V domain is set or not.
+ * @rmtoll CSR V18PWRRSTF LL_RCC_IsActiveFlag_V18PWRRST
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_V18PWRRST(void)
+{
+ return (READ_BIT(RCC->CSR, RCC_CSR_V18PWRRSTF) == (RCC_CSR_V18PWRRSTF));
+}
+#endif /* RCC_CSR_V18PWRRSTF */
+
+/**
+ * @brief Set RMVF bit to clear the reset flags.
+ * @rmtoll CSR RMVF LL_RCC_ClearResetFlags
+ * @retval None
+ */
+__STATIC_INLINE void LL_RCC_ClearResetFlags(void)
+{
+ SET_BIT(RCC->CSR, RCC_CSR_RMVF);
+}
+
+/**
+ * @}
+ */
+
+/** @defgroup RCC_LL_EF_IT_Management IT Management
+ * @{
+ */
+
+/**
+ * @brief Enable LSI ready interrupt
+ * @rmtoll CIR LSIRDYIE LL_RCC_EnableIT_LSIRDY
+ * @retval None
+ */
+__STATIC_INLINE void LL_RCC_EnableIT_LSIRDY(void)
+{
+ SET_BIT(RCC->CIR, RCC_CIR_LSIRDYIE);
+}
+
+/**
+ * @brief Enable LSE ready interrupt
+ * @rmtoll CIR LSERDYIE LL_RCC_EnableIT_LSERDY
+ * @retval None
+ */
+__STATIC_INLINE void LL_RCC_EnableIT_LSERDY(void)
+{
+ SET_BIT(RCC->CIR, RCC_CIR_LSERDYIE);
+}
+
+/**
+ * @brief Enable HSI ready interrupt
+ * @rmtoll CIR HSIRDYIE LL_RCC_EnableIT_HSIRDY
+ * @retval None
+ */
+__STATIC_INLINE void LL_RCC_EnableIT_HSIRDY(void)
+{
+ SET_BIT(RCC->CIR, RCC_CIR_HSIRDYIE);
+}
+
+/**
+ * @brief Enable HSE ready interrupt
+ * @rmtoll CIR HSERDYIE LL_RCC_EnableIT_HSERDY
+ * @retval None
+ */
+__STATIC_INLINE void LL_RCC_EnableIT_HSERDY(void)
+{
+ SET_BIT(RCC->CIR, RCC_CIR_HSERDYIE);
+}
+
+/**
+ * @brief Enable PLL ready interrupt
+ * @rmtoll CIR PLLRDYIE LL_RCC_EnableIT_PLLRDY
+ * @retval None
+ */
+__STATIC_INLINE void LL_RCC_EnableIT_PLLRDY(void)
+{
+ SET_BIT(RCC->CIR, RCC_CIR_PLLRDYIE);
+}
+
+/**
+ * @brief Enable HSI14 ready interrupt
+ * @rmtoll CIR HSI14RDYIE LL_RCC_EnableIT_HSI14RDY
+ * @retval None
+ */
+__STATIC_INLINE void LL_RCC_EnableIT_HSI14RDY(void)
+{
+ SET_BIT(RCC->CIR, RCC_CIR_HSI14RDYIE);
+}
+
+#if defined(RCC_HSI48_SUPPORT)
+/**
+ * @brief Enable HSI48 ready interrupt
+ * @rmtoll CIR HSI48RDYIE LL_RCC_EnableIT_HSI48RDY
+ * @retval None
+ */
+__STATIC_INLINE void LL_RCC_EnableIT_HSI48RDY(void)
+{
+ SET_BIT(RCC->CIR, RCC_CIR_HSI48RDYIE);
+}
+#endif /* RCC_HSI48_SUPPORT */
+
+/**
+ * @brief Disable LSI ready interrupt
+ * @rmtoll CIR LSIRDYIE LL_RCC_DisableIT_LSIRDY
+ * @retval None
+ */
+__STATIC_INLINE void LL_RCC_DisableIT_LSIRDY(void)
+{
+ CLEAR_BIT(RCC->CIR, RCC_CIR_LSIRDYIE);
+}
+
+/**
+ * @brief Disable LSE ready interrupt
+ * @rmtoll CIR LSERDYIE LL_RCC_DisableIT_LSERDY
+ * @retval None
+ */
+__STATIC_INLINE void LL_RCC_DisableIT_LSERDY(void)
+{
+ CLEAR_BIT(RCC->CIR, RCC_CIR_LSERDYIE);
+}
+
+/**
+ * @brief Disable HSI ready interrupt
+ * @rmtoll CIR HSIRDYIE LL_RCC_DisableIT_HSIRDY
+ * @retval None
+ */
+__STATIC_INLINE void LL_RCC_DisableIT_HSIRDY(void)
+{
+ CLEAR_BIT(RCC->CIR, RCC_CIR_HSIRDYIE);
+}
+
+/**
+ * @brief Disable HSE ready interrupt
+ * @rmtoll CIR HSERDYIE LL_RCC_DisableIT_HSERDY
+ * @retval None
+ */
+__STATIC_INLINE void LL_RCC_DisableIT_HSERDY(void)
+{
+ CLEAR_BIT(RCC->CIR, RCC_CIR_HSERDYIE);
+}
+
+/**
+ * @brief Disable PLL ready interrupt
+ * @rmtoll CIR PLLRDYIE LL_RCC_DisableIT_PLLRDY
+ * @retval None
+ */
+__STATIC_INLINE void LL_RCC_DisableIT_PLLRDY(void)
+{
+ CLEAR_BIT(RCC->CIR, RCC_CIR_PLLRDYIE);
+}
+
+/**
+ * @brief Disable HSI14 ready interrupt
+ * @rmtoll CIR HSI14RDYIE LL_RCC_DisableIT_HSI14RDY
+ * @retval None
+ */
+__STATIC_INLINE void LL_RCC_DisableIT_HSI14RDY(void)
+{
+ CLEAR_BIT(RCC->CIR, RCC_CIR_HSI14RDYIE);
+}
+
+#if defined(RCC_HSI48_SUPPORT)
+/**
+ * @brief Disable HSI48 ready interrupt
+ * @rmtoll CIR HSI48RDYIE LL_RCC_DisableIT_HSI48RDY
+ * @retval None
+ */
+__STATIC_INLINE void LL_RCC_DisableIT_HSI48RDY(void)
+{
+ CLEAR_BIT(RCC->CIR, RCC_CIR_HSI48RDYIE);
+}
+#endif /* RCC_HSI48_SUPPORT */
+
+/**
+ * @brief Checks if LSI ready interrupt source is enabled or disabled.
+ * @rmtoll CIR LSIRDYIE LL_RCC_IsEnabledIT_LSIRDY
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_RCC_IsEnabledIT_LSIRDY(void)
+{
+ return (READ_BIT(RCC->CIR, RCC_CIR_LSIRDYIE) == (RCC_CIR_LSIRDYIE));
+}
+
+/**
+ * @brief Checks if LSE ready interrupt source is enabled or disabled.
+ * @rmtoll CIR LSERDYIE LL_RCC_IsEnabledIT_LSERDY
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_RCC_IsEnabledIT_LSERDY(void)
+{
+ return (READ_BIT(RCC->CIR, RCC_CIR_LSERDYIE) == (RCC_CIR_LSERDYIE));
+}
+
+/**
+ * @brief Checks if HSI ready interrupt source is enabled or disabled.
+ * @rmtoll CIR HSIRDYIE LL_RCC_IsEnabledIT_HSIRDY
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_RCC_IsEnabledIT_HSIRDY(void)
+{
+ return (READ_BIT(RCC->CIR, RCC_CIR_HSIRDYIE) == (RCC_CIR_HSIRDYIE));
+}
+
+/**
+ * @brief Checks if HSE ready interrupt source is enabled or disabled.
+ * @rmtoll CIR HSERDYIE LL_RCC_IsEnabledIT_HSERDY
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_RCC_IsEnabledIT_HSERDY(void)
+{
+ return (READ_BIT(RCC->CIR, RCC_CIR_HSERDYIE) == (RCC_CIR_HSERDYIE));
+}
+
+/**
+ * @brief Checks if PLL ready interrupt source is enabled or disabled.
+ * @rmtoll CIR PLLRDYIE LL_RCC_IsEnabledIT_PLLRDY
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_RCC_IsEnabledIT_PLLRDY(void)
+{
+ return (READ_BIT(RCC->CIR, RCC_CIR_PLLRDYIE) == (RCC_CIR_PLLRDYIE));
+}
+
+/**
+ * @brief Checks if HSI14 ready interrupt source is enabled or disabled.
+ * @rmtoll CIR HSI14RDYIE LL_RCC_IsEnabledIT_HSI14RDY
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_RCC_IsEnabledIT_HSI14RDY(void)
+{
+ return (READ_BIT(RCC->CIR, RCC_CIR_HSI14RDYIE) == (RCC_CIR_HSI14RDYIE));
+}
+
+#if defined(RCC_HSI48_SUPPORT)
+/**
+ * @brief Checks if HSI48 ready interrupt source is enabled or disabled.
+ * @rmtoll CIR HSI48RDYIE LL_RCC_IsEnabledIT_HSI48RDY
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_RCC_IsEnabledIT_HSI48RDY(void)
+{
+ return (READ_BIT(RCC->CIR, RCC_CIR_HSI48RDYIE) == (RCC_CIR_HSI48RDYIE));
+}
+#endif /* RCC_HSI48_SUPPORT */
+
+/**
+ * @}
+ */
+
+#if defined(USE_FULL_LL_DRIVER)
+/** @defgroup RCC_LL_EF_Init De-initialization function
+ * @{
+ */
+ErrorStatus LL_RCC_DeInit(void);
+/**
+ * @}
+ */
+
+/** @defgroup RCC_LL_EF_Get_Freq Get system and peripherals clocks frequency functions
+ * @{
+ */
+void LL_RCC_GetSystemClocksFreq(LL_RCC_ClocksTypeDef *RCC_Clocks);
+uint32_t LL_RCC_GetUSARTClockFreq(uint32_t USARTxSource);
+uint32_t LL_RCC_GetI2CClockFreq(uint32_t I2CxSource);
+#if defined(USB_OTG_FS) || defined(USB)
+uint32_t LL_RCC_GetUSBClockFreq(uint32_t USBxSource);
+#endif /* USB_OTG_FS || USB */
+#if defined(CEC)
+uint32_t LL_RCC_GetCECClockFreq(uint32_t CECxSource);
+#endif /* CEC */
+/**
+ * @}
+ */
+#endif /* USE_FULL_LL_DRIVER */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+#endif /* RCC */
+
+/**
+ * @}
+ */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __STM32F0xx_LL_RCC_H */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_ll_spi.h b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_ll_spi.h
new file mode 100644
index 0000000..50dad8b
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_ll_spi.h
@@ -0,0 +1,2286 @@
+/**
+ ******************************************************************************
+ * @file stm32f0xx_ll_spi.h
+ * @author MCD Application Team
+ * @brief Header file of SPI LL module.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2016 STMicroelectronics.
+ * All rights reserved.
+ *
+ * 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 STM32F0xx_LL_SPI_H
+#define STM32F0xx_LL_SPI_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f0xx.h"
+
+/** @addtogroup STM32F0xx_LL_Driver
+ * @{
+ */
+
+#if defined (SPI1) || defined (SPI2)
+
+/** @defgroup SPI_LL SPI
+ * @{
+ */
+
+/* Private types -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private macros ------------------------------------------------------------*/
+
+/* Exported types ------------------------------------------------------------*/
+#if defined(USE_FULL_LL_DRIVER)
+/** @defgroup SPI_LL_ES_INIT SPI Exported Init structure
+ * @{
+ */
+
+/**
+ * @brief SPI Init structures definition
+ */
+typedef struct
+{
+ uint32_t TransferDirection; /*!< Specifies the SPI unidirectional or bidirectional data mode.
+ This parameter can be a value of @ref SPI_LL_EC_TRANSFER_MODE.
+
+ This feature can be modified afterwards using unitary function @ref LL_SPI_SetTransferDirection().*/
+
+ uint32_t Mode; /*!< Specifies the SPI mode (Master/Slave).
+ This parameter can be a value of @ref SPI_LL_EC_MODE.
+
+ This feature can be modified afterwards using unitary function @ref LL_SPI_SetMode().*/
+
+ uint32_t DataWidth; /*!< Specifies the SPI data width.
+ This parameter can be a value of @ref SPI_LL_EC_DATAWIDTH.
+
+ This feature can be modified afterwards using unitary function @ref LL_SPI_SetDataWidth().*/
+
+ uint32_t ClockPolarity; /*!< Specifies the serial clock steady state.
+ This parameter can be a value of @ref SPI_LL_EC_POLARITY.
+
+ This feature can be modified afterwards using unitary function @ref LL_SPI_SetClockPolarity().*/
+
+ uint32_t ClockPhase; /*!< Specifies the clock active edge for the bit capture.
+ This parameter can be a value of @ref SPI_LL_EC_PHASE.
+
+ This feature can be modified afterwards using unitary function @ref LL_SPI_SetClockPhase().*/
+
+ uint32_t NSS; /*!< Specifies whether the NSS signal is managed by hardware (NSS pin) or by software using the SSI bit.
+ This parameter can be a value of @ref SPI_LL_EC_NSS_MODE.
+
+ This feature can be modified afterwards using unitary function @ref LL_SPI_SetNSSMode().*/
+
+ uint32_t BaudRate; /*!< Specifies the BaudRate prescaler value which will be used to configure the transmit and receive SCK clock.
+ This parameter can be a value of @ref SPI_LL_EC_BAUDRATEPRESCALER.
+ @note The communication clock is derived from the master clock. The slave clock does not need to be set.
+
+ This feature can be modified afterwards using unitary function @ref LL_SPI_SetBaudRatePrescaler().*/
+
+ uint32_t BitOrder; /*!< Specifies whether data transfers start from MSB or LSB bit.
+ This parameter can be a value of @ref SPI_LL_EC_BIT_ORDER.
+
+ This feature can be modified afterwards using unitary function @ref LL_SPI_SetTransferBitOrder().*/
+
+ uint32_t CRCCalculation; /*!< Specifies if the CRC calculation is enabled or not.
+ This parameter can be a value of @ref SPI_LL_EC_CRC_CALCULATION.
+
+ This feature can be modified afterwards using unitary functions @ref LL_SPI_EnableCRC() and @ref LL_SPI_DisableCRC().*/
+
+ uint32_t CRCPoly; /*!< Specifies the polynomial used for the CRC calculation.
+ This parameter must be a number between Min_Data = 0x00 and Max_Data = 0xFFFF.
+
+ This feature can be modified afterwards using unitary function @ref LL_SPI_SetCRCPolynomial().*/
+
+} LL_SPI_InitTypeDef;
+
+/**
+ * @}
+ */
+#endif /* USE_FULL_LL_DRIVER */
+
+/* Exported constants --------------------------------------------------------*/
+/** @defgroup SPI_LL_Exported_Constants SPI Exported Constants
+ * @{
+ */
+
+/** @defgroup SPI_LL_EC_GET_FLAG Get Flags Defines
+ * @brief Flags defines which can be used with LL_SPI_ReadReg function
+ * @{
+ */
+#define LL_SPI_SR_RXNE SPI_SR_RXNE /*!< Rx buffer not empty flag */
+#define LL_SPI_SR_TXE SPI_SR_TXE /*!< Tx buffer empty flag */
+#define LL_SPI_SR_BSY SPI_SR_BSY /*!< Busy flag */
+#define LL_SPI_SR_CRCERR SPI_SR_CRCERR /*!< CRC error flag */
+#define LL_SPI_SR_MODF SPI_SR_MODF /*!< Mode fault flag */
+#define LL_SPI_SR_OVR SPI_SR_OVR /*!< Overrun flag */
+#define LL_SPI_SR_FRE SPI_SR_FRE /*!< TI mode frame format error flag */
+/**
+ * @}
+ */
+
+/** @defgroup SPI_LL_EC_IT IT Defines
+ * @brief IT defines which can be used with LL_SPI_ReadReg and LL_SPI_WriteReg functions
+ * @{
+ */
+#define LL_SPI_CR2_RXNEIE SPI_CR2_RXNEIE /*!< Rx buffer not empty interrupt enable */
+#define LL_SPI_CR2_TXEIE SPI_CR2_TXEIE /*!< Tx buffer empty interrupt enable */
+#define LL_SPI_CR2_ERRIE SPI_CR2_ERRIE /*!< Error interrupt enable */
+/**
+ * @}
+ */
+
+/** @defgroup SPI_LL_EC_MODE Operation Mode
+ * @{
+ */
+#define LL_SPI_MODE_MASTER (SPI_CR1_MSTR | SPI_CR1_SSI) /*!< Master configuration */
+#define LL_SPI_MODE_SLAVE 0x00000000U /*!< Slave configuration */
+/**
+ * @}
+ */
+
+/** @defgroup SPI_LL_EC_PROTOCOL Serial Protocol
+ * @{
+ */
+#define LL_SPI_PROTOCOL_MOTOROLA 0x00000000U /*!< Motorola mode. Used as default value */
+#define LL_SPI_PROTOCOL_TI (SPI_CR2_FRF) /*!< TI mode */
+/**
+ * @}
+ */
+
+/** @defgroup SPI_LL_EC_PHASE Clock Phase
+ * @{
+ */
+#define LL_SPI_PHASE_1EDGE 0x00000000U /*!< First clock transition is the first data capture edge */
+#define LL_SPI_PHASE_2EDGE (SPI_CR1_CPHA) /*!< Second clock transition is the first data capture edge */
+/**
+ * @}
+ */
+
+/** @defgroup SPI_LL_EC_POLARITY Clock Polarity
+ * @{
+ */
+#define LL_SPI_POLARITY_LOW 0x00000000U /*!< Clock to 0 when idle */
+#define LL_SPI_POLARITY_HIGH (SPI_CR1_CPOL) /*!< Clock to 1 when idle */
+/**
+ * @}
+ */
+
+/** @defgroup SPI_LL_EC_BAUDRATEPRESCALER Baud Rate Prescaler
+ * @{
+ */
+#define LL_SPI_BAUDRATEPRESCALER_DIV2 0x00000000U /*!< BaudRate control equal to fPCLK/2 */
+#define LL_SPI_BAUDRATEPRESCALER_DIV4 (SPI_CR1_BR_0) /*!< BaudRate control equal to fPCLK/4 */
+#define LL_SPI_BAUDRATEPRESCALER_DIV8 (SPI_CR1_BR_1) /*!< BaudRate control equal to fPCLK/8 */
+#define LL_SPI_BAUDRATEPRESCALER_DIV16 (SPI_CR1_BR_1 | SPI_CR1_BR_0) /*!< BaudRate control equal to fPCLK/16 */
+#define LL_SPI_BAUDRATEPRESCALER_DIV32 (SPI_CR1_BR_2) /*!< BaudRate control equal to fPCLK/32 */
+#define LL_SPI_BAUDRATEPRESCALER_DIV64 (SPI_CR1_BR_2 | SPI_CR1_BR_0) /*!< BaudRate control equal to fPCLK/64 */
+#define LL_SPI_BAUDRATEPRESCALER_DIV128 (SPI_CR1_BR_2 | SPI_CR1_BR_1) /*!< BaudRate control equal to fPCLK/128 */
+#define LL_SPI_BAUDRATEPRESCALER_DIV256 (SPI_CR1_BR_2 | SPI_CR1_BR_1 | SPI_CR1_BR_0) /*!< BaudRate control equal to fPCLK/256 */
+/**
+ * @}
+ */
+
+/** @defgroup SPI_LL_EC_BIT_ORDER Transmission Bit Order
+ * @{
+ */
+#define LL_SPI_LSB_FIRST (SPI_CR1_LSBFIRST) /*!< Data is transmitted/received with the LSB first */
+#define LL_SPI_MSB_FIRST 0x00000000U /*!< Data is transmitted/received with the MSB first */
+/**
+ * @}
+ */
+
+/** @defgroup SPI_LL_EC_TRANSFER_MODE Transfer Mode
+ * @{
+ */
+#define LL_SPI_FULL_DUPLEX 0x00000000U /*!< Full-Duplex mode. Rx and Tx transfer on 2 lines */
+#define LL_SPI_SIMPLEX_RX (SPI_CR1_RXONLY) /*!< Simplex Rx mode. Rx transfer only on 1 line */
+#define LL_SPI_HALF_DUPLEX_RX (SPI_CR1_BIDIMODE) /*!< Half-Duplex Rx mode. Rx transfer on 1 line */
+#define LL_SPI_HALF_DUPLEX_TX (SPI_CR1_BIDIMODE | SPI_CR1_BIDIOE) /*!< Half-Duplex Tx mode. Tx transfer on 1 line */
+/**
+ * @}
+ */
+
+/** @defgroup SPI_LL_EC_NSS_MODE Slave Select Pin Mode
+ * @{
+ */
+#define LL_SPI_NSS_SOFT (SPI_CR1_SSM) /*!< NSS managed internally. NSS pin not used and free */
+#define LL_SPI_NSS_HARD_INPUT 0x00000000U /*!< NSS pin used in Input. Only used in Master mode */
+#define LL_SPI_NSS_HARD_OUTPUT (((uint32_t)SPI_CR2_SSOE << 16U)) /*!< NSS pin used in Output. Only used in Slave mode as chip select */
+/**
+ * @}
+ */
+
+/** @defgroup SPI_LL_EC_DATAWIDTH Datawidth
+ * @{
+ */
+#define LL_SPI_DATAWIDTH_4BIT (SPI_CR2_DS_0 | SPI_CR2_DS_1) /*!< Data length for SPI transfer: 4 bits */
+#define LL_SPI_DATAWIDTH_5BIT (SPI_CR2_DS_2) /*!< Data length for SPI transfer: 5 bits */
+#define LL_SPI_DATAWIDTH_6BIT (SPI_CR2_DS_2 | SPI_CR2_DS_0) /*!< Data length for SPI transfer: 6 bits */
+#define LL_SPI_DATAWIDTH_7BIT (SPI_CR2_DS_2 | SPI_CR2_DS_1) /*!< Data length for SPI transfer: 7 bits */
+#define LL_SPI_DATAWIDTH_8BIT (SPI_CR2_DS_2 | SPI_CR2_DS_1 | SPI_CR2_DS_0) /*!< Data length for SPI transfer: 8 bits */
+#define LL_SPI_DATAWIDTH_9BIT (SPI_CR2_DS_3) /*!< Data length for SPI transfer: 9 bits */
+#define LL_SPI_DATAWIDTH_10BIT (SPI_CR2_DS_3 | SPI_CR2_DS_0) /*!< Data length for SPI transfer: 10 bits */
+#define LL_SPI_DATAWIDTH_11BIT (SPI_CR2_DS_3 | SPI_CR2_DS_1) /*!< Data length for SPI transfer: 11 bits */
+#define LL_SPI_DATAWIDTH_12BIT (SPI_CR2_DS_3 | SPI_CR2_DS_1 | SPI_CR2_DS_0) /*!< Data length for SPI transfer: 12 bits */
+#define LL_SPI_DATAWIDTH_13BIT (SPI_CR2_DS_3 | SPI_CR2_DS_2) /*!< Data length for SPI transfer: 13 bits */
+#define LL_SPI_DATAWIDTH_14BIT (SPI_CR2_DS_3 | SPI_CR2_DS_2 | SPI_CR2_DS_0) /*!< Data length for SPI transfer: 14 bits */
+#define LL_SPI_DATAWIDTH_15BIT (SPI_CR2_DS_3 | SPI_CR2_DS_2 | SPI_CR2_DS_1) /*!< Data length for SPI transfer: 15 bits */
+#define LL_SPI_DATAWIDTH_16BIT (SPI_CR2_DS_3 | SPI_CR2_DS_2 | SPI_CR2_DS_1 | SPI_CR2_DS_0) /*!< Data length for SPI transfer: 16 bits */
+/**
+ * @}
+ */
+#if defined(USE_FULL_LL_DRIVER)
+
+/** @defgroup SPI_LL_EC_CRC_CALCULATION CRC Calculation
+ * @{
+ */
+#define LL_SPI_CRCCALCULATION_DISABLE 0x00000000U /*!< CRC calculation disabled */
+#define LL_SPI_CRCCALCULATION_ENABLE (SPI_CR1_CRCEN) /*!< CRC calculation enabled */
+/**
+ * @}
+ */
+#endif /* USE_FULL_LL_DRIVER */
+
+/** @defgroup SPI_LL_EC_CRC_LENGTH CRC Length
+ * @{
+ */
+#define LL_SPI_CRC_8BIT 0x00000000U /*!< 8-bit CRC length */
+#define LL_SPI_CRC_16BIT (SPI_CR1_CRCL) /*!< 16-bit CRC length */
+/**
+ * @}
+ */
+
+/** @defgroup SPI_LL_EC_RX_FIFO_TH RX FIFO Threshold
+ * @{
+ */
+#define LL_SPI_RX_FIFO_TH_HALF 0x00000000U /*!< RXNE event is generated if FIFO level is greater than or equal to 1/2 (16-bit) */
+#define LL_SPI_RX_FIFO_TH_QUARTER (SPI_CR2_FRXTH) /*!< RXNE event is generated if FIFO level is greater than or equal to 1/4 (8-bit) */
+/**
+ * @}
+ */
+
+/** @defgroup SPI_LL_EC_RX_FIFO RX FIFO Level
+ * @{
+ */
+#define LL_SPI_RX_FIFO_EMPTY 0x00000000U /*!< FIFO reception empty */
+#define LL_SPI_RX_FIFO_QUARTER_FULL (SPI_SR_FRLVL_0) /*!< FIFO reception 1/4 */
+#define LL_SPI_RX_FIFO_HALF_FULL (SPI_SR_FRLVL_1) /*!< FIFO reception 1/2 */
+#define LL_SPI_RX_FIFO_FULL (SPI_SR_FRLVL_1 | SPI_SR_FRLVL_0) /*!< FIFO reception full */
+/**
+ * @}
+ */
+
+/** @defgroup SPI_LL_EC_TX_FIFO TX FIFO Level
+ * @{
+ */
+#define LL_SPI_TX_FIFO_EMPTY 0x00000000U /*!< FIFO transmission empty */
+#define LL_SPI_TX_FIFO_QUARTER_FULL (SPI_SR_FTLVL_0) /*!< FIFO transmission 1/4 */
+#define LL_SPI_TX_FIFO_HALF_FULL (SPI_SR_FTLVL_1) /*!< FIFO transmission 1/2 */
+#define LL_SPI_TX_FIFO_FULL (SPI_SR_FTLVL_1 | SPI_SR_FTLVL_0) /*!< FIFO transmission full */
+/**
+ * @}
+ */
+
+/** @defgroup SPI_LL_EC_DMA_PARITY DMA Parity
+ * @{
+ */
+#define LL_SPI_DMA_PARITY_EVEN 0x00000000U /*!< Select DMA parity Even */
+#define LL_SPI_DMA_PARITY_ODD 0x00000001U /*!< Select DMA parity Odd */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/* Exported macro ------------------------------------------------------------*/
+/** @defgroup SPI_LL_Exported_Macros SPI Exported Macros
+ * @{
+ */
+
+/** @defgroup SPI_LL_EM_WRITE_READ Common Write and read registers Macros
+ * @{
+ */
+
+/**
+ * @brief Write a value in SPI register
+ * @param __INSTANCE__ SPI Instance
+ * @param __REG__ Register to be written
+ * @param __VALUE__ Value to be written in the register
+ * @retval None
+ */
+#define LL_SPI_WriteReg(__INSTANCE__, __REG__, __VALUE__) WRITE_REG(__INSTANCE__->__REG__, (__VALUE__))
+
+/**
+ * @brief Read a value in SPI register
+ * @param __INSTANCE__ SPI Instance
+ * @param __REG__ Register to be read
+ * @retval Register value
+ */
+#define LL_SPI_ReadReg(__INSTANCE__, __REG__) READ_REG(__INSTANCE__->__REG__)
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/* Exported functions --------------------------------------------------------*/
+/** @defgroup SPI_LL_Exported_Functions SPI Exported Functions
+ * @{
+ */
+
+/** @defgroup SPI_LL_EF_Configuration Configuration
+ * @{
+ */
+
+/**
+ * @brief Enable SPI peripheral
+ * @rmtoll CR1 SPE LL_SPI_Enable
+ * @param SPIx SPI Instance
+ * @retval None
+ */
+__STATIC_INLINE void LL_SPI_Enable(SPI_TypeDef *SPIx)
+{
+ SET_BIT(SPIx->CR1, SPI_CR1_SPE);
+}
+
+/**
+ * @brief Disable SPI peripheral
+ * @note When disabling the SPI, follow the procedure described in the Reference Manual.
+ * @rmtoll CR1 SPE LL_SPI_Disable
+ * @param SPIx SPI Instance
+ * @retval None
+ */
+__STATIC_INLINE void LL_SPI_Disable(SPI_TypeDef *SPIx)
+{
+ CLEAR_BIT(SPIx->CR1, SPI_CR1_SPE);
+}
+
+/**
+ * @brief Check if SPI peripheral is enabled
+ * @rmtoll CR1 SPE LL_SPI_IsEnabled
+ * @param SPIx SPI Instance
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SPI_IsEnabled(SPI_TypeDef *SPIx)
+{
+ return ((READ_BIT(SPIx->CR1, SPI_CR1_SPE) == (SPI_CR1_SPE)) ? 1UL : 0UL);
+}
+
+/**
+ * @brief Set SPI operation mode to Master or Slave
+ * @note This bit should not be changed when communication is ongoing.
+ * @rmtoll CR1 MSTR LL_SPI_SetMode\n
+ * CR1 SSI LL_SPI_SetMode
+ * @param SPIx SPI Instance
+ * @param Mode This parameter can be one of the following values:
+ * @arg @ref LL_SPI_MODE_MASTER
+ * @arg @ref LL_SPI_MODE_SLAVE
+ * @retval None
+ */
+__STATIC_INLINE void LL_SPI_SetMode(SPI_TypeDef *SPIx, uint32_t Mode)
+{
+ MODIFY_REG(SPIx->CR1, SPI_CR1_MSTR | SPI_CR1_SSI, Mode);
+}
+
+/**
+ * @brief Get SPI operation mode (Master or Slave)
+ * @rmtoll CR1 MSTR LL_SPI_GetMode\n
+ * CR1 SSI LL_SPI_GetMode
+ * @param SPIx SPI Instance
+ * @retval Returned value can be one of the following values:
+ * @arg @ref LL_SPI_MODE_MASTER
+ * @arg @ref LL_SPI_MODE_SLAVE
+ */
+__STATIC_INLINE uint32_t LL_SPI_GetMode(SPI_TypeDef *SPIx)
+{
+ return (uint32_t)(READ_BIT(SPIx->CR1, SPI_CR1_MSTR | SPI_CR1_SSI));
+}
+
+/**
+ * @brief Set serial protocol used
+ * @note This bit should be written only when SPI is disabled (SPE = 0) for correct operation.
+ * @rmtoll CR2 FRF LL_SPI_SetStandard
+ * @param SPIx SPI Instance
+ * @param Standard This parameter can be one of the following values:
+ * @arg @ref LL_SPI_PROTOCOL_MOTOROLA
+ * @arg @ref LL_SPI_PROTOCOL_TI
+ * @retval None
+ */
+__STATIC_INLINE void LL_SPI_SetStandard(SPI_TypeDef *SPIx, uint32_t Standard)
+{
+ MODIFY_REG(SPIx->CR2, SPI_CR2_FRF, Standard);
+}
+
+/**
+ * @brief Get serial protocol used
+ * @rmtoll CR2 FRF LL_SPI_GetStandard
+ * @param SPIx SPI Instance
+ * @retval Returned value can be one of the following values:
+ * @arg @ref LL_SPI_PROTOCOL_MOTOROLA
+ * @arg @ref LL_SPI_PROTOCOL_TI
+ */
+__STATIC_INLINE uint32_t LL_SPI_GetStandard(SPI_TypeDef *SPIx)
+{
+ return (uint32_t)(READ_BIT(SPIx->CR2, SPI_CR2_FRF));
+}
+
+/**
+ * @brief Set clock phase
+ * @note This bit should not be changed when communication is ongoing.
+ * This bit is not used in SPI TI mode.
+ * @rmtoll CR1 CPHA LL_SPI_SetClockPhase
+ * @param SPIx SPI Instance
+ * @param ClockPhase This parameter can be one of the following values:
+ * @arg @ref LL_SPI_PHASE_1EDGE
+ * @arg @ref LL_SPI_PHASE_2EDGE
+ * @retval None
+ */
+__STATIC_INLINE void LL_SPI_SetClockPhase(SPI_TypeDef *SPIx, uint32_t ClockPhase)
+{
+ MODIFY_REG(SPIx->CR1, SPI_CR1_CPHA, ClockPhase);
+}
+
+/**
+ * @brief Get clock phase
+ * @rmtoll CR1 CPHA LL_SPI_GetClockPhase
+ * @param SPIx SPI Instance
+ * @retval Returned value can be one of the following values:
+ * @arg @ref LL_SPI_PHASE_1EDGE
+ * @arg @ref LL_SPI_PHASE_2EDGE
+ */
+__STATIC_INLINE uint32_t LL_SPI_GetClockPhase(SPI_TypeDef *SPIx)
+{
+ return (uint32_t)(READ_BIT(SPIx->CR1, SPI_CR1_CPHA));
+}
+
+/**
+ * @brief Set clock polarity
+ * @note This bit should not be changed when communication is ongoing.
+ * This bit is not used in SPI TI mode.
+ * @rmtoll CR1 CPOL LL_SPI_SetClockPolarity
+ * @param SPIx SPI Instance
+ * @param ClockPolarity This parameter can be one of the following values:
+ * @arg @ref LL_SPI_POLARITY_LOW
+ * @arg @ref LL_SPI_POLARITY_HIGH
+ * @retval None
+ */
+__STATIC_INLINE void LL_SPI_SetClockPolarity(SPI_TypeDef *SPIx, uint32_t ClockPolarity)
+{
+ MODIFY_REG(SPIx->CR1, SPI_CR1_CPOL, ClockPolarity);
+}
+
+/**
+ * @brief Get clock polarity
+ * @rmtoll CR1 CPOL LL_SPI_GetClockPolarity
+ * @param SPIx SPI Instance
+ * @retval Returned value can be one of the following values:
+ * @arg @ref LL_SPI_POLARITY_LOW
+ * @arg @ref LL_SPI_POLARITY_HIGH
+ */
+__STATIC_INLINE uint32_t LL_SPI_GetClockPolarity(SPI_TypeDef *SPIx)
+{
+ return (uint32_t)(READ_BIT(SPIx->CR1, SPI_CR1_CPOL));
+}
+
+/**
+ * @brief Set baud rate prescaler
+ * @note These bits should not be changed when communication is ongoing. SPI BaudRate = fPCLK/Prescaler.
+ * @rmtoll CR1 BR LL_SPI_SetBaudRatePrescaler
+ * @param SPIx SPI Instance
+ * @param BaudRate This parameter can be one of the following values:
+ * @arg @ref LL_SPI_BAUDRATEPRESCALER_DIV2
+ * @arg @ref LL_SPI_BAUDRATEPRESCALER_DIV4
+ * @arg @ref LL_SPI_BAUDRATEPRESCALER_DIV8
+ * @arg @ref LL_SPI_BAUDRATEPRESCALER_DIV16
+ * @arg @ref LL_SPI_BAUDRATEPRESCALER_DIV32
+ * @arg @ref LL_SPI_BAUDRATEPRESCALER_DIV64
+ * @arg @ref LL_SPI_BAUDRATEPRESCALER_DIV128
+ * @arg @ref LL_SPI_BAUDRATEPRESCALER_DIV256
+ * @retval None
+ */
+__STATIC_INLINE void LL_SPI_SetBaudRatePrescaler(SPI_TypeDef *SPIx, uint32_t BaudRate)
+{
+ MODIFY_REG(SPIx->CR1, SPI_CR1_BR, BaudRate);
+}
+
+/**
+ * @brief Get baud rate prescaler
+ * @rmtoll CR1 BR LL_SPI_GetBaudRatePrescaler
+ * @param SPIx SPI Instance
+ * @retval Returned value can be one of the following values:
+ * @arg @ref LL_SPI_BAUDRATEPRESCALER_DIV2
+ * @arg @ref LL_SPI_BAUDRATEPRESCALER_DIV4
+ * @arg @ref LL_SPI_BAUDRATEPRESCALER_DIV8
+ * @arg @ref LL_SPI_BAUDRATEPRESCALER_DIV16
+ * @arg @ref LL_SPI_BAUDRATEPRESCALER_DIV32
+ * @arg @ref LL_SPI_BAUDRATEPRESCALER_DIV64
+ * @arg @ref LL_SPI_BAUDRATEPRESCALER_DIV128
+ * @arg @ref LL_SPI_BAUDRATEPRESCALER_DIV256
+ */
+__STATIC_INLINE uint32_t LL_SPI_GetBaudRatePrescaler(SPI_TypeDef *SPIx)
+{
+ return (uint32_t)(READ_BIT(SPIx->CR1, SPI_CR1_BR));
+}
+
+/**
+ * @brief Set transfer bit order
+ * @note This bit should not be changed when communication is ongoing. This bit is not used in SPI TI mode.
+ * @rmtoll CR1 LSBFIRST LL_SPI_SetTransferBitOrder
+ * @param SPIx SPI Instance
+ * @param BitOrder This parameter can be one of the following values:
+ * @arg @ref LL_SPI_LSB_FIRST
+ * @arg @ref LL_SPI_MSB_FIRST
+ * @retval None
+ */
+__STATIC_INLINE void LL_SPI_SetTransferBitOrder(SPI_TypeDef *SPIx, uint32_t BitOrder)
+{
+ MODIFY_REG(SPIx->CR1, SPI_CR1_LSBFIRST, BitOrder);
+}
+
+/**
+ * @brief Get transfer bit order
+ * @rmtoll CR1 LSBFIRST LL_SPI_GetTransferBitOrder
+ * @param SPIx SPI Instance
+ * @retval Returned value can be one of the following values:
+ * @arg @ref LL_SPI_LSB_FIRST
+ * @arg @ref LL_SPI_MSB_FIRST
+ */
+__STATIC_INLINE uint32_t LL_SPI_GetTransferBitOrder(SPI_TypeDef *SPIx)
+{
+ return (uint32_t)(READ_BIT(SPIx->CR1, SPI_CR1_LSBFIRST));
+}
+
+/**
+ * @brief Set transfer direction mode
+ * @note For Half-Duplex mode, Rx Direction is set by default.
+ * In master mode, the MOSI pin is used and in slave mode, the MISO pin is used for Half-Duplex.
+ * @rmtoll CR1 RXONLY LL_SPI_SetTransferDirection\n
+ * CR1 BIDIMODE LL_SPI_SetTransferDirection\n
+ * CR1 BIDIOE LL_SPI_SetTransferDirection
+ * @param SPIx SPI Instance
+ * @param TransferDirection This parameter can be one of the following values:
+ * @arg @ref LL_SPI_FULL_DUPLEX
+ * @arg @ref LL_SPI_SIMPLEX_RX
+ * @arg @ref LL_SPI_HALF_DUPLEX_RX
+ * @arg @ref LL_SPI_HALF_DUPLEX_TX
+ * @retval None
+ */
+__STATIC_INLINE void LL_SPI_SetTransferDirection(SPI_TypeDef *SPIx, uint32_t TransferDirection)
+{
+ MODIFY_REG(SPIx->CR1, SPI_CR1_RXONLY | SPI_CR1_BIDIMODE | SPI_CR1_BIDIOE, TransferDirection);
+}
+
+/**
+ * @brief Get transfer direction mode
+ * @rmtoll CR1 RXONLY LL_SPI_GetTransferDirection\n
+ * CR1 BIDIMODE LL_SPI_GetTransferDirection\n
+ * CR1 BIDIOE LL_SPI_GetTransferDirection
+ * @param SPIx SPI Instance
+ * @retval Returned value can be one of the following values:
+ * @arg @ref LL_SPI_FULL_DUPLEX
+ * @arg @ref LL_SPI_SIMPLEX_RX
+ * @arg @ref LL_SPI_HALF_DUPLEX_RX
+ * @arg @ref LL_SPI_HALF_DUPLEX_TX
+ */
+__STATIC_INLINE uint32_t LL_SPI_GetTransferDirection(SPI_TypeDef *SPIx)
+{
+ return (uint32_t)(READ_BIT(SPIx->CR1, SPI_CR1_RXONLY | SPI_CR1_BIDIMODE | SPI_CR1_BIDIOE));
+}
+
+/**
+ * @brief Set frame data width
+ * @rmtoll CR2 DS LL_SPI_SetDataWidth
+ * @param SPIx SPI Instance
+ * @param DataWidth This parameter can be one of the following values:
+ * @arg @ref LL_SPI_DATAWIDTH_4BIT
+ * @arg @ref LL_SPI_DATAWIDTH_5BIT
+ * @arg @ref LL_SPI_DATAWIDTH_6BIT
+ * @arg @ref LL_SPI_DATAWIDTH_7BIT
+ * @arg @ref LL_SPI_DATAWIDTH_8BIT
+ * @arg @ref LL_SPI_DATAWIDTH_9BIT
+ * @arg @ref LL_SPI_DATAWIDTH_10BIT
+ * @arg @ref LL_SPI_DATAWIDTH_11BIT
+ * @arg @ref LL_SPI_DATAWIDTH_12BIT
+ * @arg @ref LL_SPI_DATAWIDTH_13BIT
+ * @arg @ref LL_SPI_DATAWIDTH_14BIT
+ * @arg @ref LL_SPI_DATAWIDTH_15BIT
+ * @arg @ref LL_SPI_DATAWIDTH_16BIT
+ * @retval None
+ */
+__STATIC_INLINE void LL_SPI_SetDataWidth(SPI_TypeDef *SPIx, uint32_t DataWidth)
+{
+ MODIFY_REG(SPIx->CR2, SPI_CR2_DS, DataWidth);
+}
+
+/**
+ * @brief Get frame data width
+ * @rmtoll CR2 DS LL_SPI_GetDataWidth
+ * @param SPIx SPI Instance
+ * @retval Returned value can be one of the following values:
+ * @arg @ref LL_SPI_DATAWIDTH_4BIT
+ * @arg @ref LL_SPI_DATAWIDTH_5BIT
+ * @arg @ref LL_SPI_DATAWIDTH_6BIT
+ * @arg @ref LL_SPI_DATAWIDTH_7BIT
+ * @arg @ref LL_SPI_DATAWIDTH_8BIT
+ * @arg @ref LL_SPI_DATAWIDTH_9BIT
+ * @arg @ref LL_SPI_DATAWIDTH_10BIT
+ * @arg @ref LL_SPI_DATAWIDTH_11BIT
+ * @arg @ref LL_SPI_DATAWIDTH_12BIT
+ * @arg @ref LL_SPI_DATAWIDTH_13BIT
+ * @arg @ref LL_SPI_DATAWIDTH_14BIT
+ * @arg @ref LL_SPI_DATAWIDTH_15BIT
+ * @arg @ref LL_SPI_DATAWIDTH_16BIT
+ */
+__STATIC_INLINE uint32_t LL_SPI_GetDataWidth(SPI_TypeDef *SPIx)
+{
+ return (uint32_t)(READ_BIT(SPIx->CR2, SPI_CR2_DS));
+}
+
+/**
+ * @brief Set threshold of RXFIFO that triggers an RXNE event
+ * @rmtoll CR2 FRXTH LL_SPI_SetRxFIFOThreshold
+ * @param SPIx SPI Instance
+ * @param Threshold This parameter can be one of the following values:
+ * @arg @ref LL_SPI_RX_FIFO_TH_HALF
+ * @arg @ref LL_SPI_RX_FIFO_TH_QUARTER
+ * @retval None
+ */
+__STATIC_INLINE void LL_SPI_SetRxFIFOThreshold(SPI_TypeDef *SPIx, uint32_t Threshold)
+{
+ MODIFY_REG(SPIx->CR2, SPI_CR2_FRXTH, Threshold);
+}
+
+/**
+ * @brief Get threshold of RXFIFO that triggers an RXNE event
+ * @rmtoll CR2 FRXTH LL_SPI_GetRxFIFOThreshold
+ * @param SPIx SPI Instance
+ * @retval Returned value can be one of the following values:
+ * @arg @ref LL_SPI_RX_FIFO_TH_HALF
+ * @arg @ref LL_SPI_RX_FIFO_TH_QUARTER
+ */
+__STATIC_INLINE uint32_t LL_SPI_GetRxFIFOThreshold(SPI_TypeDef *SPIx)
+{
+ return (uint32_t)(READ_BIT(SPIx->CR2, SPI_CR2_FRXTH));
+}
+
+/**
+ * @}
+ */
+
+/** @defgroup SPI_LL_EF_CRC_Management CRC Management
+ * @{
+ */
+
+/**
+ * @brief Enable CRC
+ * @note This bit should be written only when SPI is disabled (SPE = 0) for correct operation.
+ * @rmtoll CR1 CRCEN LL_SPI_EnableCRC
+ * @param SPIx SPI Instance
+ * @retval None
+ */
+__STATIC_INLINE void LL_SPI_EnableCRC(SPI_TypeDef *SPIx)
+{
+ SET_BIT(SPIx->CR1, SPI_CR1_CRCEN);
+}
+
+/**
+ * @brief Disable CRC
+ * @note This bit should be written only when SPI is disabled (SPE = 0) for correct operation.
+ * @rmtoll CR1 CRCEN LL_SPI_DisableCRC
+ * @param SPIx SPI Instance
+ * @retval None
+ */
+__STATIC_INLINE void LL_SPI_DisableCRC(SPI_TypeDef *SPIx)
+{
+ CLEAR_BIT(SPIx->CR1, SPI_CR1_CRCEN);
+}
+
+/**
+ * @brief Check if CRC is enabled
+ * @note This bit should be written only when SPI is disabled (SPE = 0) for correct operation.
+ * @rmtoll CR1 CRCEN LL_SPI_IsEnabledCRC
+ * @param SPIx SPI Instance
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SPI_IsEnabledCRC(SPI_TypeDef *SPIx)
+{
+ return ((READ_BIT(SPIx->CR1, SPI_CR1_CRCEN) == (SPI_CR1_CRCEN)) ? 1UL : 0UL);
+}
+
+/**
+ * @brief Set CRC Length
+ * @note This bit should be written only when SPI is disabled (SPE = 0) for correct operation.
+ * @rmtoll CR1 CRCL LL_SPI_SetCRCWidth
+ * @param SPIx SPI Instance
+ * @param CRCLength This parameter can be one of the following values:
+ * @arg @ref LL_SPI_CRC_8BIT
+ * @arg @ref LL_SPI_CRC_16BIT
+ * @retval None
+ */
+__STATIC_INLINE void LL_SPI_SetCRCWidth(SPI_TypeDef *SPIx, uint32_t CRCLength)
+{
+ MODIFY_REG(SPIx->CR1, SPI_CR1_CRCL, CRCLength);
+}
+
+/**
+ * @brief Get CRC Length
+ * @rmtoll CR1 CRCL LL_SPI_GetCRCWidth
+ * @param SPIx SPI Instance
+ * @retval Returned value can be one of the following values:
+ * @arg @ref LL_SPI_CRC_8BIT
+ * @arg @ref LL_SPI_CRC_16BIT
+ */
+__STATIC_INLINE uint32_t LL_SPI_GetCRCWidth(SPI_TypeDef *SPIx)
+{
+ return (uint32_t)(READ_BIT(SPIx->CR1, SPI_CR1_CRCL));
+}
+
+/**
+ * @brief Set CRCNext to transfer CRC on the line
+ * @note This bit has to be written as soon as the last data is written in the SPIx_DR register.
+ * @rmtoll CR1 CRCNEXT LL_SPI_SetCRCNext
+ * @param SPIx SPI Instance
+ * @retval None
+ */
+__STATIC_INLINE void LL_SPI_SetCRCNext(SPI_TypeDef *SPIx)
+{
+ SET_BIT(SPIx->CR1, SPI_CR1_CRCNEXT);
+}
+
+/**
+ * @brief Set polynomial for CRC calculation
+ * @rmtoll CRCPR CRCPOLY LL_SPI_SetCRCPolynomial
+ * @param SPIx SPI Instance
+ * @param CRCPoly This parameter must be a number between Min_Data = 0x00 and Max_Data = 0xFFFF
+ * @retval None
+ */
+__STATIC_INLINE void LL_SPI_SetCRCPolynomial(SPI_TypeDef *SPIx, uint32_t CRCPoly)
+{
+ WRITE_REG(SPIx->CRCPR, (uint16_t)CRCPoly);
+}
+
+/**
+ * @brief Get polynomial for CRC calculation
+ * @rmtoll CRCPR CRCPOLY LL_SPI_GetCRCPolynomial
+ * @param SPIx SPI Instance
+ * @retval Returned value is a number between Min_Data = 0x00 and Max_Data = 0xFFFF
+ */
+__STATIC_INLINE uint32_t LL_SPI_GetCRCPolynomial(SPI_TypeDef *SPIx)
+{
+ return (uint32_t)(READ_REG(SPIx->CRCPR));
+}
+
+/**
+ * @brief Get Rx CRC
+ * @rmtoll RXCRCR RXCRC LL_SPI_GetRxCRC
+ * @param SPIx SPI Instance
+ * @retval Returned value is a number between Min_Data = 0x00 and Max_Data = 0xFFFF
+ */
+__STATIC_INLINE uint32_t LL_SPI_GetRxCRC(SPI_TypeDef *SPIx)
+{
+ return (uint32_t)(READ_REG(SPIx->RXCRCR));
+}
+
+/**
+ * @brief Get Tx CRC
+ * @rmtoll TXCRCR TXCRC LL_SPI_GetTxCRC
+ * @param SPIx SPI Instance
+ * @retval Returned value is a number between Min_Data = 0x00 and Max_Data = 0xFFFF
+ */
+__STATIC_INLINE uint32_t LL_SPI_GetTxCRC(SPI_TypeDef *SPIx)
+{
+ return (uint32_t)(READ_REG(SPIx->TXCRCR));
+}
+
+/**
+ * @}
+ */
+
+/** @defgroup SPI_LL_EF_NSS_Management Slave Select Pin Management
+ * @{
+ */
+
+/**
+ * @brief Set NSS mode
+ * @note LL_SPI_NSS_SOFT Mode is not used in SPI TI mode.
+ * @rmtoll CR1 SSM LL_SPI_SetNSSMode\n
+ * @rmtoll CR2 SSOE LL_SPI_SetNSSMode
+ * @param SPIx SPI Instance
+ * @param NSS This parameter can be one of the following values:
+ * @arg @ref LL_SPI_NSS_SOFT
+ * @arg @ref LL_SPI_NSS_HARD_INPUT
+ * @arg @ref LL_SPI_NSS_HARD_OUTPUT
+ * @retval None
+ */
+__STATIC_INLINE void LL_SPI_SetNSSMode(SPI_TypeDef *SPIx, uint32_t NSS)
+{
+ MODIFY_REG(SPIx->CR1, SPI_CR1_SSM, NSS);
+ MODIFY_REG(SPIx->CR2, SPI_CR2_SSOE, ((uint32_t)(NSS >> 16U)));
+}
+
+/**
+ * @brief Get NSS mode
+ * @rmtoll CR1 SSM LL_SPI_GetNSSMode\n
+ * @rmtoll CR2 SSOE LL_SPI_GetNSSMode
+ * @param SPIx SPI Instance
+ * @retval Returned value can be one of the following values:
+ * @arg @ref LL_SPI_NSS_SOFT
+ * @arg @ref LL_SPI_NSS_HARD_INPUT
+ * @arg @ref LL_SPI_NSS_HARD_OUTPUT
+ */
+__STATIC_INLINE uint32_t LL_SPI_GetNSSMode(SPI_TypeDef *SPIx)
+{
+ uint32_t Ssm = (READ_BIT(SPIx->CR1, SPI_CR1_SSM));
+ uint32_t Ssoe = (READ_BIT(SPIx->CR2, SPI_CR2_SSOE) << 16U);
+ return (Ssm | Ssoe);
+}
+
+/**
+ * @brief Enable NSS pulse management
+ * @note This bit should not be changed when communication is ongoing. This bit is not used in SPI TI mode.
+ * @rmtoll CR2 NSSP LL_SPI_EnableNSSPulseMgt
+ * @param SPIx SPI Instance
+ * @retval None
+ */
+__STATIC_INLINE void LL_SPI_EnableNSSPulseMgt(SPI_TypeDef *SPIx)
+{
+ SET_BIT(SPIx->CR2, SPI_CR2_NSSP);
+}
+
+/**
+ * @brief Disable NSS pulse management
+ * @note This bit should not be changed when communication is ongoing. This bit is not used in SPI TI mode.
+ * @rmtoll CR2 NSSP LL_SPI_DisableNSSPulseMgt
+ * @param SPIx SPI Instance
+ * @retval None
+ */
+__STATIC_INLINE void LL_SPI_DisableNSSPulseMgt(SPI_TypeDef *SPIx)
+{
+ CLEAR_BIT(SPIx->CR2, SPI_CR2_NSSP);
+}
+
+/**
+ * @brief Check if NSS pulse is enabled
+ * @note This bit should not be changed when communication is ongoing. This bit is not used in SPI TI mode.
+ * @rmtoll CR2 NSSP LL_SPI_IsEnabledNSSPulse
+ * @param SPIx SPI Instance
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SPI_IsEnabledNSSPulse(SPI_TypeDef *SPIx)
+{
+ return ((READ_BIT(SPIx->CR2, SPI_CR2_NSSP) == (SPI_CR2_NSSP)) ? 1UL : 0UL);
+}
+
+/**
+ * @}
+ */
+
+/** @defgroup SPI_LL_EF_FLAG_Management FLAG Management
+ * @{
+ */
+
+/**
+ * @brief Check if Rx buffer is not empty
+ * @rmtoll SR RXNE LL_SPI_IsActiveFlag_RXNE
+ * @param SPIx SPI Instance
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SPI_IsActiveFlag_RXNE(SPI_TypeDef *SPIx)
+{
+ return ((READ_BIT(SPIx->SR, SPI_SR_RXNE) == (SPI_SR_RXNE)) ? 1UL : 0UL);
+}
+
+/**
+ * @brief Check if Tx buffer is empty
+ * @rmtoll SR TXE LL_SPI_IsActiveFlag_TXE
+ * @param SPIx SPI Instance
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SPI_IsActiveFlag_TXE(SPI_TypeDef *SPIx)
+{
+ return ((READ_BIT(SPIx->SR, SPI_SR_TXE) == (SPI_SR_TXE)) ? 1UL : 0UL);
+}
+
+/**
+ * @brief Get CRC error flag
+ * @rmtoll SR CRCERR LL_SPI_IsActiveFlag_CRCERR
+ * @param SPIx SPI Instance
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SPI_IsActiveFlag_CRCERR(SPI_TypeDef *SPIx)
+{
+ return ((READ_BIT(SPIx->SR, SPI_SR_CRCERR) == (SPI_SR_CRCERR)) ? 1UL : 0UL);
+}
+
+/**
+ * @brief Get mode fault error flag
+ * @rmtoll SR MODF LL_SPI_IsActiveFlag_MODF
+ * @param SPIx SPI Instance
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SPI_IsActiveFlag_MODF(SPI_TypeDef *SPIx)
+{
+ return ((READ_BIT(SPIx->SR, SPI_SR_MODF) == (SPI_SR_MODF)) ? 1UL : 0UL);
+}
+
+/**
+ * @brief Get overrun error flag
+ * @rmtoll SR OVR LL_SPI_IsActiveFlag_OVR
+ * @param SPIx SPI Instance
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SPI_IsActiveFlag_OVR(SPI_TypeDef *SPIx)
+{
+ return ((READ_BIT(SPIx->SR, SPI_SR_OVR) == (SPI_SR_OVR)) ? 1UL : 0UL);
+}
+
+/**
+ * @brief Get busy flag
+ * @note The BSY flag is cleared under any one of the following conditions:
+ * -When the SPI is correctly disabled
+ * -When a fault is detected in Master mode (MODF bit set to 1)
+ * -In Master mode, when it finishes a data transmission and no new data is ready to be
+ * sent
+ * -In Slave mode, when the BSY flag is set to '0' for at least one SPI clock cycle between
+ * each data transfer.
+ * @rmtoll SR BSY LL_SPI_IsActiveFlag_BSY
+ * @param SPIx SPI Instance
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SPI_IsActiveFlag_BSY(SPI_TypeDef *SPIx)
+{
+ return ((READ_BIT(SPIx->SR, SPI_SR_BSY) == (SPI_SR_BSY)) ? 1UL : 0UL);
+}
+
+/**
+ * @brief Get frame format error flag
+ * @rmtoll SR FRE LL_SPI_IsActiveFlag_FRE
+ * @param SPIx SPI Instance
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SPI_IsActiveFlag_FRE(SPI_TypeDef *SPIx)
+{
+ return ((READ_BIT(SPIx->SR, SPI_SR_FRE) == (SPI_SR_FRE)) ? 1UL : 0UL);
+}
+
+/**
+ * @brief Get FIFO reception Level
+ * @rmtoll SR FRLVL LL_SPI_GetRxFIFOLevel
+ * @param SPIx SPI Instance
+ * @retval Returned value can be one of the following values:
+ * @arg @ref LL_SPI_RX_FIFO_EMPTY
+ * @arg @ref LL_SPI_RX_FIFO_QUARTER_FULL
+ * @arg @ref LL_SPI_RX_FIFO_HALF_FULL
+ * @arg @ref LL_SPI_RX_FIFO_FULL
+ */
+__STATIC_INLINE uint32_t LL_SPI_GetRxFIFOLevel(SPI_TypeDef *SPIx)
+{
+ return (uint32_t)(READ_BIT(SPIx->SR, SPI_SR_FRLVL));
+}
+
+/**
+ * @brief Get FIFO Transmission Level
+ * @rmtoll SR FTLVL LL_SPI_GetTxFIFOLevel
+ * @param SPIx SPI Instance
+ * @retval Returned value can be one of the following values:
+ * @arg @ref LL_SPI_TX_FIFO_EMPTY
+ * @arg @ref LL_SPI_TX_FIFO_QUARTER_FULL
+ * @arg @ref LL_SPI_TX_FIFO_HALF_FULL
+ * @arg @ref LL_SPI_TX_FIFO_FULL
+ */
+__STATIC_INLINE uint32_t LL_SPI_GetTxFIFOLevel(SPI_TypeDef *SPIx)
+{
+ return (uint32_t)(READ_BIT(SPIx->SR, SPI_SR_FTLVL));
+}
+
+/**
+ * @brief Clear CRC error flag
+ * @rmtoll SR CRCERR LL_SPI_ClearFlag_CRCERR
+ * @param SPIx SPI Instance
+ * @retval None
+ */
+__STATIC_INLINE void LL_SPI_ClearFlag_CRCERR(SPI_TypeDef *SPIx)
+{
+ CLEAR_BIT(SPIx->SR, SPI_SR_CRCERR);
+}
+
+/**
+ * @brief Clear mode fault error flag
+ * @note Clearing this flag is done by a read access to the SPIx_SR
+ * register followed by a write access to the SPIx_CR1 register
+ * @rmtoll SR MODF LL_SPI_ClearFlag_MODF
+ * @param SPIx SPI Instance
+ * @retval None
+ */
+__STATIC_INLINE void LL_SPI_ClearFlag_MODF(SPI_TypeDef *SPIx)
+{
+ __IO uint32_t tmpreg_sr;
+ tmpreg_sr = SPIx->SR;
+ (void) tmpreg_sr;
+ CLEAR_BIT(SPIx->CR1, SPI_CR1_SPE);
+}
+
+/**
+ * @brief Clear overrun error flag
+ * @note Clearing this flag is done by a read access to the SPIx_DR
+ * register followed by a read access to the SPIx_SR register
+ * @rmtoll SR OVR LL_SPI_ClearFlag_OVR
+ * @param SPIx SPI Instance
+ * @retval None
+ */
+__STATIC_INLINE void LL_SPI_ClearFlag_OVR(SPI_TypeDef *SPIx)
+{
+ __IO uint32_t tmpreg;
+ tmpreg = SPIx->DR;
+ (void) tmpreg;
+ tmpreg = SPIx->SR;
+ (void) tmpreg;
+}
+
+/**
+ * @brief Clear frame format error flag
+ * @note Clearing this flag is done by reading SPIx_SR register
+ * @rmtoll SR FRE LL_SPI_ClearFlag_FRE
+ * @param SPIx SPI Instance
+ * @retval None
+ */
+__STATIC_INLINE void LL_SPI_ClearFlag_FRE(SPI_TypeDef *SPIx)
+{
+ __IO uint32_t tmpreg;
+ tmpreg = SPIx->SR;
+ (void) tmpreg;
+}
+
+/**
+ * @}
+ */
+
+/** @defgroup SPI_LL_EF_IT_Management Interrupt Management
+ * @{
+ */
+
+/**
+ * @brief Enable error interrupt
+ * @note This bit controls the generation of an interrupt when an error condition occurs (CRCERR, OVR, MODF in SPI mode, FRE at TI mode).
+ * @rmtoll CR2 ERRIE LL_SPI_EnableIT_ERR
+ * @param SPIx SPI Instance
+ * @retval None
+ */
+__STATIC_INLINE void LL_SPI_EnableIT_ERR(SPI_TypeDef *SPIx)
+{
+ SET_BIT(SPIx->CR2, SPI_CR2_ERRIE);
+}
+
+/**
+ * @brief Enable Rx buffer not empty interrupt
+ * @rmtoll CR2 RXNEIE LL_SPI_EnableIT_RXNE
+ * @param SPIx SPI Instance
+ * @retval None
+ */
+__STATIC_INLINE void LL_SPI_EnableIT_RXNE(SPI_TypeDef *SPIx)
+{
+ SET_BIT(SPIx->CR2, SPI_CR2_RXNEIE);
+}
+
+/**
+ * @brief Enable Tx buffer empty interrupt
+ * @rmtoll CR2 TXEIE LL_SPI_EnableIT_TXE
+ * @param SPIx SPI Instance
+ * @retval None
+ */
+__STATIC_INLINE void LL_SPI_EnableIT_TXE(SPI_TypeDef *SPIx)
+{
+ SET_BIT(SPIx->CR2, SPI_CR2_TXEIE);
+}
+
+/**
+ * @brief Disable error interrupt
+ * @note This bit controls the generation of an interrupt when an error condition occurs (CRCERR, OVR, MODF in SPI mode, FRE at TI mode).
+ * @rmtoll CR2 ERRIE LL_SPI_DisableIT_ERR
+ * @param SPIx SPI Instance
+ * @retval None
+ */
+__STATIC_INLINE void LL_SPI_DisableIT_ERR(SPI_TypeDef *SPIx)
+{
+ CLEAR_BIT(SPIx->CR2, SPI_CR2_ERRIE);
+}
+
+/**
+ * @brief Disable Rx buffer not empty interrupt
+ * @rmtoll CR2 RXNEIE LL_SPI_DisableIT_RXNE
+ * @param SPIx SPI Instance
+ * @retval None
+ */
+__STATIC_INLINE void LL_SPI_DisableIT_RXNE(SPI_TypeDef *SPIx)
+{
+ CLEAR_BIT(SPIx->CR2, SPI_CR2_RXNEIE);
+}
+
+/**
+ * @brief Disable Tx buffer empty interrupt
+ * @rmtoll CR2 TXEIE LL_SPI_DisableIT_TXE
+ * @param SPIx SPI Instance
+ * @retval None
+ */
+__STATIC_INLINE void LL_SPI_DisableIT_TXE(SPI_TypeDef *SPIx)
+{
+ CLEAR_BIT(SPIx->CR2, SPI_CR2_TXEIE);
+}
+
+/**
+ * @brief Check if error interrupt is enabled
+ * @rmtoll CR2 ERRIE LL_SPI_IsEnabledIT_ERR
+ * @param SPIx SPI Instance
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SPI_IsEnabledIT_ERR(SPI_TypeDef *SPIx)
+{
+ return ((READ_BIT(SPIx->CR2, SPI_CR2_ERRIE) == (SPI_CR2_ERRIE)) ? 1UL : 0UL);
+}
+
+/**
+ * @brief Check if Rx buffer not empty interrupt is enabled
+ * @rmtoll CR2 RXNEIE LL_SPI_IsEnabledIT_RXNE
+ * @param SPIx SPI Instance
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SPI_IsEnabledIT_RXNE(SPI_TypeDef *SPIx)
+{
+ return ((READ_BIT(SPIx->CR2, SPI_CR2_RXNEIE) == (SPI_CR2_RXNEIE)) ? 1UL : 0UL);
+}
+
+/**
+ * @brief Check if Tx buffer empty interrupt
+ * @rmtoll CR2 TXEIE LL_SPI_IsEnabledIT_TXE
+ * @param SPIx SPI Instance
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SPI_IsEnabledIT_TXE(SPI_TypeDef *SPIx)
+{
+ return ((READ_BIT(SPIx->CR2, SPI_CR2_TXEIE) == (SPI_CR2_TXEIE)) ? 1UL : 0UL);
+}
+
+/**
+ * @}
+ */
+
+/** @defgroup SPI_LL_EF_DMA_Management DMA Management
+ * @{
+ */
+
+/**
+ * @brief Enable DMA Rx
+ * @rmtoll CR2 RXDMAEN LL_SPI_EnableDMAReq_RX
+ * @param SPIx SPI Instance
+ * @retval None
+ */
+__STATIC_INLINE void LL_SPI_EnableDMAReq_RX(SPI_TypeDef *SPIx)
+{
+ SET_BIT(SPIx->CR2, SPI_CR2_RXDMAEN);
+}
+
+/**
+ * @brief Disable DMA Rx
+ * @rmtoll CR2 RXDMAEN LL_SPI_DisableDMAReq_RX
+ * @param SPIx SPI Instance
+ * @retval None
+ */
+__STATIC_INLINE void LL_SPI_DisableDMAReq_RX(SPI_TypeDef *SPIx)
+{
+ CLEAR_BIT(SPIx->CR2, SPI_CR2_RXDMAEN);
+}
+
+/**
+ * @brief Check if DMA Rx is enabled
+ * @rmtoll CR2 RXDMAEN LL_SPI_IsEnabledDMAReq_RX
+ * @param SPIx SPI Instance
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SPI_IsEnabledDMAReq_RX(SPI_TypeDef *SPIx)
+{
+ return ((READ_BIT(SPIx->CR2, SPI_CR2_RXDMAEN) == (SPI_CR2_RXDMAEN)) ? 1UL : 0UL);
+}
+
+/**
+ * @brief Enable DMA Tx
+ * @rmtoll CR2 TXDMAEN LL_SPI_EnableDMAReq_TX
+ * @param SPIx SPI Instance
+ * @retval None
+ */
+__STATIC_INLINE void LL_SPI_EnableDMAReq_TX(SPI_TypeDef *SPIx)
+{
+ SET_BIT(SPIx->CR2, SPI_CR2_TXDMAEN);
+}
+
+/**
+ * @brief Disable DMA Tx
+ * @rmtoll CR2 TXDMAEN LL_SPI_DisableDMAReq_TX
+ * @param SPIx SPI Instance
+ * @retval None
+ */
+__STATIC_INLINE void LL_SPI_DisableDMAReq_TX(SPI_TypeDef *SPIx)
+{
+ CLEAR_BIT(SPIx->CR2, SPI_CR2_TXDMAEN);
+}
+
+/**
+ * @brief Check if DMA Tx is enabled
+ * @rmtoll CR2 TXDMAEN LL_SPI_IsEnabledDMAReq_TX
+ * @param SPIx SPI Instance
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SPI_IsEnabledDMAReq_TX(SPI_TypeDef *SPIx)
+{
+ return ((READ_BIT(SPIx->CR2, SPI_CR2_TXDMAEN) == (SPI_CR2_TXDMAEN)) ? 1UL : 0UL);
+}
+
+/**
+ * @brief Set parity of Last DMA reception
+ * @rmtoll CR2 LDMARX LL_SPI_SetDMAParity_RX
+ * @param SPIx SPI Instance
+ * @param Parity This parameter can be one of the following values:
+ * @arg @ref LL_SPI_DMA_PARITY_ODD
+ * @arg @ref LL_SPI_DMA_PARITY_EVEN
+ * @retval None
+ */
+__STATIC_INLINE void LL_SPI_SetDMAParity_RX(SPI_TypeDef *SPIx, uint32_t Parity)
+{
+ MODIFY_REG(SPIx->CR2, SPI_CR2_LDMARX, (Parity << SPI_CR2_LDMARX_Pos));
+}
+
+/**
+ * @brief Get parity configuration for Last DMA reception
+ * @rmtoll CR2 LDMARX LL_SPI_GetDMAParity_RX
+ * @param SPIx SPI Instance
+ * @retval Returned value can be one of the following values:
+ * @arg @ref LL_SPI_DMA_PARITY_ODD
+ * @arg @ref LL_SPI_DMA_PARITY_EVEN
+ */
+__STATIC_INLINE uint32_t LL_SPI_GetDMAParity_RX(SPI_TypeDef *SPIx)
+{
+ return (uint32_t)(READ_BIT(SPIx->CR2, SPI_CR2_LDMARX) >> SPI_CR2_LDMARX_Pos);
+}
+
+/**
+ * @brief Set parity of Last DMA transmission
+ * @rmtoll CR2 LDMATX LL_SPI_SetDMAParity_TX
+ * @param SPIx SPI Instance
+ * @param Parity This parameter can be one of the following values:
+ * @arg @ref LL_SPI_DMA_PARITY_ODD
+ * @arg @ref LL_SPI_DMA_PARITY_EVEN
+ * @retval None
+ */
+__STATIC_INLINE void LL_SPI_SetDMAParity_TX(SPI_TypeDef *SPIx, uint32_t Parity)
+{
+ MODIFY_REG(SPIx->CR2, SPI_CR2_LDMATX, (Parity << SPI_CR2_LDMATX_Pos));
+}
+
+/**
+ * @brief Get parity configuration for Last DMA transmission
+ * @rmtoll CR2 LDMATX LL_SPI_GetDMAParity_TX
+ * @param SPIx SPI Instance
+ * @retval Returned value can be one of the following values:
+ * @arg @ref LL_SPI_DMA_PARITY_ODD
+ * @arg @ref LL_SPI_DMA_PARITY_EVEN
+ */
+__STATIC_INLINE uint32_t LL_SPI_GetDMAParity_TX(SPI_TypeDef *SPIx)
+{
+ return (uint32_t)(READ_BIT(SPIx->CR2, SPI_CR2_LDMATX) >> SPI_CR2_LDMATX_Pos);
+}
+
+/**
+ * @brief Get the data register address used for DMA transfer
+ * @rmtoll DR DR LL_SPI_DMA_GetRegAddr
+ * @param SPIx SPI Instance
+ * @retval Address of data register
+ */
+__STATIC_INLINE uint32_t LL_SPI_DMA_GetRegAddr(SPI_TypeDef *SPIx)
+{
+ return (uint32_t) &(SPIx->DR);
+}
+
+/**
+ * @}
+ */
+
+/** @defgroup SPI_LL_EF_DATA_Management DATA Management
+ * @{
+ */
+
+/**
+ * @brief Read 8-Bits in the data register
+ * @rmtoll DR DR LL_SPI_ReceiveData8
+ * @param SPIx SPI Instance
+ * @retval RxData Value between Min_Data=0x00 and Max_Data=0xFF
+ */
+__STATIC_INLINE uint8_t LL_SPI_ReceiveData8(SPI_TypeDef *SPIx)
+{
+ return (*((__IO uint8_t *)&SPIx->DR));
+}
+
+/**
+ * @brief Read 16-Bits in the data register
+ * @rmtoll DR DR LL_SPI_ReceiveData16
+ * @param SPIx SPI Instance
+ * @retval RxData Value between Min_Data=0x00 and Max_Data=0xFFFF
+ */
+__STATIC_INLINE uint16_t LL_SPI_ReceiveData16(SPI_TypeDef *SPIx)
+{
+ return (uint16_t)(READ_REG(SPIx->DR));
+}
+
+/**
+ * @brief Write 8-Bits in the data register
+ * @rmtoll DR DR LL_SPI_TransmitData8
+ * @param SPIx SPI Instance
+ * @param TxData Value between Min_Data=0x00 and Max_Data=0xFF
+ * @retval None
+ */
+__STATIC_INLINE void LL_SPI_TransmitData8(SPI_TypeDef *SPIx, uint8_t TxData)
+{
+#if defined (__GNUC__)
+ __IO uint8_t *spidr = ((__IO uint8_t *)&SPIx->DR);
+ *spidr = TxData;
+#else
+ *((__IO uint8_t *)&SPIx->DR) = TxData;
+#endif /* __GNUC__ */
+}
+
+/**
+ * @brief Write 16-Bits in the data register
+ * @rmtoll DR DR LL_SPI_TransmitData16
+ * @param SPIx SPI Instance
+ * @param TxData Value between Min_Data=0x00 and Max_Data=0xFFFF
+ * @retval None
+ */
+__STATIC_INLINE void LL_SPI_TransmitData16(SPI_TypeDef *SPIx, uint16_t TxData)
+{
+#if defined (__GNUC__)
+ __IO uint16_t *spidr = ((__IO uint16_t *)&SPIx->DR);
+ *spidr = TxData;
+#else
+ SPIx->DR = TxData;
+#endif /* __GNUC__ */
+}
+
+/**
+ * @}
+ */
+#if defined(USE_FULL_LL_DRIVER)
+/** @defgroup SPI_LL_EF_Init Initialization and de-initialization functions
+ * @{
+ */
+
+ErrorStatus LL_SPI_DeInit(SPI_TypeDef *SPIx);
+ErrorStatus LL_SPI_Init(SPI_TypeDef *SPIx, LL_SPI_InitTypeDef *SPI_InitStruct);
+void LL_SPI_StructInit(LL_SPI_InitTypeDef *SPI_InitStruct);
+
+/**
+ * @}
+ */
+#endif /* USE_FULL_LL_DRIVER */
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+#if defined(SPI_I2S_SUPPORT)
+/** @defgroup I2S_LL I2S
+ * @{
+ */
+
+/* Private variables ---------------------------------------------------------*/
+/* Private constants ---------------------------------------------------------*/
+/* Private macros ------------------------------------------------------------*/
+
+/* Exported types ------------------------------------------------------------*/
+#if defined(USE_FULL_LL_DRIVER)
+/** @defgroup I2S_LL_ES_INIT I2S Exported Init structure
+ * @{
+ */
+
+/**
+ * @brief I2S Init structure definition
+ */
+
+typedef struct
+{
+ uint32_t Mode; /*!< Specifies the I2S operating mode.
+ This parameter can be a value of @ref I2S_LL_EC_MODE
+
+ This feature can be modified afterwards using unitary function @ref LL_I2S_SetTransferMode().*/
+
+ uint32_t Standard; /*!< Specifies the standard used for the I2S communication.
+ This parameter can be a value of @ref I2S_LL_EC_STANDARD
+
+ This feature can be modified afterwards using unitary function @ref LL_I2S_SetStandard().*/
+
+
+ uint32_t DataFormat; /*!< Specifies the data format for the I2S communication.
+ This parameter can be a value of @ref I2S_LL_EC_DATA_FORMAT
+
+ This feature can be modified afterwards using unitary function @ref LL_I2S_SetDataFormat().*/
+
+
+ uint32_t MCLKOutput; /*!< Specifies whether the I2S MCLK output is enabled or not.
+ This parameter can be a value of @ref I2S_LL_EC_MCLK_OUTPUT
+
+ This feature can be modified afterwards using unitary functions @ref LL_I2S_EnableMasterClock() or @ref LL_I2S_DisableMasterClock.*/
+
+
+ uint32_t AudioFreq; /*!< Specifies the frequency selected for the I2S communication.
+ This parameter can be a value of @ref I2S_LL_EC_AUDIO_FREQ
+
+ Audio Frequency can be modified afterwards using Reference manual formulas to calculate Prescaler Linear, Parity
+ and unitary functions @ref LL_I2S_SetPrescalerLinear() and @ref LL_I2S_SetPrescalerParity() to set it.*/
+
+
+ uint32_t ClockPolarity; /*!< Specifies the idle state of the I2S clock.
+ This parameter can be a value of @ref I2S_LL_EC_POLARITY
+
+ This feature can be modified afterwards using unitary function @ref LL_I2S_SetClockPolarity().*/
+
+} LL_I2S_InitTypeDef;
+
+/**
+ * @}
+ */
+#endif /*USE_FULL_LL_DRIVER*/
+
+/* Exported constants --------------------------------------------------------*/
+/** @defgroup I2S_LL_Exported_Constants I2S Exported Constants
+ * @{
+ */
+
+/** @defgroup I2S_LL_EC_GET_FLAG Get Flags Defines
+ * @brief Flags defines which can be used with LL_I2S_ReadReg function
+ * @{
+ */
+#define LL_I2S_SR_RXNE LL_SPI_SR_RXNE /*!< Rx buffer not empty flag */
+#define LL_I2S_SR_TXE LL_SPI_SR_TXE /*!< Tx buffer empty flag */
+#define LL_I2S_SR_BSY LL_SPI_SR_BSY /*!< Busy flag */
+#define LL_I2S_SR_UDR SPI_SR_UDR /*!< Underrun flag */
+#define LL_I2S_SR_OVR LL_SPI_SR_OVR /*!< Overrun flag */
+#define LL_I2S_SR_FRE LL_SPI_SR_FRE /*!< TI mode frame format error flag */
+/**
+ * @}
+ */
+
+/** @defgroup SPI_LL_EC_IT IT Defines
+ * @brief IT defines which can be used with LL_SPI_ReadReg and LL_SPI_WriteReg functions
+ * @{
+ */
+#define LL_I2S_CR2_RXNEIE LL_SPI_CR2_RXNEIE /*!< Rx buffer not empty interrupt enable */
+#define LL_I2S_CR2_TXEIE LL_SPI_CR2_TXEIE /*!< Tx buffer empty interrupt enable */
+#define LL_I2S_CR2_ERRIE LL_SPI_CR2_ERRIE /*!< Error interrupt enable */
+/**
+ * @}
+ */
+
+/** @defgroup I2S_LL_EC_DATA_FORMAT Data format
+ * @{
+ */
+#define LL_I2S_DATAFORMAT_16B 0x00000000U /*!< Data length 16 bits, Channel length 16bit */
+#define LL_I2S_DATAFORMAT_16B_EXTENDED (SPI_I2SCFGR_CHLEN) /*!< Data length 16 bits, Channel length 32bit */
+#define LL_I2S_DATAFORMAT_24B (SPI_I2SCFGR_CHLEN | SPI_I2SCFGR_DATLEN_0) /*!< Data length 24 bits, Channel length 32bit */
+#define LL_I2S_DATAFORMAT_32B (SPI_I2SCFGR_CHLEN | SPI_I2SCFGR_DATLEN_1) /*!< Data length 16 bits, Channel length 32bit */
+/**
+ * @}
+ */
+
+/** @defgroup I2S_LL_EC_POLARITY Clock Polarity
+ * @{
+ */
+#define LL_I2S_POLARITY_LOW 0x00000000U /*!< Clock steady state is low level */
+#define LL_I2S_POLARITY_HIGH (SPI_I2SCFGR_CKPOL) /*!< Clock steady state is high level */
+/**
+ * @}
+ */
+
+/** @defgroup I2S_LL_EC_STANDARD I2s Standard
+ * @{
+ */
+#define LL_I2S_STANDARD_PHILIPS 0x00000000U /*!< I2S standard philips */
+#define LL_I2S_STANDARD_MSB (SPI_I2SCFGR_I2SSTD_0) /*!< MSB justified standard (left justified) */
+#define LL_I2S_STANDARD_LSB (SPI_I2SCFGR_I2SSTD_1) /*!< LSB justified standard (right justified) */
+#define LL_I2S_STANDARD_PCM_SHORT (SPI_I2SCFGR_I2SSTD_0 | SPI_I2SCFGR_I2SSTD_1) /*!< PCM standard, short frame synchronization */
+#define LL_I2S_STANDARD_PCM_LONG (SPI_I2SCFGR_I2SSTD_0 | SPI_I2SCFGR_I2SSTD_1 | SPI_I2SCFGR_PCMSYNC) /*!< PCM standard, long frame synchronization */
+/**
+ * @}
+ */
+
+/** @defgroup I2S_LL_EC_MODE Operation Mode
+ * @{
+ */
+#define LL_I2S_MODE_SLAVE_TX 0x00000000U /*!< Slave Tx configuration */
+#define LL_I2S_MODE_SLAVE_RX (SPI_I2SCFGR_I2SCFG_0) /*!< Slave Rx configuration */
+#define LL_I2S_MODE_MASTER_TX (SPI_I2SCFGR_I2SCFG_1) /*!< Master Tx configuration */
+#define LL_I2S_MODE_MASTER_RX (SPI_I2SCFGR_I2SCFG_0 | SPI_I2SCFGR_I2SCFG_1) /*!< Master Rx configuration */
+/**
+ * @}
+ */
+
+/** @defgroup I2S_LL_EC_PRESCALER_FACTOR Prescaler Factor
+ * @{
+ */
+#define LL_I2S_PRESCALER_PARITY_EVEN 0x00000000U /*!< Odd factor: Real divider value is = I2SDIV * 2 */
+#define LL_I2S_PRESCALER_PARITY_ODD (SPI_I2SPR_ODD >> 8U) /*!< Odd factor: Real divider value is = (I2SDIV * 2)+1 */
+/**
+ * @}
+ */
+
+#if defined(USE_FULL_LL_DRIVER)
+
+/** @defgroup I2S_LL_EC_MCLK_OUTPUT MCLK Output
+ * @{
+ */
+#define LL_I2S_MCLK_OUTPUT_DISABLE 0x00000000U /*!< Master clock output is disabled */
+#define LL_I2S_MCLK_OUTPUT_ENABLE (SPI_I2SPR_MCKOE) /*!< Master clock output is enabled */
+/**
+ * @}
+ */
+
+/** @defgroup I2S_LL_EC_AUDIO_FREQ Audio Frequency
+ * @{
+ */
+
+#define LL_I2S_AUDIOFREQ_192K 192000U /*!< Audio Frequency configuration 192000 Hz */
+#define LL_I2S_AUDIOFREQ_96K 96000U /*!< Audio Frequency configuration 96000 Hz */
+#define LL_I2S_AUDIOFREQ_48K 48000U /*!< Audio Frequency configuration 48000 Hz */
+#define LL_I2S_AUDIOFREQ_44K 44100U /*!< Audio Frequency configuration 44100 Hz */
+#define LL_I2S_AUDIOFREQ_32K 32000U /*!< Audio Frequency configuration 32000 Hz */
+#define LL_I2S_AUDIOFREQ_22K 22050U /*!< Audio Frequency configuration 22050 Hz */
+#define LL_I2S_AUDIOFREQ_16K 16000U /*!< Audio Frequency configuration 16000 Hz */
+#define LL_I2S_AUDIOFREQ_11K 11025U /*!< Audio Frequency configuration 11025 Hz */
+#define LL_I2S_AUDIOFREQ_8K 8000U /*!< Audio Frequency configuration 8000 Hz */
+#define LL_I2S_AUDIOFREQ_DEFAULT 2U /*!< Audio Freq not specified. Register I2SDIV = 2 */
+/**
+ * @}
+ */
+#endif /* USE_FULL_LL_DRIVER */
+
+/**
+ * @}
+ */
+
+/* Exported macro ------------------------------------------------------------*/
+/** @defgroup I2S_LL_Exported_Macros I2S Exported Macros
+ * @{
+ */
+
+/** @defgroup I2S_LL_EM_WRITE_READ Common Write and read registers Macros
+ * @{
+ */
+
+/**
+ * @brief Write a value in I2S register
+ * @param __INSTANCE__ I2S Instance
+ * @param __REG__ Register to be written
+ * @param __VALUE__ Value to be written in the register
+ * @retval None
+ */
+#define LL_I2S_WriteReg(__INSTANCE__, __REG__, __VALUE__) WRITE_REG(__INSTANCE__->__REG__, (__VALUE__))
+
+/**
+ * @brief Read a value in I2S register
+ * @param __INSTANCE__ I2S Instance
+ * @param __REG__ Register to be read
+ * @retval Register value
+ */
+#define LL_I2S_ReadReg(__INSTANCE__, __REG__) READ_REG(__INSTANCE__->__REG__)
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+
+/* Exported functions --------------------------------------------------------*/
+
+/** @defgroup I2S_LL_Exported_Functions I2S Exported Functions
+ * @{
+ */
+
+/** @defgroup I2S_LL_EF_Configuration Configuration
+ * @{
+ */
+
+/**
+ * @brief Select I2S mode and Enable I2S peripheral
+ * @rmtoll I2SCFGR I2SMOD LL_I2S_Enable\n
+ * I2SCFGR I2SE LL_I2S_Enable
+ * @param SPIx SPI Instance
+ * @retval None
+ */
+__STATIC_INLINE void LL_I2S_Enable(SPI_TypeDef *SPIx)
+{
+ SET_BIT(SPIx->I2SCFGR, SPI_I2SCFGR_I2SMOD | SPI_I2SCFGR_I2SE);
+}
+
+/**
+ * @brief Disable I2S peripheral
+ * @rmtoll I2SCFGR I2SE LL_I2S_Disable
+ * @param SPIx SPI Instance
+ * @retval None
+ */
+__STATIC_INLINE void LL_I2S_Disable(SPI_TypeDef *SPIx)
+{
+ CLEAR_BIT(SPIx->I2SCFGR, SPI_I2SCFGR_I2SMOD | SPI_I2SCFGR_I2SE);
+}
+
+/**
+ * @brief Check if I2S peripheral is enabled
+ * @rmtoll I2SCFGR I2SE LL_I2S_IsEnabled
+ * @param SPIx SPI Instance
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_I2S_IsEnabled(SPI_TypeDef *SPIx)
+{
+ return ((READ_BIT(SPIx->I2SCFGR, SPI_I2SCFGR_I2SE) == (SPI_I2SCFGR_I2SE)) ? 1UL : 0UL);
+}
+
+/**
+ * @brief Set I2S data frame length
+ * @rmtoll I2SCFGR DATLEN LL_I2S_SetDataFormat\n
+ * I2SCFGR CHLEN LL_I2S_SetDataFormat
+ * @param SPIx SPI Instance
+ * @param DataFormat This parameter can be one of the following values:
+ * @arg @ref LL_I2S_DATAFORMAT_16B
+ * @arg @ref LL_I2S_DATAFORMAT_16B_EXTENDED
+ * @arg @ref LL_I2S_DATAFORMAT_24B
+ * @arg @ref LL_I2S_DATAFORMAT_32B
+ * @retval None
+ */
+__STATIC_INLINE void LL_I2S_SetDataFormat(SPI_TypeDef *SPIx, uint32_t DataFormat)
+{
+ MODIFY_REG(SPIx->I2SCFGR, SPI_I2SCFGR_DATLEN | SPI_I2SCFGR_CHLEN, DataFormat);
+}
+
+/**
+ * @brief Get I2S data frame length
+ * @rmtoll I2SCFGR DATLEN LL_I2S_GetDataFormat\n
+ * I2SCFGR CHLEN LL_I2S_GetDataFormat
+ * @param SPIx SPI Instance
+ * @retval Returned value can be one of the following values:
+ * @arg @ref LL_I2S_DATAFORMAT_16B
+ * @arg @ref LL_I2S_DATAFORMAT_16B_EXTENDED
+ * @arg @ref LL_I2S_DATAFORMAT_24B
+ * @arg @ref LL_I2S_DATAFORMAT_32B
+ */
+__STATIC_INLINE uint32_t LL_I2S_GetDataFormat(SPI_TypeDef *SPIx)
+{
+ return (uint32_t)(READ_BIT(SPIx->I2SCFGR, SPI_I2SCFGR_DATLEN | SPI_I2SCFGR_CHLEN));
+}
+
+/**
+ * @brief Set I2S clock polarity
+ * @rmtoll I2SCFGR CKPOL LL_I2S_SetClockPolarity
+ * @param SPIx SPI Instance
+ * @param ClockPolarity This parameter can be one of the following values:
+ * @arg @ref LL_I2S_POLARITY_LOW
+ * @arg @ref LL_I2S_POLARITY_HIGH
+ * @retval None
+ */
+__STATIC_INLINE void LL_I2S_SetClockPolarity(SPI_TypeDef *SPIx, uint32_t ClockPolarity)
+{
+ SET_BIT(SPIx->I2SCFGR, ClockPolarity);
+}
+
+/**
+ * @brief Get I2S clock polarity
+ * @rmtoll I2SCFGR CKPOL LL_I2S_GetClockPolarity
+ * @param SPIx SPI Instance
+ * @retval Returned value can be one of the following values:
+ * @arg @ref LL_I2S_POLARITY_LOW
+ * @arg @ref LL_I2S_POLARITY_HIGH
+ */
+__STATIC_INLINE uint32_t LL_I2S_GetClockPolarity(SPI_TypeDef *SPIx)
+{
+ return (uint32_t)(READ_BIT(SPIx->I2SCFGR, SPI_I2SCFGR_CKPOL));
+}
+
+/**
+ * @brief Set I2S standard protocol
+ * @rmtoll I2SCFGR I2SSTD LL_I2S_SetStandard\n
+ * I2SCFGR PCMSYNC LL_I2S_SetStandard
+ * @param SPIx SPI Instance
+ * @param Standard This parameter can be one of the following values:
+ * @arg @ref LL_I2S_STANDARD_PHILIPS
+ * @arg @ref LL_I2S_STANDARD_MSB
+ * @arg @ref LL_I2S_STANDARD_LSB
+ * @arg @ref LL_I2S_STANDARD_PCM_SHORT
+ * @arg @ref LL_I2S_STANDARD_PCM_LONG
+ * @retval None
+ */
+__STATIC_INLINE void LL_I2S_SetStandard(SPI_TypeDef *SPIx, uint32_t Standard)
+{
+ MODIFY_REG(SPIx->I2SCFGR, SPI_I2SCFGR_I2SSTD | SPI_I2SCFGR_PCMSYNC, Standard);
+}
+
+/**
+ * @brief Get I2S standard protocol
+ * @rmtoll I2SCFGR I2SSTD LL_I2S_GetStandard\n
+ * I2SCFGR PCMSYNC LL_I2S_GetStandard
+ * @param SPIx SPI Instance
+ * @retval Returned value can be one of the following values:
+ * @arg @ref LL_I2S_STANDARD_PHILIPS
+ * @arg @ref LL_I2S_STANDARD_MSB
+ * @arg @ref LL_I2S_STANDARD_LSB
+ * @arg @ref LL_I2S_STANDARD_PCM_SHORT
+ * @arg @ref LL_I2S_STANDARD_PCM_LONG
+ */
+__STATIC_INLINE uint32_t LL_I2S_GetStandard(SPI_TypeDef *SPIx)
+{
+ return (uint32_t)(READ_BIT(SPIx->I2SCFGR, SPI_I2SCFGR_I2SSTD | SPI_I2SCFGR_PCMSYNC));
+}
+
+/**
+ * @brief Set I2S transfer mode
+ * @rmtoll I2SCFGR I2SCFG LL_I2S_SetTransferMode
+ * @param SPIx SPI Instance
+ * @param Mode This parameter can be one of the following values:
+ * @arg @ref LL_I2S_MODE_SLAVE_TX
+ * @arg @ref LL_I2S_MODE_SLAVE_RX
+ * @arg @ref LL_I2S_MODE_MASTER_TX
+ * @arg @ref LL_I2S_MODE_MASTER_RX
+ * @retval None
+ */
+__STATIC_INLINE void LL_I2S_SetTransferMode(SPI_TypeDef *SPIx, uint32_t Mode)
+{
+ MODIFY_REG(SPIx->I2SCFGR, SPI_I2SCFGR_I2SCFG, Mode);
+}
+
+/**
+ * @brief Get I2S transfer mode
+ * @rmtoll I2SCFGR I2SCFG LL_I2S_GetTransferMode
+ * @param SPIx SPI Instance
+ * @retval Returned value can be one of the following values:
+ * @arg @ref LL_I2S_MODE_SLAVE_TX
+ * @arg @ref LL_I2S_MODE_SLAVE_RX
+ * @arg @ref LL_I2S_MODE_MASTER_TX
+ * @arg @ref LL_I2S_MODE_MASTER_RX
+ */
+__STATIC_INLINE uint32_t LL_I2S_GetTransferMode(SPI_TypeDef *SPIx)
+{
+ return (uint32_t)(READ_BIT(SPIx->I2SCFGR, SPI_I2SCFGR_I2SCFG));
+}
+
+/**
+ * @brief Set I2S linear prescaler
+ * @rmtoll I2SPR I2SDIV LL_I2S_SetPrescalerLinear
+ * @param SPIx SPI Instance
+ * @param PrescalerLinear Value between Min_Data=0x02 and Max_Data=0xFF
+ * @retval None
+ */
+__STATIC_INLINE void LL_I2S_SetPrescalerLinear(SPI_TypeDef *SPIx, uint8_t PrescalerLinear)
+{
+ MODIFY_REG(SPIx->I2SPR, SPI_I2SPR_I2SDIV, PrescalerLinear);
+}
+
+/**
+ * @brief Get I2S linear prescaler
+ * @rmtoll I2SPR I2SDIV LL_I2S_GetPrescalerLinear
+ * @param SPIx SPI Instance
+ * @retval PrescalerLinear Value between Min_Data=0x02 and Max_Data=0xFF
+ */
+__STATIC_INLINE uint32_t LL_I2S_GetPrescalerLinear(SPI_TypeDef *SPIx)
+{
+ return (uint32_t)(READ_BIT(SPIx->I2SPR, SPI_I2SPR_I2SDIV));
+}
+
+/**
+ * @brief Set I2S parity prescaler
+ * @rmtoll I2SPR ODD LL_I2S_SetPrescalerParity
+ * @param SPIx SPI Instance
+ * @param PrescalerParity This parameter can be one of the following values:
+ * @arg @ref LL_I2S_PRESCALER_PARITY_EVEN
+ * @arg @ref LL_I2S_PRESCALER_PARITY_ODD
+ * @retval None
+ */
+__STATIC_INLINE void LL_I2S_SetPrescalerParity(SPI_TypeDef *SPIx, uint32_t PrescalerParity)
+{
+ MODIFY_REG(SPIx->I2SPR, SPI_I2SPR_ODD, PrescalerParity << 8U);
+}
+
+/**
+ * @brief Get I2S parity prescaler
+ * @rmtoll I2SPR ODD LL_I2S_GetPrescalerParity
+ * @param SPIx SPI Instance
+ * @retval Returned value can be one of the following values:
+ * @arg @ref LL_I2S_PRESCALER_PARITY_EVEN
+ * @arg @ref LL_I2S_PRESCALER_PARITY_ODD
+ */
+__STATIC_INLINE uint32_t LL_I2S_GetPrescalerParity(SPI_TypeDef *SPIx)
+{
+ return (uint32_t)(READ_BIT(SPIx->I2SPR, SPI_I2SPR_ODD) >> 8U);
+}
+
+/**
+ * @brief Enable the master clock output (Pin MCK)
+ * @rmtoll I2SPR MCKOE LL_I2S_EnableMasterClock
+ * @param SPIx SPI Instance
+ * @retval None
+ */
+__STATIC_INLINE void LL_I2S_EnableMasterClock(SPI_TypeDef *SPIx)
+{
+ SET_BIT(SPIx->I2SPR, SPI_I2SPR_MCKOE);
+}
+
+/**
+ * @brief Disable the master clock output (Pin MCK)
+ * @rmtoll I2SPR MCKOE LL_I2S_DisableMasterClock
+ * @param SPIx SPI Instance
+ * @retval None
+ */
+__STATIC_INLINE void LL_I2S_DisableMasterClock(SPI_TypeDef *SPIx)
+{
+ CLEAR_BIT(SPIx->I2SPR, SPI_I2SPR_MCKOE);
+}
+
+/**
+ * @brief Check if the master clock output (Pin MCK) is enabled
+ * @rmtoll I2SPR MCKOE LL_I2S_IsEnabledMasterClock
+ * @param SPIx SPI Instance
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_I2S_IsEnabledMasterClock(SPI_TypeDef *SPIx)
+{
+ return ((READ_BIT(SPIx->I2SPR, SPI_I2SPR_MCKOE) == (SPI_I2SPR_MCKOE)) ? 1UL : 0UL);
+}
+
+#if defined(SPI_I2SCFGR_ASTRTEN)
+/**
+ * @brief Enable asynchronous start
+ * @rmtoll I2SCFGR ASTRTEN LL_I2S_EnableAsyncStart
+ * @param SPIx SPI Instance
+ * @retval None
+ */
+__STATIC_INLINE void LL_I2S_EnableAsyncStart(SPI_TypeDef *SPIx)
+{
+ SET_BIT(SPIx->I2SCFGR, SPI_I2SCFGR_ASTRTEN);
+}
+
+/**
+ * @brief Disable asynchronous start
+ * @rmtoll I2SCFGR ASTRTEN LL_I2S_DisableAsyncStart
+ * @param SPIx SPI Instance
+ * @retval None
+ */
+__STATIC_INLINE void LL_I2S_DisableAsyncStart(SPI_TypeDef *SPIx)
+{
+ CLEAR_BIT(SPIx->I2SCFGR, SPI_I2SCFGR_ASTRTEN);
+}
+
+/**
+ * @brief Check if asynchronous start is enabled
+ * @rmtoll I2SCFGR ASTRTEN LL_I2S_IsEnabledAsyncStart
+ * @param SPIx SPI Instance
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_I2S_IsEnabledAsyncStart(SPI_TypeDef *SPIx)
+{
+ return ((READ_BIT(SPIx->I2SCFGR, SPI_I2SCFGR_ASTRTEN) == (SPI_I2SCFGR_ASTRTEN)) ? 1UL : 0UL);
+}
+#endif /* SPI_I2SCFGR_ASTRTEN */
+
+/**
+ * @}
+ */
+
+/** @defgroup I2S_LL_EF_FLAG FLAG Management
+ * @{
+ */
+
+/**
+ * @brief Check if Rx buffer is not empty
+ * @rmtoll SR RXNE LL_I2S_IsActiveFlag_RXNE
+ * @param SPIx SPI Instance
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_I2S_IsActiveFlag_RXNE(SPI_TypeDef *SPIx)
+{
+ return LL_SPI_IsActiveFlag_RXNE(SPIx);
+}
+
+/**
+ * @brief Check if Tx buffer is empty
+ * @rmtoll SR TXE LL_I2S_IsActiveFlag_TXE
+ * @param SPIx SPI Instance
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_I2S_IsActiveFlag_TXE(SPI_TypeDef *SPIx)
+{
+ return LL_SPI_IsActiveFlag_TXE(SPIx);
+}
+
+/**
+ * @brief Get busy flag
+ * @rmtoll SR BSY LL_I2S_IsActiveFlag_BSY
+ * @param SPIx SPI Instance
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_I2S_IsActiveFlag_BSY(SPI_TypeDef *SPIx)
+{
+ return LL_SPI_IsActiveFlag_BSY(SPIx);
+}
+
+/**
+ * @brief Get overrun error flag
+ * @rmtoll SR OVR LL_I2S_IsActiveFlag_OVR
+ * @param SPIx SPI Instance
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_I2S_IsActiveFlag_OVR(SPI_TypeDef *SPIx)
+{
+ return LL_SPI_IsActiveFlag_OVR(SPIx);
+}
+
+/**
+ * @brief Get underrun error flag
+ * @rmtoll SR UDR LL_I2S_IsActiveFlag_UDR
+ * @param SPIx SPI Instance
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_I2S_IsActiveFlag_UDR(SPI_TypeDef *SPIx)
+{
+ return ((READ_BIT(SPIx->SR, SPI_SR_UDR) == (SPI_SR_UDR)) ? 1UL : 0UL);
+}
+
+/**
+ * @brief Get frame format error flag
+ * @rmtoll SR FRE LL_I2S_IsActiveFlag_FRE
+ * @param SPIx SPI Instance
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_I2S_IsActiveFlag_FRE(SPI_TypeDef *SPIx)
+{
+ return LL_SPI_IsActiveFlag_FRE(SPIx);
+}
+
+/**
+ * @brief Get channel side flag.
+ * @note 0: Channel Left has to be transmitted or has been received\n
+ * 1: Channel Right has to be transmitted or has been received\n
+ * It has no significance in PCM mode.
+ * @rmtoll SR CHSIDE LL_I2S_IsActiveFlag_CHSIDE
+ * @param SPIx SPI Instance
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_I2S_IsActiveFlag_CHSIDE(SPI_TypeDef *SPIx)
+{
+ return ((READ_BIT(SPIx->SR, SPI_SR_CHSIDE) == (SPI_SR_CHSIDE)) ? 1UL : 0UL);
+}
+
+/**
+ * @brief Clear overrun error flag
+ * @rmtoll SR OVR LL_I2S_ClearFlag_OVR
+ * @param SPIx SPI Instance
+ * @retval None
+ */
+__STATIC_INLINE void LL_I2S_ClearFlag_OVR(SPI_TypeDef *SPIx)
+{
+ LL_SPI_ClearFlag_OVR(SPIx);
+}
+
+/**
+ * @brief Clear underrun error flag
+ * @rmtoll SR UDR LL_I2S_ClearFlag_UDR
+ * @param SPIx SPI Instance
+ * @retval None
+ */
+__STATIC_INLINE void LL_I2S_ClearFlag_UDR(SPI_TypeDef *SPIx)
+{
+ __IO uint32_t tmpreg;
+ tmpreg = SPIx->SR;
+ (void)tmpreg;
+}
+
+/**
+ * @brief Clear frame format error flag
+ * @rmtoll SR FRE LL_I2S_ClearFlag_FRE
+ * @param SPIx SPI Instance
+ * @retval None
+ */
+__STATIC_INLINE void LL_I2S_ClearFlag_FRE(SPI_TypeDef *SPIx)
+{
+ LL_SPI_ClearFlag_FRE(SPIx);
+}
+
+/**
+ * @}
+ */
+
+/** @defgroup I2S_LL_EF_IT Interrupt Management
+ * @{
+ */
+
+/**
+ * @brief Enable error IT
+ * @note This bit controls the generation of an interrupt when an error condition occurs (OVR, UDR and FRE in I2S mode).
+ * @rmtoll CR2 ERRIE LL_I2S_EnableIT_ERR
+ * @param SPIx SPI Instance
+ * @retval None
+ */
+__STATIC_INLINE void LL_I2S_EnableIT_ERR(SPI_TypeDef *SPIx)
+{
+ LL_SPI_EnableIT_ERR(SPIx);
+}
+
+/**
+ * @brief Enable Rx buffer not empty IT
+ * @rmtoll CR2 RXNEIE LL_I2S_EnableIT_RXNE
+ * @param SPIx SPI Instance
+ * @retval None
+ */
+__STATIC_INLINE void LL_I2S_EnableIT_RXNE(SPI_TypeDef *SPIx)
+{
+ LL_SPI_EnableIT_RXNE(SPIx);
+}
+
+/**
+ * @brief Enable Tx buffer empty IT
+ * @rmtoll CR2 TXEIE LL_I2S_EnableIT_TXE
+ * @param SPIx SPI Instance
+ * @retval None
+ */
+__STATIC_INLINE void LL_I2S_EnableIT_TXE(SPI_TypeDef *SPIx)
+{
+ LL_SPI_EnableIT_TXE(SPIx);
+}
+
+/**
+ * @brief Disable error IT
+ * @note This bit controls the generation of an interrupt when an error condition occurs (OVR, UDR and FRE in I2S mode).
+ * @rmtoll CR2 ERRIE LL_I2S_DisableIT_ERR
+ * @param SPIx SPI Instance
+ * @retval None
+ */
+__STATIC_INLINE void LL_I2S_DisableIT_ERR(SPI_TypeDef *SPIx)
+{
+ LL_SPI_DisableIT_ERR(SPIx);
+}
+
+/**
+ * @brief Disable Rx buffer not empty IT
+ * @rmtoll CR2 RXNEIE LL_I2S_DisableIT_RXNE
+ * @param SPIx SPI Instance
+ * @retval None
+ */
+__STATIC_INLINE void LL_I2S_DisableIT_RXNE(SPI_TypeDef *SPIx)
+{
+ LL_SPI_DisableIT_RXNE(SPIx);
+}
+
+/**
+ * @brief Disable Tx buffer empty IT
+ * @rmtoll CR2 TXEIE LL_I2S_DisableIT_TXE
+ * @param SPIx SPI Instance
+ * @retval None
+ */
+__STATIC_INLINE void LL_I2S_DisableIT_TXE(SPI_TypeDef *SPIx)
+{
+ LL_SPI_DisableIT_TXE(SPIx);
+}
+
+/**
+ * @brief Check if ERR IT is enabled
+ * @rmtoll CR2 ERRIE LL_I2S_IsEnabledIT_ERR
+ * @param SPIx SPI Instance
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_I2S_IsEnabledIT_ERR(SPI_TypeDef *SPIx)
+{
+ return LL_SPI_IsEnabledIT_ERR(SPIx);
+}
+
+/**
+ * @brief Check if RXNE IT is enabled
+ * @rmtoll CR2 RXNEIE LL_I2S_IsEnabledIT_RXNE
+ * @param SPIx SPI Instance
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_I2S_IsEnabledIT_RXNE(SPI_TypeDef *SPIx)
+{
+ return LL_SPI_IsEnabledIT_RXNE(SPIx);
+}
+
+/**
+ * @brief Check if TXE IT is enabled
+ * @rmtoll CR2 TXEIE LL_I2S_IsEnabledIT_TXE
+ * @param SPIx SPI Instance
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_I2S_IsEnabledIT_TXE(SPI_TypeDef *SPIx)
+{
+ return LL_SPI_IsEnabledIT_TXE(SPIx);
+}
+
+/**
+ * @}
+ */
+
+/** @defgroup I2S_LL_EF_DMA DMA Management
+ * @{
+ */
+
+/**
+ * @brief Enable DMA Rx
+ * @rmtoll CR2 RXDMAEN LL_I2S_EnableDMAReq_RX
+ * @param SPIx SPI Instance
+ * @retval None
+ */
+__STATIC_INLINE void LL_I2S_EnableDMAReq_RX(SPI_TypeDef *SPIx)
+{
+ LL_SPI_EnableDMAReq_RX(SPIx);
+}
+
+/**
+ * @brief Disable DMA Rx
+ * @rmtoll CR2 RXDMAEN LL_I2S_DisableDMAReq_RX
+ * @param SPIx SPI Instance
+ * @retval None
+ */
+__STATIC_INLINE void LL_I2S_DisableDMAReq_RX(SPI_TypeDef *SPIx)
+{
+ LL_SPI_DisableDMAReq_RX(SPIx);
+}
+
+/**
+ * @brief Check if DMA Rx is enabled
+ * @rmtoll CR2 RXDMAEN LL_I2S_IsEnabledDMAReq_RX
+ * @param SPIx SPI Instance
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_I2S_IsEnabledDMAReq_RX(SPI_TypeDef *SPIx)
+{
+ return LL_SPI_IsEnabledDMAReq_RX(SPIx);
+}
+
+/**
+ * @brief Enable DMA Tx
+ * @rmtoll CR2 TXDMAEN LL_I2S_EnableDMAReq_TX
+ * @param SPIx SPI Instance
+ * @retval None
+ */
+__STATIC_INLINE void LL_I2S_EnableDMAReq_TX(SPI_TypeDef *SPIx)
+{
+ LL_SPI_EnableDMAReq_TX(SPIx);
+}
+
+/**
+ * @brief Disable DMA Tx
+ * @rmtoll CR2 TXDMAEN LL_I2S_DisableDMAReq_TX
+ * @param SPIx SPI Instance
+ * @retval None
+ */
+__STATIC_INLINE void LL_I2S_DisableDMAReq_TX(SPI_TypeDef *SPIx)
+{
+ LL_SPI_DisableDMAReq_TX(SPIx);
+}
+
+/**
+ * @brief Check if DMA Tx is enabled
+ * @rmtoll CR2 TXDMAEN LL_I2S_IsEnabledDMAReq_TX
+ * @param SPIx SPI Instance
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_I2S_IsEnabledDMAReq_TX(SPI_TypeDef *SPIx)
+{
+ return LL_SPI_IsEnabledDMAReq_TX(SPIx);
+}
+
+/**
+ * @}
+ */
+
+/** @defgroup I2S_LL_EF_DATA DATA Management
+ * @{
+ */
+
+/**
+ * @brief Read 16-Bits in data register
+ * @rmtoll DR DR LL_I2S_ReceiveData16
+ * @param SPIx SPI Instance
+ * @retval RxData Value between Min_Data=0x0000 and Max_Data=0xFFFF
+ */
+__STATIC_INLINE uint16_t LL_I2S_ReceiveData16(SPI_TypeDef *SPIx)
+{
+ return LL_SPI_ReceiveData16(SPIx);
+}
+
+/**
+ * @brief Write 16-Bits in data register
+ * @rmtoll DR DR LL_I2S_TransmitData16
+ * @param SPIx SPI Instance
+ * @param TxData Value between Min_Data=0x0000 and Max_Data=0xFFFF
+ * @retval None
+ */
+__STATIC_INLINE void LL_I2S_TransmitData16(SPI_TypeDef *SPIx, uint16_t TxData)
+{
+ LL_SPI_TransmitData16(SPIx, TxData);
+}
+
+/**
+ * @}
+ */
+
+#if defined(USE_FULL_LL_DRIVER)
+/** @defgroup I2S_LL_EF_Init Initialization and de-initialization functions
+ * @{
+ */
+
+ErrorStatus LL_I2S_DeInit(SPI_TypeDef *SPIx);
+ErrorStatus LL_I2S_Init(SPI_TypeDef *SPIx, LL_I2S_InitTypeDef *I2S_InitStruct);
+void LL_I2S_StructInit(LL_I2S_InitTypeDef *I2S_InitStruct);
+void LL_I2S_ConfigPrescaler(SPI_TypeDef *SPIx, uint32_t PrescalerLinear, uint32_t PrescalerParity);
+
+/**
+ * @}
+ */
+#endif /* USE_FULL_LL_DRIVER */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+#endif /* SPI_I2S_SUPPORT */
+
+#endif /* defined (SPI1) || defined (SPI2) */
+
+/**
+ * @}
+ */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* STM32F0xx_LL_SPI_H */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_ll_system.h b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_ll_system.h
new file mode 100644
index 0000000..5f101d8
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_ll_system.h
@@ -0,0 +1,1852 @@
+/**
+ ******************************************************************************
+ * @file stm32f0xx_ll_system.h
+ * @author MCD Application Team
+ * @brief Header file of SYSTEM LL module.
+ @verbatim
+ ==============================================================================
+ ##### How to use this driver #####
+ ==============================================================================
+ [..]
+ The LL SYSTEM driver contains a set of generic APIs that can be
+ used by user:
+ (+) Some of the FLASH features need to be handled in the SYSTEM file.
+ (+) Access to DBGCMU registers
+ (+) Access to SYSCFG registers
+
+ @endverbatim
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2016 STMicroelectronics.
+ * All rights reserved.
+ *
+ * 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 __STM32F0xx_LL_SYSTEM_H
+#define __STM32F0xx_LL_SYSTEM_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f0xx.h"
+
+/** @addtogroup STM32F0xx_LL_Driver
+ * @{
+ */
+
+#if defined (FLASH) || defined (SYSCFG) || defined (DBGMCU)
+
+/** @defgroup SYSTEM_LL SYSTEM
+ * @{
+ */
+
+/* Private types -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+
+/* Private constants ---------------------------------------------------------*/
+/** @defgroup SYSTEM_LL_Private_Constants SYSTEM Private Constants
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/* Private macros ------------------------------------------------------------*/
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/** @defgroup SYSTEM_LL_Exported_Constants SYSTEM Exported Constants
+ * @{
+ */
+
+/** @defgroup SYSTEM_LL_EC_REMAP SYSCFG Remap
+* @{
+*/
+#define LL_SYSCFG_REMAP_FLASH (uint32_t)0x00000000U /*!< Main Flash memory mapped at 0x00000000 */
+#define LL_SYSCFG_REMAP_SYSTEMFLASH SYSCFG_CFGR1_MEM_MODE_0 /*!< System Flash memory mapped at 0x00000000 */
+#define LL_SYSCFG_REMAP_SRAM (SYSCFG_CFGR1_MEM_MODE_1 | SYSCFG_CFGR1_MEM_MODE_0) /*!< Embedded SRAM mapped at 0x00000000 */
+/**
+ * @}
+ */
+
+#if defined(SYSCFG_CFGR1_IR_MOD)
+/** @defgroup SYSTEM_LL_EC_IR_MOD SYSCFG IR Modulation
+ * @{
+ */
+#define LL_SYSCFG_IR_MOD_TIM16 (SYSCFG_CFGR1_IR_MOD_0 & SYSCFG_CFGR1_IR_MOD_1) /*!< Timer16 is selected as IR Modulation enveloppe source */
+#define LL_SYSCFG_IR_MOD_USART1 (SYSCFG_CFGR1_IR_MOD_0) /*!< USART1 is selected as IR Modulation enveloppe source */
+#define LL_SYSCFG_IR_MOD_USART4 (SYSCFG_CFGR1_IR_MOD_1) /*!< USART4 is selected as IR Modulation enveloppe source */
+/**
+ * @}
+ */
+
+#endif /* SYSCFG_CFGR1_IR_MOD */
+
+#if defined(SYSCFG_CFGR1_USART1TX_DMA_RMP) || defined(SYSCFG_CFGR1_USART1RX_DMA_RMP) || defined(SYSCFG_CFGR1_USART2_DMA_RMP) || defined(SYSCFG_CFGR1_USART3_DMA_RMP)
+/** @defgroup SYSTEM_LL_EC_USART1TX_RMP SYSCFG USART DMA Remap
+ * @{
+ */
+#if defined (SYSCFG_CFGR1_USART1TX_DMA_RMP)
+#define LL_SYSCFG_USART1TX_RMP_DMA1CH2 ((SYSCFG_CFGR1_USART1TX_DMA_RMP >> 8U) | (uint32_t)0x00000000U) /*!< USART1_TX DMA request mapped on DMA channel 2U */
+#define LL_SYSCFG_USART1TX_RMP_DMA1CH4 ((SYSCFG_CFGR1_USART1TX_DMA_RMP >> 8U) | SYSCFG_CFGR1_USART1TX_DMA_RMP) /*!< USART1_TX DMA request mapped on DMA channel 4U */
+#endif /*SYSCFG_CFGR1_USART1TX_DMA_RMP*/
+#if defined (SYSCFG_CFGR1_USART1RX_DMA_RMP)
+#define LL_SYSCFG_USART1RX_RMP_DMA1CH3 ((SYSCFG_CFGR1_USART1RX_DMA_RMP >> 8U) | (uint32_t)0x00000000U) /*!< USART1_RX DMA request mapped on DMA channel 3U */
+#define LL_SYSCFG_USART1RX_RMP_DMA1CH5 ((SYSCFG_CFGR1_USART1RX_DMA_RMP >> 8U) | SYSCFG_CFGR1_USART1RX_DMA_RMP) /*!< USART1_RX DMA request mapped on DMA channel 5 */
+#endif /*SYSCFG_CFGR1_USART1RX_DMA_RMP*/
+#if defined (SYSCFG_CFGR1_USART2_DMA_RMP)
+#define LL_SYSCFG_USART2_RMP_DMA1CH54 ((SYSCFG_CFGR1_USART2_DMA_RMP >> 8U) | (uint32_t)0x00000000U) /*!< USART2_RX and USART2_TX DMA requests mapped on DMA channel 5 and 4U respectively */
+#define LL_SYSCFG_USART2_RMP_DMA1CH67 ((SYSCFG_CFGR1_USART2_DMA_RMP >> 8U) | SYSCFG_CFGR1_USART2_DMA_RMP) /*!< USART2_RX and USART2_TX DMA requests mapped on DMA channel 6 and 7 respectively */
+#endif /*SYSCFG_CFGR1_USART2_DMA_RMP*/
+#if defined (SYSCFG_CFGR1_USART3_DMA_RMP)
+#define LL_SYSCFG_USART3_RMP_DMA1CH67 ((SYSCFG_CFGR1_USART3_DMA_RMP >> 8U) | (uint32_t)0x00000000U) /*!< USART3_RX and USART3_TX DMA requests mapped on DMA channel 6 and 7 respectively */
+#define LL_SYSCFG_USART3_RMP_DMA1CH32 ((SYSCFG_CFGR1_USART3_DMA_RMP >> 8U) | SYSCFG_CFGR1_USART3_DMA_RMP) /*!< USART3_RX and USART3_TX DMA requests mapped on DMA channel 3U and 2U respectively */
+#endif /* SYSCFG_CFGR1_USART3_DMA_RMP */
+/**
+ * @}
+ */
+#endif /* SYSCFG_CFGR1_USART1TX_DMA_RMP || SYSCFG_CFGR1_USART1RX_DMA_RMP || SYSCFG_CFGR1_USART2_DMA_RMP || SYSCFG_CFGR1_USART3_DMA_RMP */
+
+#if defined (SYSCFG_CFGR1_SPI2_DMA_RMP)
+/** @defgroup SYSTEM_LL_EC_SPI2_RMP_DMA1 SYSCFG SPI2 DMA Remap
+ * @{
+ */
+#define LL_SYSCFG_SPI2_RMP_DMA1_CH45 (uint32_t)0x00000000U /*!< SPI2_RX and SPI2_TX DMA requests mapped on DMA channel 4U and 5 respectively */
+#define LL_SYSCFG_SPI2_RMP_DMA1_CH67 SYSCFG_CFGR1_SPI2_DMA_RMP /*!< SPI2_RX and SPI2_TX DMA requests mapped on DMA channel 6 and 7 respectively */
+/**
+ * @}
+ */
+
+#endif /*SYSCFG_CFGR1_SPI2_DMA_RMP*/
+
+#if defined (SYSCFG_CFGR1_I2C1_DMA_RMP)
+/** @defgroup SYSTEM_LL_EC_I2C1_RMP_DMA1 SYSCFG I2C1 DMA Remap
+ * @{
+ */
+#define LL_SYSCFG_I2C1_RMP_DMA1_CH32 (uint32_t)0x00000000U /*!< I2C1_RX and I2C1_TX DMA requests mapped on DMA channel 3U and 2U respectively */
+#define LL_SYSCFG_I2C1_RMP_DMA1_CH76 SYSCFG_CFGR1_I2C1_DMA_RMP /*!< I2C1_RX and I2C1_TX DMA requests mapped on DMA channel 7 and 6 respectively */
+/**
+ * @}
+ */
+
+#endif /*SYSCFG_CFGR1_I2C1_DMA_RMP*/
+
+#if defined(SYSCFG_CFGR1_ADC_DMA_RMP)
+/** @defgroup SYSTEM_LL_EC_ADC1_RMP_DMA1 SYSCFG ADC1 DMA Remap
+ * @{
+ */
+#define LL_SYSCFG_ADC1_RMP_DMA1_CH1 (uint32_t)0x00000000U /*!< ADC DMA request mapped on DMA channel 1U */
+#define LL_SYSCFG_ADC1_RMP_DMA1_CH2 SYSCFG_CFGR1_ADC_DMA_RMP /*!< ADC DMA request mapped on DMA channel 2U */
+/**
+ * @}
+ */
+
+#endif /* SYSCFG_CFGR1_ADC_DMA_RMP */
+
+#if defined(SYSCFG_CFGR1_TIM16_DMA_RMP) || defined(SYSCFG_CFGR1_TIM17_DMA_RMP) || defined(SYSCFG_CFGR1_TIM1_DMA_RMP) || defined(SYSCFG_CFGR1_TIM2_DMA_RMP) || defined(SYSCFG_CFGR1_TIM3_DMA_RMP)
+/** @defgroup SYSTEM_LL_EC_TIM16_RMP_DMA1 SYSCFG TIM DMA Remap
+ * @{
+ */
+#if defined(SYSCFG_CFGR1_TIM16_DMA_RMP)
+#if defined (SYSCFG_CFGR1_TIM16_DMA_RMP2)
+#define LL_SYSCFG_TIM16_RMP_DMA1_CH3 (((SYSCFG_CFGR1_TIM16_DMA_RMP | SYSCFG_CFGR1_TIM16_DMA_RMP2) >> 8U) | (uint32_t)0x00000000U) /*!< TIM16_CH1 and TIM16_UP DMA requests mapped on DMA channel 3 */
+#define LL_SYSCFG_TIM16_RMP_DMA1_CH4 (((SYSCFG_CFGR1_TIM16_DMA_RMP | SYSCFG_CFGR1_TIM16_DMA_RMP2) >> 8U) | SYSCFG_CFGR1_TIM16_DMA_RMP) /*!< TIM16_CH1 and TIM16_UP DMA requests mapped on DMA channel 4 */
+#define LL_SYSCFG_TIM16_RMP_DMA1_CH6 ((SYSCFG_CFGR1_TIM16_DMA_RMP2 >> 8U) | SYSCFG_CFGR1_TIM16_DMA_RMP2) /*!< TIM16_CH1 and TIM16_UP DMA requests mapped on DMA channel 6 */
+#else
+#define LL_SYSCFG_TIM16_RMP_DMA1_CH3 ((SYSCFG_CFGR1_TIM16_DMA_RMP >> 8U) | (uint32_t)0x00000000U) /*!< TIM16_CH1 and TIM16_UP DMA requests mapped on DMA channel 3 */
+#define LL_SYSCFG_TIM16_RMP_DMA1_CH4 ((SYSCFG_CFGR1_TIM16_DMA_RMP >> 8U) | SYSCFG_CFGR1_TIM16_DMA_RMP) /*!< TIM16_CH1 and TIM16_UP DMA requests mapped on DMA channel 4 */
+#endif /* SYSCFG_CFGR1_TIM16_DMA_RMP2 */
+#endif /* SYSCFG_CFGR1_TIM16_DMA_RMP */
+#if defined(SYSCFG_CFGR1_TIM17_DMA_RMP)
+#if defined (SYSCFG_CFGR1_TIM17_DMA_RMP2)
+#define LL_SYSCFG_TIM17_RMP_DMA1_CH1 (((SYSCFG_CFGR1_TIM17_DMA_RMP | SYSCFG_CFGR1_TIM17_DMA_RMP2) >> 8U) | (uint32_t)0x00000000U) /*!< TIM17_CH1 and TIM17_UP DMA requests mapped on DMA channel 1 */
+#define LL_SYSCFG_TIM17_RMP_DMA1_CH2 (((SYSCFG_CFGR1_TIM17_DMA_RMP | SYSCFG_CFGR1_TIM17_DMA_RMP2) >> 8U) | SYSCFG_CFGR1_TIM17_DMA_RMP) /*!< TIM17_CH1 and TIM17_UP DMA requests mapped on DMA channel 2 */
+#define LL_SYSCFG_TIM17_RMP_DMA1_CH7 ((SYSCFG_CFGR1_TIM17_DMA_RMP2 >> 8U) | SYSCFG_CFGR1_TIM17_DMA_RMP2) /*!< TIM17_CH1 and TIM17_UP DMA requests mapped on DMA channel 7 */
+#else
+#define LL_SYSCFG_TIM17_RMP_DMA1_CH1 ((SYSCFG_CFGR1_TIM17_DMA_RMP >> 8U) | (uint32_t)0x00000000U) /*!< TIM17_CH1 and TIM17_UP DMA requests mapped on DMA channel 1 */
+#define LL_SYSCFG_TIM17_RMP_DMA1_CH2 ((SYSCFG_CFGR1_TIM17_DMA_RMP >> 8U) | SYSCFG_CFGR1_TIM17_DMA_RMP) /*!< TIM17_CH1 and TIM17_UP DMA requests mapped on DMA channel 2 */
+#endif /* SYSCFG_CFGR1_TIM17_DMA_RMP2 */
+#endif /* SYSCFG_CFGR1_TIM17_DMA_RMP */
+#if defined (SYSCFG_CFGR1_TIM1_DMA_RMP)
+#define LL_SYSCFG_TIM1_RMP_DMA1_CH234 ((SYSCFG_CFGR1_TIM1_DMA_RMP >> 8U) | (uint32_t)0x00000000U) /*!< TIM1_CH1, TIM1_CH2 and TIM1_CH3 DMA requests mapped on DMAchannel 2, 3 and 4 respectively */
+#define LL_SYSCFG_TIM1_RMP_DMA1_CH6 ((SYSCFG_CFGR1_TIM1_DMA_RMP >> 8U) | SYSCFG_CFGR1_TIM1_DMA_RMP) /*!< TIM1_CH1, TIM1_CH2 and TIM1_CH3 DMA requests mapped on DMA channel 6 */
+#endif /*SYSCFG_CFGR1_TIM1_DMA_RMP*/
+#if defined (SYSCFG_CFGR1_TIM2_DMA_RMP)
+#define LL_SYSCFG_TIM2_RMP_DMA1_CH34 ((SYSCFG_CFGR1_TIM2_DMA_RMP >> 8U) | (uint32_t)0x00000000U) /*!< TIM2_CH2 and TIM2_CH4 DMA requests mapped on DMA channel 3 and 4 respectively */
+#define LL_SYSCFG_TIM2_RMP_DMA1_CH7 ((SYSCFG_CFGR1_TIM2_DMA_RMP >> 8U) | SYSCFG_CFGR1_TIM2_DMA_RMP) /*!< TIM2_CH2 and TIM2_CH4 DMA requests mapped on DMA channel 7 */
+#endif /*SYSCFG_CFGR1_TIM2_DMA_RMP*/
+#if defined (SYSCFG_CFGR1_TIM3_DMA_RMP)
+#define LL_SYSCFG_TIM3_RMP_DMA1_CH4 ((SYSCFG_CFGR1_TIM3_DMA_RMP >> 8U) | (uint32_t)0x00000000U) /*!< TIM3_CH1 and TIM3_TRIG DMA requests mapped on DMA channel 4 */
+#define LL_SYSCFG_TIM3_RMP_DMA1_CH6 ((SYSCFG_CFGR1_TIM3_DMA_RMP >> 8U) | SYSCFG_CFGR1_TIM3_DMA_RMP) /*!< TIM3_CH1 and TIM3_TRIG DMA requests mapped on DMA channel 6 */
+#endif /*SYSCFG_CFGR1_TIM3_DMA_RMP*/
+/**
+ * @}
+ */
+
+#endif /* SYSCFG_CFGR1_TIM16_DMA_RMP || SYSCFG_CFGR1_TIM17_DMA_RMP || SYSCFG_CFGR1_TIM1_DMA_RMP || SYSCFG_CFGR1_TIM2_DMA_RMP || SYSCFG_CFGR1_TIM3_DMA_RMP */
+
+/** @defgroup SYSTEM_LL_EC_I2C_FASTMODEPLUS SYSCFG I2C FASTMODEPLUS
+ * @{
+ */
+#define LL_SYSCFG_I2C_FASTMODEPLUS_PB6 SYSCFG_CFGR1_I2C_FMP_PB6 /*!< I2C PB6 Fast mode plus */
+#define LL_SYSCFG_I2C_FASTMODEPLUS_PB7 SYSCFG_CFGR1_I2C_FMP_PB7 /*!< I2C PB7 Fast mode plus */
+#define LL_SYSCFG_I2C_FASTMODEPLUS_PB8 SYSCFG_CFGR1_I2C_FMP_PB8 /*!< I2C PB8 Fast mode plus */
+#define LL_SYSCFG_I2C_FASTMODEPLUS_PB9 SYSCFG_CFGR1_I2C_FMP_PB9 /*!< I2C PB9 Fast mode plus */
+#if defined(SYSCFG_CFGR1_I2C_FMP_I2C1)
+#define LL_SYSCFG_I2C_FASTMODEPLUS_I2C1 SYSCFG_CFGR1_I2C_FMP_I2C1 /*!< Enable Fast Mode Plus on PB10, PB11, PF6 and PF7 */
+#endif /*SYSCFG_CFGR1_I2C_FMP_I2C1*/
+#if defined(SYSCFG_CFGR1_I2C_FMP_I2C2)
+#define LL_SYSCFG_I2C_FASTMODEPLUS_I2C2 SYSCFG_CFGR1_I2C_FMP_I2C2 /*!< Enable I2C2 Fast mode plus */
+#endif /*SYSCFG_CFGR1_I2C_FMP_I2C2*/
+#if defined(SYSCFG_CFGR1_I2C_FMP_PA9)
+#define LL_SYSCFG_I2C_FASTMODEPLUS_PA9 SYSCFG_CFGR1_I2C_FMP_PA9 /*!< Enable Fast Mode Plus on PA9 */
+#endif /*SYSCFG_CFGR1_I2C_FMP_PA9*/
+#if defined(SYSCFG_CFGR1_I2C_FMP_PA10)
+#define LL_SYSCFG_I2C_FASTMODEPLUS_PA10 SYSCFG_CFGR1_I2C_FMP_PA10 /*!< Enable Fast Mode Plus on PA10 */
+#endif /*SYSCFG_CFGR1_I2C_FMP_PA10*/
+/**
+ * @}
+ */
+
+/** @defgroup SYSTEM_LL_EC_EXTI_PORT SYSCFG EXTI PORT
+ * @{
+ */
+#define LL_SYSCFG_EXTI_PORTA (uint32_t)0U /*!< EXTI PORT A */
+#define LL_SYSCFG_EXTI_PORTB (uint32_t)1U /*!< EXTI PORT B */
+#define LL_SYSCFG_EXTI_PORTC (uint32_t)2U /*!< EXTI PORT C */
+#if defined(GPIOD_BASE)
+#define LL_SYSCFG_EXTI_PORTD (uint32_t)3U /*!< EXTI PORT D */
+#endif /*GPIOD_BASE*/
+#if defined(GPIOE_BASE)
+#define LL_SYSCFG_EXTI_PORTE (uint32_t)4U /*!< EXTI PORT E */
+#endif /*GPIOE_BASE*/
+#define LL_SYSCFG_EXTI_PORTF (uint32_t)5U /*!< EXTI PORT F */
+/**
+ * @}
+ */
+
+/** @defgroup SYSTEM_LL_EC_EXTI_LINE SYSCFG EXTI LINE
+ * @{
+ */
+#define LL_SYSCFG_EXTI_LINE0 (uint32_t)(0U << 16U | 0U) /*!< EXTI_POSITION_0 | EXTICR[0] */
+#define LL_SYSCFG_EXTI_LINE1 (uint32_t)(4U << 16U | 0U) /*!< EXTI_POSITION_4 | EXTICR[0] */
+#define LL_SYSCFG_EXTI_LINE2 (uint32_t)(8U << 16U | 0U) /*!< EXTI_POSITION_8 | EXTICR[0] */
+#define LL_SYSCFG_EXTI_LINE3 (uint32_t)(12U << 16U | 0U) /*!< EXTI_POSITION_12 | EXTICR[0] */
+#define LL_SYSCFG_EXTI_LINE4 (uint32_t)(0U << 16U | 1U) /*!< EXTI_POSITION_0 | EXTICR[1] */
+#define LL_SYSCFG_EXTI_LINE5 (uint32_t)(4U << 16U | 1U) /*!< EXTI_POSITION_4 | EXTICR[1] */
+#define LL_SYSCFG_EXTI_LINE6 (uint32_t)(8U << 16U | 1U) /*!< EXTI_POSITION_8 | EXTICR[1] */
+#define LL_SYSCFG_EXTI_LINE7 (uint32_t)(12U << 16U | 1U) /*!< EXTI_POSITION_12 | EXTICR[1] */
+#define LL_SYSCFG_EXTI_LINE8 (uint32_t)(0U << 16U | 2U) /*!< EXTI_POSITION_0 | EXTICR[2] */
+#define LL_SYSCFG_EXTI_LINE9 (uint32_t)(4U << 16U | 2U) /*!< EXTI_POSITION_4 | EXTICR[2] */
+#define LL_SYSCFG_EXTI_LINE10 (uint32_t)(8U << 16U | 2U) /*!< EXTI_POSITION_8 | EXTICR[2] */
+#define LL_SYSCFG_EXTI_LINE11 (uint32_t)(12U << 16U | 2U) /*!< EXTI_POSITION_12 | EXTICR[2] */
+#define LL_SYSCFG_EXTI_LINE12 (uint32_t)(0U << 16U | 3U) /*!< EXTI_POSITION_0 | EXTICR[3] */
+#define LL_SYSCFG_EXTI_LINE13 (uint32_t)(4U << 16U | 3U) /*!< EXTI_POSITION_4 | EXTICR[3] */
+#define LL_SYSCFG_EXTI_LINE14 (uint32_t)(8U << 16U | 3U) /*!< EXTI_POSITION_8 | EXTICR[3] */
+#define LL_SYSCFG_EXTI_LINE15 (uint32_t)(12U << 16U | 3U) /*!< EXTI_POSITION_12 | EXTICR[3] */
+/**
+ * @}
+ */
+
+/** @defgroup SYSTEM_LL_EC_TIMBREAK SYSCFG TIMER BREAK
+ * @{
+ */
+#if defined(SYSCFG_CFGR2_PVD_LOCK)
+#define LL_SYSCFG_TIMBREAK_PVD SYSCFG_CFGR2_PVD_LOCK /*!< Enables and locks the PVD connection
+ with TIM1/15/16U/17 Break Input and also
+ the PVDE and PLS bits of the Power Control Interface */
+#endif /*SYSCFG_CFGR2_PVD_LOCK*/
+#define LL_SYSCFG_TIMBREAK_SRAM_PARITY SYSCFG_CFGR2_SRAM_PARITY_LOCK /*!< Enables and locks the SRAM_PARITY error signal
+ with Break Input of TIM1/15/16/17 */
+#define LL_SYSCFG_TIMBREAK_LOCKUP SYSCFG_CFGR2_LOCKUP_LOCK /*!< Enables and locks the LOCKUP (Hardfault) output of
+ CortexM0 with Break Input of TIM1/15/16/17 */
+/**
+ * @}
+ */
+
+/** @defgroup SYSTEM_LL_EC_APB1_GRP1_STOP_IP DBGMCU APB1 GRP1 STOP IP
+ * @{
+ */
+#if defined(DBGMCU_APB1_FZ_DBG_TIM2_STOP)
+#define LL_DBGMCU_APB1_GRP1_TIM2_STOP DBGMCU_APB1_FZ_DBG_TIM2_STOP /*!< TIM2 counter stopped when core is halted */
+#endif /*DBGMCU_APB1_FZ_DBG_TIM2_STOP*/
+#define LL_DBGMCU_APB1_GRP1_TIM3_STOP DBGMCU_APB1_FZ_DBG_TIM3_STOP /*!< TIM3 counter stopped when core is halted */
+#if defined(DBGMCU_APB1_FZ_DBG_TIM6_STOP)
+#define LL_DBGMCU_APB1_GRP1_TIM6_STOP DBGMCU_APB1_FZ_DBG_TIM6_STOP /*!< TIM6 counter stopped when core is halted */
+#endif /*DBGMCU_APB1_FZ_DBG_TIM6_STOP*/
+#if defined(DBGMCU_APB1_FZ_DBG_TIM7_STOP)
+#define LL_DBGMCU_APB1_GRP1_TIM7_STOP DBGMCU_APB1_FZ_DBG_TIM7_STOP /*!< TIM7 counter stopped when core is halted */
+#endif /*DBGMCU_APB1_FZ_DBG_TIM7_STOP*/
+#define LL_DBGMCU_APB1_GRP1_TIM14_STOP DBGMCU_APB1_FZ_DBG_TIM14_STOP /*!< TIM14 counter stopped when core is halted */
+#define LL_DBGMCU_APB1_GRP1_RTC_STOP DBGMCU_APB1_FZ_DBG_RTC_STOP /*!< RTC Calendar frozen when core is halted */
+#define LL_DBGMCU_APB1_GRP1_WWDG_STOP DBGMCU_APB1_FZ_DBG_WWDG_STOP /*!< Debug Window Watchdog stopped when Core is halted */
+#define LL_DBGMCU_APB1_GRP1_IWDG_STOP DBGMCU_APB1_FZ_DBG_IWDG_STOP /*!< Debug Independent Watchdog stopped when Core is halted */
+#define LL_DBGMCU_APB1_GRP1_I2C1_STOP DBGMCU_APB1_FZ_DBG_I2C1_SMBUS_TIMEOUT /*!< I2C1 SMBUS timeout mode stopped when Core is halted */
+#if defined(DBGMCU_APB1_FZ_DBG_CAN_STOP)
+#define LL_DBGMCU_APB1_GRP1_CAN_STOP DBGMCU_APB1_FZ_DBG_CAN_STOP /*!< CAN debug stopped when Core is halted */
+#endif /*DBGMCU_APB1_FZ_DBG_CAN_STOP*/
+/**
+ * @}
+ */
+
+/** @defgroup SYSTEM_LL_EC_APB1 GRP2_STOP_IP DBGMCU APB1 GRP2 STOP IP
+ * @{
+ */
+#define LL_DBGMCU_APB1_GRP2_TIM1_STOP DBGMCU_APB2_FZ_DBG_TIM1_STOP /*!< TIM1 counter stopped when core is halted */
+#if defined(DBGMCU_APB2_FZ_DBG_TIM15_STOP)
+#define LL_DBGMCU_APB1_GRP2_TIM15_STOP DBGMCU_APB2_FZ_DBG_TIM15_STOP /*!< TIM15 counter stopped when core is halted */
+#endif /*DBGMCU_APB2_FZ_DBG_TIM15_STOP*/
+#define LL_DBGMCU_APB1_GRP2_TIM16_STOP DBGMCU_APB2_FZ_DBG_TIM16_STOP /*!< TIM16 counter stopped when core is halted */
+#define LL_DBGMCU_APB1_GRP2_TIM17_STOP DBGMCU_APB2_FZ_DBG_TIM17_STOP /*!< TIM17 counter stopped when core is halted */
+/**
+ * @}
+ */
+
+/** @defgroup SYSTEM_LL_EC_LATENCY FLASH LATENCY
+ * @{
+ */
+#define LL_FLASH_LATENCY_0 0x00000000U /*!< FLASH Zero Latency cycle */
+#define LL_FLASH_LATENCY_1 FLASH_ACR_LATENCY /*!< FLASH One Latency cycle */
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/* Exported macro ------------------------------------------------------------*/
+
+/* Exported functions --------------------------------------------------------*/
+/** @defgroup SYSTEM_LL_Exported_Functions SYSTEM Exported Functions
+ * @{
+ */
+
+/** @defgroup SYSTEM_LL_EF_SYSCFG SYSCFG
+ * @{
+ */
+
+/**
+ * @brief Set memory mapping at address 0x00000000
+ * @rmtoll SYSCFG_CFGR1 MEM_MODE LL_SYSCFG_SetRemapMemory
+ * @param Memory This parameter can be one of the following values:
+ * @arg @ref LL_SYSCFG_REMAP_FLASH
+ * @arg @ref LL_SYSCFG_REMAP_SYSTEMFLASH
+ * @arg @ref LL_SYSCFG_REMAP_SRAM
+ * @retval None
+ */
+__STATIC_INLINE void LL_SYSCFG_SetRemapMemory(uint32_t Memory)
+{
+ MODIFY_REG(SYSCFG->CFGR1, SYSCFG_CFGR1_MEM_MODE, Memory);
+}
+
+/**
+ * @brief Get memory mapping at address 0x00000000
+ * @rmtoll SYSCFG_CFGR1 MEM_MODE LL_SYSCFG_GetRemapMemory
+ * @retval Returned value can be one of the following values:
+ * @arg @ref LL_SYSCFG_REMAP_FLASH
+ * @arg @ref LL_SYSCFG_REMAP_SYSTEMFLASH
+ * @arg @ref LL_SYSCFG_REMAP_SRAM
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_GetRemapMemory(void)
+{
+ return (uint32_t)(READ_BIT(SYSCFG->CFGR1, SYSCFG_CFGR1_MEM_MODE));
+}
+
+#if defined(SYSCFG_CFGR1_IR_MOD)
+/**
+ * @brief Set IR Modulation Envelope signal source.
+ * @rmtoll SYSCFG_CFGR1 IR_MOD LL_SYSCFG_SetIRModEnvelopeSignal
+ * @param Source This parameter can be one of the following values:
+ * @arg @ref LL_SYSCFG_IR_MOD_TIM16
+ * @arg @ref LL_SYSCFG_IR_MOD_USART1
+ * @arg @ref LL_SYSCFG_IR_MOD_USART4
+ * @retval None
+ */
+__STATIC_INLINE void LL_SYSCFG_SetIRModEnvelopeSignal(uint32_t Source)
+{
+ MODIFY_REG(SYSCFG->CFGR1, SYSCFG_CFGR1_IR_MOD, Source);
+}
+
+/**
+ * @brief Get IR Modulation Envelope signal source.
+ * @rmtoll SYSCFG_CFGR1 IR_MOD LL_SYSCFG_GetIRModEnvelopeSignal
+ * @retval Returned value can be one of the following values:
+ * @arg @ref LL_SYSCFG_IR_MOD_TIM16
+ * @arg @ref LL_SYSCFG_IR_MOD_USART1
+ * @arg @ref LL_SYSCFG_IR_MOD_USART4
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_GetIRModEnvelopeSignal(void)
+{
+ return (uint32_t)(READ_BIT(SYSCFG->CFGR1, SYSCFG_CFGR1_IR_MOD));
+}
+#endif /* SYSCFG_CFGR1_IR_MOD */
+
+#if defined(SYSCFG_CFGR1_USART1TX_DMA_RMP) || defined(SYSCFG_CFGR1_USART1RX_DMA_RMP) || defined(SYSCFG_CFGR1_USART2_DMA_RMP) || defined(SYSCFG_CFGR1_USART3_DMA_RMP)
+/**
+ * @brief Set DMA request remapping bits for USART
+ * @rmtoll SYSCFG_CFGR1 USART1TX_DMA_RMP LL_SYSCFG_SetRemapDMA_USART\n
+ * SYSCFG_CFGR1 USART1RX_DMA_RMP LL_SYSCFG_SetRemapDMA_USART\n
+ * SYSCFG_CFGR1 USART2_DMA_RMP LL_SYSCFG_SetRemapDMA_USART\n
+ * SYSCFG_CFGR1 USART3_DMA_RMP LL_SYSCFG_SetRemapDMA_USART
+ * @param Remap This parameter can be one of the following values:
+ * @arg @ref LL_SYSCFG_USART1TX_RMP_DMA1CH2 (*)
+ * @arg @ref LL_SYSCFG_USART1TX_RMP_DMA1CH4 (*)
+ * @arg @ref LL_SYSCFG_USART1RX_RMP_DMA1CH3 (*)
+ * @arg @ref LL_SYSCFG_USART1RX_RMP_DMA1CH5 (*)
+ * @arg @ref LL_SYSCFG_USART2_RMP_DMA1CH54 (*)
+ * @arg @ref LL_SYSCFG_USART2_RMP_DMA1CH67 (*)
+ * @arg @ref LL_SYSCFG_USART3_RMP_DMA1CH67 (*)
+ * @arg @ref LL_SYSCFG_USART3_RMP_DMA1CH32 (*)
+ *
+ * (*) value not defined in all devices.
+ * @retval None
+ */
+__STATIC_INLINE void LL_SYSCFG_SetRemapDMA_USART(uint32_t Remap)
+{
+ MODIFY_REG(SYSCFG->CFGR1, (Remap & 0x00FF00FFU) << 8U, (Remap & 0xFF00FF00U));
+}
+#endif /* SYSCFG_CFGR1_USART1TX_DMA_RMP || SYSCFG_CFGR1_USART1RX_DMA_RMP || SYSCFG_CFGR1_USART2_DMA_RMP || SYSCFG_CFGR1_USART3_DMA_RMP */
+
+#if defined(SYSCFG_CFGR1_SPI2_DMA_RMP)
+/**
+ * @brief Set DMA request remapping bits for SPI
+ * @rmtoll SYSCFG_CFGR1 SPI2_DMA_RMP LL_SYSCFG_SetRemapDMA_SPI
+ * @param Remap This parameter can be one of the following values:
+ * @arg @ref LL_SYSCFG_SPI2_RMP_DMA1_CH45
+ * @arg @ref LL_SYSCFG_SPI2_RMP_DMA1_CH67
+ * @retval None
+ */
+__STATIC_INLINE void LL_SYSCFG_SetRemapDMA_SPI(uint32_t Remap)
+{
+ MODIFY_REG(SYSCFG->CFGR1, SYSCFG_CFGR1_SPI2_DMA_RMP, Remap);
+}
+#endif /* SYSCFG_CFGR1_SPI2_DMA_RMP */
+
+#if defined(SYSCFG_CFGR1_I2C1_DMA_RMP)
+/**
+ * @brief Set DMA request remapping bits for I2C
+ * @rmtoll SYSCFG_CFGR1 I2C1_DMA_RMP LL_SYSCFG_SetRemapDMA_I2C
+ * @param Remap This parameter can be one of the following values:
+ * @arg @ref LL_SYSCFG_I2C1_RMP_DMA1_CH32
+ * @arg @ref LL_SYSCFG_I2C1_RMP_DMA1_CH76
+ * @retval None
+ */
+__STATIC_INLINE void LL_SYSCFG_SetRemapDMA_I2C(uint32_t Remap)
+{
+ MODIFY_REG(SYSCFG->CFGR1, SYSCFG_CFGR1_I2C1_DMA_RMP, Remap);
+}
+#endif /* SYSCFG_CFGR1_I2C1_DMA_RMP */
+
+#if defined(SYSCFG_CFGR1_ADC_DMA_RMP)
+/**
+ * @brief Set DMA request remapping bits for ADC
+ * @rmtoll SYSCFG_CFGR1 ADC_DMA_RMP LL_SYSCFG_SetRemapDMA_ADC
+ * @param Remap This parameter can be one of the following values:
+ * @arg @ref LL_SYSCFG_ADC1_RMP_DMA1_CH1
+ * @arg @ref LL_SYSCFG_ADC1_RMP_DMA1_CH2
+ * @retval None
+ */
+__STATIC_INLINE void LL_SYSCFG_SetRemapDMA_ADC(uint32_t Remap)
+{
+ MODIFY_REG(SYSCFG->CFGR1, SYSCFG_CFGR1_ADC_DMA_RMP, Remap);
+}
+#endif /* SYSCFG_CFGR1_ADC_DMA_RMP */
+
+#if defined(SYSCFG_CFGR1_TIM16_DMA_RMP) || defined(SYSCFG_CFGR1_TIM17_DMA_RMP) || defined(SYSCFG_CFGR1_TIM1_DMA_RMP) || defined(SYSCFG_CFGR1_TIM2_DMA_RMP) || defined(SYSCFG_CFGR1_TIM3_DMA_RMP)
+/**
+ * @brief Set DMA request remapping bits for TIM
+ * @rmtoll SYSCFG_CFGR1 TIM16_DMA_RMP LL_SYSCFG_SetRemapDMA_TIM\n
+ * SYSCFG_CFGR1 TIM17_DMA_RMP LL_SYSCFG_SetRemapDMA_TIM\n
+ * SYSCFG_CFGR1 TIM16_DMA_RMP2 LL_SYSCFG_SetRemapDMA_TIM\n
+ * SYSCFG_CFGR1 TIM17_DMA_RMP2 LL_SYSCFG_SetRemapDMA_TIM\n
+ * SYSCFG_CFGR1 TIM1_DMA_RMP LL_SYSCFG_SetRemapDMA_TIM\n
+ * SYSCFG_CFGR1 TIM2_DMA_RMP LL_SYSCFG_SetRemapDMA_TIM\n
+ * SYSCFG_CFGR1 TIM3_DMA_RMP LL_SYSCFG_SetRemapDMA_TIM
+ * @param Remap This parameter can be one of the following values:
+ * @arg @ref LL_SYSCFG_TIM16_RMP_DMA1_CH3 (*)
+ * @arg @ref LL_SYSCFG_TIM16_RMP_DMA1_CH4 (*)
+ * @arg @ref LL_SYSCFG_TIM16_RMP_DMA1_CH6 (*)
+ * @arg @ref LL_SYSCFG_TIM17_RMP_DMA1_CH1 (*)
+ * @arg @ref LL_SYSCFG_TIM17_RMP_DMA1_CH2 (*)
+ * @arg @ref LL_SYSCFG_TIM17_RMP_DMA1_CH7 (*)
+ * @arg @ref LL_SYSCFG_TIM1_RMP_DMA1_CH234 (*)
+ * @arg @ref LL_SYSCFG_TIM1_RMP_DMA1_CH6 (*)
+ * @arg @ref LL_SYSCFG_TIM2_RMP_DMA1_CH34 (*)
+ * @arg @ref LL_SYSCFG_TIM2_RMP_DMA1_CH7 (*)
+ * @arg @ref LL_SYSCFG_TIM3_RMP_DMA1_CH4 (*)
+ * @arg @ref LL_SYSCFG_TIM3_RMP_DMA1_CH6 (*)
+ *
+ * (*) value not defined in all devices.
+ * @retval None
+ */
+__STATIC_INLINE void LL_SYSCFG_SetRemapDMA_TIM(uint32_t Remap)
+{
+ MODIFY_REG(SYSCFG->CFGR1, (Remap & 0x00FF00FFU) << 8U, (Remap & 0xFF00FF00U));
+}
+#endif /* SYSCFG_CFGR1_TIM16_DMA_RMP || SYSCFG_CFGR1_TIM17_DMA_RMP || SYSCFG_CFGR1_TIM1_DMA_RMP || SYSCFG_CFGR1_TIM2_DMA_RMP || SYSCFG_CFGR1_TIM3_DMA_RMP */
+
+#if defined(SYSCFG_CFGR1_PA11_PA12_RMP)
+/**
+ * @brief Enable PIN pair PA11/12 mapped instead of PA9/10 (control the mapping of either
+ * PA9/10 or PA11/12 pin pair on small pin-count packages)
+ * @rmtoll SYSCFG_CFGR1 PA11_PA12_RMP LL_SYSCFG_EnablePinRemap
+ * @retval None
+ */
+__STATIC_INLINE void LL_SYSCFG_EnablePinRemap(void)
+{
+ SET_BIT(SYSCFG->CFGR1, SYSCFG_CFGR1_PA11_PA12_RMP);
+}
+
+/**
+ * @brief Disable PIN pair PA11/12 mapped instead of PA9/10 (control the mapping of either
+ * PA9/10 or PA11/12 pin pair on small pin-count packages)
+ * @rmtoll SYSCFG_CFGR1 PA11_PA12_RMP LL_SYSCFG_DisablePinRemap
+ * @retval None
+ */
+__STATIC_INLINE void LL_SYSCFG_DisablePinRemap(void)
+{
+ CLEAR_BIT(SYSCFG->CFGR1, SYSCFG_CFGR1_PA11_PA12_RMP);
+}
+#endif /* SYSCFG_CFGR1_PA11_PA12_RMP */
+
+/**
+ * @brief Enable the I2C fast mode plus driving capability.
+ * @rmtoll SYSCFG_CFGR1 I2C_FMP_PB6 LL_SYSCFG_EnableFastModePlus\n
+ * SYSCFG_CFGR1 I2C_FMP_PB7 LL_SYSCFG_EnableFastModePlus\n
+ * SYSCFG_CFGR1 I2C_FMP_PB8 LL_SYSCFG_EnableFastModePlus\n
+ * SYSCFG_CFGR1 I2C_FMP_PB9 LL_SYSCFG_EnableFastModePlus\n
+ * SYSCFG_CFGR1 I2C_FMP_I2C1 LL_SYSCFG_EnableFastModePlus\n
+ * SYSCFG_CFGR1 I2C_FMP_I2C2 LL_SYSCFG_EnableFastModePlus\n
+ * SYSCFG_CFGR1 I2C_FMP_PA9 LL_SYSCFG_EnableFastModePlus\n
+ * SYSCFG_CFGR1 I2C_FMP_PA10 LL_SYSCFG_EnableFastModePlus
+ * @param ConfigFastModePlus This parameter can be a combination of the following values:
+ * @arg @ref LL_SYSCFG_I2C_FASTMODEPLUS_PB6
+ * @arg @ref LL_SYSCFG_I2C_FASTMODEPLUS_PB7
+ * @arg @ref LL_SYSCFG_I2C_FASTMODEPLUS_PB8
+ * @arg @ref LL_SYSCFG_I2C_FASTMODEPLUS_PB9
+ * @arg @ref LL_SYSCFG_I2C_FASTMODEPLUS_I2C1 (*)
+ * @arg @ref LL_SYSCFG_I2C_FASTMODEPLUS_I2C2 (*)
+ * @arg @ref LL_SYSCFG_I2C_FASTMODEPLUS_PA9 (*)
+ * @arg @ref LL_SYSCFG_I2C_FASTMODEPLUS_PA10 (*)
+ *
+ * (*) value not defined in all devices
+ * @retval None
+ */
+__STATIC_INLINE void LL_SYSCFG_EnableFastModePlus(uint32_t ConfigFastModePlus)
+{
+ SET_BIT(SYSCFG->CFGR1, ConfigFastModePlus);
+}
+
+/**
+ * @brief Disable the I2C fast mode plus driving capability.
+ * @rmtoll SYSCFG_CFGR1 I2C_FMP_PB6 LL_SYSCFG_DisableFastModePlus\n
+ * SYSCFG_CFGR1 I2C_FMP_PB7 LL_SYSCFG_DisableFastModePlus\n
+ * SYSCFG_CFGR1 I2C_FMP_PB8 LL_SYSCFG_DisableFastModePlus\n
+ * SYSCFG_CFGR1 I2C_FMP_PB9 LL_SYSCFG_DisableFastModePlus\n
+ * SYSCFG_CFGR1 I2C_FMP_I2C1 LL_SYSCFG_DisableFastModePlus\n
+ * SYSCFG_CFGR1 I2C_FMP_I2C2 LL_SYSCFG_DisableFastModePlus\n
+ * SYSCFG_CFGR1 I2C_FMP_PA9 LL_SYSCFG_DisableFastModePlus\n
+ * SYSCFG_CFGR1 I2C_FMP_PA10 LL_SYSCFG_DisableFastModePlus
+ * @param ConfigFastModePlus This parameter can be a combination of the following values:
+ * @arg @ref LL_SYSCFG_I2C_FASTMODEPLUS_PB6
+ * @arg @ref LL_SYSCFG_I2C_FASTMODEPLUS_PB7
+ * @arg @ref LL_SYSCFG_I2C_FASTMODEPLUS_PB8
+ * @arg @ref LL_SYSCFG_I2C_FASTMODEPLUS_PB9
+ * @arg @ref LL_SYSCFG_I2C_FASTMODEPLUS_I2C1 (*)
+ * @arg @ref LL_SYSCFG_I2C_FASTMODEPLUS_I2C2 (*)
+ * @arg @ref LL_SYSCFG_I2C_FASTMODEPLUS_PA9 (*)
+ * @arg @ref LL_SYSCFG_I2C_FASTMODEPLUS_PA10 (*)
+ *
+ * (*) value not defined in all devices
+ * @retval None
+ */
+__STATIC_INLINE void LL_SYSCFG_DisableFastModePlus(uint32_t ConfigFastModePlus)
+{
+ CLEAR_BIT(SYSCFG->CFGR1, ConfigFastModePlus);
+}
+
+/**
+ * @brief Configure source input for the EXTI external interrupt.
+ * @rmtoll SYSCFG_EXTICR1 EXTI0 LL_SYSCFG_SetEXTISource\n
+ * SYSCFG_EXTICR1 EXTI1 LL_SYSCFG_SetEXTISource\n
+ * SYSCFG_EXTICR1 EXTI2 LL_SYSCFG_SetEXTISource\n
+ * SYSCFG_EXTICR1 EXTI3 LL_SYSCFG_SetEXTISource\n
+ * SYSCFG_EXTICR2 EXTI4 LL_SYSCFG_SetEXTISource\n
+ * SYSCFG_EXTICR2 EXTI5 LL_SYSCFG_SetEXTISource\n
+ * SYSCFG_EXTICR2 EXTI6 LL_SYSCFG_SetEXTISource\n
+ * SYSCFG_EXTICR2 EXTI7 LL_SYSCFG_SetEXTISource\n
+ * SYSCFG_EXTICR3 EXTI8 LL_SYSCFG_SetEXTISource\n
+ * SYSCFG_EXTICR3 EXTI9 LL_SYSCFG_SetEXTISource\n
+ * SYSCFG_EXTICR3 EXTI10 LL_SYSCFG_SetEXTISource\n
+ * SYSCFG_EXTICR3 EXTI11 LL_SYSCFG_SetEXTISource\n
+ * SYSCFG_EXTICR4 EXTI12 LL_SYSCFG_SetEXTISource\n
+ * SYSCFG_EXTICR4 EXTI13 LL_SYSCFG_SetEXTISource\n
+ * SYSCFG_EXTICR4 EXTI14 LL_SYSCFG_SetEXTISource\n
+ * SYSCFG_EXTICR4 EXTI15 LL_SYSCFG_SetEXTISource
+ * @param Port This parameter can be one of the following values:
+ * @arg @ref LL_SYSCFG_EXTI_PORTA
+ * @arg @ref LL_SYSCFG_EXTI_PORTB
+ * @arg @ref LL_SYSCFG_EXTI_PORTC
+ * @arg @ref LL_SYSCFG_EXTI_PORTD (*)
+ * @arg @ref LL_SYSCFG_EXTI_PORTE (*)
+ * @arg @ref LL_SYSCFG_EXTI_PORTF
+ *
+ * (*) value not defined in all devices
+ * @param Line This parameter can be one of the following values:
+ * @arg @ref LL_SYSCFG_EXTI_LINE0
+ * @arg @ref LL_SYSCFG_EXTI_LINE1
+ * @arg @ref LL_SYSCFG_EXTI_LINE2
+ * @arg @ref LL_SYSCFG_EXTI_LINE3
+ * @arg @ref LL_SYSCFG_EXTI_LINE4
+ * @arg @ref LL_SYSCFG_EXTI_LINE5
+ * @arg @ref LL_SYSCFG_EXTI_LINE6
+ * @arg @ref LL_SYSCFG_EXTI_LINE7
+ * @arg @ref LL_SYSCFG_EXTI_LINE8
+ * @arg @ref LL_SYSCFG_EXTI_LINE9
+ * @arg @ref LL_SYSCFG_EXTI_LINE10
+ * @arg @ref LL_SYSCFG_EXTI_LINE11
+ * @arg @ref LL_SYSCFG_EXTI_LINE12
+ * @arg @ref LL_SYSCFG_EXTI_LINE13
+ * @arg @ref LL_SYSCFG_EXTI_LINE14
+ * @arg @ref LL_SYSCFG_EXTI_LINE15
+ * @retval None
+ */
+__STATIC_INLINE void LL_SYSCFG_SetEXTISource(uint32_t Port, uint32_t Line)
+{
+ MODIFY_REG(SYSCFG->EXTICR[Line & 0xFF], SYSCFG_EXTICR1_EXTI0 << (Line >> 16), Port << (Line >> 16));
+}
+
+/**
+ * @brief Get the configured defined for specific EXTI Line
+ * @rmtoll SYSCFG_EXTICR1 EXTI0 LL_SYSCFG_SetEXTISource\n
+ * SYSCFG_EXTICR1 EXTI1 LL_SYSCFG_SetEXTISource\n
+ * SYSCFG_EXTICR1 EXTI2 LL_SYSCFG_SetEXTISource\n
+ * SYSCFG_EXTICR1 EXTI3 LL_SYSCFG_SetEXTISource\n
+ * SYSCFG_EXTICR2 EXTI4 LL_SYSCFG_SetEXTISource\n
+ * SYSCFG_EXTICR2 EXTI5 LL_SYSCFG_SetEXTISource\n
+ * SYSCFG_EXTICR2 EXTI6 LL_SYSCFG_SetEXTISource\n
+ * SYSCFG_EXTICR2 EXTI7 LL_SYSCFG_SetEXTISource\n
+ * SYSCFG_EXTICR3 EXTI8 LL_SYSCFG_SetEXTISource\n
+ * SYSCFG_EXTICR3 EXTI9 LL_SYSCFG_SetEXTISource\n
+ * SYSCFG_EXTICR3 EXTI10 LL_SYSCFG_SetEXTISource\n
+ * SYSCFG_EXTICR3 EXTI11 LL_SYSCFG_SetEXTISource\n
+ * SYSCFG_EXTICR4 EXTI12 LL_SYSCFG_SetEXTISource\n
+ * SYSCFG_EXTICR4 EXTI13 LL_SYSCFG_SetEXTISource\n
+ * SYSCFG_EXTICR4 EXTI14 LL_SYSCFG_SetEXTISource\n
+ * SYSCFG_EXTICR4 EXTI15 LL_SYSCFG_SetEXTISource
+ * @param Line This parameter can be one of the following values:
+ * @arg @ref LL_SYSCFG_EXTI_LINE0
+ * @arg @ref LL_SYSCFG_EXTI_LINE1
+ * @arg @ref LL_SYSCFG_EXTI_LINE2
+ * @arg @ref LL_SYSCFG_EXTI_LINE3
+ * @arg @ref LL_SYSCFG_EXTI_LINE4
+ * @arg @ref LL_SYSCFG_EXTI_LINE5
+ * @arg @ref LL_SYSCFG_EXTI_LINE6
+ * @arg @ref LL_SYSCFG_EXTI_LINE7
+ * @arg @ref LL_SYSCFG_EXTI_LINE8
+ * @arg @ref LL_SYSCFG_EXTI_LINE9
+ * @arg @ref LL_SYSCFG_EXTI_LINE10
+ * @arg @ref LL_SYSCFG_EXTI_LINE11
+ * @arg @ref LL_SYSCFG_EXTI_LINE12
+ * @arg @ref LL_SYSCFG_EXTI_LINE13
+ * @arg @ref LL_SYSCFG_EXTI_LINE14
+ * @arg @ref LL_SYSCFG_EXTI_LINE15
+ * @retval Returned value can be one of the following values:
+ * @arg @ref LL_SYSCFG_EXTI_PORTA
+ * @arg @ref LL_SYSCFG_EXTI_PORTB
+ * @arg @ref LL_SYSCFG_EXTI_PORTC
+ * @arg @ref LL_SYSCFG_EXTI_PORTD (*)
+ * @arg @ref LL_SYSCFG_EXTI_PORTE (*)
+ * @arg @ref LL_SYSCFG_EXTI_PORTF
+ *
+ * (*) value not defined in all devices
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_GetEXTISource(uint32_t Line)
+{
+ return (uint32_t)(READ_BIT(SYSCFG->EXTICR[Line & 0xFF], (SYSCFG_EXTICR1_EXTI0 << (Line >> 16))) >> (Line >> 16));
+}
+
+#if defined(SYSCFG_ITLINE0_SR_EWDG)
+/**
+ * @brief Check if Window watchdog interrupt occurred or not.
+ * @rmtoll SYSCFG_ITLINE0 SR_EWDG LL_SYSCFG_IsActiveFlag_WWDG
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_WWDG(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[0], SYSCFG_ITLINE0_SR_EWDG) == (SYSCFG_ITLINE0_SR_EWDG));
+}
+#endif /* SYSCFG_ITLINE0_SR_EWDG */
+
+#if defined(SYSCFG_ITLINE1_SR_PVDOUT)
+/**
+ * @brief Check if PVD supply monitoring interrupt occurred or not (EXTI line 16).
+ * @rmtoll SYSCFG_ITLINE1 SR_PVDOUT LL_SYSCFG_IsActiveFlag_PVDOUT
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_PVDOUT(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[1], SYSCFG_ITLINE1_SR_PVDOUT) == (SYSCFG_ITLINE1_SR_PVDOUT));
+}
+#endif /* SYSCFG_ITLINE1_SR_PVDOUT */
+
+#if defined(SYSCFG_ITLINE1_SR_VDDIO2)
+/**
+ * @brief Check if VDDIO2 supply monitoring interrupt occurred or not (EXTI line 31).
+ * @rmtoll SYSCFG_ITLINE1 SR_VDDIO2 LL_SYSCFG_IsActiveFlag_VDDIO2
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_VDDIO2(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[1], SYSCFG_ITLINE1_SR_VDDIO2) == (SYSCFG_ITLINE1_SR_VDDIO2));
+}
+#endif /* SYSCFG_ITLINE1_SR_VDDIO2 */
+
+#if defined(SYSCFG_ITLINE2_SR_RTC_WAKEUP)
+/**
+ * @brief Check if RTC Wake Up interrupt occurred or not (EXTI line 20).
+ * @rmtoll SYSCFG_ITLINE2 SR_RTC_WAKEUP LL_SYSCFG_IsActiveFlag_RTC_WAKEUP
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_RTC_WAKEUP(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[2], SYSCFG_ITLINE2_SR_RTC_WAKEUP) == (SYSCFG_ITLINE2_SR_RTC_WAKEUP));
+}
+#endif /* SYSCFG_ITLINE2_SR_RTC_WAKEUP */
+
+#if defined(SYSCFG_ITLINE2_SR_RTC_TSTAMP)
+/**
+ * @brief Check if RTC Tamper and TimeStamp interrupt occurred or not (EXTI line 19).
+ * @rmtoll SYSCFG_ITLINE2 SR_RTC_TSTAMP LL_SYSCFG_IsActiveFlag_RTC_TSTAMP
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_RTC_TSTAMP(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[2], SYSCFG_ITLINE2_SR_RTC_TSTAMP) == (SYSCFG_ITLINE2_SR_RTC_TSTAMP));
+}
+#endif /* SYSCFG_ITLINE2_SR_RTC_TSTAMP */
+
+#if defined(SYSCFG_ITLINE2_SR_RTC_ALRA)
+/**
+ * @brief Check if RTC Alarm interrupt occurred or not (EXTI line 17).
+ * @rmtoll SYSCFG_ITLINE2 SR_RTC_ALRA LL_SYSCFG_IsActiveFlag_RTC_ALRA
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_RTC_ALRA(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[2], SYSCFG_ITLINE2_SR_RTC_ALRA) == (SYSCFG_ITLINE2_SR_RTC_ALRA));
+}
+#endif /* SYSCFG_ITLINE2_SR_RTC_ALRA */
+
+#if defined(SYSCFG_ITLINE3_SR_FLASH_ITF)
+/**
+ * @brief Check if Flash interface interrupt occurred or not.
+ * @rmtoll SYSCFG_ITLINE3 SR_FLASH_ITF LL_SYSCFG_IsActiveFlag_FLASH_ITF
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_FLASH_ITF(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[3], SYSCFG_ITLINE3_SR_FLASH_ITF) == (SYSCFG_ITLINE3_SR_FLASH_ITF));
+}
+#endif /* SYSCFG_ITLINE3_SR_FLASH_ITF */
+
+#if defined(SYSCFG_ITLINE4_SR_CRS)
+/**
+ * @brief Check if Clock recovery system interrupt occurred or not.
+ * @rmtoll SYSCFG_ITLINE4 SR_CRS LL_SYSCFG_IsActiveFlag_CRS
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_CRS(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[4], SYSCFG_ITLINE4_SR_CRS) == (SYSCFG_ITLINE4_SR_CRS));
+}
+#endif /* SYSCFG_ITLINE4_SR_CRS */
+
+#if defined(SYSCFG_ITLINE4_SR_CLK_CTRL)
+/**
+ * @brief Check if Reset and clock control interrupt occurred or not.
+ * @rmtoll SYSCFG_ITLINE4 SR_CLK_CTRL LL_SYSCFG_IsActiveFlag_CLK_CTRL
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_CLK_CTRL(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[4], SYSCFG_ITLINE4_SR_CLK_CTRL) == (SYSCFG_ITLINE4_SR_CLK_CTRL));
+}
+#endif /* SYSCFG_ITLINE4_SR_CLK_CTRL */
+
+#if defined(SYSCFG_ITLINE5_SR_EXTI0)
+/**
+ * @brief Check if EXTI line 0 interrupt occurred or not.
+ * @rmtoll SYSCFG_ITLINE5 SR_EXTI0 LL_SYSCFG_IsActiveFlag_EXTI0
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_EXTI0(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[5], SYSCFG_ITLINE5_SR_EXTI0) == (SYSCFG_ITLINE5_SR_EXTI0));
+}
+#endif /* SYSCFG_ITLINE5_SR_EXTI0 */
+
+#if defined(SYSCFG_ITLINE5_SR_EXTI1)
+/**
+ * @brief Check if EXTI line 1 interrupt occurred or not.
+ * @rmtoll SYSCFG_ITLINE5 SR_EXTI1 LL_SYSCFG_IsActiveFlag_EXTI1
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_EXTI1(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[5], SYSCFG_ITLINE5_SR_EXTI1) == (SYSCFG_ITLINE5_SR_EXTI1));
+}
+#endif /* SYSCFG_ITLINE5_SR_EXTI1 */
+
+#if defined(SYSCFG_ITLINE6_SR_EXTI2)
+/**
+ * @brief Check if EXTI line 2 interrupt occurred or not.
+ * @rmtoll SYSCFG_ITLINE6 SR_EXTI2 LL_SYSCFG_IsActiveFlag_EXTI2
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_EXTI2(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[6], SYSCFG_ITLINE6_SR_EXTI2) == (SYSCFG_ITLINE6_SR_EXTI2));
+}
+#endif /* SYSCFG_ITLINE6_SR_EXTI2 */
+
+#if defined(SYSCFG_ITLINE6_SR_EXTI3)
+/**
+ * @brief Check if EXTI line 3 interrupt occurred or not.
+ * @rmtoll SYSCFG_ITLINE6 SR_EXTI3 LL_SYSCFG_IsActiveFlag_EXTI3
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_EXTI3(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[6], SYSCFG_ITLINE6_SR_EXTI3) == (SYSCFG_ITLINE6_SR_EXTI3));
+}
+#endif /* SYSCFG_ITLINE6_SR_EXTI3 */
+
+#if defined(SYSCFG_ITLINE7_SR_EXTI4)
+/**
+ * @brief Check if EXTI line 4 interrupt occurred or not.
+ * @rmtoll SYSCFG_ITLINE7 SR_EXTI4 LL_SYSCFG_IsActiveFlag_EXTI4
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_EXTI4(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[7], SYSCFG_ITLINE7_SR_EXTI4) == (SYSCFG_ITLINE7_SR_EXTI4));
+}
+#endif /* SYSCFG_ITLINE7_SR_EXTI4 */
+
+#if defined(SYSCFG_ITLINE7_SR_EXTI5)
+/**
+ * @brief Check if EXTI line 5 interrupt occurred or not.
+ * @rmtoll SYSCFG_ITLINE7 SR_EXTI5 LL_SYSCFG_IsActiveFlag_EXTI5
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_EXTI5(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[7], SYSCFG_ITLINE7_SR_EXTI5) == (SYSCFG_ITLINE7_SR_EXTI5));
+}
+#endif /* SYSCFG_ITLINE7_SR_EXTI5 */
+
+#if defined(SYSCFG_ITLINE7_SR_EXTI6)
+/**
+ * @brief Check if EXTI line 6 interrupt occurred or not.
+ * @rmtoll SYSCFG_ITLINE7 SR_EXTI6 LL_SYSCFG_IsActiveFlag_EXTI6
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_EXTI6(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[7], SYSCFG_ITLINE7_SR_EXTI6) == (SYSCFG_ITLINE7_SR_EXTI6));
+}
+#endif /* SYSCFG_ITLINE7_SR_EXTI6 */
+
+#if defined(SYSCFG_ITLINE7_SR_EXTI7)
+/**
+ * @brief Check if EXTI line 7 interrupt occurred or not.
+ * @rmtoll SYSCFG_ITLINE7 SR_EXTI7 LL_SYSCFG_IsActiveFlag_EXTI7
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_EXTI7(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[7], SYSCFG_ITLINE7_SR_EXTI7) == (SYSCFG_ITLINE7_SR_EXTI7));
+}
+#endif /* SYSCFG_ITLINE7_SR_EXTI7 */
+
+#if defined(SYSCFG_ITLINE7_SR_EXTI8)
+/**
+ * @brief Check if EXTI line 8 interrupt occurred or not.
+ * @rmtoll SYSCFG_ITLINE7 SR_EXTI8 LL_SYSCFG_IsActiveFlag_EXTI8
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_EXTI8(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[7], SYSCFG_ITLINE7_SR_EXTI8) == (SYSCFG_ITLINE7_SR_EXTI8));
+}
+#endif /* SYSCFG_ITLINE7_SR_EXTI8 */
+
+#if defined(SYSCFG_ITLINE7_SR_EXTI9)
+/**
+ * @brief Check if EXTI line 9 interrupt occurred or not.
+ * @rmtoll SYSCFG_ITLINE7 SR_EXTI9 LL_SYSCFG_IsActiveFlag_EXTI9
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_EXTI9(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[7], SYSCFG_ITLINE7_SR_EXTI9) == (SYSCFG_ITLINE7_SR_EXTI9));
+}
+#endif /* SYSCFG_ITLINE7_SR_EXTI9 */
+
+#if defined(SYSCFG_ITLINE7_SR_EXTI10)
+/**
+ * @brief Check if EXTI line 10 interrupt occurred or not.
+ * @rmtoll SYSCFG_ITLINE7 SR_EXTI10 LL_SYSCFG_IsActiveFlag_EXTI10
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_EXTI10(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[7], SYSCFG_ITLINE7_SR_EXTI10) == (SYSCFG_ITLINE7_SR_EXTI10));
+}
+#endif /* SYSCFG_ITLINE7_SR_EXTI10 */
+
+#if defined(SYSCFG_ITLINE7_SR_EXTI11)
+/**
+ * @brief Check if EXTI line 11 interrupt occurred or not.
+ * @rmtoll SYSCFG_ITLINE7 SR_EXTI11 LL_SYSCFG_IsActiveFlag_EXTI11
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_EXTI11(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[7], SYSCFG_ITLINE7_SR_EXTI11) == (SYSCFG_ITLINE7_SR_EXTI11));
+}
+#endif /* SYSCFG_ITLINE7_SR_EXTI11 */
+
+#if defined(SYSCFG_ITLINE7_SR_EXTI12)
+/**
+ * @brief Check if EXTI line 12 interrupt occurred or not.
+ * @rmtoll SYSCFG_ITLINE7 SR_EXTI12 LL_SYSCFG_IsActiveFlag_EXTI12
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_EXTI12(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[7], SYSCFG_ITLINE7_SR_EXTI12) == (SYSCFG_ITLINE7_SR_EXTI12));
+}
+#endif /* SYSCFG_ITLINE7_SR_EXTI12 */
+
+#if defined(SYSCFG_ITLINE7_SR_EXTI13)
+/**
+ * @brief Check if EXTI line 13 interrupt occurred or not.
+ * @rmtoll SYSCFG_ITLINE7 SR_EXTI13 LL_SYSCFG_IsActiveFlag_EXTI13
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_EXTI13(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[7], SYSCFG_ITLINE7_SR_EXTI13) == (SYSCFG_ITLINE7_SR_EXTI13));
+}
+#endif /* SYSCFG_ITLINE7_SR_EXTI13 */
+
+#if defined(SYSCFG_ITLINE7_SR_EXTI14)
+/**
+ * @brief Check if EXTI line 14 interrupt occurred or not.
+ * @rmtoll SYSCFG_ITLINE7 SR_EXTI14 LL_SYSCFG_IsActiveFlag_EXTI14
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_EXTI14(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[7], SYSCFG_ITLINE7_SR_EXTI14) == (SYSCFG_ITLINE7_SR_EXTI14));
+}
+#endif /* SYSCFG_ITLINE7_SR_EXTI14 */
+
+#if defined(SYSCFG_ITLINE7_SR_EXTI15)
+/**
+ * @brief Check if EXTI line 15 interrupt occurred or not.
+ * @rmtoll SYSCFG_ITLINE7 SR_EXTI15 LL_SYSCFG_IsActiveFlag_EXTI15
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_EXTI15(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[7], SYSCFG_ITLINE7_SR_EXTI15) == (SYSCFG_ITLINE7_SR_EXTI15));
+}
+#endif /* SYSCFG_ITLINE7_SR_EXTI15 */
+
+#if defined(SYSCFG_ITLINE8_SR_TSC_EOA)
+/**
+ * @brief Check if Touch sensing controller end of acquisition interrupt occurred or not.
+ * @rmtoll SYSCFG_ITLINE8 SR_TSC_EOA LL_SYSCFG_IsActiveFlag_TSC_EOA
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_TSC_EOA(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[8], SYSCFG_ITLINE8_SR_TSC_EOA) == (SYSCFG_ITLINE8_SR_TSC_EOA));
+}
+#endif /* SYSCFG_ITLINE8_SR_TSC_EOA */
+
+#if defined(SYSCFG_ITLINE8_SR_TSC_MCE)
+/**
+ * @brief Check if Touch sensing controller max counterror interrupt occurred or not.
+ * @rmtoll SYSCFG_ITLINE8 SR_TSC_MCE LL_SYSCFG_IsActiveFlag_TSC_MCE
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_TSC_MCE(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[8], SYSCFG_ITLINE8_SR_TSC_MCE) == (SYSCFG_ITLINE8_SR_TSC_MCE));
+}
+#endif /* SYSCFG_ITLINE8_SR_TSC_MCE */
+
+#if defined(SYSCFG_ITLINE9_SR_DMA1_CH1)
+/**
+ * @brief Check if DMA1 channel 1 interrupt occurred or not.
+ * @rmtoll SYSCFG_ITLINE9 SR_DMA1_CH1 LL_SYSCFG_IsActiveFlag_DMA1_CH1
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_DMA1_CH1(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[9], SYSCFG_ITLINE9_SR_DMA1_CH1) == (SYSCFG_ITLINE9_SR_DMA1_CH1));
+}
+#endif /* SYSCFG_ITLINE9_SR_DMA1_CH1 */
+
+#if defined(SYSCFG_ITLINE10_SR_DMA1_CH2)
+/**
+ * @brief Check if DMA1 channel 2 interrupt occurred or not.
+ * @rmtoll SYSCFG_ITLINE10 SR_DMA1_CH2 LL_SYSCFG_IsActiveFlag_DMA1_CH2
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_DMA1_CH2(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[10], SYSCFG_ITLINE10_SR_DMA1_CH2) == (SYSCFG_ITLINE10_SR_DMA1_CH2));
+}
+#endif /* SYSCFG_ITLINE10_SR_DMA1_CH2 */
+
+#if defined(SYSCFG_ITLINE10_SR_DMA1_CH3)
+/**
+ * @brief Check if DMA1 channel 3 interrupt occurred or not.
+ * @rmtoll SYSCFG_ITLINE10 SR_DMA1_CH3 LL_SYSCFG_IsActiveFlag_DMA1_CH3
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_DMA1_CH3(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[10], SYSCFG_ITLINE10_SR_DMA1_CH3) == (SYSCFG_ITLINE10_SR_DMA1_CH3));
+}
+#endif /* SYSCFG_ITLINE10_SR_DMA1_CH3 */
+
+#if defined(SYSCFG_ITLINE10_SR_DMA2_CH1)
+/**
+ * @brief Check if DMA2 channel 1 interrupt occurred or not.
+ * @rmtoll SYSCFG_ITLINE10 SR_DMA2_CH1 LL_SYSCFG_IsActiveFlag_DMA2_CH1
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_DMA2_CH1(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[10], SYSCFG_ITLINE10_SR_DMA2_CH1) == (SYSCFG_ITLINE10_SR_DMA2_CH1));
+}
+#endif /* SYSCFG_ITLINE10_SR_DMA2_CH1 */
+
+#if defined(SYSCFG_ITLINE10_SR_DMA2_CH2)
+/**
+ * @brief Check if DMA2 channel 2 interrupt occurred or not.
+ * @rmtoll SYSCFG_ITLINE10 SR_DMA2_CH2 LL_SYSCFG_IsActiveFlag_DMA2_CH2
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_DMA2_CH2(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[10], SYSCFG_ITLINE10_SR_DMA2_CH2) == (SYSCFG_ITLINE10_SR_DMA2_CH2));
+}
+#endif /* SYSCFG_ITLINE10_SR_DMA2_CH2 */
+
+#if defined(SYSCFG_ITLINE11_SR_DMA1_CH4)
+/**
+ * @brief Check if DMA1 channel 4 interrupt occurred or not.
+ * @rmtoll SYSCFG_ITLINE11 SR_DMA1_CH4 LL_SYSCFG_IsActiveFlag_DMA1_CH4
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_DMA1_CH4(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[11], SYSCFG_ITLINE11_SR_DMA1_CH4) == (SYSCFG_ITLINE11_SR_DMA1_CH4));
+}
+#endif /* SYSCFG_ITLINE11_SR_DMA1_CH4 */
+
+#if defined(SYSCFG_ITLINE11_SR_DMA1_CH5)
+/**
+ * @brief Check if DMA1 channel 5 interrupt occurred or not.
+ * @rmtoll SYSCFG_ITLINE11 SR_DMA1_CH5 LL_SYSCFG_IsActiveFlag_DMA1_CH5
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_DMA1_CH5(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[11], SYSCFG_ITLINE11_SR_DMA1_CH5) == (SYSCFG_ITLINE11_SR_DMA1_CH5));
+}
+#endif /* SYSCFG_ITLINE11_SR_DMA1_CH5 */
+
+#if defined(SYSCFG_ITLINE11_SR_DMA1_CH6)
+/**
+ * @brief Check if DMA1 channel 6 interrupt occurred or not.
+ * @rmtoll SYSCFG_ITLINE11 SR_DMA1_CH6 LL_SYSCFG_IsActiveFlag_DMA1_CH6
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_DMA1_CH6(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[11], SYSCFG_ITLINE11_SR_DMA1_CH6) == (SYSCFG_ITLINE11_SR_DMA1_CH6));
+}
+#endif /* SYSCFG_ITLINE11_SR_DMA1_CH6 */
+
+#if defined(SYSCFG_ITLINE11_SR_DMA1_CH7)
+/**
+ * @brief Check if DMA1 channel 7 interrupt occurred or not.
+ * @rmtoll SYSCFG_ITLINE11 SR_DMA1_CH7 LL_SYSCFG_IsActiveFlag_DMA1_CH7
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_DMA1_CH7(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[11], SYSCFG_ITLINE11_SR_DMA1_CH7) == (SYSCFG_ITLINE11_SR_DMA1_CH7));
+}
+#endif /* SYSCFG_ITLINE11_SR_DMA1_CH7 */
+
+#if defined(SYSCFG_ITLINE11_SR_DMA2_CH3)
+/**
+ * @brief Check if DMA2 channel 3 interrupt occurred or not.
+ * @rmtoll SYSCFG_ITLINE11 SR_DMA2_CH3 LL_SYSCFG_IsActiveFlag_DMA2_CH3
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_DMA2_CH3(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[11], SYSCFG_ITLINE11_SR_DMA2_CH3) == (SYSCFG_ITLINE11_SR_DMA2_CH3));
+}
+#endif /* SYSCFG_ITLINE11_SR_DMA2_CH3 */
+
+#if defined(SYSCFG_ITLINE11_SR_DMA2_CH4)
+/**
+ * @brief Check if DMA2 channel 4 interrupt occurred or not.
+ * @rmtoll SYSCFG_ITLINE11 SR_DMA2_CH4 LL_SYSCFG_IsActiveFlag_DMA2_CH4
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_DMA2_CH4(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[11], SYSCFG_ITLINE11_SR_DMA2_CH4) == (SYSCFG_ITLINE11_SR_DMA2_CH4));
+}
+#endif /* SYSCFG_ITLINE11_SR_DMA2_CH4 */
+
+#if defined(SYSCFG_ITLINE11_SR_DMA2_CH5)
+/**
+ * @brief Check if DMA2 channel 5 interrupt occurred or not.
+ * @rmtoll SYSCFG_ITLINE11 SR_DMA2_CH5 LL_SYSCFG_IsActiveFlag_DMA2_CH5
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_DMA2_CH5(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[11], SYSCFG_ITLINE11_SR_DMA2_CH5) == (SYSCFG_ITLINE11_SR_DMA2_CH5));
+}
+#endif /* SYSCFG_ITLINE11_SR_DMA2_CH5 */
+
+#if defined(SYSCFG_ITLINE12_SR_ADC)
+/**
+ * @brief Check if ADC interrupt occurred or not.
+ * @rmtoll SYSCFG_ITLINE12 SR_ADC LL_SYSCFG_IsActiveFlag_ADC
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_ADC(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[12], SYSCFG_ITLINE12_SR_ADC) == (SYSCFG_ITLINE12_SR_ADC));
+}
+#endif /* SYSCFG_ITLINE12_SR_ADC */
+
+#if defined(SYSCFG_ITLINE12_SR_COMP1)
+/**
+ * @brief Check if Comparator 1 interrupt occurred or not (EXTI line 21).
+ * @rmtoll SYSCFG_ITLINE12 SR_COMP1 LL_SYSCFG_IsActiveFlag_COMP1
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_COMP1(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[12], SYSCFG_ITLINE12_SR_COMP1) == (SYSCFG_ITLINE12_SR_COMP1));
+}
+#endif /* SYSCFG_ITLINE12_SR_COMP1 */
+
+#if defined(SYSCFG_ITLINE12_SR_COMP2)
+/**
+ * @brief Check if Comparator 2 interrupt occurred or not (EXTI line 22).
+ * @rmtoll SYSCFG_ITLINE12 SR_COMP2 LL_SYSCFG_IsActiveFlag_COMP2
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_COMP2(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[12], SYSCFG_ITLINE12_SR_COMP2) == (SYSCFG_ITLINE12_SR_COMP2));
+}
+#endif /* SYSCFG_ITLINE12_SR_COMP2 */
+
+#if defined(SYSCFG_ITLINE13_SR_TIM1_BRK)
+/**
+ * @brief Check if Timer 1 break interrupt occurred or not.
+ * @rmtoll SYSCFG_ITLINE13 SR_TIM1_BRK LL_SYSCFG_IsActiveFlag_TIM1_BRK
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_TIM1_BRK(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[13], SYSCFG_ITLINE13_SR_TIM1_BRK) == (SYSCFG_ITLINE13_SR_TIM1_BRK));
+}
+#endif /* SYSCFG_ITLINE13_SR_TIM1_BRK */
+
+#if defined(SYSCFG_ITLINE13_SR_TIM1_UPD)
+/**
+ * @brief Check if Timer 1 update interrupt occurred or not.
+ * @rmtoll SYSCFG_ITLINE13 SR_TIM1_UPD LL_SYSCFG_IsActiveFlag_TIM1_UPD
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_TIM1_UPD(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[13], SYSCFG_ITLINE13_SR_TIM1_UPD) == (SYSCFG_ITLINE13_SR_TIM1_UPD));
+}
+#endif /* SYSCFG_ITLINE13_SR_TIM1_UPD */
+
+#if defined(SYSCFG_ITLINE13_SR_TIM1_TRG)
+/**
+ * @brief Check if Timer 1 trigger interrupt occurred or not.
+ * @rmtoll SYSCFG_ITLINE13 SR_TIM1_TRG LL_SYSCFG_IsActiveFlag_TIM1_TRG
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_TIM1_TRG(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[13], SYSCFG_ITLINE13_SR_TIM1_TRG) == (SYSCFG_ITLINE13_SR_TIM1_TRG));
+}
+#endif /* SYSCFG_ITLINE13_SR_TIM1_TRG */
+
+#if defined(SYSCFG_ITLINE13_SR_TIM1_CCU)
+/**
+ * @brief Check if Timer 1 commutation interrupt occurred or not.
+ * @rmtoll SYSCFG_ITLINE13 SR_TIM1_CCU LL_SYSCFG_IsActiveFlag_TIM1_CCU
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_TIM1_CCU(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[13], SYSCFG_ITLINE13_SR_TIM1_CCU) == (SYSCFG_ITLINE13_SR_TIM1_CCU));
+}
+#endif /* SYSCFG_ITLINE13_SR_TIM1_CCU */
+
+#if defined(SYSCFG_ITLINE14_SR_TIM1_CC)
+/**
+ * @brief Check if Timer 1 capture compare interrupt occurred or not.
+ * @rmtoll SYSCFG_ITLINE14 SR_TIM1_CC LL_SYSCFG_IsActiveFlag_TIM1_CC
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_TIM1_CC(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[14], SYSCFG_ITLINE14_SR_TIM1_CC) == (SYSCFG_ITLINE14_SR_TIM1_CC));
+}
+#endif /* SYSCFG_ITLINE14_SR_TIM1_CC */
+
+#if defined(SYSCFG_ITLINE15_SR_TIM2_GLB)
+/**
+ * @brief Check if Timer 2 interrupt occurred or not.
+ * @rmtoll SYSCFG_ITLINE15 SR_TIM2_GLB LL_SYSCFG_IsActiveFlag_TIM2
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_TIM2(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[15], SYSCFG_ITLINE15_SR_TIM2_GLB) == (SYSCFG_ITLINE15_SR_TIM2_GLB));
+}
+#endif /* SYSCFG_ITLINE15_SR_TIM2_GLB */
+
+#if defined(SYSCFG_ITLINE16_SR_TIM3_GLB)
+/**
+ * @brief Check if Timer 3 interrupt occurred or not.
+ * @rmtoll SYSCFG_ITLINE16 SR_TIM3_GLB LL_SYSCFG_IsActiveFlag_TIM3
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_TIM3(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[16], SYSCFG_ITLINE16_SR_TIM3_GLB) == (SYSCFG_ITLINE16_SR_TIM3_GLB));
+}
+#endif /* SYSCFG_ITLINE16_SR_TIM3_GLB */
+
+#if defined(SYSCFG_ITLINE17_SR_DAC)
+/**
+ * @brief Check if DAC underrun interrupt occurred or not.
+ * @rmtoll SYSCFG_ITLINE17 SR_DAC LL_SYSCFG_IsActiveFlag_DAC
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_DAC(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[17], SYSCFG_ITLINE17_SR_DAC) == (SYSCFG_ITLINE17_SR_DAC));
+}
+#endif /* SYSCFG_ITLINE17_SR_DAC */
+
+#if defined(SYSCFG_ITLINE17_SR_TIM6_GLB)
+/**
+ * @brief Check if Timer 6 interrupt occurred or not.
+ * @rmtoll SYSCFG_ITLINE17 SR_TIM6_GLB LL_SYSCFG_IsActiveFlag_TIM6
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_TIM6(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[17], SYSCFG_ITLINE17_SR_TIM6_GLB) == (SYSCFG_ITLINE17_SR_TIM6_GLB));
+}
+#endif /* SYSCFG_ITLINE17_SR_TIM6_GLB */
+
+#if defined(SYSCFG_ITLINE18_SR_TIM7_GLB)
+/**
+ * @brief Check if Timer 7 interrupt occurred or not.
+ * @rmtoll SYSCFG_ITLINE18 SR_TIM7_GLB LL_SYSCFG_IsActiveFlag_TIM7
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_TIM7(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[18], SYSCFG_ITLINE18_SR_TIM7_GLB) == (SYSCFG_ITLINE18_SR_TIM7_GLB));
+}
+#endif /* SYSCFG_ITLINE18_SR_TIM7_GLB */
+
+#if defined(SYSCFG_ITLINE19_SR_TIM14_GLB)
+/**
+ * @brief Check if Timer 14 interrupt occurred or not.
+ * @rmtoll SYSCFG_ITLINE19 SR_TIM14_GLB LL_SYSCFG_IsActiveFlag_TIM14
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_TIM14(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[19], SYSCFG_ITLINE19_SR_TIM14_GLB) == (SYSCFG_ITLINE19_SR_TIM14_GLB));
+}
+#endif /* SYSCFG_ITLINE19_SR_TIM14_GLB */
+
+#if defined(SYSCFG_ITLINE20_SR_TIM15_GLB)
+/**
+ * @brief Check if Timer 15 interrupt occurred or not.
+ * @rmtoll SYSCFG_ITLINE20 SR_TIM15_GLB LL_SYSCFG_IsActiveFlag_TIM15
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_TIM15(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[20], SYSCFG_ITLINE20_SR_TIM15_GLB) == (SYSCFG_ITLINE20_SR_TIM15_GLB));
+}
+#endif /* SYSCFG_ITLINE20_SR_TIM15_GLB */
+
+#if defined(SYSCFG_ITLINE21_SR_TIM16_GLB)
+/**
+ * @brief Check if Timer 16 interrupt occurred or not.
+ * @rmtoll SYSCFG_ITLINE21 SR_TIM16_GLB LL_SYSCFG_IsActiveFlag_TIM16
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_TIM16(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[21], SYSCFG_ITLINE21_SR_TIM16_GLB) == (SYSCFG_ITLINE21_SR_TIM16_GLB));
+}
+#endif /* SYSCFG_ITLINE21_SR_TIM16_GLB */
+
+#if defined(SYSCFG_ITLINE22_SR_TIM17_GLB)
+/**
+ * @brief Check if Timer 17 interrupt occurred or not.
+ * @rmtoll SYSCFG_ITLINE22 SR_TIM17_GLB LL_SYSCFG_IsActiveFlag_TIM17
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_TIM17(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[22], SYSCFG_ITLINE22_SR_TIM17_GLB) == (SYSCFG_ITLINE22_SR_TIM17_GLB));
+}
+#endif /* SYSCFG_ITLINE22_SR_TIM17_GLB */
+
+#if defined(SYSCFG_ITLINE23_SR_I2C1_GLB)
+/**
+ * @brief Check if I2C1 interrupt occurred or not, combined with EXTI line 23.
+ * @rmtoll SYSCFG_ITLINE23 SR_I2C1_GLB LL_SYSCFG_IsActiveFlag_I2C1
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_I2C1(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[23], SYSCFG_ITLINE23_SR_I2C1_GLB) == (SYSCFG_ITLINE23_SR_I2C1_GLB));
+}
+#endif /* SYSCFG_ITLINE23_SR_I2C1_GLB */
+
+#if defined(SYSCFG_ITLINE24_SR_I2C2_GLB)
+/**
+ * @brief Check if I2C2 interrupt occurred or not.
+ * @rmtoll SYSCFG_ITLINE24 SR_I2C2_GLB LL_SYSCFG_IsActiveFlag_I2C2
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_I2C2(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[24], SYSCFG_ITLINE24_SR_I2C2_GLB) == (SYSCFG_ITLINE24_SR_I2C2_GLB));
+}
+#endif /* SYSCFG_ITLINE24_SR_I2C2_GLB */
+
+#if defined(SYSCFG_ITLINE25_SR_SPI1)
+/**
+ * @brief Check if SPI1 interrupt occurred or not.
+ * @rmtoll SYSCFG_ITLINE25 SR_SPI1 LL_SYSCFG_IsActiveFlag_SPI1
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_SPI1(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[25], SYSCFG_ITLINE25_SR_SPI1) == (SYSCFG_ITLINE25_SR_SPI1));
+}
+#endif /* SYSCFG_ITLINE25_SR_SPI1 */
+
+#if defined(SYSCFG_ITLINE26_SR_SPI2)
+/**
+ * @brief Check if SPI2 interrupt occurred or not.
+ * @rmtoll SYSCFG_ITLINE26 SR_SPI2 LL_SYSCFG_IsActiveFlag_SPI2
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_SPI2(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[26], SYSCFG_ITLINE26_SR_SPI2) == (SYSCFG_ITLINE26_SR_SPI2));
+}
+#endif /* SYSCFG_ITLINE26_SR_SPI2 */
+
+#if defined(SYSCFG_ITLINE27_SR_USART1_GLB)
+/**
+ * @brief Check if USART1 interrupt occurred or not, combined with EXTI line 25.
+ * @rmtoll SYSCFG_ITLINE27 SR_USART1_GLB LL_SYSCFG_IsActiveFlag_USART1
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_USART1(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[27], SYSCFG_ITLINE27_SR_USART1_GLB) == (SYSCFG_ITLINE27_SR_USART1_GLB));
+}
+#endif /* SYSCFG_ITLINE27_SR_USART1_GLB */
+
+#if defined(SYSCFG_ITLINE28_SR_USART2_GLB)
+/**
+ * @brief Check if USART2 interrupt occurred or not, combined with EXTI line 26.
+ * @rmtoll SYSCFG_ITLINE28 SR_USART2_GLB LL_SYSCFG_IsActiveFlag_USART2
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_USART2(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[28], SYSCFG_ITLINE28_SR_USART2_GLB) == (SYSCFG_ITLINE28_SR_USART2_GLB));
+}
+#endif /* SYSCFG_ITLINE28_SR_USART2_GLB */
+
+#if defined(SYSCFG_ITLINE29_SR_USART3_GLB)
+/**
+ * @brief Check if USART3 interrupt occurred or not, combined with EXTI line 28.
+ * @rmtoll SYSCFG_ITLINE29 SR_USART3_GLB LL_SYSCFG_IsActiveFlag_USART3
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_USART3(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[29], SYSCFG_ITLINE29_SR_USART3_GLB) == (SYSCFG_ITLINE29_SR_USART3_GLB));
+}
+#endif /* SYSCFG_ITLINE29_SR_USART3_GLB */
+
+#if defined(SYSCFG_ITLINE29_SR_USART4_GLB)
+/**
+ * @brief Check if USART4 interrupt occurred or not.
+ * @rmtoll SYSCFG_ITLINE29 SR_USART4_GLB LL_SYSCFG_IsActiveFlag_USART4
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_USART4(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[29], SYSCFG_ITLINE29_SR_USART4_GLB) == (SYSCFG_ITLINE29_SR_USART4_GLB));
+}
+#endif /* SYSCFG_ITLINE29_SR_USART4_GLB */
+
+#if defined(SYSCFG_ITLINE29_SR_USART5_GLB)
+/**
+ * @brief Check if USART5 interrupt occurred or not.
+ * @rmtoll SYSCFG_ITLINE29 SR_USART5_GLB LL_SYSCFG_IsActiveFlag_USART5
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_USART5(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[29], SYSCFG_ITLINE29_SR_USART5_GLB) == (SYSCFG_ITLINE29_SR_USART5_GLB));
+}
+#endif /* SYSCFG_ITLINE29_SR_USART5_GLB */
+
+#if defined(SYSCFG_ITLINE29_SR_USART6_GLB)
+/**
+ * @brief Check if USART6 interrupt occurred or not.
+ * @rmtoll SYSCFG_ITLINE29 SR_USART6_GLB LL_SYSCFG_IsActiveFlag_USART6
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_USART6(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[29], SYSCFG_ITLINE29_SR_USART6_GLB) == (SYSCFG_ITLINE29_SR_USART6_GLB));
+}
+#endif /* SYSCFG_ITLINE29_SR_USART6_GLB */
+
+#if defined(SYSCFG_ITLINE29_SR_USART7_GLB)
+/**
+ * @brief Check if USART7 interrupt occurred or not.
+ * @rmtoll SYSCFG_ITLINE29 SR_USART7_GLB LL_SYSCFG_IsActiveFlag_USART7
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_USART7(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[29], SYSCFG_ITLINE29_SR_USART7_GLB) == (SYSCFG_ITLINE29_SR_USART7_GLB));
+}
+#endif /* SYSCFG_ITLINE29_SR_USART7_GLB */
+
+#if defined(SYSCFG_ITLINE29_SR_USART8_GLB)
+/**
+ * @brief Check if USART8 interrupt occurred or not.
+ * @rmtoll SYSCFG_ITLINE29 SR_USART8_GLB LL_SYSCFG_IsActiveFlag_USART8
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_USART8(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[29], SYSCFG_ITLINE29_SR_USART8_GLB) == (SYSCFG_ITLINE29_SR_USART8_GLB));
+}
+#endif /* SYSCFG_ITLINE29_SR_USART8_GLB */
+
+#if defined(SYSCFG_ITLINE30_SR_CAN)
+/**
+ * @brief Check if CAN interrupt occurred or not.
+ * @rmtoll SYSCFG_ITLINE30 SR_CAN LL_SYSCFG_IsActiveFlag_CAN
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_CAN(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[30], SYSCFG_ITLINE30_SR_CAN) == (SYSCFG_ITLINE30_SR_CAN));
+}
+#endif /* SYSCFG_ITLINE30_SR_CAN */
+
+#if defined(SYSCFG_ITLINE30_SR_CEC)
+/**
+ * @brief Check if CEC interrupt occurred or not, combined with EXTI line 27.
+ * @rmtoll SYSCFG_ITLINE30 SR_CEC LL_SYSCFG_IsActiveFlag_CEC
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_CEC(void)
+{
+ return (READ_BIT(SYSCFG->IT_LINE_SR[30], SYSCFG_ITLINE30_SR_CEC) == (SYSCFG_ITLINE30_SR_CEC));
+}
+#endif /* SYSCFG_ITLINE30_SR_CEC */
+
+/**
+ * @brief Set connections to TIMx Break inputs
+ * @rmtoll SYSCFG_CFGR2 LOCKUP_LOCK LL_SYSCFG_SetTIMBreakInputs\n
+ * SYSCFG_CFGR2 SRAM_PARITY_LOCK LL_SYSCFG_SetTIMBreakInputs\n
+ * SYSCFG_CFGR2 PVD_LOCK LL_SYSCFG_SetTIMBreakInputs
+ * @param Break This parameter can be a combination of the following values:
+ * @arg @ref LL_SYSCFG_TIMBREAK_PVD (*)
+ * @arg @ref LL_SYSCFG_TIMBREAK_SRAM_PARITY
+ * @arg @ref LL_SYSCFG_TIMBREAK_LOCKUP
+ *
+ * (*) value not defined in all devices
+ * @retval None
+ */
+__STATIC_INLINE void LL_SYSCFG_SetTIMBreakInputs(uint32_t Break)
+{
+#if defined(SYSCFG_CFGR2_PVD_LOCK)
+ MODIFY_REG(SYSCFG->CFGR2, SYSCFG_CFGR2_LOCKUP_LOCK | SYSCFG_CFGR2_SRAM_PARITY_LOCK | SYSCFG_CFGR2_PVD_LOCK, Break);
+#else
+ MODIFY_REG(SYSCFG->CFGR2, SYSCFG_CFGR2_LOCKUP_LOCK | SYSCFG_CFGR2_SRAM_PARITY_LOCK, Break);
+#endif /*SYSCFG_CFGR2_PVD_LOCK*/
+}
+
+/**
+ * @brief Get connections to TIMx Break inputs
+ * @rmtoll SYSCFG_CFGR2 LOCKUP_LOCK LL_SYSCFG_GetTIMBreakInputs\n
+ * SYSCFG_CFGR2 SRAM_PARITY_LOCK LL_SYSCFG_GetTIMBreakInputs\n
+ * SYSCFG_CFGR2 PVD_LOCK LL_SYSCFG_GetTIMBreakInputs
+ * @retval Returned value can be can be a combination of the following values:
+ * @arg @ref LL_SYSCFG_TIMBREAK_PVD (*)
+ * @arg @ref LL_SYSCFG_TIMBREAK_SRAM_PARITY
+ * @arg @ref LL_SYSCFG_TIMBREAK_LOCKUP
+ *
+ * (*) value not defined in all devices
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_GetTIMBreakInputs(void)
+{
+#if defined(SYSCFG_CFGR2_PVD_LOCK)
+ return (uint32_t)(READ_BIT(SYSCFG->CFGR2,
+ SYSCFG_CFGR2_LOCKUP_LOCK | SYSCFG_CFGR2_SRAM_PARITY_LOCK | SYSCFG_CFGR2_PVD_LOCK));
+#else
+ return (uint32_t)(READ_BIT(SYSCFG->CFGR2, SYSCFG_CFGR2_LOCKUP_LOCK | SYSCFG_CFGR2_SRAM_PARITY_LOCK));
+#endif /*SYSCFG_CFGR2_PVD_LOCK*/
+}
+
+/**
+ * @brief Check if SRAM parity error detected
+ * @rmtoll SYSCFG_CFGR2 SRAM_PEF LL_SYSCFG_IsActiveFlag_SP
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_SP(void)
+{
+ return (READ_BIT(SYSCFG->CFGR2, SYSCFG_CFGR2_SRAM_PEF) == (SYSCFG_CFGR2_SRAM_PEF));
+}
+
+/**
+ * @brief Clear SRAM parity error flag
+ * @rmtoll SYSCFG_CFGR2 SRAM_PEF LL_SYSCFG_ClearFlag_SP
+ * @retval None
+ */
+__STATIC_INLINE void LL_SYSCFG_ClearFlag_SP(void)
+{
+ SET_BIT(SYSCFG->CFGR2, SYSCFG_CFGR2_SRAM_PEF);
+}
+
+/**
+ * @}
+ */
+
+/** @defgroup SYSTEM_LL_EF_DBGMCU DBGMCU
+ * @{
+ */
+
+/**
+ * @brief Return the device identifier
+ * @note For STM32F03x devices, the device ID is 0x444
+ * @note For STM32F04x devices, the device ID is 0x445.
+ * @note For STM32F05x devices, the device ID is 0x440
+ * @note For STM32F07x devices, the device ID is 0x448
+ * @note For STM32F09x devices, the device ID is 0x442
+ * @rmtoll DBGMCU_IDCODE DEV_ID LL_DBGMCU_GetDeviceID
+ * @retval Values between Min_Data=0x00 and Max_Data=0xFFF
+ */
+__STATIC_INLINE uint32_t LL_DBGMCU_GetDeviceID(void)
+{
+ return (uint32_t)(READ_BIT(DBGMCU->IDCODE, DBGMCU_IDCODE_DEV_ID));
+}
+
+/**
+ * @brief Return the device revision identifier
+ * @note This field indicates the revision of the device.
+ For example, it is read as 0x1000 for Revision 1.0.
+ * @rmtoll DBGMCU_IDCODE REV_ID LL_DBGMCU_GetRevisionID
+ * @retval Values between Min_Data=0x00 and Max_Data=0xFFFF
+ */
+__STATIC_INLINE uint32_t LL_DBGMCU_GetRevisionID(void)
+{
+ return (uint32_t)(READ_BIT(DBGMCU->IDCODE, DBGMCU_IDCODE_REV_ID) >> DBGMCU_IDCODE_REV_ID_Pos);
+}
+
+/**
+ * @brief Enable the Debug Module during STOP mode
+ * @rmtoll DBGMCU_CR DBG_STOP LL_DBGMCU_EnableDBGStopMode
+ * @retval None
+ */
+__STATIC_INLINE void LL_DBGMCU_EnableDBGStopMode(void)
+{
+ SET_BIT(DBGMCU->CR, DBGMCU_CR_DBG_STOP);
+}
+
+/**
+ * @brief Disable the Debug Module during STOP mode
+ * @rmtoll DBGMCU_CR DBG_STOP LL_DBGMCU_DisableDBGStopMode
+ * @retval None
+ */
+__STATIC_INLINE void LL_DBGMCU_DisableDBGStopMode(void)
+{
+ CLEAR_BIT(DBGMCU->CR, DBGMCU_CR_DBG_STOP);
+}
+
+/**
+ * @brief Enable the Debug Module during STANDBY mode
+ * @rmtoll DBGMCU_CR DBG_STANDBY LL_DBGMCU_EnableDBGStandbyMode
+ * @retval None
+ */
+__STATIC_INLINE void LL_DBGMCU_EnableDBGStandbyMode(void)
+{
+ SET_BIT(DBGMCU->CR, DBGMCU_CR_DBG_STANDBY);
+}
+
+/**
+ * @brief Disable the Debug Module during STANDBY mode
+ * @rmtoll DBGMCU_CR DBG_STANDBY LL_DBGMCU_DisableDBGStandbyMode
+ * @retval None
+ */
+__STATIC_INLINE void LL_DBGMCU_DisableDBGStandbyMode(void)
+{
+ CLEAR_BIT(DBGMCU->CR, DBGMCU_CR_DBG_STANDBY);
+}
+
+/**
+ * @brief Freeze APB1 peripherals (group1 peripherals)
+ * @rmtoll DBGMCU_APB1FZ DBG_TIM2_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n
+ * DBGMCU_APB1FZ DBG_TIM3_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n
+ * DBGMCU_APB1FZ DBG_TIM6_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n
+ * DBGMCU_APB1FZ DBG_TIM7_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n
+ * DBGMCU_APB1FZ DBG_TIM14_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n
+ * DBGMCU_APB1FZ DBG_RTC_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n
+ * DBGMCU_APB1FZ DBG_WWDG_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n
+ * DBGMCU_APB1FZ DBG_IWDG_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n
+ * DBGMCU_APB1FZ DBG_I2C1_SMBUS_TIMEOUT LL_DBGMCU_APB1_GRP1_FreezePeriph\n
+ * DBGMCU_APB1FZ DBG_CAN_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph
+ * @param Periphs This parameter can be a combination of the following values:
+ * @arg @ref LL_DBGMCU_APB1_GRP1_TIM2_STOP (*)
+ * @arg @ref LL_DBGMCU_APB1_GRP1_TIM3_STOP
+ * @arg @ref LL_DBGMCU_APB1_GRP1_TIM6_STOP (*)
+ * @arg @ref LL_DBGMCU_APB1_GRP1_TIM7_STOP (*)
+ * @arg @ref LL_DBGMCU_APB1_GRP1_TIM14_STOP
+ * @arg @ref LL_DBGMCU_APB1_GRP1_RTC_STOP
+ * @arg @ref LL_DBGMCU_APB1_GRP1_WWDG_STOP
+ * @arg @ref LL_DBGMCU_APB1_GRP1_IWDG_STOP
+ * @arg @ref LL_DBGMCU_APB1_GRP1_I2C1_STOP
+ * @arg @ref LL_DBGMCU_APB1_GRP1_CAN_STOP (*)
+ *
+ * (*) value not defined in all devices
+ * @retval None
+ */
+__STATIC_INLINE void LL_DBGMCU_APB1_GRP1_FreezePeriph(uint32_t Periphs)
+{
+ SET_BIT(DBGMCU->APB1FZ, Periphs);
+}
+
+/**
+ * @brief Unfreeze APB1 peripherals (group1 peripherals)
+ * @rmtoll DBGMCU_APB1FZ DBG_TIM2_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n
+ * DBGMCU_APB1FZ DBG_TIM3_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n
+ * DBGMCU_APB1FZ DBG_TIM6_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n
+ * DBGMCU_APB1FZ DBG_TIM7_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n
+ * DBGMCU_APB1FZ DBG_TIM14_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n
+ * DBGMCU_APB1FZ DBG_RTC_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n
+ * DBGMCU_APB1FZ DBG_WWDG_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n
+ * DBGMCU_APB1FZ DBG_IWDG_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n
+ * DBGMCU_APB1FZ DBG_I2C1_SMBUS_TIMEOUT LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n
+ * DBGMCU_APB1FZ DBG_CAN_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph
+ * @param Periphs This parameter can be a combination of the following values:
+ * @arg @ref LL_DBGMCU_APB1_GRP1_TIM2_STOP (*)
+ * @arg @ref LL_DBGMCU_APB1_GRP1_TIM3_STOP
+ * @arg @ref LL_DBGMCU_APB1_GRP1_TIM6_STOP (*)
+ * @arg @ref LL_DBGMCU_APB1_GRP1_TIM7_STOP (*)
+ * @arg @ref LL_DBGMCU_APB1_GRP1_TIM14_STOP
+ * @arg @ref LL_DBGMCU_APB1_GRP1_RTC_STOP
+ * @arg @ref LL_DBGMCU_APB1_GRP1_WWDG_STOP
+ * @arg @ref LL_DBGMCU_APB1_GRP1_IWDG_STOP
+ * @arg @ref LL_DBGMCU_APB1_GRP1_I2C1_STOP
+ * @arg @ref LL_DBGMCU_APB1_GRP1_CAN_STOP (*)
+ *
+ * (*) value not defined in all devices
+ * @retval None
+ */
+__STATIC_INLINE void LL_DBGMCU_APB1_GRP1_UnFreezePeriph(uint32_t Periphs)
+{
+ CLEAR_BIT(DBGMCU->APB1FZ, Periphs);
+}
+
+/**
+ * @brief Freeze APB1 peripherals (group2 peripherals)
+ * @rmtoll DBGMCU_APB2FZ DBG_TIM1_STOP LL_DBGMCU_APB1_GRP2_FreezePeriph\n
+ * DBGMCU_APB2FZ DBG_TIM15_STOP LL_DBGMCU_APB1_GRP2_FreezePeriph\n
+ * DBGMCU_APB2FZ DBG_TIM16_STOP LL_DBGMCU_APB1_GRP2_FreezePeriph\n
+ * DBGMCU_APB2FZ DBG_TIM17_STOP LL_DBGMCU_APB1_GRP2_FreezePeriph
+ * @param Periphs This parameter can be a combination of the following values:
+ * @arg @ref LL_DBGMCU_APB1_GRP2_TIM1_STOP
+ * @arg @ref LL_DBGMCU_APB1_GRP2_TIM15_STOP (*)
+ * @arg @ref LL_DBGMCU_APB1_GRP2_TIM16_STOP
+ * @arg @ref LL_DBGMCU_APB1_GRP2_TIM17_STOP
+ *
+ * (*) value not defined in all devices
+ * @retval None
+ */
+__STATIC_INLINE void LL_DBGMCU_APB1_GRP2_FreezePeriph(uint32_t Periphs)
+{
+ SET_BIT(DBGMCU->APB2FZ, Periphs);
+}
+
+/**
+ * @brief Unfreeze APB1 peripherals (group2 peripherals)
+ * @rmtoll DBGMCU_APB2FZ DBG_TIM1_STOP LL_DBGMCU_APB1_GRP2_UnFreezePeriph\n
+ * DBGMCU_APB2FZ DBG_TIM15_STOP LL_DBGMCU_APB1_GRP2_UnFreezePeriph\n
+ * DBGMCU_APB2FZ DBG_TIM16_STOP LL_DBGMCU_APB1_GRP2_UnFreezePeriph\n
+ * DBGMCU_APB2FZ DBG_TIM17_STOP LL_DBGMCU_APB1_GRP2_UnFreezePeriph
+ * @param Periphs This parameter can be a combination of the following values:
+ * @arg @ref LL_DBGMCU_APB1_GRP2_TIM1_STOP
+ * @arg @ref LL_DBGMCU_APB1_GRP2_TIM15_STOP (*)
+ * @arg @ref LL_DBGMCU_APB1_GRP2_TIM16_STOP
+ * @arg @ref LL_DBGMCU_APB1_GRP2_TIM17_STOP
+ *
+ * (*) value not defined in all devices
+ * @retval None
+ */
+__STATIC_INLINE void LL_DBGMCU_APB1_GRP2_UnFreezePeriph(uint32_t Periphs)
+{
+ CLEAR_BIT(DBGMCU->APB2FZ, Periphs);
+}
+/**
+ * @}
+ */
+
+/** @defgroup SYSTEM_LL_EF_FLASH FLASH
+ * @{
+ */
+
+/**
+ * @brief Set FLASH Latency
+ * @rmtoll FLASH_ACR LATENCY LL_FLASH_SetLatency
+ * @param Latency This parameter can be one of the following values:
+ * @arg @ref LL_FLASH_LATENCY_0
+ * @arg @ref LL_FLASH_LATENCY_1
+ * @retval None
+ */
+__STATIC_INLINE void LL_FLASH_SetLatency(uint32_t Latency)
+{
+ MODIFY_REG(FLASH->ACR, FLASH_ACR_LATENCY, Latency);
+}
+
+/**
+ * @brief Get FLASH Latency
+ * @rmtoll FLASH_ACR LATENCY LL_FLASH_GetLatency
+ * @retval Returned value can be one of the following values:
+ * @arg @ref LL_FLASH_LATENCY_0
+ * @arg @ref LL_FLASH_LATENCY_1
+ */
+__STATIC_INLINE uint32_t LL_FLASH_GetLatency(void)
+{
+ return (uint32_t)(READ_BIT(FLASH->ACR, FLASH_ACR_LATENCY));
+}
+
+/**
+ * @brief Enable Prefetch
+ * @rmtoll FLASH_ACR PRFTBE LL_FLASH_EnablePrefetch
+ * @retval None
+ */
+__STATIC_INLINE void LL_FLASH_EnablePrefetch(void)
+{
+ SET_BIT(FLASH->ACR, FLASH_ACR_PRFTBE);
+}
+
+/**
+ * @brief Disable Prefetch
+ * @rmtoll FLASH_ACR PRFTBE LL_FLASH_DisablePrefetch
+ * @retval None
+ */
+__STATIC_INLINE void LL_FLASH_DisablePrefetch(void)
+{
+ CLEAR_BIT(FLASH->ACR, FLASH_ACR_PRFTBE);
+}
+
+/**
+ * @brief Check if Prefetch buffer is enabled
+ * @rmtoll FLASH_ACR PRFTBS LL_FLASH_IsPrefetchEnabled
+ * @retval State of bit (1 or 0).
+ */
+__STATIC_INLINE uint32_t LL_FLASH_IsPrefetchEnabled(void)
+{
+ return (READ_BIT(FLASH->ACR, FLASH_ACR_PRFTBS) == (FLASH_ACR_PRFTBS));
+}
+
+
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+#endif /* defined (FLASH) || defined (SYSCFG) || defined (DBGMCU) */
+
+/**
+ * @}
+ */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __STM32F0xx_LL_SYSTEM_H */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_ll_utils.h b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_ll_utils.h
new file mode 100644
index 0000000..3b7c020
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Inc/stm32f0xx_ll_utils.h
@@ -0,0 +1,274 @@
+/**
+ ******************************************************************************
+ * @file stm32f0xx_ll_utils.h
+ * @author MCD Application Team
+ * @brief Header file of UTILS LL module.
+ @verbatim
+ ==============================================================================
+ ##### How to use this driver #####
+ ==============================================================================
+ [..]
+ The LL UTILS driver contains a set of generic APIs that can be
+ used by user:
+ (+) Device electronic signature
+ (+) Timing functions
+ (+) PLL configuration functions
+
+ @endverbatim
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2016 STMicroelectronics.
+ * All rights reserved.
+ *
+ * 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 __STM32F0xx_LL_UTILS_H
+#define __STM32F0xx_LL_UTILS_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f0xx.h"
+
+/** @addtogroup STM32F0xx_LL_Driver
+ * @{
+ */
+
+/** @defgroup UTILS_LL UTILS
+ * @{
+ */
+
+/* Private types -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+
+/* Private constants ---------------------------------------------------------*/
+/** @defgroup UTILS_LL_Private_Constants UTILS Private Constants
+ * @{
+ */
+
+/* Max delay can be used in LL_mDelay */
+#define LL_MAX_DELAY 0xFFFFFFFFU
+
+/**
+ * @brief Unique device ID register base address
+ */
+#define UID_BASE_ADDRESS UID_BASE
+
+/**
+ * @brief Flash size data register base address
+ */
+#define FLASHSIZE_BASE_ADDRESS FLASHSIZE_BASE
+
+/**
+ * @}
+ */
+
+/* Private macros ------------------------------------------------------------*/
+/** @defgroup UTILS_LL_Private_Macros UTILS Private Macros
+ * @{
+ */
+/**
+ * @}
+ */
+/* Exported types ------------------------------------------------------------*/
+/** @defgroup UTILS_LL_ES_INIT UTILS Exported structures
+ * @{
+ */
+/**
+ * @brief UTILS PLL structure definition
+ */
+typedef struct
+{
+ uint32_t PLLMul; /*!< Multiplication factor for PLL VCO input clock.
+ This parameter can be a value of @ref RCC_LL_EC_PLL_MUL
+
+ This feature can be modified afterwards using unitary function
+ @ref LL_RCC_PLL_ConfigDomain_SYS(). */
+
+#if defined(RCC_PLLSRC_PREDIV1_SUPPORT)
+ uint32_t PLLDiv; /*!< Division factor for PLL VCO output clock.
+ This parameter can be a value of @ref RCC_LL_EC_PREDIV_DIV
+
+ This feature can be modified afterwards using unitary function
+ @ref LL_RCC_PLL_ConfigDomain_SYS(). */
+#else
+ uint32_t Prediv; /*!< Division factor for HSE used as PLL clock source.
+ This parameter can be a value of @ref RCC_LL_EC_PREDIV_DIV
+
+ This feature can be modified afterwards using unitary function
+ @ref LL_RCC_PLL_ConfigDomain_SYS(). */
+#endif /* RCC_PLLSRC_PREDIV1_SUPPORT */
+} LL_UTILS_PLLInitTypeDef;
+
+/**
+ * @brief UTILS System, AHB and APB buses clock configuration structure definition
+ */
+typedef struct
+{
+ uint32_t AHBCLKDivider; /*!< The AHB clock (HCLK) divider. This clock is derived from the system clock (SYSCLK).
+ This parameter can be a value of @ref RCC_LL_EC_SYSCLK_DIV
+
+ This feature can be modified afterwards using unitary function
+ @ref LL_RCC_SetAHBPrescaler(). */
+
+ uint32_t APB1CLKDivider; /*!< The APB1 clock (PCLK1) divider. This clock is derived from the AHB clock (HCLK).
+ This parameter can be a value of @ref RCC_LL_EC_APB1_DIV
+
+ This feature can be modified afterwards using unitary function
+ @ref LL_RCC_SetAPB1Prescaler(). */
+} LL_UTILS_ClkInitTypeDef;
+
+/**
+ * @}
+ */
+
+/* Exported constants --------------------------------------------------------*/
+/** @defgroup UTILS_LL_Exported_Constants UTILS Exported Constants
+ * @{
+ */
+
+/** @defgroup UTILS_EC_HSE_BYPASS HSE Bypass activation
+ * @{
+ */
+#define LL_UTILS_HSEBYPASS_OFF 0x00000000U /*!< HSE Bypass is not enabled */
+#define LL_UTILS_HSEBYPASS_ON 0x00000001U /*!< HSE Bypass is enabled */
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/* Exported macro ------------------------------------------------------------*/
+
+/* Exported functions --------------------------------------------------------*/
+/** @defgroup UTILS_LL_Exported_Functions UTILS Exported Functions
+ * @{
+ */
+
+/** @defgroup UTILS_EF_DEVICE_ELECTRONIC_SIGNATURE DEVICE ELECTRONIC SIGNATURE
+ * @{
+ */
+
+/**
+ * @brief Get Word0 of the unique device identifier (UID based on 96 bits)
+ * @retval UID[31:0]: X and Y coordinates on the wafer expressed in BCD format
+ */
+__STATIC_INLINE uint32_t LL_GetUID_Word0(void)
+{
+ return (uint32_t)(READ_REG(*((uint32_t *)UID_BASE_ADDRESS)));
+}
+
+/**
+ * @brief Get Word1 of the unique device identifier (UID based on 96 bits)
+ * @retval UID[63:32]: Wafer number (UID[39:32]) & LOT_NUM[23:0] (UID[63:40])
+ */
+__STATIC_INLINE uint32_t LL_GetUID_Word1(void)
+{
+ return (uint32_t)(READ_REG(*((uint32_t *)(UID_BASE_ADDRESS + 4U))));
+}
+
+/**
+ * @brief Get Word2 of the unique device identifier (UID based on 96 bits)
+ * @retval UID[95:64]: Lot number (ASCII encoded) - LOT_NUM[55:24]
+ */
+__STATIC_INLINE uint32_t LL_GetUID_Word2(void)
+{
+ return (uint32_t)(READ_REG(*((uint32_t *)(UID_BASE_ADDRESS + 8U))));
+}
+
+/**
+ * @brief Get Flash memory size
+ * @note This bitfield indicates the size of the device Flash memory expressed in
+ * Kbytes. As an example, 0x040 corresponds to 64 Kbytes.
+ * @retval FLASH_SIZE[15:0]: Flash memory size
+ */
+__STATIC_INLINE uint32_t LL_GetFlashSize(void)
+{
+ return (uint16_t)(READ_REG(*((uint32_t *)FLASHSIZE_BASE_ADDRESS)));
+}
+
+
+/**
+ * @}
+ */
+
+/** @defgroup UTILS_LL_EF_DELAY DELAY
+ * @{
+ */
+
+/**
+ * @brief This function configures the Cortex-M SysTick source of the time base.
+ * @param HCLKFrequency HCLK frequency in Hz (can be calculated thanks to RCC helper macro)
+ * @note When a RTOS is used, it is recommended to avoid changing the SysTick
+ * configuration by calling this function, for a delay use rather osDelay RTOS service.
+ * @param Ticks Number of ticks
+ * @retval None
+ */
+__STATIC_INLINE void LL_InitTick(uint32_t HCLKFrequency, uint32_t Ticks)
+{
+ /* Configure the SysTick to have interrupt in 1ms time base */
+ SysTick->LOAD = (uint32_t)((HCLKFrequency / Ticks) - 1UL); /* set reload register */
+ SysTick->VAL = 0UL; /* Load the SysTick Counter Value */
+ SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk |
+ SysTick_CTRL_ENABLE_Msk; /* Enable the Systick Timer */
+}
+
+void LL_Init1msTick(uint32_t HCLKFrequency);
+void LL_mDelay(uint32_t Delay);
+
+/**
+ * @}
+ */
+
+/** @defgroup UTILS_EF_SYSTEM SYSTEM
+ * @{
+ */
+
+void LL_SetSystemCoreClock(uint32_t HCLKFrequency);
+#if defined(FLASH_ACR_LATENCY)
+ErrorStatus LL_SetFlashLatency(uint32_t Frequency);
+#endif /* FLASH_ACR_LATENCY */
+ErrorStatus LL_PLL_ConfigSystemClock_HSI(LL_UTILS_PLLInitTypeDef *UTILS_PLLInitStruct,
+ LL_UTILS_ClkInitTypeDef *UTILS_ClkInitStruct);
+#if defined(RCC_CFGR_SW_HSI48)
+ErrorStatus LL_PLL_ConfigSystemClock_HSI48(LL_UTILS_PLLInitTypeDef *UTILS_PLLInitStruct,
+ LL_UTILS_ClkInitTypeDef *UTILS_ClkInitStruct);
+#endif /*RCC_CFGR_SW_HSI48*/
+ErrorStatus LL_PLL_ConfigSystemClock_HSE(uint32_t HSEFrequency, uint32_t HSEBypass,
+ LL_UTILS_PLLInitTypeDef *UTILS_PLLInitStruct, LL_UTILS_ClkInitTypeDef *UTILS_ClkInitStruct);
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __STM32F0xx_LL_UTILS_H */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/License.md b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/License.md
new file mode 100644
index 0000000..017be72
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/License.md
@@ -0,0 +1,3 @@
+# Copyright (c) 2016 STMicroelectronics
+
+This software component is licensed by STMicroelectronics under the **BSD 3-Clause** license. You may not use this file except in compliance with this license. You may obtain a copy of the license [here](https://opensource.org/licenses/BSD-3-Clause).
\ No newline at end of file
diff --git a/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal.c b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal.c
new file mode 100644
index 0000000..940c0ca
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal.c
@@ -0,0 +1,514 @@
+/**
+ ******************************************************************************
+ * @file stm32f0xx_hal.c
+ * @author MCD Application Team
+ * @brief HAL module driver.
+ * This is the common part of the HAL initialization
+ *
+ @verbatim
+ ==============================================================================
+ ##### How to use this driver #####
+ ==============================================================================
+ [..]
+ The common HAL driver contains a set of generic and common APIs that can be
+ used by the PPP peripheral drivers and the user to start using the HAL.
+ [..]
+ The HAL contains two APIs categories:
+ (+) HAL Initialization and de-initialization functions
+ (+) HAL Control functions
+
+ @endverbatim
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2016 STMicroelectronics.
+ * All rights reserved.
+ *
+ * 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 "stm32f0xx_hal.h"
+
+/** @addtogroup STM32F0xx_HAL_Driver
+ * @{
+ */
+
+/** @defgroup HAL HAL
+ * @brief HAL module driver.
+ * @{
+ */
+
+#ifdef HAL_MODULE_ENABLED
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/** @defgroup HAL_Private_Constants HAL Private Constants
+ * @{
+ */
+/**
+ * @brief STM32F0xx HAL Driver version number V1.7.6
+ */
+#define __STM32F0xx_HAL_VERSION_MAIN (0x01U) /*!< [31:24] main version */
+#define __STM32F0xx_HAL_VERSION_SUB1 (0x07U) /*!< [23:16] sub1 version */
+#define __STM32F0xx_HAL_VERSION_SUB2 (0x06U) /*!< [15:8] sub2 version */
+#define __STM32F0xx_HAL_VERSION_RC (0x00U) /*!< [7:0] release candidate */
+#define __STM32F0xx_HAL_VERSION ((__STM32F0xx_HAL_VERSION_MAIN << 24U)\
+ |(__STM32F0xx_HAL_VERSION_SUB1 << 16U)\
+ |(__STM32F0xx_HAL_VERSION_SUB2 << 8U )\
+ |(__STM32F0xx_HAL_VERSION_RC))
+
+#define IDCODE_DEVID_MASK (0x00000FFFU)
+/**
+ * @}
+ */
+
+/* Private macro -------------------------------------------------------------*/
+/** @defgroup HAL_Private_Macros HAL Private Macros
+ * @{
+ */
+/**
+ * @}
+ */
+
+/* Exported variables ---------------------------------------------------------*/
+/** @defgroup HAL_Private_Variables HAL Exported Variables
+ * @{
+ */
+__IO uint32_t uwTick;
+uint32_t uwTickPrio = (1UL << __NVIC_PRIO_BITS); /* Invalid PRIO */
+HAL_TickFreqTypeDef uwTickFreq = HAL_TICK_FREQ_DEFAULT; /* 1KHz */
+/**
+ * @}
+ */
+/* Private function prototypes -----------------------------------------------*/
+/* Exported functions ---------------------------------------------------------*/
+
+/** @defgroup HAL_Exported_Functions HAL Exported Functions
+ * @{
+ */
+
+/** @defgroup HAL_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:
+ (+) Initializes the Flash interface, the NVIC allocation and initial clock
+ configuration. It initializes the systick also when timeout is needed
+ and the backup domain when enabled.
+ (+) de-Initializes common part of the HAL.
+ (+) Configure The time base source to have 1ms time base with a dedicated
+ Tick interrupt priority.
+ (++) SysTick timer is used by default as source of time base, but user
+ can eventually implement his proper time base source (a general purpose
+ timer for example or other time source), keeping in mind that Time base
+ duration should be kept 1ms since PPP_TIMEOUT_VALUEs are defined and
+ handled in milliseconds basis.
+ (++) Time base configuration function (HAL_InitTick ()) is called automatically
+ at the beginning of the program after reset by HAL_Init() or at any time
+ when clock is configured, by HAL_RCC_ClockConfig().
+ (++) Source of time base is configured to generate interrupts at regular
+ time intervals. Care must be taken if HAL_Delay() is called from a
+ peripheral ISR process, the Tick interrupt line must have higher priority
+ (numerically lower) than the peripheral interrupt. Otherwise the caller
+ ISR process will be blocked.
+ (++) functions affecting time base configurations are declared as __Weak
+ to make override possible in case of other implementations in user file.
+
+@endverbatim
+ * @{
+ */
+
+/**
+ * @brief This function configures the Flash prefetch,
+ * Configures time base source, NVIC and Low level hardware
+ * @note This function is called at the beginning of program after reset and before
+ * the clock configuration
+ * @note The time base configuration is based on HSI clock when exiting from Reset.
+ * Once done, time base tick start incrementing.
+ * In the default implementation,Systick is used as source of time base.
+ * The tick variable is incremented each 1ms in its ISR.
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_Init(void)
+{
+ /* Configure Flash prefetch */
+#if (PREFETCH_ENABLE != 0)
+ __HAL_FLASH_PREFETCH_BUFFER_ENABLE();
+#endif /* PREFETCH_ENABLE */
+
+ /* Use systick as time base source and configure 1ms tick (default clock after Reset is HSI) */
+
+ HAL_InitTick(TICK_INT_PRIORITY);
+
+ /* Init the low level hardware */
+ HAL_MspInit();
+
+ /* Return function status */
+ return HAL_OK;
+}
+
+/**
+ * @brief This function de-Initialize common part of the HAL and stops the SysTick
+ * of time base.
+ * @note This function is optional.
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_DeInit(void)
+{
+ /* Reset of all peripherals */
+ __HAL_RCC_APB1_FORCE_RESET();
+ __HAL_RCC_APB1_RELEASE_RESET();
+
+ __HAL_RCC_APB2_FORCE_RESET();
+ __HAL_RCC_APB2_RELEASE_RESET();
+
+ __HAL_RCC_AHB_FORCE_RESET();
+ __HAL_RCC_AHB_RELEASE_RESET();
+
+ /* De-Init the low level hardware */
+ HAL_MspDeInit();
+
+ /* Return function status */
+ return HAL_OK;
+}
+
+/**
+ * @brief Initialize the MSP.
+ * @retval None
+ */
+__weak void HAL_MspInit(void)
+{
+ /* NOTE : This function should not be modified, when the callback is needed,
+ the HAL_MspInit could be implemented in the user file
+ */
+}
+
+/**
+ * @brief DeInitializes the MSP.
+ * @retval None
+ */
+__weak void HAL_MspDeInit(void)
+{
+ /* NOTE : This function should not be modified, when the callback is needed,
+ the HAL_MspDeInit could be implemented in the user file
+ */
+}
+
+/**
+ * @brief This function configures the source of the time base.
+ * The time source is configured to have 1ms time base with a dedicated
+ * Tick interrupt priority.
+ * @note This function is called automatically at the beginning of program after
+ * reset by HAL_Init() or at any time when clock is reconfigured by HAL_RCC_ClockConfig().
+ * @note In the default implementation, SysTick timer is the source of time base.
+ * It is used to generate interrupts at regular time intervals.
+ * Care must be taken if HAL_Delay() is called from a peripheral ISR process,
+ * The SysTick interrupt must have higher priority (numerically lower)
+ * than the peripheral interrupt. Otherwise the caller ISR process will be blocked.
+ * The function is declared as __Weak to be overwritten in case of other
+ * implementation in user file.
+ * @param TickPriority Tick interrupt priority.
+ * @retval HAL status
+ */
+__weak HAL_StatusTypeDef HAL_InitTick(uint32_t TickPriority)
+{
+ /*Configure the SysTick to have interrupt in 1ms time basis*/
+ if (HAL_SYSTICK_Config(SystemCoreClock / (1000U / uwTickFreq)) > 0U)
+ {
+ return HAL_ERROR;
+ }
+
+ /* Configure the SysTick IRQ priority */
+ if (TickPriority < (1UL << __NVIC_PRIO_BITS))
+ {
+ HAL_NVIC_SetPriority(SysTick_IRQn, TickPriority, 0U);
+ uwTickPrio = TickPriority;
+ }
+ else
+ {
+ return HAL_ERROR;
+ }
+
+ /* Return function status */
+ return HAL_OK;
+}
+
+/**
+ * @}
+ */
+
+/** @defgroup HAL_Exported_Functions_Group2 HAL Control functions
+ * @brief HAL Control functions
+ *
+@verbatim
+ ===============================================================================
+ ##### HAL Control functions #####
+ ===============================================================================
+ [..] This section provides functions allowing to:
+ (+) Provide a tick value in millisecond
+ (+) Provide a blocking delay in millisecond
+ (+) Suspend the time base source interrupt
+ (+) Resume the time base source interrupt
+ (+) Get the HAL API driver version
+ (+) Get the device identifier
+ (+) Get the device revision identifier
+ (+) Enable/Disable Debug module during Sleep mode
+ (+) Enable/Disable Debug module during STOP mode
+ (+) Enable/Disable Debug module during STANDBY mode
+
+@endverbatim
+ * @{
+ */
+
+/**
+ * @brief This function is called to increment a global variable "uwTick"
+ * used as application time base.
+ * @note In the default implementation, this variable is incremented each 1ms
+ * in SysTick ISR.
+ * @note This function is declared as __weak to be overwritten in case of other
+ * implementations in user file.
+ * @retval None
+ */
+__weak void HAL_IncTick(void)
+{
+ uwTick += uwTickFreq;
+}
+
+/**
+ * @brief Provides a tick value in millisecond.
+ * @note This function is declared as __weak to be overwritten in case of other
+ * implementations in user file.
+ * @retval tick value
+ */
+__weak uint32_t HAL_GetTick(void)
+{
+ return uwTick;
+}
+
+/**
+ * @brief This function returns a tick priority.
+ * @retval tick priority
+ */
+uint32_t HAL_GetTickPrio(void)
+{
+ return uwTickPrio;
+}
+
+/**
+ * @brief Set new tick Freq.
+ * @retval status
+ */
+HAL_StatusTypeDef HAL_SetTickFreq(HAL_TickFreqTypeDef Freq)
+{
+ HAL_StatusTypeDef status = HAL_OK;
+ HAL_TickFreqTypeDef prevTickFreq;
+
+ assert_param(IS_TICKFREQ(Freq));
+
+ if (uwTickFreq != Freq)
+ {
+ /* Back up uwTickFreq frequency */
+ prevTickFreq = uwTickFreq;
+
+ /* Update uwTickFreq global variable used by HAL_InitTick() */
+ uwTickFreq = Freq;
+
+ /* Apply the new tick Freq */
+ status = HAL_InitTick(uwTickPrio);
+
+ if (status != HAL_OK)
+ {
+ /* Restore previous tick frequency */
+ uwTickFreq = prevTickFreq;
+ }
+ }
+
+ return status;
+}
+
+/**
+ * @brief return tick frequency.
+ * @retval tick period in Hz
+ */
+HAL_TickFreqTypeDef HAL_GetTickFreq(void)
+{
+ return uwTickFreq;
+}
+
+/**
+ * @brief This function provides accurate delay (in milliseconds) based
+ * on variable incremented.
+ * @note In the default implementation , SysTick timer is the source of time base.
+ * It is used to generate interrupts at regular time intervals where uwTick
+ * is incremented.
+ * @note ThiS function is declared as __weak to be overwritten in case of other
+ * implementations in user file.
+ * @param Delay specifies the delay time length, in milliseconds.
+ * @retval None
+ */
+__weak void HAL_Delay(uint32_t Delay)
+{
+ uint32_t tickstart = HAL_GetTick();
+ uint32_t wait = Delay;
+
+ /* Add a freq to guarantee minimum wait */
+ if (wait < HAL_MAX_DELAY)
+ {
+ wait += (uint32_t)(uwTickFreq);
+ }
+
+ while((HAL_GetTick() - tickstart) < wait)
+ {
+ }
+}
+
+/**
+ * @brief Suspend Tick increment.
+ * @note In the default implementation , SysTick timer is the source of time base. It is
+ * used to generate interrupts at regular time intervals. Once HAL_SuspendTick()
+ * is called, the the SysTick interrupt will be disabled and so Tick increment
+ * is suspended.
+ * @note This function is declared as __weak to be overwritten in case of other
+ * implementations in user file.
+ * @retval None
+ */
+__weak void HAL_SuspendTick(void)
+
+{
+ /* Disable SysTick Interrupt */
+ CLEAR_BIT(SysTick->CTRL,SysTick_CTRL_TICKINT_Msk);
+}
+
+/**
+ * @brief Resume Tick increment.
+ * @note In the default implementation , SysTick timer is the source of time base. It is
+ * used to generate interrupts at regular time intervals. Once HAL_ResumeTick()
+ * is called, the the SysTick interrupt will be enabled and so Tick increment
+ * is resumed.
+ * @note This function is declared as __weak to be overwritten in case of other
+ * implementations in user file.
+ * @retval None
+ */
+__weak void HAL_ResumeTick(void)
+{
+ /* Enable SysTick Interrupt */
+ SET_BIT(SysTick->CTRL,SysTick_CTRL_TICKINT_Msk);
+}
+
+/**
+ * @brief This method returns the HAL revision
+ * @retval version 0xXYZR (8bits for each decimal, R for RC)
+ */
+uint32_t HAL_GetHalVersion(void)
+{
+ return __STM32F0xx_HAL_VERSION;
+}
+
+/**
+ * @brief Returns the device revision identifier.
+ * @retval Device revision identifier
+ */
+uint32_t HAL_GetREVID(void)
+{
+ return((DBGMCU->IDCODE) >> 16U);
+}
+
+/**
+ * @brief Returns the device identifier.
+ * @retval Device identifier
+ */
+uint32_t HAL_GetDEVID(void)
+{
+ return((DBGMCU->IDCODE) & IDCODE_DEVID_MASK);
+}
+
+/**
+ * @brief Returns first word of the unique device identifier (UID based on 96 bits)
+ * @retval Device identifier
+ */
+uint32_t HAL_GetUIDw0(void)
+{
+ return(READ_REG(*((uint32_t *)UID_BASE)));
+}
+
+/**
+ * @brief Returns second word of the unique device identifier (UID based on 96 bits)
+ * @retval Device identifier
+ */
+uint32_t HAL_GetUIDw1(void)
+{
+ return(READ_REG(*((uint32_t *)(UID_BASE + 4U))));
+}
+
+/**
+ * @brief Returns third word of the unique device identifier (UID based on 96 bits)
+ * @retval Device identifier
+ */
+uint32_t HAL_GetUIDw2(void)
+{
+ return(READ_REG(*((uint32_t *)(UID_BASE + 8U))));
+}
+
+/**
+ * @brief Enable the Debug Module during STOP mode
+ * @retval None
+ */
+void HAL_DBGMCU_EnableDBGStopMode(void)
+{
+ SET_BIT(DBGMCU->CR, DBGMCU_CR_DBG_STOP);
+}
+
+/**
+ * @brief Disable the Debug Module during STOP mode
+ * @retval None
+ */
+void HAL_DBGMCU_DisableDBGStopMode(void)
+{
+ CLEAR_BIT(DBGMCU->CR, DBGMCU_CR_DBG_STOP);
+}
+
+/**
+ * @brief Enable the Debug Module during STANDBY mode
+ * @retval None
+ */
+void HAL_DBGMCU_EnableDBGStandbyMode(void)
+{
+ SET_BIT(DBGMCU->CR, DBGMCU_CR_DBG_STANDBY);
+}
+
+/**
+ * @brief Disable the Debug Module during STANDBY mode
+ * @retval None
+ */
+void HAL_DBGMCU_DisableDBGStandbyMode(void)
+{
+ CLEAR_BIT(DBGMCU->CR, DBGMCU_CR_DBG_STANDBY);
+}
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+#endif /* HAL_MODULE_ENABLED */
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_cortex.c b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_cortex.c
new file mode 100644
index 0000000..157426e
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_cortex.c
@@ -0,0 +1,341 @@
+/**
+ ******************************************************************************
+ * @file stm32f0xx_hal_cortex.c
+ * @author MCD Application Team
+ * @brief CORTEX HAL module driver.
+ * This file provides firmware functions to manage the following
+ * functionalities of the CORTEX:
+ * + Initialization and de-initialization functions
+ * + Peripheral Control functions
+ *
+ * @verbatim
+ ==============================================================================
+ ##### How to use this driver #####
+ ==============================================================================
+
+ [..]
+ *** How to configure Interrupts using CORTEX HAL driver ***
+ ===========================================================
+ [..]
+ This section provides functions allowing to configure the NVIC interrupts (IRQ).
+ The Cortex-M0 exceptions are managed by CMSIS functions.
+ (#) Enable and Configure the priority of the selected IRQ Channels.
+ The priority can be 0..3.
+
+ -@- Lower priority values gives higher priority.
+ -@- Priority Order:
+ (#@) Lowest priority.
+ (#@) Lowest hardware priority (IRQn position).
+
+ (#) Configure the priority of the selected IRQ Channels using HAL_NVIC_SetPriority()
+
+ (#) Enable the selected IRQ Channels using HAL_NVIC_EnableIRQ()
+
+ -@- Negative value of IRQn_Type are not allowed.
+
+
+ [..]
+ *** How to configure Systick using CORTEX HAL driver ***
+ ========================================================
+ [..]
+ Setup SysTick Timer for time base.
+
+ (+) The HAL_SYSTICK_Config()function calls the SysTick_Config() function which
+ is a CMSIS function that:
+ (++) Configures the SysTick Reload register with value passed as function parameter.
+ (++) Configures the SysTick IRQ priority to the lowest value (0x03).
+ (++) Resets the SysTick Counter register.
+ (++) Configures the SysTick Counter clock source to be Core Clock Source (HCLK).
+ (++) Enables the SysTick Interrupt.
+ (++) Starts the SysTick Counter.
+
+ (+) You can change the SysTick Clock source to be HCLK_Div8 by calling the macro
+ HAL_SYSTICK_CLKSourceConfig(SYSTICK_CLKSOURCE_HCLK_DIV8) just after the
+ HAL_SYSTICK_Config() function call. The HAL_SYSTICK_CLKSourceConfig() macro is defined
+ inside the stm32f0xx_hal_cortex.h file.
+
+ (+) You can change the SysTick IRQ priority by calling the
+ HAL_NVIC_SetPriority(SysTick_IRQn,...) function just after the HAL_SYSTICK_Config() function
+ call. The HAL_NVIC_SetPriority() call the NVIC_SetPriority() function which is a CMSIS function.
+
+ (+) To adjust the SysTick time base, use the following formula:
+
+ Reload Value = SysTick Counter Clock (Hz) x Desired Time base (s)
+ (++) Reload Value is the parameter to be passed for HAL_SYSTICK_Config() function
+ (++) Reload Value should not exceed 0xFFFFFF
+
+ @endverbatim
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2016 STMicroelectronics.
+ * All rights reserved.
+ *
+ * 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 "stm32f0xx_hal.h"
+
+/** @addtogroup STM32F0xx_HAL_Driver
+ * @{
+ */
+
+/** @defgroup CORTEX CORTEX
+ * @brief CORTEX CORTEX HAL module driver
+ * @{
+ */
+
+#ifdef HAL_CORTEX_MODULE_ENABLED
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Exported functions ---------------------------------------------------------*/
+
+/** @defgroup CORTEX_Exported_Functions CORTEX Exported Functions
+ * @{
+ */
+
+
+/** @defgroup CORTEX_Exported_Functions_Group1 Initialization and de-initialization functions
+ * @brief Initialization and Configuration functions
+ *
+@verbatim
+ ==============================================================================
+ ##### Initialization and de-initialization functions #####
+ ==============================================================================
+ [..]
+ This section provides the CORTEX HAL driver functions allowing to configure Interrupts
+ Systick functionalities
+
+@endverbatim
+ * @{
+ */
+
+/**
+ * @brief Sets the priority of an interrupt.
+ * @param IRQn External interrupt number .
+ * This parameter can be an enumerator of IRQn_Type enumeration
+ * (For the complete STM32 Devices IRQ Channels list, please refer to stm32f0xx.h file)
+ * @param PreemptPriority The preemption priority for the IRQn channel.
+ * This parameter can be a value between 0 and 3.
+ * A lower priority value indicates a higher priority
+ * @param SubPriority the subpriority level for the IRQ channel.
+ * with stm32f0xx devices, this parameter is a dummy value and it is ignored, because
+ * no subpriority supported in Cortex M0 based products.
+ * @retval None
+ */
+void HAL_NVIC_SetPriority(IRQn_Type IRQn, uint32_t PreemptPriority, uint32_t SubPriority)
+{
+ /* Check the parameters */
+ assert_param(IS_NVIC_PREEMPTION_PRIORITY(PreemptPriority));
+ NVIC_SetPriority(IRQn,PreemptPriority);
+}
+
+/**
+ * @brief Enables a device specific interrupt in the NVIC interrupt controller.
+ * @note To configure interrupts priority correctly, the NVIC_PriorityGroupConfig()
+ * function should be called before.
+ * @param IRQn External interrupt number.
+ * This parameter can be an enumerator of IRQn_Type enumeration
+ * (For the complete STM32 Devices IRQ Channels list, please refer to the appropriate CMSIS device file (stm32f0xxxx.h))
+ * @retval None
+ */
+void HAL_NVIC_EnableIRQ(IRQn_Type IRQn)
+{
+ /* Check the parameters */
+ assert_param(IS_NVIC_DEVICE_IRQ(IRQn));
+
+ /* Enable interrupt */
+ NVIC_EnableIRQ(IRQn);
+}
+
+/**
+ * @brief Disables a device specific interrupt in the NVIC interrupt controller.
+ * @param IRQn External interrupt number.
+ * This parameter can be an enumerator of IRQn_Type enumeration
+ * (For the complete STM32 Devices IRQ Channels list, please refer to the appropriate CMSIS device file (stm32f0xxxx.h))
+ * @retval None
+ */
+void HAL_NVIC_DisableIRQ(IRQn_Type IRQn)
+{
+ /* Check the parameters */
+ assert_param(IS_NVIC_DEVICE_IRQ(IRQn));
+
+ /* Disable interrupt */
+ NVIC_DisableIRQ(IRQn);
+}
+
+/**
+ * @brief Initiates a system reset request to reset the MCU.
+ * @retval None
+ */
+void HAL_NVIC_SystemReset(void)
+{
+ /* System Reset */
+ NVIC_SystemReset();
+}
+
+/**
+ * @brief Initializes the System Timer and its interrupt, and starts the System Tick Timer.
+ * Counter is in free running mode to generate periodic interrupts.
+ * @param TicksNumb Specifies the ticks Number of ticks between two interrupts.
+ * @retval status: - 0 Function succeeded.
+ * - 1 Function failed.
+ */
+uint32_t HAL_SYSTICK_Config(uint32_t TicksNumb)
+{
+ return SysTick_Config(TicksNumb);
+}
+/**
+ * @}
+ */
+
+/** @defgroup CORTEX_Exported_Functions_Group2 Peripheral Control functions
+ * @brief Cortex control functions
+ *
+@verbatim
+ ==============================================================================
+ ##### Peripheral Control functions #####
+ ==============================================================================
+ [..]
+ This subsection provides a set of functions allowing to control the CORTEX
+ (NVIC, SYSTICK) functionalities.
+
+
+@endverbatim
+ * @{
+ */
+
+
+/**
+ * @brief Gets the priority of an interrupt.
+ * @param IRQn External interrupt number.
+ * This parameter can be an enumerator of IRQn_Type enumeration
+ * (For the complete STM32 Devices IRQ Channels list, please refer to the appropriate CMSIS device file (stm32f0xxxx.h))
+ * @retval None
+ */
+uint32_t HAL_NVIC_GetPriority(IRQn_Type IRQn)
+{
+ /* Get priority for Cortex-M system or device specific interrupts */
+ return NVIC_GetPriority(IRQn);
+}
+
+/**
+ * @brief Sets Pending bit of an external interrupt.
+ * @param IRQn External interrupt number
+ * This parameter can be an enumerator of IRQn_Type enumeration
+ * (For the complete STM32 Devices IRQ Channels list, please refer to the appropriate CMSIS device file (stm32f0xxxx.h))
+ * @retval None
+ */
+void HAL_NVIC_SetPendingIRQ(IRQn_Type IRQn)
+{
+ /* Check the parameters */
+ assert_param(IS_NVIC_DEVICE_IRQ(IRQn));
+
+ /* Set interrupt pending */
+ NVIC_SetPendingIRQ(IRQn);
+}
+
+/**
+ * @brief Gets Pending Interrupt (reads the pending register in the NVIC
+ * and returns the pending bit for the specified interrupt).
+ * @param IRQn External interrupt number.
+ * This parameter can be an enumerator of IRQn_Type enumeration
+ * (For the complete STM32 Devices IRQ Channels list, please refer to the appropriate CMSIS device file (stm32f0xxxx.h))
+ * @retval status: - 0 Interrupt status is not pending.
+ * - 1 Interrupt status is pending.
+ */
+uint32_t HAL_NVIC_GetPendingIRQ(IRQn_Type IRQn)
+{
+ /* Check the parameters */
+ assert_param(IS_NVIC_DEVICE_IRQ(IRQn));
+
+ /* Return 1 if pending else 0 */
+ return NVIC_GetPendingIRQ(IRQn);
+}
+
+/**
+ * @brief Clears the pending bit of an external interrupt.
+ * @param IRQn External interrupt number.
+ * This parameter can be an enumerator of IRQn_Type enumeration
+ * (For the complete STM32 Devices IRQ Channels list, please refer to the appropriate CMSIS device file (stm32f0xxxx.h))
+ * @retval None
+ */
+void HAL_NVIC_ClearPendingIRQ(IRQn_Type IRQn)
+{
+ /* Check the parameters */
+ assert_param(IS_NVIC_DEVICE_IRQ(IRQn));
+
+ /* Clear pending interrupt */
+ NVIC_ClearPendingIRQ(IRQn);
+}
+
+/**
+ * @brief Configures the SysTick clock source.
+ * @param CLKSource specifies the SysTick clock source.
+ * This parameter can be one of the following values:
+ * @arg SYSTICK_CLKSOURCE_HCLK_DIV8: AHB clock divided by 8 selected as SysTick clock source.
+ * @arg SYSTICK_CLKSOURCE_HCLK: AHB clock selected as SysTick clock source.
+ * @retval None
+ */
+void HAL_SYSTICK_CLKSourceConfig(uint32_t CLKSource)
+{
+ /* Check the parameters */
+ assert_param(IS_SYSTICK_CLK_SOURCE(CLKSource));
+ if (CLKSource == SYSTICK_CLKSOURCE_HCLK)
+ {
+ SysTick->CTRL |= SYSTICK_CLKSOURCE_HCLK;
+ }
+ else
+ {
+ SysTick->CTRL &= ~SYSTICK_CLKSOURCE_HCLK;
+ }
+}
+
+/**
+ * @brief This function handles SYSTICK interrupt request.
+ * @retval None
+ */
+void HAL_SYSTICK_IRQHandler(void)
+{
+ HAL_SYSTICK_Callback();
+}
+
+/**
+ * @brief SYSTICK callback.
+ * @retval None
+ */
+__weak void HAL_SYSTICK_Callback(void)
+{
+ /* NOTE : This function Should not be modified, when the callback is needed,
+ the HAL_SYSTICK_Callback could be implemented in the user file
+ */
+}
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+#endif /* HAL_CORTEX_MODULE_ENABLED */
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_crc.c b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_crc.c
new file mode 100644
index 0000000..7d72a93
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_crc.c
@@ -0,0 +1,520 @@
+/**
+ ******************************************************************************
+ * @file stm32f0xx_hal_crc.c
+ * @author MCD Application Team
+ * @brief CRC HAL module driver.
+ * This file provides firmware functions to manage the following
+ * functionalities of the Cyclic Redundancy Check (CRC) peripheral:
+ * + Initialization and de-initialization functions
+ * + Peripheral Control functions
+ * + Peripheral State functions
+ *
+ @verbatim
+ ===============================================================================
+ ##### How to use this driver #####
+ ===============================================================================
+ [..]
+ (+) Enable CRC AHB clock using __HAL_RCC_CRC_CLK_ENABLE();
+ (+) Initialize CRC calculator
+ (++) specify generating polynomial (peripheral default or non-default one)
+ (++) specify initialization value (peripheral default or non-default one)
+ (++) specify input data format
+ (++) specify input or output data inversion mode if any
+ (+) Use HAL_CRC_Accumulate() function to compute the CRC value of the
+ input data buffer starting with the previously computed CRC as
+ initialization value
+ (+) Use HAL_CRC_Calculate() function to compute the CRC value of the
+ input data buffer starting with the defined initialization value
+ (default or non-default) to initiate CRC calculation
+
+ @endverbatim
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2016 STMicroelectronics.
+ * All rights reserved.
+ *
+ * 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 "stm32f0xx_hal.h"
+
+/** @addtogroup STM32F0xx_HAL_Driver
+ * @{
+ */
+
+/** @defgroup CRC CRC
+ * @brief CRC HAL module driver.
+ * @{
+ */
+
+#ifdef HAL_CRC_MODULE_ENABLED
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/** @defgroup CRC_Private_Functions CRC Private Functions
+ * @{
+ */
+static uint32_t CRC_Handle_8(CRC_HandleTypeDef *hcrc, uint8_t pBuffer[], uint32_t BufferLength);
+static uint32_t CRC_Handle_16(CRC_HandleTypeDef *hcrc, uint16_t pBuffer[], uint32_t BufferLength);
+/**
+ * @}
+ */
+
+/* Exported functions --------------------------------------------------------*/
+
+/** @defgroup CRC_Exported_Functions CRC Exported Functions
+ * @{
+ */
+
+/** @defgroup CRC_Exported_Functions_Group1 Initialization and de-initialization functions
+ * @brief Initialization and Configuration functions.
+ *
+@verbatim
+ ===============================================================================
+ ##### Initialization and de-initialization functions #####
+ ===============================================================================
+ [..] This section provides functions allowing to:
+ (+) Initialize the CRC according to the specified parameters
+ in the CRC_InitTypeDef and create the associated handle
+ (+) DeInitialize the CRC peripheral
+ (+) Initialize the CRC MSP (MCU Specific Package)
+ (+) DeInitialize the CRC MSP
+
+@endverbatim
+ * @{
+ */
+
+/**
+ * @brief Initialize the CRC according to the specified
+ * parameters in the CRC_InitTypeDef and create the associated handle.
+ * @param hcrc CRC handle
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_CRC_Init(CRC_HandleTypeDef *hcrc)
+{
+ /* Check the CRC handle allocation */
+ if (hcrc == NULL)
+ {
+ return HAL_ERROR;
+ }
+
+ /* Check the parameters */
+ assert_param(IS_CRC_ALL_INSTANCE(hcrc->Instance));
+
+ if (hcrc->State == HAL_CRC_STATE_RESET)
+ {
+ /* Allocate lock resource and initialize it */
+ hcrc->Lock = HAL_UNLOCKED;
+ /* Init the low level hardware */
+ HAL_CRC_MspInit(hcrc);
+ }
+
+ hcrc->State = HAL_CRC_STATE_BUSY;
+
+#if defined(CRC_POL_POL)
+ /* check whether or not non-default generating polynomial has been
+ * picked up by user */
+ assert_param(IS_DEFAULT_POLYNOMIAL(hcrc->Init.DefaultPolynomialUse));
+ if (hcrc->Init.DefaultPolynomialUse == DEFAULT_POLYNOMIAL_ENABLE)
+ {
+ /* initialize peripheral with default generating polynomial */
+ WRITE_REG(hcrc->Instance->POL, DEFAULT_CRC32_POLY);
+ MODIFY_REG(hcrc->Instance->CR, CRC_CR_POLYSIZE, CRC_POLYLENGTH_32B);
+ }
+ else
+ {
+ /* initialize CRC peripheral with generating polynomial defined by user */
+ if (HAL_CRCEx_Polynomial_Set(hcrc, hcrc->Init.GeneratingPolynomial, hcrc->Init.CRCLength) != HAL_OK)
+ {
+ return HAL_ERROR;
+ }
+ }
+#endif /* CRC_POL_POL */
+
+ /* check whether or not non-default CRC initial value has been
+ * picked up by user */
+ assert_param(IS_DEFAULT_INIT_VALUE(hcrc->Init.DefaultInitValueUse));
+ if (hcrc->Init.DefaultInitValueUse == DEFAULT_INIT_VALUE_ENABLE)
+ {
+ WRITE_REG(hcrc->Instance->INIT, DEFAULT_CRC_INITVALUE);
+ }
+ else
+ {
+ WRITE_REG(hcrc->Instance->INIT, hcrc->Init.InitValue);
+ }
+
+
+ /* set input data inversion mode */
+ assert_param(IS_CRC_INPUTDATA_INVERSION_MODE(hcrc->Init.InputDataInversionMode));
+ MODIFY_REG(hcrc->Instance->CR, CRC_CR_REV_IN, hcrc->Init.InputDataInversionMode);
+
+ /* set output data inversion mode */
+ assert_param(IS_CRC_OUTPUTDATA_INVERSION_MODE(hcrc->Init.OutputDataInversionMode));
+ MODIFY_REG(hcrc->Instance->CR, CRC_CR_REV_OUT, hcrc->Init.OutputDataInversionMode);
+
+ /* makes sure the input data format (bytes, halfwords or words stream)
+ * is properly specified by user */
+ assert_param(IS_CRC_INPUTDATA_FORMAT(hcrc->InputDataFormat));
+
+ /* Change CRC peripheral state */
+ hcrc->State = HAL_CRC_STATE_READY;
+
+ /* Return function status */
+ return HAL_OK;
+}
+
+/**
+ * @brief DeInitialize the CRC peripheral.
+ * @param hcrc CRC handle
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_CRC_DeInit(CRC_HandleTypeDef *hcrc)
+{
+ /* Check the CRC handle allocation */
+ if (hcrc == NULL)
+ {
+ return HAL_ERROR;
+ }
+
+ /* Check the parameters */
+ assert_param(IS_CRC_ALL_INSTANCE(hcrc->Instance));
+
+ /* Check the CRC peripheral state */
+ if (hcrc->State == HAL_CRC_STATE_BUSY)
+ {
+ return HAL_BUSY;
+ }
+
+ /* Change CRC peripheral state */
+ hcrc->State = HAL_CRC_STATE_BUSY;
+
+ /* Reset CRC calculation unit */
+ __HAL_CRC_DR_RESET(hcrc);
+
+ /* Reset IDR register content */
+ CLEAR_BIT(hcrc->Instance->IDR, CRC_IDR_IDR);
+
+ /* DeInit the low level hardware */
+ HAL_CRC_MspDeInit(hcrc);
+
+ /* Change CRC peripheral state */
+ hcrc->State = HAL_CRC_STATE_RESET;
+
+ /* Process unlocked */
+ __HAL_UNLOCK(hcrc);
+
+ /* Return function status */
+ return HAL_OK;
+}
+
+/**
+ * @brief Initializes the CRC MSP.
+ * @param hcrc CRC handle
+ * @retval None
+ */
+__weak void HAL_CRC_MspInit(CRC_HandleTypeDef *hcrc)
+{
+ /* Prevent unused argument(s) compilation warning */
+ UNUSED(hcrc);
+
+ /* NOTE : This function should not be modified, when the callback is needed,
+ the HAL_CRC_MspInit can be implemented in the user file
+ */
+}
+
+/**
+ * @brief DeInitialize the CRC MSP.
+ * @param hcrc CRC handle
+ * @retval None
+ */
+__weak void HAL_CRC_MspDeInit(CRC_HandleTypeDef *hcrc)
+{
+ /* Prevent unused argument(s) compilation warning */
+ UNUSED(hcrc);
+
+ /* NOTE : This function should not be modified, when the callback is needed,
+ the HAL_CRC_MspDeInit can be implemented in the user file
+ */
+}
+
+/**
+ * @}
+ */
+
+/** @defgroup CRC_Exported_Functions_Group2 Peripheral Control functions
+ * @brief management functions.
+ *
+@verbatim
+ ===============================================================================
+ ##### Peripheral Control functions #####
+ ===============================================================================
+ [..] This section provides functions allowing to:
+ (+) compute the 7, 8, 16 or 32-bit CRC value of an 8, 16 or 32-bit data buffer
+ using combination of the previous CRC value and the new one.
+
+ [..] or
+
+ (+) compute the 7, 8, 16 or 32-bit CRC value of an 8, 16 or 32-bit data buffer
+ independently of the previous CRC value.
+
+@endverbatim
+ * @{
+ */
+
+/**
+ * @brief Compute the 7, 8, 16 or 32-bit CRC value of an 8, 16 or 32-bit data buffer
+ * starting with the previously computed CRC as initialization value.
+ * @param hcrc CRC handle
+ * @param pBuffer pointer to the input data buffer, exact input data format is
+ * provided by hcrc->InputDataFormat.
+ * @param BufferLength input data buffer length (number of bytes if pBuffer
+ * type is * uint8_t, number of half-words if pBuffer type is * uint16_t,
+ * number of words if pBuffer type is * uint32_t).
+ * @note By default, the API expects a uint32_t pointer as input buffer parameter.
+ * Input buffer pointers with other types simply need to be cast in uint32_t
+ * and the API will internally adjust its input data processing based on the
+ * handle field hcrc->InputDataFormat.
+ * @retval uint32_t CRC (returned value LSBs for CRC shorter than 32 bits)
+ */
+uint32_t HAL_CRC_Accumulate(CRC_HandleTypeDef *hcrc, uint32_t pBuffer[], uint32_t BufferLength)
+{
+ uint32_t index; /* CRC input data buffer index */
+ uint32_t temp = 0U; /* CRC output (read from hcrc->Instance->DR register) */
+
+ /* Change CRC peripheral state */
+ hcrc->State = HAL_CRC_STATE_BUSY;
+
+ switch (hcrc->InputDataFormat)
+ {
+ case CRC_INPUTDATA_FORMAT_WORDS:
+ /* Enter Data to the CRC calculator */
+ for (index = 0U; index < BufferLength; index++)
+ {
+ hcrc->Instance->DR = pBuffer[index];
+ }
+ temp = hcrc->Instance->DR;
+ break;
+
+ case CRC_INPUTDATA_FORMAT_BYTES:
+ temp = CRC_Handle_8(hcrc, (uint8_t *)pBuffer, BufferLength);
+ break;
+
+ case CRC_INPUTDATA_FORMAT_HALFWORDS:
+ temp = CRC_Handle_16(hcrc, (uint16_t *)(void *)pBuffer, BufferLength); /* Derogation MisraC2012 R.11.5 */
+ break;
+ default:
+ break;
+ }
+
+ /* Change CRC peripheral state */
+ hcrc->State = HAL_CRC_STATE_READY;
+
+ /* Return the CRC computed value */
+ return temp;
+}
+
+/**
+ * @brief Compute the 7, 8, 16 or 32-bit CRC value of an 8, 16 or 32-bit data buffer
+ * starting with hcrc->Instance->INIT as initialization value.
+ * @param hcrc CRC handle
+ * @param pBuffer pointer to the input data buffer, exact input data format is
+ * provided by hcrc->InputDataFormat.
+ * @param BufferLength input data buffer length (number of bytes if pBuffer
+ * type is * uint8_t, number of half-words if pBuffer type is * uint16_t,
+ * number of words if pBuffer type is * uint32_t).
+ * @note By default, the API expects a uint32_t pointer as input buffer parameter.
+ * Input buffer pointers with other types simply need to be cast in uint32_t
+ * and the API will internally adjust its input data processing based on the
+ * handle field hcrc->InputDataFormat.
+ * @retval uint32_t CRC (returned value LSBs for CRC shorter than 32 bits)
+ */
+uint32_t HAL_CRC_Calculate(CRC_HandleTypeDef *hcrc, uint32_t pBuffer[], uint32_t BufferLength)
+{
+ uint32_t index; /* CRC input data buffer index */
+ uint32_t temp = 0U; /* CRC output (read from hcrc->Instance->DR register) */
+
+ /* Change CRC peripheral state */
+ hcrc->State = HAL_CRC_STATE_BUSY;
+
+ /* Reset CRC Calculation Unit (hcrc->Instance->INIT is
+ * written in hcrc->Instance->DR) */
+ __HAL_CRC_DR_RESET(hcrc);
+
+ switch (hcrc->InputDataFormat)
+ {
+ case CRC_INPUTDATA_FORMAT_WORDS:
+ /* Enter 32-bit input data to the CRC calculator */
+ for (index = 0U; index < BufferLength; index++)
+ {
+ hcrc->Instance->DR = pBuffer[index];
+ }
+ temp = hcrc->Instance->DR;
+ break;
+
+ case CRC_INPUTDATA_FORMAT_BYTES:
+ /* Specific 8-bit input data handling */
+ temp = CRC_Handle_8(hcrc, (uint8_t *)pBuffer, BufferLength);
+ break;
+
+ case CRC_INPUTDATA_FORMAT_HALFWORDS:
+ /* Specific 16-bit input data handling */
+ temp = CRC_Handle_16(hcrc, (uint16_t *)(void *)pBuffer, BufferLength); /* Derogation MisraC2012 R.11.5 */
+ break;
+
+ default:
+ break;
+ }
+
+ /* Change CRC peripheral state */
+ hcrc->State = HAL_CRC_STATE_READY;
+
+ /* Return the CRC computed value */
+ return temp;
+}
+
+/**
+ * @}
+ */
+
+/** @defgroup CRC_Exported_Functions_Group3 Peripheral State functions
+ * @brief Peripheral State functions.
+ *
+@verbatim
+ ===============================================================================
+ ##### Peripheral State functions #####
+ ===============================================================================
+ [..]
+ This subsection permits to get in run-time the status of the peripheral.
+
+@endverbatim
+ * @{
+ */
+
+/**
+ * @brief Return the CRC handle state.
+ * @param hcrc CRC handle
+ * @retval HAL state
+ */
+HAL_CRC_StateTypeDef HAL_CRC_GetState(CRC_HandleTypeDef *hcrc)
+{
+ /* Return CRC handle state */
+ return hcrc->State;
+}
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/** @addtogroup CRC_Private_Functions
+ * @{
+ */
+
+/**
+ * @brief Enter 8-bit input data to the CRC calculator.
+ * Specific data handling to optimize processing time.
+ * @param hcrc CRC handle
+ * @param pBuffer pointer to the input data buffer
+ * @param BufferLength input data buffer length
+ * @retval uint32_t CRC (returned value LSBs for CRC shorter than 32 bits)
+ */
+static uint32_t CRC_Handle_8(CRC_HandleTypeDef *hcrc, uint8_t pBuffer[], uint32_t BufferLength)
+{
+ uint32_t i; /* input data buffer index */
+ uint16_t data;
+ __IO uint16_t *pReg;
+
+ /* Processing time optimization: 4 bytes are entered in a row with a single word write,
+ * last bytes must be carefully fed to the CRC calculator to ensure a correct type
+ * handling by the peripheral */
+ for (i = 0U; i < (BufferLength / 4U); i++)
+ {
+ hcrc->Instance->DR = ((uint32_t)pBuffer[4U * i] << 24U) | \
+ ((uint32_t)pBuffer[(4U * i) + 1U] << 16U) | \
+ ((uint32_t)pBuffer[(4U * i) + 2U] << 8U) | \
+ (uint32_t)pBuffer[(4U * i) + 3U];
+ }
+ /* last bytes specific handling */
+ if ((BufferLength % 4U) != 0U)
+ {
+ if ((BufferLength % 4U) == 1U)
+ {
+ *(__IO uint8_t *)(__IO void *)(&hcrc->Instance->DR) = pBuffer[4U * i]; /* Derogation MisraC2012 R.11.5 */
+ }
+ if ((BufferLength % 4U) == 2U)
+ {
+ data = ((uint16_t)(pBuffer[4U * i]) << 8U) | (uint16_t)pBuffer[(4U * i) + 1U];
+ pReg = (__IO uint16_t *)(__IO void *)(&hcrc->Instance->DR); /* Derogation MisraC2012 R.11.5 */
+ *pReg = data;
+ }
+ if ((BufferLength % 4U) == 3U)
+ {
+ data = ((uint16_t)(pBuffer[4U * i]) << 8U) | (uint16_t)pBuffer[(4U * i) + 1U];
+ pReg = (__IO uint16_t *)(__IO void *)(&hcrc->Instance->DR); /* Derogation MisraC2012 R.11.5 */
+ *pReg = data;
+
+ *(__IO uint8_t *)(__IO void *)(&hcrc->Instance->DR) = pBuffer[(4U * i) + 2U]; /* Derogation MisraC2012 R.11.5 */
+ }
+ }
+
+ /* Return the CRC computed value */
+ return hcrc->Instance->DR;
+}
+
+/**
+ * @brief Enter 16-bit input data to the CRC calculator.
+ * Specific data handling to optimize processing time.
+ * @param hcrc CRC handle
+ * @param pBuffer pointer to the input data buffer
+ * @param BufferLength input data buffer length
+ * @retval uint32_t CRC (returned value LSBs for CRC shorter than 32 bits)
+ */
+static uint32_t CRC_Handle_16(CRC_HandleTypeDef *hcrc, uint16_t pBuffer[], uint32_t BufferLength)
+{
+ uint32_t i; /* input data buffer index */
+ __IO uint16_t *pReg;
+
+ /* Processing time optimization: 2 HalfWords are entered in a row with a single word write,
+ * in case of odd length, last HalfWord must be carefully fed to the CRC calculator to ensure
+ * a correct type handling by the peripheral */
+ for (i = 0U; i < (BufferLength / 2U); i++)
+ {
+ hcrc->Instance->DR = ((uint32_t)pBuffer[2U * i] << 16U) | (uint32_t)pBuffer[(2U * i) + 1U];
+ }
+ if ((BufferLength % 2U) != 0U)
+ {
+ pReg = (__IO uint16_t *)(__IO void *)(&hcrc->Instance->DR); /* Derogation MisraC2012 R.11.5 */
+ *pReg = pBuffer[2U * i];
+ }
+
+ /* Return the CRC computed value */
+ return hcrc->Instance->DR;
+}
+
+/**
+ * @}
+ */
+
+#endif /* HAL_CRC_MODULE_ENABLED */
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_crc_ex.c b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_crc_ex.c
new file mode 100644
index 0000000..73ca899
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_crc_ex.c
@@ -0,0 +1,227 @@
+/**
+ ******************************************************************************
+ * @file stm32f0xx_hal_crc_ex.c
+ * @author MCD Application Team
+ * @brief Extended CRC HAL module driver.
+ * This file provides firmware functions to manage the extended
+ * functionalities of the CRC peripheral.
+ *
+ @verbatim
+================================================================================
+ ##### How to use this driver #####
+================================================================================
+ [..]
+ (+) Set user-defined generating polynomial through HAL_CRCEx_Polynomial_Set()
+ (+) Configure Input or Output data inversion
+
+ @endverbatim
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2016 STMicroelectronics.
+ * All rights reserved.
+ *
+ * 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 "stm32f0xx_hal.h"
+
+/** @addtogroup STM32F0xx_HAL_Driver
+ * @{
+ */
+
+/** @defgroup CRCEx CRCEx
+ * @brief CRC Extended HAL module driver
+ * @{
+ */
+
+#ifdef HAL_CRC_MODULE_ENABLED
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Exported functions --------------------------------------------------------*/
+
+/** @defgroup CRCEx_Exported_Functions CRC Extended Exported Functions
+ * @{
+ */
+
+/** @defgroup CRCEx_Exported_Functions_Group1 Extended Initialization/de-initialization functions
+ * @brief Extended Initialization and Configuration functions.
+ *
+@verbatim
+ ===============================================================================
+ ##### Extended configuration functions #####
+ ===============================================================================
+ [..] This section provides functions allowing to:
+ (+) Configure the generating polynomial
+ (+) Configure the input data inversion
+ (+) Configure the output data inversion
+
+@endverbatim
+ * @{
+ */
+
+
+#if defined(CRC_POL_POL)
+/**
+ * @brief Initialize the CRC polynomial if different from default one.
+ * @param hcrc CRC handle
+ * @param Pol CRC generating polynomial (7, 8, 16 or 32-bit long).
+ * This parameter is written in normal representation, e.g.
+ * @arg for a polynomial of degree 7, X^7 + X^6 + X^5 + X^2 + 1 is written 0x65
+ * @arg for a polynomial of degree 16, X^16 + X^12 + X^5 + 1 is written 0x1021
+ * @param PolyLength CRC polynomial length.
+ * This parameter can be one of the following values:
+ * @arg @ref CRC_POLYLENGTH_7B 7-bit long CRC (generating polynomial of degree 7)
+ * @arg @ref CRC_POLYLENGTH_8B 8-bit long CRC (generating polynomial of degree 8)
+ * @arg @ref CRC_POLYLENGTH_16B 16-bit long CRC (generating polynomial of degree 16)
+ * @arg @ref CRC_POLYLENGTH_32B 32-bit long CRC (generating polynomial of degree 32)
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_CRCEx_Polynomial_Set(CRC_HandleTypeDef *hcrc, uint32_t Pol, uint32_t PolyLength)
+{
+ HAL_StatusTypeDef status = HAL_OK;
+ uint32_t msb = 31U; /* polynomial degree is 32 at most, so msb is initialized to max value */
+
+ /* Check the parameters */
+ assert_param(IS_CRC_POL_LENGTH(PolyLength));
+
+ /* check polynomial definition vs polynomial size:
+ * polynomial length must be aligned with polynomial
+ * definition. HAL_ERROR is reported if Pol degree is
+ * larger than that indicated by PolyLength.
+ * Look for MSB position: msb will contain the degree of
+ * the second to the largest polynomial member. E.g., for
+ * X^7 + X^6 + X^5 + X^2 + 1, msb = 6. */
+ while ((msb-- > 0U) && ((Pol & ((uint32_t)(0x1U) << (msb & 0x1FU))) == 0U))
+ {
+ }
+
+ switch (PolyLength)
+ {
+ case CRC_POLYLENGTH_7B:
+ if (msb >= HAL_CRC_LENGTH_7B)
+ {
+ status = HAL_ERROR;
+ }
+ break;
+ case CRC_POLYLENGTH_8B:
+ if (msb >= HAL_CRC_LENGTH_8B)
+ {
+ status = HAL_ERROR;
+ }
+ break;
+ case CRC_POLYLENGTH_16B:
+ if (msb >= HAL_CRC_LENGTH_16B)
+ {
+ status = HAL_ERROR;
+ }
+ break;
+
+ case CRC_POLYLENGTH_32B:
+ /* no polynomial definition vs. polynomial length issue possible */
+ break;
+ default:
+ status = HAL_ERROR;
+ break;
+ }
+ if (status == HAL_OK)
+ {
+ /* set generating polynomial */
+ WRITE_REG(hcrc->Instance->POL, Pol);
+
+ /* set generating polynomial size */
+ MODIFY_REG(hcrc->Instance->CR, CRC_CR_POLYSIZE, PolyLength);
+ }
+ /* Return function status */
+ return status;
+}
+#endif /* CRC_POL_POL */
+
+/**
+ * @brief Set the Reverse Input data mode.
+ * @param hcrc CRC handle
+ * @param InputReverseMode Input Data inversion mode.
+ * This parameter can be one of the following values:
+ * @arg @ref CRC_INPUTDATA_INVERSION_NONE no change in bit order (default value)
+ * @arg @ref CRC_INPUTDATA_INVERSION_BYTE Byte-wise bit reversal
+ * @arg @ref CRC_INPUTDATA_INVERSION_HALFWORD HalfWord-wise bit reversal
+ * @arg @ref CRC_INPUTDATA_INVERSION_WORD Word-wise bit reversal
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_CRCEx_Input_Data_Reverse(CRC_HandleTypeDef *hcrc, uint32_t InputReverseMode)
+{
+ /* Check the parameters */
+ assert_param(IS_CRC_INPUTDATA_INVERSION_MODE(InputReverseMode));
+
+ /* Change CRC peripheral state */
+ hcrc->State = HAL_CRC_STATE_BUSY;
+
+ /* set input data inversion mode */
+ MODIFY_REG(hcrc->Instance->CR, CRC_CR_REV_IN, InputReverseMode);
+ /* Change CRC peripheral state */
+ hcrc->State = HAL_CRC_STATE_READY;
+
+ /* Return function status */
+ return HAL_OK;
+}
+
+/**
+ * @brief Set the Reverse Output data mode.
+ * @param hcrc CRC handle
+ * @param OutputReverseMode Output Data inversion mode.
+ * This parameter can be one of the following values:
+ * @arg @ref CRC_OUTPUTDATA_INVERSION_DISABLE no CRC inversion (default value)
+ * @arg @ref CRC_OUTPUTDATA_INVERSION_ENABLE bit-level inversion (e.g. for a 8-bit CRC: 0xB5 becomes 0xAD)
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_CRCEx_Output_Data_Reverse(CRC_HandleTypeDef *hcrc, uint32_t OutputReverseMode)
+{
+ /* Check the parameters */
+ assert_param(IS_CRC_OUTPUTDATA_INVERSION_MODE(OutputReverseMode));
+
+ /* Change CRC peripheral state */
+ hcrc->State = HAL_CRC_STATE_BUSY;
+
+ /* set output data inversion mode */
+ MODIFY_REG(hcrc->Instance->CR, CRC_CR_REV_OUT, OutputReverseMode);
+
+ /* Change CRC peripheral state */
+ hcrc->State = HAL_CRC_STATE_READY;
+
+ /* Return function status */
+ return HAL_OK;
+}
+
+
+
+
+/**
+ * @}
+ */
+
+
+/**
+ * @}
+ */
+
+
+#endif /* HAL_CRC_MODULE_ENABLED */
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_dma.c b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_dma.c
new file mode 100644
index 0000000..0b3ab97
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_dma.c
@@ -0,0 +1,901 @@
+/**
+ ******************************************************************************
+ * @file stm32f0xx_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 Reference manual for connection between peripherals
+ and DMA requests .
+
+ (#) For a given Channel, program the required configuration through the following parameters:
+ 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_Channel_IRQHandler() called under DMA_IRQHandler() Interrupt subroutine
+ (+) At the end of data transfer HAL_DMA_IRQHandler() function is executed and user can
+ add his own function by customization of function pointer XferCpltCallback and
+ XferErrorCallback (i.e a member of DMA handle structure).
+
+ *** DMA HAL driver macros list ***
+ =============================================
+ [..]
+ Below the list of most used macros in DMA HAL driver.
+
+ [..]
+ (@) You can refer to the DMA HAL driver header file for more useful macros
+
+ @endverbatim
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2016 STMicroelectronics.
+ * All rights reserved.
+ *
+ * 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 "stm32f0xx_hal.h"
+
+/** @addtogroup STM32F0xx_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);
+static void DMA_CalcBaseAndBitshift(DMA_HandleTypeDef *hdma);
+/**
+ * @}
+ */
+
+/* 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 = 0U;
+
+ /* Check the DMA handle allocation */
+ if(NULL == hdma)
+ {
+ 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));
+
+ /* Change DMA peripheral state */
+ hdma->State = HAL_DMA_STATE_BUSY;
+
+ /* Get the CR register value */
+ tmp = hdma->Instance->CCR;
+
+ /* Clear PL, MSIZE, PSIZE, MINC, PINC, CIRC, DIR bits */
+ tmp &= ((uint32_t)~(DMA_CCR_PL | DMA_CCR_MSIZE | DMA_CCR_PSIZE | \
+ DMA_CCR_MINC | DMA_CCR_PINC | DMA_CCR_CIRC | \
+ DMA_CCR_DIR));
+
+ /* Prepare the DMA Channel configuration */
+ tmp |= hdma->Init.Direction |
+ hdma->Init.PeriphInc | hdma->Init.MemInc |
+ hdma->Init.PeriphDataAlignment | hdma->Init.MemDataAlignment |
+ hdma->Init.Mode | hdma->Init.Priority;
+
+ /* Write to DMA Channel CR register */
+ hdma->Instance->CCR = tmp;
+
+ /* Initialize DmaBaseAddress and ChannelIndex parameters used
+ by HAL_DMA_IRQHandler() and HAL_DMA_PollForTransfer() */
+ DMA_CalcBaseAndBitshift(hdma);
+
+ /* 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 */
+ hdma->Instance->CCR &= ~DMA_CCR_EN;
+
+ /* Reset DMA Channel control register */
+ hdma->Instance->CCR = 0U;
+
+ /* Reset DMA Channel Number of Data to Transfer register */
+ hdma->Instance->CNDTR = 0U;
+
+ /* Reset DMA Channel peripheral address register */
+ hdma->Instance->CPAR = 0U;
+
+ /* Reset DMA Channel memory address register */
+ hdma->Instance->CMAR = 0U;
+
+/* Get DMA Base Address */
+ DMA_CalcBaseAndBitshift(hdma);
+
+ /* Clear all flags */
+ hdma->DmaBaseAddress->IFCR = DMA_FLAG_GL1 << hdma->ChannelIndex;
+
+ /* Clean callbacks */
+ hdma->XferCpltCallback = NULL;
+ hdma->XferHalfCpltCallback = NULL;
+ hdma->XferErrorCallback = NULL;
+ hdma->XferAbortCallback = NULL;
+
+ /* Reset the error code */
+ hdma->ErrorCode = HAL_DMA_ERROR_NONE;
+
+ /* Reset 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 I/O operation functions
+ *
+@verbatim
+ ===============================================================================
+ ##### IO operation functions #####
+ ===============================================================================
+ [..] This section provides functions allowing to:
+ (+) Configure the source, destination address and data length and Start DMA transfer
+ (+) Configure the source, destination address and data length and
+ Start DMA transfer with interrupt
+ (+) Abort DMA transfer
+ (+) Poll for transfer complete
+ (+) Handle DMA interrupt request
+
+@endverbatim
+ * @{
+ */
+
+/**
+ * @brief 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 */
+ hdma->Instance->CCR &= ~DMA_CCR_EN;
+
+ /* Configure the source, destination address and the data length */
+ DMA_SetConfig(hdma, SrcAddress, DstAddress, DataLength);
+
+ /* Enable the Peripheral */
+ hdma->Instance->CCR |= DMA_CCR_EN;
+ }
+ else
+ {
+ /* Process Unlocked */
+ __HAL_UNLOCK(hdma);
+
+ /* Remain BUSY */
+ 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 */
+ hdma->Instance->CCR &= ~DMA_CCR_EN;
+
+ /* Configure the source, destination address and the data length */
+ DMA_SetConfig(hdma, SrcAddress, DstAddress, DataLength);
+
+ /* Enable the transfer complete, & transfer error interrupts */
+ /* Half transfer interrupt is optional: enable it only if associated callback is available */
+ if(NULL != hdma->XferHalfCpltCallback )
+ {
+ hdma->Instance->CCR |= (DMA_IT_TC | DMA_IT_HT | DMA_IT_TE);
+ }
+ else
+ {
+ hdma->Instance->CCR |= (DMA_IT_TC | DMA_IT_TE);
+ hdma->Instance->CCR &= ~DMA_IT_HT;
+ }
+
+ /* Enable the Peripheral */
+ hdma->Instance->CCR |= DMA_CCR_EN;
+ }
+ 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)
+{
+ if(hdma->State != HAL_DMA_STATE_BUSY)
+ {
+ /* no transfer ongoing */
+ hdma->ErrorCode = HAL_DMA_ERROR_NO_XFER;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hdma);
+
+ return HAL_ERROR;
+ }
+ else
+ {
+ /* Disable DMA IT */
+ hdma->Instance->CCR &= ~(DMA_IT_TC | DMA_IT_HT | DMA_IT_TE);
+
+ /* Disable the channel */
+ hdma->Instance->CCR &= ~DMA_CCR_EN;
+
+ /* Clear all flags */
+ hdma->DmaBaseAddress->IFCR = (DMA_FLAG_GL1 << hdma->ChannelIndex);
+ }
+ /* Change the DMA state*/
+ hdma->State = HAL_DMA_STATE_READY;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hdma);
+
+ return HAL_OK;
+}
+
+/**
+ * @brief Abort the DMA Transfer in Interrupt mode.
+ * @param hdma pointer to a DMA_HandleTypeDef structure that contains
+ * the configuration information for the specified DMA Stream.
+ * @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 */
+ hdma->Instance->CCR &= ~(DMA_IT_TC | DMA_IT_HT | DMA_IT_TE);
+
+ /* Disable the channel */
+ hdma->Instance->CCR &= ~DMA_CCR_EN;
+
+ /* Clear all flags */
+ hdma->DmaBaseAddress->IFCR = DMA_FLAG_GL1 << hdma->ChannelIndex;
+
+ /* 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, uint32_t CompleteLevel, uint32_t Timeout)
+{
+ uint32_t temp;
+ uint32_t tickstart = 0U;
+
+ 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 (RESET != (hdma->Instance->CCR & DMA_CCR_CIRC))
+ {
+ 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;
+ }
+ else
+ {
+ /* Half Transfer Complete flag */
+ temp = DMA_FLAG_HT1 << hdma->ChannelIndex;
+ }
+
+ /* Get tick */
+ tickstart = HAL_GetTick();
+
+ while(RESET == (hdma->DmaBaseAddress->ISR & temp))
+ {
+ if(RESET != (hdma->DmaBaseAddress->ISR & (DMA_FLAG_TE1 << hdma->ChannelIndex)))
+ {
+ /* When a DMA transfer error occurs */
+ /* A hardware clear of its EN bits is performed */
+ /* Clear all flags */
+ hdma->DmaBaseAddress->IFCR = DMA_FLAG_GL1 << hdma->ChannelIndex;
+
+ /* 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((Timeout == 0U) || ((HAL_GetTick() - tickstart) > Timeout))
+ {
+ /* 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;
+
+ /* 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;
+ }
+
+ /* 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 ((RESET != (flag_it & (DMA_FLAG_HT1 << hdma->ChannelIndex))) && (RESET != (source_it & DMA_IT_HT)))
+ {
+ /* 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 */
+ hdma->Instance->CCR &= ~DMA_IT_HT;
+ }
+
+ /* Clear the half transfer complete flag */
+ hdma->DmaBaseAddress->IFCR = DMA_FLAG_HT1 << hdma->ChannelIndex;
+
+ /* DMA peripheral state is not updated in Half Transfer */
+ /* State is updated only in Transfer Complete case */
+
+ if(hdma->XferHalfCpltCallback != NULL)
+ {
+ /* Half transfer callback */
+ hdma->XferHalfCpltCallback(hdma);
+ }
+ }
+
+ /* Transfer Complete Interrupt management ***********************************/
+ else if ((RESET != (flag_it & (DMA_FLAG_TC1 << hdma->ChannelIndex))) && (RESET != (source_it & DMA_IT_TC)))
+ {
+ if((hdma->Instance->CCR & DMA_CCR_CIRC) == 0U)
+ {
+ /* Disable the transfer complete & transfer error interrupts */
+ /* if the DMA mode is not CIRCULAR */
+ hdma->Instance->CCR &= ~(DMA_IT_TC | DMA_IT_TE);
+
+ /* Change the DMA state */
+ hdma->State = HAL_DMA_STATE_READY;
+ }
+
+ /* Clear the transfer complete flag */
+ hdma->DmaBaseAddress->IFCR = DMA_FLAG_TC1 << hdma->ChannelIndex;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hdma);
+
+ if(hdma->XferCpltCallback != NULL)
+ {
+ /* Transfer complete callback */
+ hdma->XferCpltCallback(hdma);
+ }
+ }
+
+ /* Transfer Error Interrupt management ***************************************/
+ else if (( RESET != (flag_it & (DMA_FLAG_TE1 << hdma->ChannelIndex))) && (RESET != (source_it & DMA_IT_TE)))
+ {
+ /* When a DMA transfer error occurs */
+ /* A hardware clear of its EN bits is performed */
+ /* Then, disable all DMA interrupts */
+ hdma->Instance->CCR &= ~(DMA_IT_TC | DMA_IT_HT | DMA_IT_TE);
+
+ /* Clear all flags */
+ hdma->DmaBaseAddress->IFCR = DMA_FLAG_GL1 << hdma->ChannelIndex;
+
+ /* 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);
+ }
+ }
+}
+
+/**
+ * @brief Register callbacks
+ * @param hdma pointer to a DMA_HandleTypeDef structure that contains
+ * the configuration information for the specified DMA Stream.
+ * @param CallbackID User Callback identifer
+ * a HAL_DMA_CallbackIDTypeDef ENUM as parameter.
+ * @param pCallback pointer to private callback 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 Stream.
+ * @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 functions
+ * @brief Peripheral State functions
+ *
+@verbatim
+ ===============================================================================
+ ##### State and Errors functions #####
+ ===============================================================================
+ [..]
+ This subsection provides functions allowing to
+ (+) Check the DMA state
+ (+) Get error code
+
+@endverbatim
+ * @{
+ */
+
+/**
+ * @brief Returns the DMA state.
+ * @param hdma pointer to a DMA_HandleTypeDef structure that contains
+ * the configuration information for the specified DMA Channel.
+ * @retval HAL state
+ */
+HAL_DMA_StateTypeDef HAL_DMA_GetState(DMA_HandleTypeDef *hdma)
+{
+ return hdma->State;
+}
+
+/**
+ * @brief Return the DMA error code
+ * @param hdma pointer to a DMA_HandleTypeDef structure that contains
+ * the configuration information for the specified DMA Channel.
+ * @retval DMA Error Code
+ */
+uint32_t HAL_DMA_GetError(DMA_HandleTypeDef *hdma)
+{
+ return hdma->ErrorCode;
+}
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/** @addtogroup DMA_Private_Functions
+ * @{
+ */
+
+/**
+ * @brief Set the DMA Transfer parameters.
+ * @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_FLAG_GL1 << hdma->ChannelIndex);
+
+ /* 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;
+ }
+}
+
+/**
+ * @brief set the DMA base address and channel index depending on DMA instance
+ * @param hdma pointer to a DMA_HandleTypeDef structure that contains
+ * the configuration information for the specified DMA Stream.
+ * @retval None
+ */
+static void DMA_CalcBaseAndBitshift(DMA_HandleTypeDef *hdma)
+{
+#if defined (DMA2)
+ /* calculation of 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
+}
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+#endif /* HAL_DMA_MODULE_ENABLED */
+
+/**
+ * @}
+ */
+
+ /**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_exti.c b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_exti.c
new file mode 100644
index 0000000..c5d1fb5
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_exti.c
@@ -0,0 +1,549 @@
+/**
+ ******************************************************************************
+ * @file stm32f0xx_hal_exti.c
+ * @author MCD Application Team
+ * @brief EXTI HAL module driver.
+ * This file provides firmware functions to manage the following
+ * functionalities of the Extended Interrupts and events controller (EXTI) peripheral:
+ * + Initialization and de-initialization functions
+ * + IO operation functions
+ *
+ @verbatim
+ ==============================================================================
+ ##### EXTI Peripheral features #####
+ ==============================================================================
+ [..]
+ (+) Each Exti line can be configured within this driver.
+
+ (+) Exti line can be configured in 3 different modes
+ (++) Interrupt
+ (++) Event
+ (++) Both of them
+
+ (+) Configurable Exti lines can be configured with 3 different triggers
+ (++) Rising
+ (++) Falling
+ (++) Both of them
+
+ (+) When set in interrupt mode, configurable Exti lines have two different
+ interrupts pending registers which allow to distinguish which transition
+ occurs:
+ (++) Rising edge pending interrupt
+ (++) Falling
+
+ (+) Exti lines 0 to 15 are linked to gpio pin number 0 to 15. Gpio port can
+ be selected through multiplexer.
+
+ ##### How to use this driver #####
+ ==============================================================================
+ [..]
+
+ (#) Configure the EXTI line using HAL_EXTI_SetConfigLine().
+ (++) Choose the interrupt line number by setting "Line" member from
+ EXTI_ConfigTypeDef structure.
+ (++) Configure the interrupt and/or event mode using "Mode" member from
+ EXTI_ConfigTypeDef structure.
+ (++) For configurable lines, configure rising and/or falling trigger
+ "Trigger" member from EXTI_ConfigTypeDef structure.
+ (++) For Exti lines linked to gpio, choose gpio port using "GPIOSel"
+ member from GPIO_InitTypeDef structure.
+
+ (#) Get current Exti configuration of a dedicated line using
+ HAL_EXTI_GetConfigLine().
+ (++) Provide exiting handle as parameter.
+ (++) Provide pointer on EXTI_ConfigTypeDef structure as second parameter.
+
+ (#) Clear Exti configuration of a dedicated line using HAL_EXTI_GetConfigLine().
+ (++) Provide exiting handle as parameter.
+
+ (#) Register callback to treat Exti interrupts using HAL_EXTI_RegisterCallback().
+ (++) Provide exiting handle as first parameter.
+ (++) Provide which callback will be registered using one value from
+ EXTI_CallbackIDTypeDef.
+ (++) Provide callback function pointer.
+
+ (#) Get interrupt pending bit using HAL_EXTI_GetPending().
+
+ (#) Clear interrupt pending bit using HAL_EXTI_GetPending().
+
+ (#) Generate software interrupt using HAL_EXTI_GenerateSWI().
+
+ @endverbatim
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2019 STMicroelectronics.
+ * All rights reserved.
+ *
+ * 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 "stm32f0xx_hal.h"
+
+/** @addtogroup STM32F0xx_HAL_Driver
+ * @{
+ */
+
+/** @addtogroup EXTI
+ * @{
+ */
+/** MISRA C:2012 deviation rule has been granted for following rule:
+ * Rule-18.1_b - Medium: Array `EXTICR' 1st subscript interval [0,7] may be out
+ * of bounds [0,3] in following API :
+ * HAL_EXTI_SetConfigLine
+ * HAL_EXTI_GetConfigLine
+ * HAL_EXTI_ClearConfigLine
+ */
+
+#ifdef HAL_EXTI_MODULE_ENABLED
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private defines -----------------------------------------------------------*/
+/** @defgroup EXTI_Private_Constants EXTI Private Constants
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/* Private macros ------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Exported functions --------------------------------------------------------*/
+
+/** @addtogroup EXTI_Exported_Functions
+ * @{
+ */
+
+/** @addtogroup EXTI_Exported_Functions_Group1
+ * @brief Configuration functions
+ *
+@verbatim
+ ===============================================================================
+ ##### Configuration functions #####
+ ===============================================================================
+
+@endverbatim
+ * @{
+ */
+
+/**
+ * @brief Set configuration of a dedicated Exti line.
+ * @param hexti Exti handle.
+ * @param pExtiConfig Pointer on EXTI configuration to be set.
+ * @retval HAL Status.
+ */
+HAL_StatusTypeDef HAL_EXTI_SetConfigLine(EXTI_HandleTypeDef *hexti, EXTI_ConfigTypeDef *pExtiConfig)
+{
+ uint32_t regval;
+ uint32_t linepos;
+ uint32_t maskline;
+
+ /* Check null pointer */
+ if ((hexti == NULL) || (pExtiConfig == NULL))
+ {
+ return HAL_ERROR;
+ }
+
+ /* Check parameters */
+ assert_param(IS_EXTI_LINE(pExtiConfig->Line));
+ assert_param(IS_EXTI_MODE(pExtiConfig->Mode));
+
+ /* Assign line number to handle */
+ hexti->Line = pExtiConfig->Line;
+
+ /* Compute line mask */
+ linepos = (pExtiConfig->Line & EXTI_PIN_MASK);
+ maskline = (1uL << linepos);
+
+ /* Configure triggers for configurable lines */
+ if ((pExtiConfig->Line & EXTI_CONFIG) != 0x00u)
+ {
+ assert_param(IS_EXTI_TRIGGER(pExtiConfig->Trigger));
+
+ /* Configure rising trigger */
+ /* Mask or set line */
+ if ((pExtiConfig->Trigger & EXTI_TRIGGER_RISING) != 0x00u)
+ {
+ EXTI->RTSR |= maskline;
+ }
+ else
+ {
+ EXTI->RTSR &= ~maskline;
+ }
+
+ /* Configure falling trigger */
+ /* Mask or set line */
+ if ((pExtiConfig->Trigger & EXTI_TRIGGER_FALLING) != 0x00u)
+ {
+ EXTI->FTSR |= maskline;
+ }
+ else
+ {
+ EXTI->FTSR &= ~maskline;
+ }
+
+
+ /* Configure gpio port selection in case of gpio exti line */
+ if ((pExtiConfig->Line & EXTI_GPIO) == EXTI_GPIO)
+ {
+ assert_param(IS_EXTI_GPIO_PORT(pExtiConfig->GPIOSel));
+ assert_param(IS_EXTI_GPIO_PIN(linepos));
+
+ regval = SYSCFG->EXTICR[linepos >> 2u];
+ regval &= ~(SYSCFG_EXTICR1_EXTI0 << (SYSCFG_EXTICR1_EXTI1_Pos * (linepos & 0x03u)));
+ regval |= (pExtiConfig->GPIOSel << (SYSCFG_EXTICR1_EXTI1_Pos * (linepos & 0x03u)));
+ SYSCFG->EXTICR[linepos >> 2u] = regval;
+ }
+ }
+
+ /* Configure interrupt mode : read current mode */
+ /* Mask or set line */
+ if ((pExtiConfig->Mode & EXTI_MODE_INTERRUPT) != 0x00u)
+ {
+ EXTI->IMR |= maskline;
+ }
+ else
+ {
+ EXTI->IMR &= ~maskline;
+ }
+
+ /* Configure event mode : read current mode */
+ /* Mask or set line */
+ if ((pExtiConfig->Mode & EXTI_MODE_EVENT) != 0x00u)
+ {
+ EXTI->EMR |= maskline;
+ }
+ else
+ {
+ EXTI->EMR &= ~maskline;
+ }
+
+ return HAL_OK;
+}
+
+/**
+ * @brief Get configuration of a dedicated Exti line.
+ * @param hexti Exti handle.
+ * @param pExtiConfig Pointer on structure to store Exti configuration.
+ * @retval HAL Status.
+ */
+HAL_StatusTypeDef HAL_EXTI_GetConfigLine(EXTI_HandleTypeDef *hexti, EXTI_ConfigTypeDef *pExtiConfig)
+{
+ uint32_t regval;
+ uint32_t linepos;
+ uint32_t maskline;
+
+ /* Check null pointer */
+ if ((hexti == NULL) || (pExtiConfig == NULL))
+ {
+ return HAL_ERROR;
+ }
+
+ /* Check the parameter */
+ assert_param(IS_EXTI_LINE(hexti->Line));
+
+ /* Store handle line number to configuration structure */
+ pExtiConfig->Line = hexti->Line;
+
+ /* Compute line mask */
+ linepos = (pExtiConfig->Line & EXTI_PIN_MASK);
+ maskline = (1uL << linepos);
+
+ /* 1] Get core mode : interrupt */
+
+ /* Check if selected line is enable */
+ if ((EXTI->IMR & maskline) != 0x00u)
+ {
+ pExtiConfig->Mode = EXTI_MODE_INTERRUPT;
+ }
+ else
+ {
+ pExtiConfig->Mode = EXTI_MODE_NONE;
+ }
+
+ /* Get event mode */
+ /* Check if selected line is enable */
+ if ((EXTI->EMR & maskline) != 0x00u)
+ {
+ pExtiConfig->Mode |= EXTI_MODE_EVENT;
+ }
+
+ /* Get default Trigger and GPIOSel configuration */
+ pExtiConfig->Trigger = EXTI_TRIGGER_NONE;
+ pExtiConfig->GPIOSel = 0x00u;
+
+ /* 2] Get trigger for configurable lines : rising */
+ if ((pExtiConfig->Line & EXTI_CONFIG) != 0x00u)
+ {
+ /* Check if configuration of selected line is enable */
+ if ((EXTI->RTSR & maskline) != 0x00u)
+ {
+ pExtiConfig->Trigger = EXTI_TRIGGER_RISING;
+ }
+
+ /* Get falling configuration */
+ /* Check if configuration of selected line is enable */
+ if ((EXTI->FTSR & maskline) != 0x00u)
+ {
+ pExtiConfig->Trigger |= EXTI_TRIGGER_FALLING;
+ }
+
+ /* Get Gpio port selection for gpio lines */
+ if ((pExtiConfig->Line & EXTI_GPIO) == EXTI_GPIO)
+ {
+ assert_param(IS_EXTI_GPIO_PIN(linepos));
+
+ regval = SYSCFG->EXTICR[linepos >> 2u];
+ pExtiConfig->GPIOSel = ((regval << (SYSCFG_EXTICR1_EXTI1_Pos * (3uL - (linepos & 0x03u)))) >> 24);
+ }
+ }
+
+ return HAL_OK;
+}
+
+/**
+ * @brief Clear whole configuration of a dedicated Exti line.
+ * @param hexti Exti handle.
+ * @retval HAL Status.
+ */
+HAL_StatusTypeDef HAL_EXTI_ClearConfigLine(EXTI_HandleTypeDef *hexti)
+{
+ uint32_t regval;
+ uint32_t linepos;
+ uint32_t maskline;
+
+ /* Check null pointer */
+ if (hexti == NULL)
+ {
+ return HAL_ERROR;
+ }
+
+ /* Check the parameter */
+ assert_param(IS_EXTI_LINE(hexti->Line));
+
+ /* compute line mask */
+ linepos = (hexti->Line & EXTI_PIN_MASK);
+ maskline = (1uL << linepos);
+
+ /* 1] Clear interrupt mode */
+ EXTI->IMR = (EXTI->IMR & ~maskline);
+
+ /* 2] Clear event mode */
+ EXTI->EMR = (EXTI->EMR & ~maskline);
+
+ /* 3] Clear triggers in case of configurable lines */
+ if ((hexti->Line & EXTI_CONFIG) != 0x00u)
+ {
+ EXTI->RTSR = (EXTI->RTSR & ~maskline);
+ EXTI->FTSR = (EXTI->FTSR & ~maskline);
+
+ /* Get Gpio port selection for gpio lines */
+ if ((hexti->Line & EXTI_GPIO) == EXTI_GPIO)
+ {
+ assert_param(IS_EXTI_GPIO_PIN(linepos));
+
+ regval = SYSCFG->EXTICR[linepos >> 2u];
+ regval &= ~(SYSCFG_EXTICR1_EXTI0 << (SYSCFG_EXTICR1_EXTI1_Pos * (linepos & 0x03u)));
+ SYSCFG->EXTICR[linepos >> 2u] = regval;
+ }
+ }
+
+ return HAL_OK;
+}
+
+/**
+ * @brief Register callback for a dedicated Exti line.
+ * @param hexti Exti handle.
+ * @param CallbackID User callback identifier.
+ * This parameter can be one of @arg @ref EXTI_CallbackIDTypeDef values.
+ * @param pPendingCbfn function pointer to be stored as callback.
+ * @retval HAL Status.
+ */
+HAL_StatusTypeDef HAL_EXTI_RegisterCallback(EXTI_HandleTypeDef *hexti, EXTI_CallbackIDTypeDef CallbackID, void (*pPendingCbfn)(void))
+{
+ HAL_StatusTypeDef status = HAL_OK;
+
+ switch (CallbackID)
+ {
+ case HAL_EXTI_COMMON_CB_ID:
+ hexti->PendingCallback = pPendingCbfn;
+ break;
+
+ default:
+ status = HAL_ERROR;
+ break;
+ }
+
+ return status;
+}
+
+/**
+ * @brief Store line number as handle private field.
+ * @param hexti Exti handle.
+ * @param ExtiLine Exti line number.
+ * This parameter can be from 0 to @ref EXTI_LINE_NB.
+ * @retval HAL Status.
+ */
+HAL_StatusTypeDef HAL_EXTI_GetHandle(EXTI_HandleTypeDef *hexti, uint32_t ExtiLine)
+{
+ /* Check the parameters */
+ assert_param(IS_EXTI_LINE(ExtiLine));
+
+ /* Check null pointer */
+ if (hexti == NULL)
+ {
+ return HAL_ERROR;
+ }
+ else
+ {
+ /* Store line number as handle private field */
+ hexti->Line = ExtiLine;
+
+ return HAL_OK;
+ }
+}
+
+/**
+ * @}
+ */
+
+/** @addtogroup EXTI_Exported_Functions_Group2
+ * @brief EXTI IO functions.
+ *
+@verbatim
+ ===============================================================================
+ ##### IO operation functions #####
+ ===============================================================================
+
+@endverbatim
+ * @{
+ */
+
+/**
+ * @brief Handle EXTI interrupt request.
+ * @param hexti Exti handle.
+ * @retval none.
+ */
+void HAL_EXTI_IRQHandler(EXTI_HandleTypeDef *hexti)
+{
+ uint32_t regval;
+ uint32_t maskline;
+
+ /* Compute line mask */
+ maskline = (1uL << (hexti->Line & EXTI_PIN_MASK));
+
+ /* Get pending bit */
+ regval = (EXTI->PR & maskline);
+ if (regval != 0x00u)
+ {
+ /* Clear pending bit */
+ EXTI->PR = maskline;
+
+ /* Call callback */
+ if (hexti->PendingCallback != NULL)
+ {
+ hexti->PendingCallback();
+ }
+ }
+}
+
+/**
+ * @brief Get interrupt pending bit of a dedicated line.
+ * @param hexti Exti handle.
+ * @param Edge Specify which pending edge as to be checked.
+ * This parameter can be one of the following values:
+ * @arg @ref EXTI_TRIGGER_RISING_FALLING
+ * This parameter is kept for compatibility with other series.
+ * @retval 1 if interrupt is pending else 0.
+ */
+uint32_t HAL_EXTI_GetPending(EXTI_HandleTypeDef *hexti, uint32_t Edge)
+{
+ uint32_t regval;
+ uint32_t linepos;
+ uint32_t maskline;
+
+ /* Check parameters */
+ assert_param(IS_EXTI_LINE(hexti->Line));
+ assert_param(IS_EXTI_CONFIG_LINE(hexti->Line));
+ assert_param(IS_EXTI_PENDING_EDGE(Edge));
+
+ /* Compute line mask */
+ linepos = (hexti->Line & EXTI_PIN_MASK);
+ maskline = (1uL << linepos);
+
+ /* return 1 if bit is set else 0 */
+ regval = ((EXTI->PR & maskline) >> linepos);
+ return regval;
+}
+
+/**
+ * @brief Clear interrupt pending bit of a dedicated line.
+ * @param hexti Exti handle.
+ * @param Edge Specify which pending edge as to be clear.
+ * This parameter can be one of the following values:
+ * @arg @ref EXTI_TRIGGER_RISING_FALLING
+ * This parameter is kept for compatibility with other series.
+ * @retval None.
+ */
+void HAL_EXTI_ClearPending(EXTI_HandleTypeDef *hexti, uint32_t Edge)
+{
+ uint32_t maskline;
+
+ /* Check parameters */
+ assert_param(IS_EXTI_LINE(hexti->Line));
+ assert_param(IS_EXTI_CONFIG_LINE(hexti->Line));
+ assert_param(IS_EXTI_PENDING_EDGE(Edge));
+
+ /* Compute line mask */
+ maskline = (1uL << (hexti->Line & EXTI_PIN_MASK));
+
+ /* Clear Pending bit */
+ EXTI->PR = maskline;
+}
+
+/**
+ * @brief Generate a software interrupt for a dedicated line.
+ * @param hexti Exti handle.
+ * @retval None.
+ */
+void HAL_EXTI_GenerateSWI(EXTI_HandleTypeDef *hexti)
+{
+ uint32_t maskline;
+
+ /* Check parameters */
+ assert_param(IS_EXTI_LINE(hexti->Line));
+ assert_param(IS_EXTI_CONFIG_LINE(hexti->Line));
+
+ /* Compute line mask */
+ maskline = (1uL << (hexti->Line & EXTI_PIN_MASK));
+
+ /* Generate Software interrupt */
+ EXTI->SWIER = maskline;
+}
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+#endif /* HAL_EXTI_MODULE_ENABLED */
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_flash.c b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_flash.c
new file mode 100644
index 0000000..a4a0821
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_flash.c
@@ -0,0 +1,694 @@
+/**
+ ******************************************************************************
+ * @file stm32f0xx_hal_flash.c
+ * @author MCD Application Team
+ * @brief FLASH HAL module driver.
+ * This file provides firmware functions to manage the following
+ * functionalities of the internal FLASH memory:
+ * + Program operations functions
+ * + Memory Control functions
+ * + Peripheral State functions
+ *
+ @verbatim
+ ==============================================================================
+ ##### FLASH peripheral features #####
+ ==============================================================================
+ [..] The Flash memory interface manages CPU AHB I-Code and D-Code accesses
+ to the Flash memory. It implements the erase and program Flash memory operations
+ and the read and write protection mechanisms.
+
+ [..] The Flash memory interface accelerates code execution with a system of instruction
+ prefetch.
+
+ [..] The FLASH main features are:
+ (+) Flash memory read operations
+ (+) Flash memory program/erase operations
+ (+) Read / write protections
+ (+) Prefetch on I-Code
+ (+) Option Bytes programming
+
+
+ ##### How to use this driver #####
+ ==============================================================================
+ [..]
+ This driver provides functions and macros to configure and program the FLASH
+ memory of all STM32F0xx devices.
+
+ (#) FLASH Memory I/O Programming functions: this group includes all needed
+ functions to erase and program the main memory:
+ (++) Lock and Unlock the FLASH interface
+ (++) Erase function: Erase page, erase all pages
+ (++) Program functions: half word, word and doubleword
+ (#) FLASH Option Bytes Programming functions: this group includes all needed
+ functions to manage the Option Bytes:
+ (++) Lock and Unlock the Option Bytes
+ (++) Set/Reset the write protection
+ (++) Set the Read protection Level
+ (++) Program the user Option Bytes
+ (++) Launch the Option Bytes loader
+ (++) Erase Option Bytes
+ (++) Program the data Option Bytes
+ (++) Get the Write protection.
+ (++) Get the user option bytes.
+
+ (#) Interrupts and flags management functions : this group
+ includes all needed functions to:
+ (++) Handle FLASH interrupts
+ (++) Wait for last FLASH operation according to its status
+ (++) Get error flag status
+
+ [..] In addition to these function, this driver includes a set of macros allowing
+ to handle the following operations:
+
+ (+) Set/Get the latency
+ (+) Enable/Disable the prefetch buffer
+ (+) Enable/Disable the FLASH interrupts
+ (+) Monitor the FLASH flags status
+
+ @endverbatim
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2016 STMicroelectronics.
+ * All rights reserved.
+ *
+ * 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 "stm32f0xx_hal.h"
+
+/** @addtogroup STM32F0xx_HAL_Driver
+ * @{
+ */
+
+#ifdef HAL_FLASH_MODULE_ENABLED
+
+/** @defgroup FLASH FLASH
+ * @brief FLASH HAL module driver
+ * @{
+ */
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/** @defgroup FLASH_Private_Constants FLASH Private Constants
+ * @{
+ */
+/**
+ * @}
+ */
+
+/* Private macro ---------------------------- ---------------------------------*/
+/** @defgroup FLASH_Private_Macros FLASH Private Macros
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/* Private variables ---------------------------------------------------------*/
+/** @defgroup FLASH_Private_Variables FLASH Private Variables
+ * @{
+ */
+/* Variables used for Erase pages under interruption*/
+FLASH_ProcessTypeDef pFlash;
+/**
+ * @}
+ */
+
+/* Private function prototypes -----------------------------------------------*/
+/** @defgroup FLASH_Private_Functions FLASH Private Functions
+ * @{
+ */
+static void FLASH_Program_HalfWord(uint32_t Address, uint16_t Data);
+static void FLASH_SetErrorCode(void);
+extern void FLASH_PageErase(uint32_t PageAddress);
+/**
+ * @}
+ */
+
+/* Exported functions ---------------------------------------------------------*/
+/** @defgroup FLASH_Exported_Functions FLASH Exported Functions
+ * @{
+ */
+
+/** @defgroup FLASH_Exported_Functions_Group1 Programming operation functions
+ * @brief Programming operation functions
+ *
+@verbatim
+@endverbatim
+ * @{
+ */
+
+/**
+ * @brief Program halfword, word or double word at a specified address
+ * @note The function HAL_FLASH_Unlock() should be called before to unlock the FLASH interface
+ * The function HAL_FLASH_Lock() should be called after to lock the FLASH interface
+ *
+ * @note If an erase and a program operations are requested simultaneously,
+ * the erase operation is performed before the program one.
+ *
+ * @note FLASH should be previously erased before new programming (only exception to this
+ * is when 0x0000 is programmed)
+ *
+ * @param TypeProgram Indicate the way to program at a specified address.
+ * This parameter can be a value of @ref FLASH_Type_Program
+ * @param Address Specifie the address to be programmed.
+ * @param Data Specifie the data to be programmed
+ *
+ * @retval HAL_StatusTypeDef HAL Status
+ */
+HAL_StatusTypeDef HAL_FLASH_Program(uint32_t TypeProgram, uint32_t Address, uint64_t Data)
+{
+ HAL_StatusTypeDef status = HAL_ERROR;
+ uint8_t index = 0U;
+ uint8_t nbiterations = 0U;
+
+ /* Process Locked */
+ __HAL_LOCK(&pFlash);
+
+ /* Check the parameters */
+ assert_param(IS_FLASH_TYPEPROGRAM(TypeProgram));
+ assert_param(IS_FLASH_PROGRAM_ADDRESS(Address));
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation(FLASH_TIMEOUT_VALUE);
+
+ if(status == HAL_OK)
+ {
+ if(TypeProgram == FLASH_TYPEPROGRAM_HALFWORD)
+ {
+ /* Program halfword (16-bit) at a specified address. */
+ nbiterations = 1U;
+ }
+ else if(TypeProgram == FLASH_TYPEPROGRAM_WORD)
+ {
+ /* Program word (32-bit = 2*16-bit) at a specified address. */
+ nbiterations = 2U;
+ }
+ else
+ {
+ /* Program double word (64-bit = 4*16-bit) at a specified address. */
+ nbiterations = 4U;
+ }
+
+ for (index = 0U; index < nbiterations; index++)
+ {
+ FLASH_Program_HalfWord((Address + (2U*index)), (uint16_t)(Data >> (16U*index)));
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation(FLASH_TIMEOUT_VALUE);
+
+ /* If the program operation is completed, disable the PG Bit */
+ CLEAR_BIT(FLASH->CR, FLASH_CR_PG);
+ /* In case of error, stop programming procedure */
+ if (status != HAL_OK)
+ {
+ break;
+ }
+ }
+ }
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(&pFlash);
+
+ return status;
+}
+
+/**
+ * @brief Program halfword, word or double word at a specified address with interrupt enabled.
+ * @note The function HAL_FLASH_Unlock() should be called before to unlock the FLASH interface
+ * The function HAL_FLASH_Lock() should be called after to lock the FLASH interface
+ *
+ * @note If an erase and a program operations are requested simultaneously,
+ * the erase operation is performed before the program one.
+ *
+ * @param TypeProgram Indicate the way to program at a specified address.
+ * This parameter can be a value of @ref FLASH_Type_Program
+ * @param Address Specifie the address to be programmed.
+ * @param Data Specifie the data to be programmed
+ *
+ * @retval HAL_StatusTypeDef HAL Status
+ */
+HAL_StatusTypeDef HAL_FLASH_Program_IT(uint32_t TypeProgram, uint32_t Address, uint64_t Data)
+{
+ HAL_StatusTypeDef status = HAL_OK;
+
+ /* Process Locked */
+ __HAL_LOCK(&pFlash);
+
+ /* Check the parameters */
+ assert_param(IS_FLASH_TYPEPROGRAM(TypeProgram));
+ assert_param(IS_FLASH_PROGRAM_ADDRESS(Address));
+
+ /* Enable End of FLASH Operation and Error source interrupts */
+ __HAL_FLASH_ENABLE_IT(FLASH_IT_EOP | FLASH_IT_ERR);
+
+ pFlash.Address = Address;
+ pFlash.Data = Data;
+
+ if(TypeProgram == FLASH_TYPEPROGRAM_HALFWORD)
+ {
+ pFlash.ProcedureOnGoing = FLASH_PROC_PROGRAMHALFWORD;
+ /* Program halfword (16-bit) at a specified address. */
+ pFlash.DataRemaining = 1U;
+ }
+ else if(TypeProgram == FLASH_TYPEPROGRAM_WORD)
+ {
+ pFlash.ProcedureOnGoing = FLASH_PROC_PROGRAMWORD;
+ /* Program word (32-bit : 2*16-bit) at a specified address. */
+ pFlash.DataRemaining = 2U;
+ }
+ else
+ {
+ pFlash.ProcedureOnGoing = FLASH_PROC_PROGRAMDOUBLEWORD;
+ /* Program double word (64-bit : 4*16-bit) at a specified address. */
+ pFlash.DataRemaining = 4U;
+ }
+
+ /* Program halfword (16-bit) at a specified address. */
+ FLASH_Program_HalfWord(Address, (uint16_t)Data);
+
+ return status;
+}
+
+/**
+ * @brief This function handles FLASH interrupt request.
+ * @retval None
+ */
+void HAL_FLASH_IRQHandler(void)
+{
+ uint32_t addresstmp = 0U;
+
+ /* Check FLASH operation error flags */
+ if(__HAL_FLASH_GET_FLAG(FLASH_FLAG_WRPERR) ||__HAL_FLASH_GET_FLAG(FLASH_FLAG_PGERR))
+ {
+ /* Return the faulty address */
+ addresstmp = pFlash.Address;
+ /* Reset address */
+ pFlash.Address = 0xFFFFFFFFU;
+
+ /* Save the Error code */
+ FLASH_SetErrorCode();
+
+ /* FLASH error interrupt user callback */
+ HAL_FLASH_OperationErrorCallback(addresstmp);
+
+ /* Stop the procedure ongoing */
+ pFlash.ProcedureOnGoing = FLASH_PROC_NONE;
+ }
+
+ /* Check FLASH End of Operation flag */
+ if(__HAL_FLASH_GET_FLAG(FLASH_FLAG_EOP))
+ {
+ /* Clear FLASH End of Operation pending bit */
+ __HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_EOP);
+
+ /* Process can continue only if no error detected */
+ if(pFlash.ProcedureOnGoing != FLASH_PROC_NONE)
+ {
+ if(pFlash.ProcedureOnGoing == FLASH_PROC_PAGEERASE)
+ {
+ /* Nb of pages to erased can be decreased */
+ pFlash.DataRemaining--;
+
+ /* Check if there are still pages to erase */
+ if(pFlash.DataRemaining != 0U)
+ {
+ addresstmp = pFlash.Address;
+ /*Indicate user which sector has been erased */
+ HAL_FLASH_EndOfOperationCallback(addresstmp);
+
+ /*Increment sector number*/
+ addresstmp = pFlash.Address + FLASH_PAGE_SIZE;
+ pFlash.Address = addresstmp;
+
+ /* If the erase operation is completed, disable the PER Bit */
+ CLEAR_BIT(FLASH->CR, FLASH_CR_PER);
+
+ FLASH_PageErase(addresstmp);
+ }
+ else
+ {
+ /* No more pages to Erase, user callback can be called. */
+ /* Reset Sector and stop Erase pages procedure */
+ pFlash.Address = addresstmp = 0xFFFFFFFFU;
+ pFlash.ProcedureOnGoing = FLASH_PROC_NONE;
+ /* FLASH EOP interrupt user callback */
+ HAL_FLASH_EndOfOperationCallback(addresstmp);
+ }
+ }
+ else if(pFlash.ProcedureOnGoing == FLASH_PROC_MASSERASE)
+ {
+ /* Operation is completed, disable the MER Bit */
+ CLEAR_BIT(FLASH->CR, FLASH_CR_MER);
+
+ /* MassErase ended. Return the selected bank */
+ /* FLASH EOP interrupt user callback */
+ HAL_FLASH_EndOfOperationCallback(0);
+
+ /* Stop Mass Erase procedure*/
+ pFlash.ProcedureOnGoing = FLASH_PROC_NONE;
+ }
+ else
+ {
+ /* Nb of 16-bit data to program can be decreased */
+ pFlash.DataRemaining--;
+
+ /* Check if there are still 16-bit data to program */
+ if(pFlash.DataRemaining != 0U)
+ {
+ /* Increment address to 16-bit */
+ pFlash.Address += 2;
+ addresstmp = pFlash.Address;
+
+ /* Shift to have next 16-bit data */
+ pFlash.Data = (pFlash.Data >> 16U);
+
+ /* Operation is completed, disable the PG Bit */
+ CLEAR_BIT(FLASH->CR, FLASH_CR_PG);
+
+ /*Program halfword (16-bit) at a specified address.*/
+ FLASH_Program_HalfWord(addresstmp, (uint16_t)pFlash.Data);
+ }
+ else
+ {
+ /* Program ended. Return the selected address */
+ /* FLASH EOP interrupt user callback */
+ if (pFlash.ProcedureOnGoing == FLASH_PROC_PROGRAMHALFWORD)
+ {
+ HAL_FLASH_EndOfOperationCallback(pFlash.Address);
+ }
+ else if (pFlash.ProcedureOnGoing == FLASH_PROC_PROGRAMWORD)
+ {
+ HAL_FLASH_EndOfOperationCallback(pFlash.Address - 2U);
+ }
+ else
+ {
+ HAL_FLASH_EndOfOperationCallback(pFlash.Address - 6U);
+ }
+
+ /* Reset Address and stop Program procedure */
+ pFlash.Address = 0xFFFFFFFFU;
+ pFlash.ProcedureOnGoing = FLASH_PROC_NONE;
+ }
+ }
+ }
+ }
+
+
+ if(pFlash.ProcedureOnGoing == FLASH_PROC_NONE)
+ {
+ /* Operation is completed, disable the PG, PER and MER Bits */
+ CLEAR_BIT(FLASH->CR, (FLASH_CR_PG | FLASH_CR_PER | FLASH_CR_MER));
+
+ /* Disable End of FLASH Operation and Error source interrupts */
+ __HAL_FLASH_DISABLE_IT(FLASH_IT_EOP | FLASH_IT_ERR);
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(&pFlash);
+ }
+}
+
+/**
+ * @brief FLASH end of operation interrupt callback
+ * @param ReturnValue The value saved in this parameter depends on the ongoing procedure
+ * - Mass Erase: No return value expected
+ * - Pages Erase: Address of the page which has been erased
+ * (if 0xFFFFFFFF, it means that all the selected pages have been erased)
+ * - Program: Address which was selected for data program
+ * @retval none
+ */
+__weak void HAL_FLASH_EndOfOperationCallback(uint32_t ReturnValue)
+{
+ /* Prevent unused argument(s) compilation warning */
+ UNUSED(ReturnValue);
+
+ /* NOTE : This function Should not be modified, when the callback is needed,
+ the HAL_FLASH_EndOfOperationCallback could be implemented in the user file
+ */
+}
+
+/**
+ * @brief FLASH operation error interrupt callback
+ * @param ReturnValue The value saved in this parameter depends on the ongoing procedure
+ * - Mass Erase: No return value expected
+ * - Pages Erase: Address of the page which returned an error
+ * - Program: Address which was selected for data program
+ * @retval none
+ */
+__weak void HAL_FLASH_OperationErrorCallback(uint32_t ReturnValue)
+{
+ /* Prevent unused argument(s) compilation warning */
+ UNUSED(ReturnValue);
+
+ /* NOTE : This function Should not be modified, when the callback is needed,
+ the HAL_FLASH_OperationErrorCallback could be implemented in the user file
+ */
+}
+
+/**
+ * @}
+ */
+
+/** @defgroup FLASH_Exported_Functions_Group2 Peripheral Control functions
+ * @brief management functions
+ *
+@verbatim
+ ===============================================================================
+ ##### Peripheral Control functions #####
+ ===============================================================================
+ [..]
+ This subsection provides a set of functions allowing to control the FLASH
+ memory operations.
+
+@endverbatim
+ * @{
+ */
+
+/**
+ * @brief Unlock the FLASH control register access
+ * @retval HAL Status
+ */
+HAL_StatusTypeDef HAL_FLASH_Unlock(void)
+{
+ HAL_StatusTypeDef status = HAL_OK;
+
+ if(READ_BIT(FLASH->CR, FLASH_CR_LOCK) != RESET)
+ {
+ /* Authorize the FLASH Registers access */
+ WRITE_REG(FLASH->KEYR, FLASH_KEY1);
+ WRITE_REG(FLASH->KEYR, FLASH_KEY2);
+
+ /* Verify Flash is unlocked */
+ if(READ_BIT(FLASH->CR, FLASH_CR_LOCK) != RESET)
+ {
+ status = HAL_ERROR;
+ }
+ }
+
+ return status;
+}
+
+/**
+ * @brief Locks the FLASH control register access
+ * @retval HAL Status
+ */
+HAL_StatusTypeDef HAL_FLASH_Lock(void)
+{
+ /* Set the LOCK Bit to lock the FLASH Registers access */
+ SET_BIT(FLASH->CR, FLASH_CR_LOCK);
+
+ return HAL_OK;
+}
+
+/**
+ * @brief Unlock the FLASH Option Control Registers access.
+ * @retval HAL Status
+ */
+HAL_StatusTypeDef HAL_FLASH_OB_Unlock(void)
+{
+ if (HAL_IS_BIT_CLR(FLASH->CR, FLASH_CR_OPTWRE))
+ {
+ /* Authorizes the Option Byte register programming */
+ WRITE_REG(FLASH->OPTKEYR, FLASH_OPTKEY1);
+ WRITE_REG(FLASH->OPTKEYR, FLASH_OPTKEY2);
+ }
+ else
+ {
+ return HAL_ERROR;
+ }
+
+ return HAL_OK;
+}
+
+/**
+ * @brief Lock the FLASH Option Control Registers access.
+ * @retval HAL Status
+ */
+HAL_StatusTypeDef HAL_FLASH_OB_Lock(void)
+{
+ /* Clear the OPTWRE Bit to lock the FLASH Option Byte Registers access */
+ CLEAR_BIT(FLASH->CR, FLASH_CR_OPTWRE);
+
+ return HAL_OK;
+}
+
+/**
+ * @brief Launch the option byte loading.
+ * @note This function will reset automatically the MCU.
+ * @retval HAL Status
+ */
+HAL_StatusTypeDef HAL_FLASH_OB_Launch(void)
+{
+ /* Set the OBL_Launch bit to launch the option byte loading */
+ SET_BIT(FLASH->CR, FLASH_CR_OBL_LAUNCH);
+
+ /* Wait for last operation to be completed */
+ return(FLASH_WaitForLastOperation(FLASH_TIMEOUT_VALUE));
+}
+
+/**
+ * @}
+ */
+
+/** @defgroup FLASH_Exported_Functions_Group3 Peripheral errors functions
+ * @brief Peripheral errors functions
+ *
+@verbatim
+ ===============================================================================
+ ##### Peripheral Errors functions #####
+ ===============================================================================
+ [..]
+ This subsection permit to get in run-time errors of the FLASH peripheral.
+
+@endverbatim
+ * @{
+ */
+
+/**
+ * @brief Get the specific FLASH error flag.
+ * @retval FLASH_ErrorCode The returned value can be:
+ * @ref FLASH_Error_Codes
+ */
+uint32_t HAL_FLASH_GetError(void)
+{
+ return pFlash.ErrorCode;
+}
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/** @addtogroup FLASH_Private_Functions
+ * @{
+ */
+
+/**
+ * @brief Program a half-word (16-bit) at a specified address.
+ * @param Address specify the address to be programmed.
+ * @param Data specify the data to be programmed.
+ * @retval None
+ */
+static void FLASH_Program_HalfWord(uint32_t Address, uint16_t Data)
+{
+ /* Clean the error context */
+ pFlash.ErrorCode = HAL_FLASH_ERROR_NONE;
+
+ /* Proceed to program the new data */
+ SET_BIT(FLASH->CR, FLASH_CR_PG);
+
+ /* Write data in the address */
+ *(__IO uint16_t*)Address = Data;
+}
+
+/**
+ * @brief Wait for a FLASH operation to complete.
+ * @param Timeout maximum flash operation timeout
+ * @retval HAL Status
+ */
+HAL_StatusTypeDef FLASH_WaitForLastOperation(uint32_t Timeout)
+{
+ /* Wait for the FLASH operation to complete by polling on BUSY flag to be reset.
+ Even if the FLASH operation fails, the BUSY flag will be reset and an error
+ flag will be set */
+
+ uint32_t tickstart = HAL_GetTick();
+
+ while(__HAL_FLASH_GET_FLAG(FLASH_FLAG_BSY))
+ {
+ if (Timeout != HAL_MAX_DELAY)
+ {
+ if((Timeout == 0U) || ((HAL_GetTick()-tickstart) > Timeout))
+ {
+ return HAL_TIMEOUT;
+ }
+ }
+ }
+
+ /* Check FLASH End of Operation flag */
+ if (__HAL_FLASH_GET_FLAG(FLASH_FLAG_EOP))
+ {
+ /* Clear FLASH End of Operation pending bit */
+ __HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_EOP);
+ }
+
+ if(__HAL_FLASH_GET_FLAG(FLASH_FLAG_WRPERR) ||
+ __HAL_FLASH_GET_FLAG(FLASH_FLAG_PGERR))
+ {
+ /*Save the error code*/
+ FLASH_SetErrorCode();
+ return HAL_ERROR;
+ }
+
+ /* There is no error flag set */
+ return HAL_OK;
+}
+
+
+/**
+ * @brief Set the specific FLASH error flag.
+ * @retval None
+ */
+static void FLASH_SetErrorCode(void)
+{
+ uint32_t flags = 0U;
+
+ if(__HAL_FLASH_GET_FLAG(FLASH_FLAG_WRPERR))
+ {
+ pFlash.ErrorCode |= HAL_FLASH_ERROR_WRP;
+ flags |= FLASH_FLAG_WRPERR;
+ }
+ if(__HAL_FLASH_GET_FLAG(FLASH_FLAG_PGERR))
+ {
+ pFlash.ErrorCode |= HAL_FLASH_ERROR_PROG;
+ flags |= FLASH_FLAG_PGERR;
+ }
+ /* Clear FLASH error pending bits */
+ __HAL_FLASH_CLEAR_FLAG(flags);
+}
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+#endif /* HAL_FLASH_MODULE_ENABLED */
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_flash_ex.c b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_flash_ex.c
new file mode 100644
index 0000000..62d2ac9
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_flash_ex.c
@@ -0,0 +1,984 @@
+/**
+ ******************************************************************************
+ * @file stm32f0xx_hal_flash_ex.c
+ * @author MCD Application Team
+ * @brief Extended FLASH HAL module driver.
+ *
+ * This file provides firmware functions to manage the following
+ * functionalities of the FLASH peripheral:
+ * + Extended Initialization/de-initialization functions
+ * + Extended I/O operation functions
+ * + Extended Peripheral Control functions
+ *
+ @verbatim
+ ==============================================================================
+ ##### Flash peripheral extended features #####
+ ==============================================================================
+
+ ##### How to use this driver #####
+ ==============================================================================
+ [..] This driver provides functions to configure and program the FLASH memory
+ of all STM32F0xxx devices. It includes
+
+ (++) Set/Reset the write protection
+ (++) Program the user Option Bytes
+ (++) Get the Read protection Level
+
+ @endverbatim
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2016 STMicroelectronics.
+ * All rights reserved.
+ *
+ * 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 "stm32f0xx_hal.h"
+
+/** @addtogroup STM32F0xx_HAL_Driver
+ * @{
+ */
+#ifdef HAL_FLASH_MODULE_ENABLED
+
+/** @addtogroup FLASH
+ * @{
+ */
+/** @addtogroup FLASH_Private_Variables
+ * @{
+ */
+/* Variables used for Erase pages under interruption*/
+extern FLASH_ProcessTypeDef pFlash;
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/** @defgroup FLASHEx FLASHEx
+ * @brief FLASH HAL Extension module driver
+ * @{
+ */
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/** @defgroup FLASHEx_Private_Constants FLASHEx Private Constants
+ * @{
+ */
+#define FLASH_POSITION_IWDGSW_BIT 8U
+#define FLASH_POSITION_OB_USERDATA0_BIT 16U
+#define FLASH_POSITION_OB_USERDATA1_BIT 24U
+/**
+ * @}
+ */
+
+/* Private macro -------------------------------------------------------------*/
+/** @defgroup FLASHEx_Private_Macros FLASHEx Private Macros
+ * @{
+ */
+/**
+ * @}
+ */
+
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/** @defgroup FLASHEx_Private_Functions FLASHEx Private Functions
+ * @{
+ */
+/* Erase operations */
+static void FLASH_MassErase(void);
+void FLASH_PageErase(uint32_t PageAddress);
+
+/* Option bytes control */
+static HAL_StatusTypeDef FLASH_OB_EnableWRP(uint32_t WriteProtectPage);
+static HAL_StatusTypeDef FLASH_OB_DisableWRP(uint32_t WriteProtectPage);
+static HAL_StatusTypeDef FLASH_OB_RDP_LevelConfig(uint8_t ReadProtectLevel);
+static HAL_StatusTypeDef FLASH_OB_UserConfig(uint8_t UserConfig);
+static HAL_StatusTypeDef FLASH_OB_ProgramData(uint32_t Address, uint8_t Data);
+static uint32_t FLASH_OB_GetWRP(void);
+static uint32_t FLASH_OB_GetRDP(void);
+static uint8_t FLASH_OB_GetUser(void);
+
+/**
+ * @}
+ */
+
+/* Exported functions ---------------------------------------------------------*/
+/** @defgroup FLASHEx_Exported_Functions FLASHEx Exported Functions
+ * @{
+ */
+
+/** @defgroup FLASHEx_Exported_Functions_Group1 FLASHEx Memory Erasing functions
+ * @brief FLASH Memory Erasing functions
+ *
+@verbatim
+ ==============================================================================
+ ##### FLASH Erasing Programming functions #####
+ ==============================================================================
+
+ [..] The FLASH Memory Erasing functions, includes the following functions:
+ (+) HAL_FLASHEx_Erase: return only when erase has been done
+ (+) HAL_FLASHEx_Erase_IT: end of erase is done when HAL_FLASH_EndOfOperationCallback
+ is called with parameter 0xFFFFFFFF
+
+ [..] Any operation of erase should follow these steps:
+ (#) Call the HAL_FLASH_Unlock() function to enable the flash control register and
+ program memory access.
+ (#) Call the desired function to erase page.
+ (#) Call the HAL_FLASH_Lock() to disable the flash program memory access
+ (recommended to protect the FLASH memory against possible unwanted operation).
+
+@endverbatim
+ * @{
+ */
+
+
+/**
+ * @brief Perform a mass erase or erase the specified FLASH memory pages
+ * @note To correctly run this function, the @ref HAL_FLASH_Unlock() function
+ * must be called before.
+ * Call the @ref HAL_FLASH_Lock() to disable the flash memory access
+ * (recommended to protect the FLASH memory against possible unwanted operation)
+ * @param[in] pEraseInit pointer to an FLASH_EraseInitTypeDef structure that
+ * contains the configuration information for the erasing.
+ *
+ * @param[out] PageError pointer to variable that
+ * contains the configuration information on faulty page in case of error
+ * (0xFFFFFFFF means that all the pages have been correctly erased)
+ *
+ * @retval HAL_StatusTypeDef HAL Status
+ */
+HAL_StatusTypeDef HAL_FLASHEx_Erase(FLASH_EraseInitTypeDef *pEraseInit, uint32_t *PageError)
+{
+ HAL_StatusTypeDef status = HAL_ERROR;
+ uint32_t address = 0U;
+
+ /* Process Locked */
+ __HAL_LOCK(&pFlash);
+
+ /* Check the parameters */
+ assert_param(IS_FLASH_TYPEERASE(pEraseInit->TypeErase));
+
+ if (pEraseInit->TypeErase == FLASH_TYPEERASE_MASSERASE)
+ {
+ /* Mass Erase requested for Bank1 */
+ /* Wait for last operation to be completed */
+ if (FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE) == HAL_OK)
+ {
+ /*Mass erase to be done*/
+ FLASH_MassErase();
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE);
+
+ /* If the erase operation is completed, disable the MER Bit */
+ CLEAR_BIT(FLASH->CR, FLASH_CR_MER);
+ }
+ }
+ else
+ {
+ /* Page Erase is requested */
+ /* Check the parameters */
+ assert_param(IS_FLASH_PROGRAM_ADDRESS(pEraseInit->PageAddress));
+ assert_param(IS_FLASH_NB_PAGES(pEraseInit->PageAddress, pEraseInit->NbPages));
+
+ /* Page Erase requested on address located on bank1 */
+ /* Wait for last operation to be completed */
+ if (FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE) == HAL_OK)
+ {
+ /*Initialization of PageError variable*/
+ *PageError = 0xFFFFFFFFU;
+
+ /* Erase page by page to be done*/
+ for(address = pEraseInit->PageAddress;
+ address < ((pEraseInit->NbPages * FLASH_PAGE_SIZE) + pEraseInit->PageAddress);
+ address += FLASH_PAGE_SIZE)
+ {
+ FLASH_PageErase(address);
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE);
+
+ /* If the erase operation is completed, disable the PER Bit */
+ CLEAR_BIT(FLASH->CR, FLASH_CR_PER);
+
+ if (status != HAL_OK)
+ {
+ /* In case of error, stop erase procedure and return the faulty address */
+ *PageError = address;
+ break;
+ }
+ }
+ }
+ }
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(&pFlash);
+
+ return status;
+}
+
+/**
+ * @brief Perform a mass erase or erase the specified FLASH memory pages with interrupt enabled
+ * @note To correctly run this function, the @ref HAL_FLASH_Unlock() function
+ * must be called before.
+ * Call the @ref HAL_FLASH_Lock() to disable the flash memory access
+ * (recommended to protect the FLASH memory against possible unwanted operation)
+ * @param pEraseInit pointer to an FLASH_EraseInitTypeDef structure that
+ * contains the configuration information for the erasing.
+ *
+ * @retval HAL_StatusTypeDef HAL Status
+ */
+HAL_StatusTypeDef HAL_FLASHEx_Erase_IT(FLASH_EraseInitTypeDef *pEraseInit)
+{
+ HAL_StatusTypeDef status = HAL_OK;
+
+ /* Process Locked */
+ __HAL_LOCK(&pFlash);
+
+ /* If procedure already ongoing, reject the next one */
+ if (pFlash.ProcedureOnGoing != FLASH_PROC_NONE)
+ {
+ return HAL_ERROR;
+ }
+
+ /* Check the parameters */
+ assert_param(IS_FLASH_TYPEERASE(pEraseInit->TypeErase));
+
+ /* Enable End of FLASH Operation and Error source interrupts */
+ __HAL_FLASH_ENABLE_IT(FLASH_IT_EOP | FLASH_IT_ERR);
+
+ if (pEraseInit->TypeErase == FLASH_TYPEERASE_MASSERASE)
+ {
+ /*Mass erase to be done*/
+ pFlash.ProcedureOnGoing = FLASH_PROC_MASSERASE;
+ FLASH_MassErase();
+ }
+ else
+ {
+ /* Erase by page to be done*/
+
+ /* Check the parameters */
+ assert_param(IS_FLASH_PROGRAM_ADDRESS(pEraseInit->PageAddress));
+ assert_param(IS_FLASH_NB_PAGES(pEraseInit->PageAddress, pEraseInit->NbPages));
+
+ pFlash.ProcedureOnGoing = FLASH_PROC_PAGEERASE;
+ pFlash.DataRemaining = pEraseInit->NbPages;
+ pFlash.Address = pEraseInit->PageAddress;
+
+ /*Erase 1st page and wait for IT*/
+ FLASH_PageErase(pEraseInit->PageAddress);
+ }
+
+ return status;
+}
+
+/**
+ * @}
+ */
+
+/** @defgroup FLASHEx_Exported_Functions_Group2 Option Bytes Programming functions
+ * @brief Option Bytes Programming functions
+ *
+@verbatim
+ ==============================================================================
+ ##### Option Bytes Programming functions #####
+ ==============================================================================
+ [..]
+ This subsection provides a set of functions allowing to control the FLASH
+ option bytes operations.
+
+@endverbatim
+ * @{
+ */
+
+/**
+ * @brief Erases the FLASH option bytes.
+ * @note This functions erases all option bytes except the Read protection (RDP).
+ * The function @ref HAL_FLASH_Unlock() should be called before to unlock the FLASH interface
+ * The function @ref HAL_FLASH_OB_Unlock() should be called before to unlock the options bytes
+ * The function @ref HAL_FLASH_OB_Launch() should be called after to force the reload of the options bytes
+ * (system reset will occur)
+ * @retval HAL status
+ */
+
+HAL_StatusTypeDef HAL_FLASHEx_OBErase(void)
+{
+ uint8_t rdptmp = OB_RDP_LEVEL_0;
+ HAL_StatusTypeDef status = HAL_ERROR;
+
+ /* Get the actual read protection Option Byte value */
+ rdptmp = FLASH_OB_GetRDP();
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE);
+
+ if(status == HAL_OK)
+ {
+ /* Clean the error context */
+ pFlash.ErrorCode = HAL_FLASH_ERROR_NONE;
+
+ /* If the previous operation is completed, proceed to erase the option bytes */
+ SET_BIT(FLASH->CR, FLASH_CR_OPTER);
+ SET_BIT(FLASH->CR, FLASH_CR_STRT);
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE);
+
+ /* If the erase operation is completed, disable the OPTER Bit */
+ CLEAR_BIT(FLASH->CR, FLASH_CR_OPTER);
+
+ if(status == HAL_OK)
+ {
+ /* Restore the last read protection Option Byte value */
+ status = FLASH_OB_RDP_LevelConfig(rdptmp);
+ }
+ }
+
+ /* Return the erase status */
+ return status;
+}
+
+/**
+ * @brief Program option bytes
+ * @note The function @ref HAL_FLASH_Unlock() should be called before to unlock the FLASH interface
+ * The function @ref HAL_FLASH_OB_Unlock() should be called before to unlock the options bytes
+ * The function @ref HAL_FLASH_OB_Launch() should be called after to force the reload of the options bytes
+ * (system reset will occur)
+ *
+ * @param pOBInit pointer to an FLASH_OBInitStruct structure that
+ * contains the configuration information for the programming.
+ *
+ * @retval HAL_StatusTypeDef HAL Status
+ */
+HAL_StatusTypeDef HAL_FLASHEx_OBProgram(FLASH_OBProgramInitTypeDef *pOBInit)
+{
+ HAL_StatusTypeDef status = HAL_ERROR;
+
+ /* Process Locked */
+ __HAL_LOCK(&pFlash);
+
+ /* Check the parameters */
+ assert_param(IS_OPTIONBYTE(pOBInit->OptionType));
+
+ /* Write protection configuration */
+ if((pOBInit->OptionType & OPTIONBYTE_WRP) == OPTIONBYTE_WRP)
+ {
+ assert_param(IS_WRPSTATE(pOBInit->WRPState));
+ if (pOBInit->WRPState == OB_WRPSTATE_ENABLE)
+ {
+ /* Enable of Write protection on the selected page */
+ status = FLASH_OB_EnableWRP(pOBInit->WRPPage);
+ }
+ else
+ {
+ /* Disable of Write protection on the selected page */
+ status = FLASH_OB_DisableWRP(pOBInit->WRPPage);
+ }
+ if (status != HAL_OK)
+ {
+ /* Process Unlocked */
+ __HAL_UNLOCK(&pFlash);
+ return status;
+ }
+ }
+
+ /* Read protection configuration */
+ if((pOBInit->OptionType & OPTIONBYTE_RDP) == OPTIONBYTE_RDP)
+ {
+ status = FLASH_OB_RDP_LevelConfig(pOBInit->RDPLevel);
+ if (status != HAL_OK)
+ {
+ /* Process Unlocked */
+ __HAL_UNLOCK(&pFlash);
+ return status;
+ }
+ }
+
+ /* USER configuration */
+ if((pOBInit->OptionType & OPTIONBYTE_USER) == OPTIONBYTE_USER)
+ {
+ status = FLASH_OB_UserConfig(pOBInit->USERConfig);
+ if (status != HAL_OK)
+ {
+ /* Process Unlocked */
+ __HAL_UNLOCK(&pFlash);
+ return status;
+ }
+ }
+
+ /* DATA configuration*/
+ if((pOBInit->OptionType & OPTIONBYTE_DATA) == OPTIONBYTE_DATA)
+ {
+ status = FLASH_OB_ProgramData(pOBInit->DATAAddress, pOBInit->DATAData);
+ if (status != HAL_OK)
+ {
+ /* Process Unlocked */
+ __HAL_UNLOCK(&pFlash);
+ return status;
+ }
+ }
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(&pFlash);
+
+ return status;
+}
+
+/**
+ * @brief Get the Option byte configuration
+ * @param pOBInit pointer to an FLASH_OBInitStruct structure that
+ * contains the configuration information for the programming.
+ *
+ * @retval None
+ */
+void HAL_FLASHEx_OBGetConfig(FLASH_OBProgramInitTypeDef *pOBInit)
+{
+ pOBInit->OptionType = OPTIONBYTE_WRP | OPTIONBYTE_RDP | OPTIONBYTE_USER;
+
+ /*Get WRP*/
+ pOBInit->WRPPage = FLASH_OB_GetWRP();
+
+ /*Get RDP Level*/
+ pOBInit->RDPLevel = FLASH_OB_GetRDP();
+
+ /*Get USER*/
+ pOBInit->USERConfig = FLASH_OB_GetUser();
+}
+
+/**
+ * @brief Get the Option byte user data
+ * @param DATAAdress Address of the option byte DATA
+ * This parameter can be one of the following values:
+ * @arg @ref OB_DATA_ADDRESS_DATA0
+ * @arg @ref OB_DATA_ADDRESS_DATA1
+ * @retval Value programmed in USER data
+ */
+uint32_t HAL_FLASHEx_OBGetUserData(uint32_t DATAAdress)
+{
+ uint32_t value = 0U;
+
+ if (DATAAdress == OB_DATA_ADDRESS_DATA0)
+ {
+ /* Get value programmed in OB USER Data0 */
+ value = READ_BIT(FLASH->OBR, FLASH_OBR_DATA0) >> FLASH_POSITION_OB_USERDATA0_BIT;
+ }
+ else
+ {
+ /* Get value programmed in OB USER Data1 */
+ value = READ_BIT(FLASH->OBR, FLASH_OBR_DATA1) >> FLASH_POSITION_OB_USERDATA1_BIT;
+ }
+
+ return value;
+}
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/** @addtogroup FLASHEx_Private_Functions
+ * @{
+ */
+
+/**
+ * @brief Full erase of FLASH memory Bank
+ *
+ * @retval None
+ */
+static void FLASH_MassErase(void)
+{
+ /* Clean the error context */
+ pFlash.ErrorCode = HAL_FLASH_ERROR_NONE;
+
+ /* Only bank1 will be erased*/
+ SET_BIT(FLASH->CR, FLASH_CR_MER);
+ SET_BIT(FLASH->CR, FLASH_CR_STRT);
+}
+
+/**
+ * @brief Enable the write protection of the desired pages
+ * @note An option byte erase is done automatically in this function.
+ * @note When the memory read protection level is selected (RDP level = 1),
+ * it is not possible to program or erase the flash page i if
+ * debug features are connected or boot code is executed in RAM, even if nWRPi = 1
+ *
+ * @param WriteProtectPage specifies the page(s) to be write protected.
+ * The value of this parameter depend on device used within the same series
+ * @retval HAL status
+ */
+static HAL_StatusTypeDef FLASH_OB_EnableWRP(uint32_t WriteProtectPage)
+{
+ HAL_StatusTypeDef status = HAL_OK;
+ uint16_t WRP0_Data = 0xFFFFU;
+#if defined(OB_WRP1_WRP1)
+ uint16_t WRP1_Data = 0xFFFFU;
+#endif /* OB_WRP1_WRP1 */
+#if defined(OB_WRP2_WRP2)
+ uint16_t WRP2_Data = 0xFFFFU;
+#endif /* OB_WRP2_WRP2 */
+#if defined(OB_WRP3_WRP3)
+ uint16_t WRP3_Data = 0xFFFFU;
+#endif /* OB_WRP3_WRP3 */
+
+ /* Check the parameters */
+ assert_param(IS_OB_WRP(WriteProtectPage));
+
+ /* Get current write protected pages and the new pages to be protected ******/
+ WriteProtectPage = (uint32_t)(~((~FLASH_OB_GetWRP()) | WriteProtectPage));
+
+#if defined(OB_WRP_PAGES0TO15MASK)
+ WRP0_Data = (uint16_t)(WriteProtectPage & OB_WRP_PAGES0TO15MASK);
+#elif defined(OB_WRP_PAGES0TO31MASK)
+ WRP0_Data = (uint16_t)(WriteProtectPage & OB_WRP_PAGES0TO31MASK);
+#endif /* OB_WRP_PAGES0TO31MASK */
+
+#if defined(OB_WRP_PAGES16TO31MASK)
+ WRP1_Data = (uint16_t)((WriteProtectPage & OB_WRP_PAGES16TO31MASK) >> 8U);
+#elif defined(OB_WRP_PAGES32TO63MASK)
+ WRP1_Data = (uint16_t)((WriteProtectPage & OB_WRP_PAGES32TO63MASK) >> 8U);
+#endif /* OB_WRP_PAGES32TO63MASK */
+
+#if defined(OB_WRP_PAGES32TO47MASK)
+ WRP2_Data = (uint16_t)((WriteProtectPage & OB_WRP_PAGES32TO47MASK) >> 16U);
+#endif /* OB_WRP_PAGES32TO47MASK */
+
+#if defined(OB_WRP_PAGES48TO63MASK)
+ WRP3_Data = (uint16_t)((WriteProtectPage & OB_WRP_PAGES48TO63MASK) >> 24U);
+#elif defined(OB_WRP_PAGES48TO127MASK)
+ WRP3_Data = (uint16_t)((WriteProtectPage & OB_WRP_PAGES48TO127MASK) >> 24U);
+#endif /* OB_WRP_PAGES48TO63MASK */
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE);
+
+ if(status == HAL_OK)
+ {
+ /* Clean the error context */
+ pFlash.ErrorCode = HAL_FLASH_ERROR_NONE;
+
+ /* To be able to write again option byte, need to perform a option byte erase */
+ status = HAL_FLASHEx_OBErase();
+ if (status == HAL_OK)
+ {
+ /* Enable write protection */
+ SET_BIT(FLASH->CR, FLASH_CR_OPTPG);
+
+#if defined(OB_WRP0_WRP0)
+ if(WRP0_Data != 0xFFU)
+ {
+ OB->WRP0 &= WRP0_Data;
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE);
+ }
+#endif /* OB_WRP0_WRP0 */
+
+#if defined(OB_WRP1_WRP1)
+ if((status == HAL_OK) && (WRP1_Data != 0xFFU))
+ {
+ OB->WRP1 &= WRP1_Data;
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE);
+ }
+#endif /* OB_WRP1_WRP1 */
+
+#if defined(OB_WRP2_WRP2)
+ if((status == HAL_OK) && (WRP2_Data != 0xFFU))
+ {
+ OB->WRP2 &= WRP2_Data;
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE);
+ }
+#endif /* OB_WRP2_WRP2 */
+
+#if defined(OB_WRP3_WRP3)
+ if((status == HAL_OK) && (WRP3_Data != 0xFFU))
+ {
+ OB->WRP3 &= WRP3_Data;
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE);
+ }
+#endif /* OB_WRP3_WRP3 */
+
+ /* if the program operation is completed, disable the OPTPG Bit */
+ CLEAR_BIT(FLASH->CR, FLASH_CR_OPTPG);
+ }
+ }
+
+ return status;
+}
+
+/**
+ * @brief Disable the write protection of the desired pages
+ * @note An option byte erase is done automatically in this function.
+ * @note When the memory read protection level is selected (RDP level = 1),
+ * it is not possible to program or erase the flash page i if
+ * debug features are connected or boot code is executed in RAM, even if nWRPi = 1
+ *
+ * @param WriteProtectPage specifies the page(s) to be write unprotected.
+ * The value of this parameter depend on device used within the same series
+ * @retval HAL status
+ */
+static HAL_StatusTypeDef FLASH_OB_DisableWRP(uint32_t WriteProtectPage)
+{
+ HAL_StatusTypeDef status = HAL_OK;
+ uint16_t WRP0_Data = 0xFFFFU;
+#if defined(OB_WRP1_WRP1)
+ uint16_t WRP1_Data = 0xFFFFU;
+#endif /* OB_WRP1_WRP1 */
+#if defined(OB_WRP2_WRP2)
+ uint16_t WRP2_Data = 0xFFFFU;
+#endif /* OB_WRP2_WRP2 */
+#if defined(OB_WRP3_WRP3)
+ uint16_t WRP3_Data = 0xFFFFU;
+#endif /* OB_WRP3_WRP3 */
+
+ /* Check the parameters */
+ assert_param(IS_OB_WRP(WriteProtectPage));
+
+ /* Get current write protected pages and the new pages to be unprotected ******/
+ WriteProtectPage = (FLASH_OB_GetWRP() | WriteProtectPage);
+
+#if defined(OB_WRP_PAGES0TO15MASK)
+ WRP0_Data = (uint16_t)(WriteProtectPage & OB_WRP_PAGES0TO15MASK);
+#elif defined(OB_WRP_PAGES0TO31MASK)
+ WRP0_Data = (uint16_t)(WriteProtectPage & OB_WRP_PAGES0TO31MASK);
+#endif /* OB_WRP_PAGES0TO31MASK */
+
+#if defined(OB_WRP_PAGES16TO31MASK)
+ WRP1_Data = (uint16_t)((WriteProtectPage & OB_WRP_PAGES16TO31MASK) >> 8U);
+#elif defined(OB_WRP_PAGES32TO63MASK)
+ WRP1_Data = (uint16_t)((WriteProtectPage & OB_WRP_PAGES32TO63MASK) >> 8U);
+#endif /* OB_WRP_PAGES32TO63MASK */
+
+#if defined(OB_WRP_PAGES32TO47MASK)
+ WRP2_Data = (uint16_t)((WriteProtectPage & OB_WRP_PAGES32TO47MASK) >> 16U);
+#endif /* OB_WRP_PAGES32TO47MASK */
+
+#if defined(OB_WRP_PAGES48TO63MASK)
+ WRP3_Data = (uint16_t)((WriteProtectPage & OB_WRP_PAGES48TO63MASK) >> 24U);
+#elif defined(OB_WRP_PAGES48TO127MASK)
+ WRP3_Data = (uint16_t)((WriteProtectPage & OB_WRP_PAGES48TO127MASK) >> 24U);
+#endif /* OB_WRP_PAGES48TO63MASK */
+
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE);
+
+ if(status == HAL_OK)
+ {
+ /* Clean the error context */
+ pFlash.ErrorCode = HAL_FLASH_ERROR_NONE;
+
+ /* To be able to write again option byte, need to perform a option byte erase */
+ status = HAL_FLASHEx_OBErase();
+ if (status == HAL_OK)
+ {
+ SET_BIT(FLASH->CR, FLASH_CR_OPTPG);
+
+#if defined(OB_WRP0_WRP0)
+ if(WRP0_Data != 0xFFU)
+ {
+ OB->WRP0 &= WRP0_Data;
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE);
+ }
+#endif /* OB_WRP0_WRP0 */
+
+#if defined(OB_WRP1_WRP1)
+ if((status == HAL_OK) && (WRP1_Data != 0xFFU))
+ {
+ OB->WRP1 &= WRP1_Data;
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE);
+ }
+#endif /* OB_WRP1_WRP1 */
+
+#if defined(OB_WRP2_WRP2)
+ if((status == HAL_OK) && (WRP2_Data != 0xFFU))
+ {
+ OB->WRP2 &= WRP2_Data;
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE);
+ }
+#endif /* OB_WRP2_WRP2 */
+
+#if defined(OB_WRP3_WRP3)
+ if((status == HAL_OK) && (WRP3_Data != 0xFFU))
+ {
+ OB->WRP3 &= WRP3_Data;
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE);
+ }
+#endif /* OB_WRP3_WRP3 */
+
+ /* if the program operation is completed, disable the OPTPG Bit */
+ CLEAR_BIT(FLASH->CR, FLASH_CR_OPTPG);
+ }
+ }
+ return status;
+}
+
+/**
+ * @brief Set the read protection level.
+ * @param ReadProtectLevel specifies the read protection level.
+ * This parameter can be one of the following values:
+ * @arg @ref OB_RDP_LEVEL_0 No protection
+ * @arg @ref OB_RDP_LEVEL_1 Read protection of the memory
+ * @arg @ref OB_RDP_LEVEL_2 Full chip protection
+ * @note Warning: When enabling OB_RDP level 2 it's no more possible to go back to level 1 or 0
+ * @retval HAL status
+ */
+static HAL_StatusTypeDef FLASH_OB_RDP_LevelConfig(uint8_t ReadProtectLevel)
+{
+ HAL_StatusTypeDef status = HAL_OK;
+
+ /* Check the parameters */
+ assert_param(IS_OB_RDP_LEVEL(ReadProtectLevel));
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE);
+
+ if(status == HAL_OK)
+ {
+ /* Clean the error context */
+ pFlash.ErrorCode = HAL_FLASH_ERROR_NONE;
+
+ /* If the previous operation is completed, proceed to erase the option bytes */
+ SET_BIT(FLASH->CR, FLASH_CR_OPTER);
+ SET_BIT(FLASH->CR, FLASH_CR_STRT);
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE);
+
+ /* If the erase operation is completed, disable the OPTER Bit */
+ CLEAR_BIT(FLASH->CR, FLASH_CR_OPTER);
+
+ if(status == HAL_OK)
+ {
+ /* Enable the Option Bytes Programming operation */
+ SET_BIT(FLASH->CR, FLASH_CR_OPTPG);
+
+ WRITE_REG(OB->RDP, ReadProtectLevel);
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE);
+
+ /* if the program operation is completed, disable the OPTPG Bit */
+ CLEAR_BIT(FLASH->CR, FLASH_CR_OPTPG);
+ }
+ }
+
+ return status;
+}
+
+/**
+ * @brief Program the FLASH User Option Byte.
+ * @note Programming of the OB should be performed only after an erase (otherwise PGERR occurs)
+ * @param UserConfig The FLASH User Option Bytes values: IWDG_SW(Bit0), RST_STOP(Bit1), RST_STDBY(Bit2), nBOOT1(Bit4),
+ * VDDA_Analog_Monitoring(Bit5) and SRAM_Parity_Enable(Bit6).
+ * For few devices, following option bytes are available: nBOOT0(Bit3) & BOOT_SEL(Bit7).
+ * @retval HAL status
+ */
+static HAL_StatusTypeDef FLASH_OB_UserConfig(uint8_t UserConfig)
+{
+ HAL_StatusTypeDef status = HAL_OK;
+
+ /* Check the parameters */
+ assert_param(IS_OB_IWDG_SOURCE((UserConfig&OB_IWDG_SW)));
+ assert_param(IS_OB_STOP_SOURCE((UserConfig&OB_STOP_NO_RST)));
+ assert_param(IS_OB_STDBY_SOURCE((UserConfig&OB_STDBY_NO_RST)));
+ assert_param(IS_OB_BOOT1((UserConfig&OB_BOOT1_SET)));
+ assert_param(IS_OB_VDDA_ANALOG((UserConfig&OB_VDDA_ANALOG_ON)));
+ assert_param(IS_OB_SRAM_PARITY((UserConfig&OB_SRAM_PARITY_RESET)));
+#if defined(FLASH_OBR_BOOT_SEL)
+ assert_param(IS_OB_BOOT_SEL((UserConfig&OB_BOOT_SEL_SET)));
+ assert_param(IS_OB_BOOT0((UserConfig&OB_BOOT0_SET)));
+#endif /* FLASH_OBR_BOOT_SEL */
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE);
+
+ if(status == HAL_OK)
+ {
+ /* Clean the error context */
+ pFlash.ErrorCode = HAL_FLASH_ERROR_NONE;
+
+ /* Enable the Option Bytes Programming operation */
+ SET_BIT(FLASH->CR, FLASH_CR_OPTPG);
+
+#if defined(FLASH_OBR_BOOT_SEL)
+ OB->USER = UserConfig;
+#else
+ OB->USER = (UserConfig | 0x88U);
+#endif
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE);
+
+ /* if the program operation is completed, disable the OPTPG Bit */
+ CLEAR_BIT(FLASH->CR, FLASH_CR_OPTPG);
+ }
+
+ return status;
+}
+
+/**
+ * @brief Programs a half word at a specified Option Byte Data address.
+ * @note The function @ref HAL_FLASH_Unlock() should be called before to unlock the FLASH interface
+ * The function @ref HAL_FLASH_OB_Unlock() should be called before to unlock the options bytes
+ * The function @ref HAL_FLASH_OB_Launch() should be called after to force the reload of the options bytes
+ * (system reset will occur)
+ * Programming of the OB should be performed only after an erase (otherwise PGERR occurs)
+ * @param Address specifies the address to be programmed.
+ * This parameter can be 0x1FFFF804 or 0x1FFFF806.
+ * @param Data specifies the data to be programmed.
+ * @retval HAL status
+ */
+static HAL_StatusTypeDef FLASH_OB_ProgramData(uint32_t Address, uint8_t Data)
+{
+ HAL_StatusTypeDef status = HAL_ERROR;
+
+ /* Check the parameters */
+ assert_param(IS_OB_DATA_ADDRESS(Address));
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE);
+
+ if(status == HAL_OK)
+ {
+ /* Clean the error context */
+ pFlash.ErrorCode = HAL_FLASH_ERROR_NONE;
+
+ /* Enables the Option Bytes Programming operation */
+ SET_BIT(FLASH->CR, FLASH_CR_OPTPG);
+ *(__IO uint16_t*)Address = Data;
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE);
+
+ /* If the program operation is completed, disable the OPTPG Bit */
+ CLEAR_BIT(FLASH->CR, FLASH_CR_OPTPG);
+ }
+ /* Return the Option Byte Data Program Status */
+ return status;
+}
+
+/**
+ * @brief Return the FLASH Write Protection Option Bytes value.
+ * @retval The FLASH Write Protection Option Bytes value
+ */
+static uint32_t FLASH_OB_GetWRP(void)
+{
+ /* Return the FLASH write protection Register value */
+ return (uint32_t)(READ_REG(FLASH->WRPR));
+}
+
+/**
+ * @brief Returns the FLASH Read Protection level.
+ * @retval FLASH RDP level
+ * This parameter can be one of the following values:
+ * @arg @ref OB_RDP_LEVEL_0 No protection
+ * @arg @ref OB_RDP_LEVEL_1 Read protection of the memory
+ * @arg @ref OB_RDP_LEVEL_2 Full chip protection
+ */
+static uint32_t FLASH_OB_GetRDP(void)
+{
+ uint32_t tmp_reg;
+
+ /* Read RDP level bits */
+ tmp_reg = READ_BIT(FLASH->OBR, (FLASH_OBR_RDPRT1 | FLASH_OBR_RDPRT2));
+
+ if (tmp_reg == 0U)
+ {
+ return OB_RDP_LEVEL_0;
+ }
+ else if ((tmp_reg & FLASH_OBR_RDPRT2) == FLASH_OBR_RDPRT2)
+ {
+ return OB_RDP_LEVEL_2;
+ }
+ else
+ {
+ return OB_RDP_LEVEL_1;
+ }
+}
+
+/**
+ * @brief Return the FLASH User Option Byte value.
+ * @retval The FLASH User Option Bytes values: IWDG_SW(Bit0), RST_STOP(Bit1), RST_STDBY(Bit2), nBOOT1(Bit4),
+ * VDDA_Analog_Monitoring(Bit5) and SRAM_Parity_Enable(Bit6).
+ * For few devices, following option bytes are available: nBOOT0(Bit3) & BOOT_SEL(Bit7).
+ */
+static uint8_t FLASH_OB_GetUser(void)
+{
+ /* Return the User Option Byte */
+ return (uint8_t)((READ_REG(FLASH->OBR) & FLASH_OBR_USER) >> FLASH_POSITION_IWDGSW_BIT);
+}
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/** @addtogroup FLASH
+ * @{
+ */
+
+/** @addtogroup FLASH_Private_Functions
+ * @{
+ */
+
+/**
+ * @brief Erase the specified FLASH memory page
+ * @param PageAddress FLASH page to erase
+ * The value of this parameter depend on device used within the same series
+ *
+ * @retval None
+ */
+void FLASH_PageErase(uint32_t PageAddress)
+{
+ /* Clean the error context */
+ pFlash.ErrorCode = HAL_FLASH_ERROR_NONE;
+
+ /* Proceed to erase the page */
+ SET_BIT(FLASH->CR, FLASH_CR_PER);
+ WRITE_REG(FLASH->AR, PageAddress);
+ SET_BIT(FLASH->CR, FLASH_CR_STRT);
+}
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+#endif /* HAL_FLASH_MODULE_ENABLED */
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_gpio.c b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_gpio.c
new file mode 100644
index 0000000..f15acf1
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_gpio.c
@@ -0,0 +1,540 @@
+/**
+ ******************************************************************************
+ * @file stm32f0xx_hal_gpio.c
+ * @author MCD Application Team
+ * @brief GPIO HAL module driver.
+ * This file provides firmware functions to manage the following
+ * functionalities of the General Purpose Input/Output (GPIO) peripheral:
+ * + Initialization and de-initialization functions
+ * + IO operation functions
+ *
+ @verbatim
+ ==============================================================================
+ ##### GPIO Peripheral features #####
+ ==============================================================================
+ [..]
+ (+) Each port bit of the general-purpose I/O (GPIO) ports can be individually
+ configured by software in several modes:
+ (++) Input mode
+ (++) Analog mode
+ (++) Output mode
+ (++) Alternate function mode
+ (++) External interrupt/event lines
+
+ (+) During and just after reset, the alternate functions and external interrupt
+ lines are not active and the I/O ports are configured in input floating mode.
+
+ (+) All GPIO pins have weak internal pull-up and pull-down resistors, which can be
+ activated or not.
+
+ (+) In Output or Alternate mode, each IO can be configured on open-drain or push-pull
+ type and the IO speed can be selected depending on the VDD value.
+
+ (+) The microcontroller IO pins are connected to onboard peripherals/modules through a
+ multiplexer that allows only one peripheral alternate function (AF) connected
+ to an IO pin at a time. In this way, there can be no conflict between peripherals
+ sharing the same IO pin.
+
+ (+) All ports have external interrupt/event capability. To use external interrupt
+ lines, the port must be configured in input mode. All available GPIO pins are
+ connected to the 16 external interrupt/event lines from EXTI0 to EXTI15.
+
+ (+) The external interrupt/event controller consists of up to 28 edge detectors
+ (16 lines are connected to GPIO) for generating event/interrupt requests (each
+ input line can be independently configured to select the type (interrupt or event)
+ and the corresponding trigger event (rising or falling or both). Each line can
+ also be masked independently.
+
+ ##### How to use this driver #####
+ ==============================================================================
+ [..]
+ (#) Enable the GPIO AHB clock using the following function : __HAL_RCC_GPIOx_CLK_ENABLE().
+
+ (#) Configure the GPIO pin(s) using HAL_GPIO_Init().
+ (++) Configure the IO mode using "Mode" member from GPIO_InitTypeDef structure
+ (++) Activate Pull-up, Pull-down resistor using "Pull" member from GPIO_InitTypeDef
+ structure.
+ (++) In case of Output or alternate function mode selection: the speed is
+ configured through "Speed" member from GPIO_InitTypeDef structure.
+ (++) In alternate mode is selection, the alternate function connected to the IO
+ is configured through "Alternate" member from GPIO_InitTypeDef structure.
+ (++) Analog mode is required when a pin is to be used as ADC channel
+ or DAC output.
+ (++) In case of external interrupt/event selection the "Mode" member from
+ GPIO_InitTypeDef structure select the type (interrupt or event) and
+ the corresponding trigger event (rising or falling or both).
+
+ (#) In case of external interrupt/event mode selection, configure NVIC IRQ priority
+ mapped to the EXTI line using HAL_NVIC_SetPriority() and enable it using
+ HAL_NVIC_EnableIRQ().
+
+ (#) HAL_GPIO_DeInit allows to set register values to their reset value. It's also
+ recommended to use it to unconfigure pin which was used as an external interrupt
+ or in event mode. That's the only way to reset corresponding bit in EXTI & SYSCFG
+ registers.
+
+ (#) To get the level of a pin configured in input mode use HAL_GPIO_ReadPin().
+
+ (#) To set/reset the level of a pin configured in output mode use
+ HAL_GPIO_WritePin()/HAL_GPIO_TogglePin().
+
+ (#) To lock pin configuration until next reset use HAL_GPIO_LockPin().
+
+ (#) During and just after reset, the alternate functions are not
+ active and the GPIO pins are configured in input floating mode (except JTAG
+ pins).
+
+ (#) The LSE oscillator pins OSC32_IN and OSC32_OUT can be used as general purpose
+ (PC14 and PC15, respectively) when the LSE oscillator is off. The LSE has
+ priority over the GPIO function.
+
+ (#) The HSE oscillator pins OSC_IN/OSC_OUT can be used as
+ general purpose PF0 and PF1, respectively, when the HSE oscillator is off.
+ The HSE has priority over the GPIO function.
+
+ @endverbatim
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2016 STMicroelectronics.
+ * All rights reserved.
+ *
+ * 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 "stm32f0xx_hal.h"
+
+/** @addtogroup STM32F0xx_HAL_Driver
+ * @{
+ */
+
+/** @defgroup GPIO GPIO
+ * @brief GPIO HAL module driver
+ * @{
+ */
+
+/** MISRA C:2012 deviation rule has been granted for following rules:
+ * Rule-18.1_d - Medium: Array pointer `GPIOx' is accessed with index [..,..]
+ * which may be out of array bounds [..,UNKNOWN] in following APIs:
+ * HAL_GPIO_Init
+ * HAL_GPIO_DeInit
+ */
+
+#ifdef HAL_GPIO_MODULE_ENABLED
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private defines -----------------------------------------------------------*/
+/** @addtogroup GPIO_Private_Constants GPIO Private Constants
+ * @{
+ */
+#define GPIO_NUMBER 16U
+/**
+ * @}
+ */
+
+/* Private macros ------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Exported functions --------------------------------------------------------*/
+
+/** @defgroup GPIO_Exported_Functions GPIO Exported Functions
+ * @{
+ */
+
+/** @defgroup GPIO_Exported_Functions_Group1 Initialization/de-initialization functions
+ * @brief Initialization and Configuration functions
+ *
+@verbatim
+ ===============================================================================
+ ##### Initialization and de-initialization functions #####
+ ===============================================================================
+
+@endverbatim
+ * @{
+ */
+
+/**
+ * @brief Initialize the GPIOx peripheral according to the specified parameters in the GPIO_Init.
+ * @param GPIOx where x can be (A..F) to select the GPIO peripheral for STM32F0 family
+ * @param GPIO_Init pointer to a GPIO_InitTypeDef structure that contains
+ * the configuration information for the specified GPIO peripheral.
+ * @retval None
+ */
+void HAL_GPIO_Init(GPIO_TypeDef *GPIOx, GPIO_InitTypeDef *GPIO_Init)
+{
+ uint32_t position = 0x00u;
+ uint32_t iocurrent;
+ uint32_t temp;
+
+ /* Check the parameters */
+ assert_param(IS_GPIO_ALL_INSTANCE(GPIOx));
+ assert_param(IS_GPIO_PIN(GPIO_Init->Pin));
+ assert_param(IS_GPIO_MODE(GPIO_Init->Mode));
+
+ /* Configure the port pins */
+ while (((GPIO_Init->Pin) >> position) != 0x00u)
+ {
+ /* Get current io position */
+ iocurrent = (GPIO_Init->Pin) & (1uL << position);
+
+ if (iocurrent != 0x00u)
+ {
+ /*--------------------- GPIO Mode Configuration ------------------------*/
+ /* In case of Output or Alternate function mode selection */
+ if(((GPIO_Init->Mode & GPIO_MODE) == MODE_OUTPUT) ||
+ ((GPIO_Init->Mode & GPIO_MODE) == MODE_AF))
+ {
+ /* Check the Speed parameter */
+ assert_param(IS_GPIO_SPEED(GPIO_Init->Speed));
+ /* Configure the IO Speed */
+ temp = GPIOx->OSPEEDR;
+ temp &= ~(GPIO_OSPEEDER_OSPEEDR0 << (position * 2u));
+ temp |= (GPIO_Init->Speed << (position * 2u));
+ GPIOx->OSPEEDR = temp;
+
+ /* Configure the IO Output Type */
+ temp = GPIOx->OTYPER;
+ temp &= ~(GPIO_OTYPER_OT_0 << position) ;
+ temp |= (((GPIO_Init->Mode & OUTPUT_TYPE) >> OUTPUT_TYPE_Pos) << position);
+ GPIOx->OTYPER = temp;
+ }
+
+ if((GPIO_Init->Mode & GPIO_MODE) != MODE_ANALOG)
+ {
+ /* Check the Pull parameter */
+ assert_param(IS_GPIO_PULL(GPIO_Init->Pull));
+
+ /* Activate the Pull-up or Pull down resistor for the current IO */
+ temp = GPIOx->PUPDR;
+ temp &= ~(GPIO_PUPDR_PUPDR0 << (position * 2u));
+ temp |= ((GPIO_Init->Pull) << (position * 2u));
+ GPIOx->PUPDR = temp;
+ }
+
+ /* In case of Alternate function mode selection */
+ if((GPIO_Init->Mode & GPIO_MODE) == MODE_AF)
+ {
+ /* Check the Alternate function parameters */
+ assert_param(IS_GPIO_AF_INSTANCE(GPIOx));
+ assert_param(IS_GPIO_AF(GPIO_Init->Alternate));
+
+ /* Configure Alternate function mapped with the current IO */
+ temp = GPIOx->AFR[position >> 3u];
+ temp &= ~(0xFu << ((position & 0x07u) * 4u));
+ temp |= ((GPIO_Init->Alternate) << ((position & 0x07u) * 4u));
+ GPIOx->AFR[position >> 3u] = temp;
+ }
+
+ /* Configure IO Direction mode (Input, Output, Alternate or Analog) */
+ temp = GPIOx->MODER;
+ temp &= ~(GPIO_MODER_MODER0 << (position * 2u));
+ temp |= ((GPIO_Init->Mode & GPIO_MODE) << (position * 2u));
+ GPIOx->MODER = temp;
+
+ /*--------------------- EXTI Mode Configuration ------------------------*/
+ /* Configure the External Interrupt or event for the current IO */
+ if((GPIO_Init->Mode & EXTI_MODE) != 0x00u)
+ {
+ /* Enable SYSCFG Clock */
+ __HAL_RCC_SYSCFG_CLK_ENABLE();
+
+ temp = SYSCFG->EXTICR[position >> 2u];
+ temp &= ~(0x0FuL << (4u * (position & 0x03u)));
+ temp |= (GPIO_GET_INDEX(GPIOx) << (4u * (position & 0x03u)));
+ SYSCFG->EXTICR[position >> 2u] = temp;
+
+ /* Clear EXTI line configuration */
+ temp = EXTI->IMR;
+ temp &= ~(iocurrent);
+ if((GPIO_Init->Mode & EXTI_IT) != 0x00u)
+ {
+ temp |= iocurrent;
+ }
+ EXTI->IMR = temp;
+
+ temp = EXTI->EMR;
+ temp &= ~(iocurrent);
+ if((GPIO_Init->Mode & EXTI_EVT) != 0x00u)
+ {
+ temp |= iocurrent;
+ }
+ EXTI->EMR = temp;
+
+ /* Clear Rising Falling edge configuration */
+ temp = EXTI->RTSR;
+ temp &= ~(iocurrent);
+ if((GPIO_Init->Mode & TRIGGER_RISING) != 0x00u)
+ {
+ temp |= iocurrent;
+ }
+ EXTI->RTSR = temp;
+
+ temp = EXTI->FTSR;
+ temp &= ~(iocurrent);
+ if((GPIO_Init->Mode & TRIGGER_FALLING) != 0x00u)
+ {
+ temp |= iocurrent;
+ }
+ EXTI->FTSR = temp;
+ }
+ }
+
+ position++;
+ }
+}
+
+/**
+ * @brief De-initialize the GPIOx peripheral registers to their default reset values.
+ * @param GPIOx where x can be (A..F) to select the GPIO peripheral for STM32F0 family
+ * @param GPIO_Pin specifies the port bit to be written.
+ * This parameter can be one of GPIO_PIN_x where x can be (0..15).
+ * @retval None
+ */
+void HAL_GPIO_DeInit(GPIO_TypeDef *GPIOx, uint32_t GPIO_Pin)
+{
+ uint32_t position = 0x00u;
+ uint32_t iocurrent;
+ uint32_t tmp;
+
+ /* Check the parameters */
+ assert_param(IS_GPIO_ALL_INSTANCE(GPIOx));
+ assert_param(IS_GPIO_PIN(GPIO_Pin));
+
+ /* Configure the port pins */
+ while ((GPIO_Pin >> position) != 0x00u)
+ {
+ /* Get current io position */
+ iocurrent = (GPIO_Pin) & (1uL << position);
+
+ if (iocurrent != 0x00u)
+ {
+ /*------------------------- EXTI Mode Configuration --------------------*/
+ /* Clear the External Interrupt or Event for the current IO */
+
+ tmp = SYSCFG->EXTICR[position >> 2u];
+ tmp &= (0x0FuL << (4u * (position & 0x03u)));
+ if (tmp == (GPIO_GET_INDEX(GPIOx) << (4u * (position & 0x03u))))
+ {
+ /* Clear EXTI line configuration */
+ EXTI->IMR &= ~((uint32_t)iocurrent);
+ EXTI->EMR &= ~((uint32_t)iocurrent);
+
+ /* Clear Rising Falling edge configuration */
+ EXTI->RTSR &= ~((uint32_t)iocurrent);
+ EXTI->FTSR &= ~((uint32_t)iocurrent);
+
+ /* Configure the External Interrupt or event for the current IO */
+ tmp = 0x0FuL << (4u * (position & 0x03u));
+ SYSCFG->EXTICR[position >> 2u] &= ~tmp;
+ }
+
+ /*------------------------- GPIO Mode Configuration --------------------*/
+ /* Configure IO Direction in Input Floating Mode */
+ GPIOx->MODER &= ~(GPIO_MODER_MODER0 << (position * 2u));
+
+ /* Configure the default Alternate Function in current IO */
+ GPIOx->AFR[position >> 3u] &= ~(0xFu << ((uint32_t)(position & 0x07u) * 4u)) ;
+
+ /* Deactivate the Pull-up and Pull-down resistor for the current IO */
+ GPIOx->PUPDR &= ~(GPIO_PUPDR_PUPDR0 << (position * 2u));
+
+ /* Configure the default value IO Output Type */
+ GPIOx->OTYPER &= ~(GPIO_OTYPER_OT_0 << position) ;
+
+ /* Configure the default value for IO Speed */
+ GPIOx->OSPEEDR &= ~(GPIO_OSPEEDER_OSPEEDR0 << (position * 2u));
+
+ }
+
+ position++;
+ }
+}
+
+/**
+ * @}
+ */
+
+/** @defgroup GPIO_Exported_Functions_Group2 IO operation functions
+ * @brief GPIO Read, Write, Toggle, Lock and EXTI management functions.
+ *
+@verbatim
+ ===============================================================================
+ ##### IO operation functions #####
+ ===============================================================================
+
+@endverbatim
+ * @{
+ */
+
+/**
+ * @brief Read the specified input port pin.
+ * @param GPIOx where x can be (A..F) to select the GPIO peripheral for STM32F0 family
+ * @param GPIO_Pin specifies the port bit to read.
+ * This parameter can be GPIO_PIN_x where x can be (0..15).
+ * @retval The input port pin value.
+ */
+GPIO_PinState HAL_GPIO_ReadPin(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin)
+{
+ GPIO_PinState bitstatus;
+
+ /* Check the parameters */
+ assert_param(IS_GPIO_PIN(GPIO_Pin));
+
+ if ((GPIOx->IDR & GPIO_Pin) != (uint32_t)GPIO_PIN_RESET)
+ {
+ bitstatus = GPIO_PIN_SET;
+ }
+ else
+ {
+ bitstatus = GPIO_PIN_RESET;
+ }
+ return bitstatus;
+ }
+
+/**
+ * @brief Set or clear the selected data port bit.
+ * @note This function uses GPIOx_BSRR and GPIOx_BRR registers to allow atomic read/modify
+ * accesses. In this way, there is no risk of an IRQ occurring between
+ * the read and the modify access.
+ *
+ * @param GPIOx where x can be (A..H) to select the GPIO peripheral for STM32F0 family
+ * @param GPIO_Pin specifies the port bit to be written.
+ * This parameter can be one of GPIO_PIN_x where x can be (0..15).
+ * @param PinState specifies the value to be written to the selected bit.
+ * This parameter can be one of the GPIO_PinState enum values:
+ * @arg GPIO_PIN_RESET: to clear the port pin
+ * @arg GPIO_PIN_SET: to set the port pin
+ * @retval None
+ */
+void HAL_GPIO_WritePin(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin, GPIO_PinState PinState)
+{
+ /* Check the parameters */
+ assert_param(IS_GPIO_PIN(GPIO_Pin));
+ assert_param(IS_GPIO_PIN_ACTION(PinState));
+
+ if (PinState != GPIO_PIN_RESET)
+ {
+ GPIOx->BSRR = (uint32_t)GPIO_Pin;
+ }
+ else
+ {
+ GPIOx->BRR = (uint32_t)GPIO_Pin;
+ }
+}
+
+/**
+ * @brief Toggle the specified GPIO pin.
+ * @param GPIOx where x can be (A..F) to select the GPIO peripheral for STM32F0 family
+ * @param GPIO_Pin specifies the pin to be toggled.
+ * @retval None
+ */
+void HAL_GPIO_TogglePin(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin)
+{
+ uint32_t odr;
+
+ /* Check the parameters */
+ assert_param(IS_GPIO_PIN(GPIO_Pin));
+
+ /* get current Ouput Data Register value */
+ odr = GPIOx->ODR;
+
+ /* Set selected pins that were at low level, and reset ones that were high */
+ GPIOx->BSRR = ((odr & GPIO_Pin) << GPIO_NUMBER) | (~odr & GPIO_Pin);
+}
+
+/**
+* @brief Locks GPIO Pins configuration registers.
+* @note The locked registers are GPIOx_MODER, GPIOx_OTYPER, GPIOx_OSPEEDR,
+* GPIOx_PUPDR, GPIOx_AFRL and GPIOx_AFRH.
+* @note The configuration of the locked GPIO pins can no longer be modified
+* until the next reset.
+ * @param GPIOx where x can be (A..F) to select the GPIO peripheral for STM32F0 family
+ * @param GPIO_Pin specifies the port bits to be locked.
+* This parameter can be any combination of GPIO_Pin_x where x can be (0..15).
+* @retval None
+*/
+HAL_StatusTypeDef HAL_GPIO_LockPin(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin)
+{
+ __IO uint32_t tmp = GPIO_LCKR_LCKK;
+
+ /* Check the parameters */
+ assert_param(IS_GPIO_LOCK_INSTANCE(GPIOx));
+ assert_param(IS_GPIO_PIN(GPIO_Pin));
+
+ /* Apply lock key write sequence */
+ SET_BIT(tmp, GPIO_Pin);
+ /* Set LCKx bit(s): LCKK='1' + LCK[15-0] */
+ GPIOx->LCKR = tmp;
+ /* Reset LCKx bit(s): LCKK='0' + LCK[15-0] */
+ GPIOx->LCKR = GPIO_Pin;
+ /* Set LCKx bit(s): LCKK='1' + LCK[15-0] */
+ GPIOx->LCKR = tmp;
+ /* Read LCKK register. This read is mandatory to complete key lock sequence */
+ tmp = GPIOx->LCKR;
+
+ /* read again in order to confirm lock is active */
+ if((GPIOx->LCKR & GPIO_LCKR_LCKK) != 0x00u)
+ {
+ return HAL_OK;
+ }
+ else
+ {
+ return HAL_ERROR;
+ }
+}
+
+/**
+ * @brief Handle EXTI interrupt request.
+ * @param GPIO_Pin Specifies the port pin connected to corresponding EXTI line.
+ * @retval None
+ */
+void HAL_GPIO_EXTI_IRQHandler(uint16_t GPIO_Pin)
+{
+ /* EXTI line interrupt detected */
+ if(__HAL_GPIO_EXTI_GET_IT(GPIO_Pin) != 0x00u)
+ {
+ __HAL_GPIO_EXTI_CLEAR_IT(GPIO_Pin);
+ HAL_GPIO_EXTI_Callback(GPIO_Pin);
+ }
+}
+
+/**
+ * @brief EXTI line detection callback.
+ * @param GPIO_Pin Specifies the port pin connected to corresponding EXTI line.
+ * @retval None
+ */
+__weak void HAL_GPIO_EXTI_Callback(uint16_t GPIO_Pin)
+{
+ /* Prevent unused argument(s) compilation warning */
+ UNUSED(GPIO_Pin);
+
+ /* NOTE: This function should not be modified, when the callback is needed,
+ the HAL_GPIO_EXTI_Callback could be implemented in the user file
+ */
+}
+
+/**
+ * @}
+ */
+
+
+/**
+ * @}
+ */
+
+#endif /* HAL_GPIO_MODULE_ENABLED */
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_i2c.c b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_i2c.c
new file mode 100644
index 0000000..b38f6c9
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_i2c.c
@@ -0,0 +1,6794 @@
+/**
+ ******************************************************************************
+ * @file stm32f0xx_hal_i2c.c
+ * @author MCD Application Team
+ * @brief I2C HAL module driver.
+ * This file provides firmware functions to manage the following
+ * functionalities of the Inter Integrated Circuit (I2C) peripheral:
+ * + Initialization and de-initialization functions
+ * + IO operation functions
+ * + Peripheral State and Errors functions
+ *
+ @verbatim
+ ==============================================================================
+ ##### How to use this driver #####
+ ==============================================================================
+ [..]
+ The I2C HAL driver can be used as follows:
+
+ (#) Declare a I2C_HandleTypeDef handle structure, for example:
+ I2C_HandleTypeDef hi2c;
+
+ (#)Initialize the I2C low level resources by implementing the HAL_I2C_MspInit() API:
+ (##) Enable the I2Cx interface clock
+ (##) I2C pins configuration
+ (+++) Enable the clock for the I2C GPIOs
+ (+++) Configure I2C pins as alternate function open-drain
+ (##) NVIC configuration if you need to use interrupt process
+ (+++) Configure the I2Cx interrupt priority
+ (+++) Enable the NVIC I2C IRQ Channel
+ (##) DMA Configuration if you need to use DMA process
+ (+++) Declare a DMA_HandleTypeDef handle structure for
+ the transmit or receive channel
+ (+++) Enable the DMAx interface clock using
+ (+++) Configure the DMA handle parameters
+ (+++) Configure the DMA Tx or Rx channel
+ (+++) Associate the initialized DMA handle to the hi2c DMA Tx or Rx handle
+ (+++) Configure the priority and enable the NVIC for the transfer complete interrupt on
+ the DMA Tx or Rx channel
+
+ (#) Configure the Communication Clock Timing, Own Address1, Master Addressing mode, Dual Addressing mode,
+ Own Address2, Own Address2 Mask, General call and Nostretch mode in the hi2c Init structure.
+
+ (#) Initialize the I2C registers by calling the HAL_I2C_Init(), configures also the low level Hardware
+ (GPIO, CLOCK, NVIC...etc) by calling the customized HAL_I2C_MspInit(&hi2c) API.
+
+ (#) To check if target device is ready for communication, use the function HAL_I2C_IsDeviceReady()
+
+ (#) For I2C IO and IO MEM operations, three operation modes are available within this driver :
+
+ *** Polling mode IO operation ***
+ =================================
+ [..]
+ (+) Transmit in master mode an amount of data in blocking mode using HAL_I2C_Master_Transmit()
+ (+) Receive in master mode an amount of data in blocking mode using HAL_I2C_Master_Receive()
+ (+) Transmit in slave mode an amount of data in blocking mode using HAL_I2C_Slave_Transmit()
+ (+) Receive in slave mode an amount of data in blocking mode using HAL_I2C_Slave_Receive()
+
+ *** Polling mode IO MEM operation ***
+ =====================================
+ [..]
+ (+) Write an amount of data in blocking mode to a specific memory address using HAL_I2C_Mem_Write()
+ (+) Read an amount of data in blocking mode from a specific memory address using HAL_I2C_Mem_Read()
+
+
+ *** Interrupt mode IO operation ***
+ ===================================
+ [..]
+ (+) Transmit in master mode an amount of data in non-blocking mode using HAL_I2C_Master_Transmit_IT()
+ (+) At transmission end of transfer, HAL_I2C_MasterTxCpltCallback() is executed and users can
+ add their own code by customization of function pointer HAL_I2C_MasterTxCpltCallback()
+ (+) Receive in master mode an amount of data in non-blocking mode using HAL_I2C_Master_Receive_IT()
+ (+) At reception end of transfer, HAL_I2C_MasterRxCpltCallback() is executed and users can
+ add their own code by customization of function pointer HAL_I2C_MasterRxCpltCallback()
+ (+) Transmit in slave mode an amount of data in non-blocking mode using HAL_I2C_Slave_Transmit_IT()
+ (+) At transmission end of transfer, HAL_I2C_SlaveTxCpltCallback() is executed and users can
+ add their own code by customization of function pointer HAL_I2C_SlaveTxCpltCallback()
+ (+) Receive in slave mode an amount of data in non-blocking mode using HAL_I2C_Slave_Receive_IT()
+ (+) At reception end of transfer, HAL_I2C_SlaveRxCpltCallback() is executed and users can
+ add their own code by customization of function pointer HAL_I2C_SlaveRxCpltCallback()
+ (+) In case of transfer Error, HAL_I2C_ErrorCallback() function is executed and users can
+ add their own code by customization of function pointer HAL_I2C_ErrorCallback()
+ (+) Abort a master I2C process communication with Interrupt using HAL_I2C_Master_Abort_IT()
+ (+) End of abort process, HAL_I2C_AbortCpltCallback() is executed and users can
+ add their own code by customization of function pointer HAL_I2C_AbortCpltCallback()
+ (+) Discard a slave I2C process communication using __HAL_I2C_GENERATE_NACK() macro.
+ This action will inform Master to generate a Stop condition to discard the communication.
+
+
+ *** Interrupt mode or DMA mode IO sequential operation ***
+ ==========================================================
+ [..]
+ (@) These interfaces allow to manage a sequential transfer with a repeated start condition
+ when a direction change during transfer
+ [..]
+ (+) A specific option field manage the different steps of a sequential transfer
+ (+) Option field values are defined through I2C_XFEROPTIONS and are listed below:
+ (++) I2C_FIRST_AND_LAST_FRAME: No sequential usage, functional is same as associated interfaces in
+ no sequential mode
+ (++) I2C_FIRST_FRAME: Sequential usage, this option allow to manage a sequence with start condition, address
+ and data to transfer without a final stop condition
+ (++) I2C_FIRST_AND_NEXT_FRAME: Sequential usage (Master only), this option allow to manage a sequence with
+ start condition, address and data to transfer without a final stop condition,
+ an then permit a call the same master sequential interface several times
+ (like HAL_I2C_Master_Seq_Transmit_IT() then HAL_I2C_Master_Seq_Transmit_IT()
+ or HAL_I2C_Master_Seq_Transmit_DMA() then HAL_I2C_Master_Seq_Transmit_DMA())
+ (++) I2C_NEXT_FRAME: Sequential usage, this option allow to manage a sequence with a restart condition, address
+ and with new data to transfer if the direction change or manage only the new data to
+ transfer
+ if no direction change and without a final stop condition in both cases
+ (++) I2C_LAST_FRAME: Sequential usage, this option allow to manage a sequance with a restart condition, address
+ and with new data to transfer if the direction change or manage only the new data to
+ transfer
+ if no direction change and with a final stop condition in both cases
+ (++) I2C_LAST_FRAME_NO_STOP: Sequential usage (Master only), this option allow to manage a restart condition
+ after several call of the same master sequential interface several times
+ (link with option I2C_FIRST_AND_NEXT_FRAME).
+ Usage can, transfer several bytes one by one using
+ HAL_I2C_Master_Seq_Transmit_IT
+ or HAL_I2C_Master_Seq_Receive_IT
+ or HAL_I2C_Master_Seq_Transmit_DMA
+ or HAL_I2C_Master_Seq_Receive_DMA
+ with option I2C_FIRST_AND_NEXT_FRAME then I2C_NEXT_FRAME.
+ Then usage of this option I2C_LAST_FRAME_NO_STOP at the last Transmit or
+ Receive sequence permit to call the opposite interface Receive or Transmit
+ without stopping the communication and so generate a restart condition.
+ (++) I2C_OTHER_FRAME: Sequential usage (Master only), this option allow to manage a restart condition after
+ each call of the same master sequential
+ interface.
+ Usage can, transfer several bytes one by one with a restart with slave address between
+ each bytes using
+ HAL_I2C_Master_Seq_Transmit_IT
+ or HAL_I2C_Master_Seq_Receive_IT
+ or HAL_I2C_Master_Seq_Transmit_DMA
+ or HAL_I2C_Master_Seq_Receive_DMA
+ with option I2C_FIRST_FRAME then I2C_OTHER_FRAME.
+ Then usage of this option I2C_OTHER_AND_LAST_FRAME at the last frame to help automatic
+ generation of STOP condition.
+
+ (+) Different sequential I2C interfaces are listed below:
+ (++) Sequential transmit in master I2C mode an amount of data in non-blocking mode using
+ HAL_I2C_Master_Seq_Transmit_IT() or using HAL_I2C_Master_Seq_Transmit_DMA()
+ (+++) At transmission end of current frame transfer, HAL_I2C_MasterTxCpltCallback() is executed and
+ users can add their own code by customization of function pointer HAL_I2C_MasterTxCpltCallback()
+ (++) Sequential receive in master I2C mode an amount of data in non-blocking mode using
+ HAL_I2C_Master_Seq_Receive_IT() or using HAL_I2C_Master_Seq_Receive_DMA()
+ (+++) At reception end of current frame transfer, HAL_I2C_MasterRxCpltCallback() is executed and users can
+ add their own code by customization of function pointer HAL_I2C_MasterRxCpltCallback()
+ (++) Abort a master IT or DMA I2C process communication with Interrupt using HAL_I2C_Master_Abort_IT()
+ (+++) End of abort process, HAL_I2C_AbortCpltCallback() is executed and users can
+ add their own code by customization of function pointer HAL_I2C_AbortCpltCallback()
+ (++) Enable/disable the Address listen mode in slave I2C mode using HAL_I2C_EnableListen_IT()
+ HAL_I2C_DisableListen_IT()
+ (+++) When address slave I2C match, HAL_I2C_AddrCallback() is executed and users can
+ add their own code to check the Address Match Code and the transmission direction request by master
+ (Write/Read).
+ (+++) At Listen mode end HAL_I2C_ListenCpltCallback() is executed and users can
+ add their own code by customization of function pointer HAL_I2C_ListenCpltCallback()
+ (++) Sequential transmit in slave I2C mode an amount of data in non-blocking mode using
+ HAL_I2C_Slave_Seq_Transmit_IT() or using HAL_I2C_Slave_Seq_Transmit_DMA()
+ (+++) At transmission end of current frame transfer, HAL_I2C_SlaveTxCpltCallback() is executed and
+ users can add their own code by customization of function pointer HAL_I2C_SlaveTxCpltCallback()
+ (++) Sequential receive in slave I2C mode an amount of data in non-blocking mode using
+ HAL_I2C_Slave_Seq_Receive_IT() or using HAL_I2C_Slave_Seq_Receive_DMA()
+ (+++) At reception end of current frame transfer, HAL_I2C_SlaveRxCpltCallback() is executed and users can
+ add their own code by customization of function pointer HAL_I2C_SlaveRxCpltCallback()
+ (++) In case of transfer Error, HAL_I2C_ErrorCallback() function is executed and users can
+ add their own code by customization of function pointer HAL_I2C_ErrorCallback()
+ (++) Discard a slave I2C process communication using __HAL_I2C_GENERATE_NACK() macro.
+ This action will inform Master to generate a Stop condition to discard the communication.
+
+ *** Interrupt mode IO MEM operation ***
+ =======================================
+ [..]
+ (+) Write an amount of data in non-blocking mode with Interrupt to a specific memory address using
+ HAL_I2C_Mem_Write_IT()
+ (+) At Memory end of write transfer, HAL_I2C_MemTxCpltCallback() is executed and users can
+ add their own code by customization of function pointer HAL_I2C_MemTxCpltCallback()
+ (+) Read an amount of data in non-blocking mode with Interrupt from a specific memory address using
+ HAL_I2C_Mem_Read_IT()
+ (+) At Memory end of read transfer, HAL_I2C_MemRxCpltCallback() is executed and users can
+ add their own code by customization of function pointer HAL_I2C_MemRxCpltCallback()
+ (+) In case of transfer Error, HAL_I2C_ErrorCallback() function is executed and users can
+ add their own code by customization of function pointer HAL_I2C_ErrorCallback()
+
+ *** DMA mode IO operation ***
+ ==============================
+ [..]
+ (+) Transmit in master mode an amount of data in non-blocking mode (DMA) using
+ HAL_I2C_Master_Transmit_DMA()
+ (+) At transmission end of transfer, HAL_I2C_MasterTxCpltCallback() is executed and users can
+ add their own code by customization of function pointer HAL_I2C_MasterTxCpltCallback()
+ (+) Receive in master mode an amount of data in non-blocking mode (DMA) using
+ HAL_I2C_Master_Receive_DMA()
+ (+) At reception end of transfer, HAL_I2C_MasterRxCpltCallback() is executed and users can
+ add their own code by customization of function pointer HAL_I2C_MasterRxCpltCallback()
+ (+) Transmit in slave mode an amount of data in non-blocking mode (DMA) using
+ HAL_I2C_Slave_Transmit_DMA()
+ (+) At transmission end of transfer, HAL_I2C_SlaveTxCpltCallback() is executed and users can
+ add their own code by customization of function pointer HAL_I2C_SlaveTxCpltCallback()
+ (+) Receive in slave mode an amount of data in non-blocking mode (DMA) using
+ HAL_I2C_Slave_Receive_DMA()
+ (+) At reception end of transfer, HAL_I2C_SlaveRxCpltCallback() is executed and users can
+ add their own code by customization of function pointer HAL_I2C_SlaveRxCpltCallback()
+ (+) In case of transfer Error, HAL_I2C_ErrorCallback() function is executed and users can
+ add their own code by customization of function pointer HAL_I2C_ErrorCallback()
+ (+) Abort a master I2C process communication with Interrupt using HAL_I2C_Master_Abort_IT()
+ (+) End of abort process, HAL_I2C_AbortCpltCallback() is executed and users can
+ add their own code by customization of function pointer HAL_I2C_AbortCpltCallback()
+ (+) Discard a slave I2C process communication using __HAL_I2C_GENERATE_NACK() macro.
+ This action will inform Master to generate a Stop condition to discard the communication.
+
+ *** DMA mode IO MEM operation ***
+ =================================
+ [..]
+ (+) Write an amount of data in non-blocking mode with DMA to a specific memory address using
+ HAL_I2C_Mem_Write_DMA()
+ (+) At Memory end of write transfer, HAL_I2C_MemTxCpltCallback() is executed and users can
+ add their own code by customization of function pointer HAL_I2C_MemTxCpltCallback()
+ (+) Read an amount of data in non-blocking mode with DMA from a specific memory address using
+ HAL_I2C_Mem_Read_DMA()
+ (+) At Memory end of read transfer, HAL_I2C_MemRxCpltCallback() is executed and users can
+ add their own code by customization of function pointer HAL_I2C_MemRxCpltCallback()
+ (+) In case of transfer Error, HAL_I2C_ErrorCallback() function is executed and users can
+ add their own code by customization of function pointer HAL_I2C_ErrorCallback()
+
+
+ *** I2C HAL driver macros list ***
+ ==================================
+ [..]
+ Below the list of most used macros in I2C HAL driver.
+
+ (+) __HAL_I2C_ENABLE: Enable the I2C peripheral
+ (+) __HAL_I2C_DISABLE: Disable the I2C peripheral
+ (+) __HAL_I2C_GENERATE_NACK: Generate a Non-Acknowledge I2C peripheral in Slave mode
+ (+) __HAL_I2C_GET_FLAG: Check whether the specified I2C flag is set or not
+ (+) __HAL_I2C_CLEAR_FLAG: Clear the specified I2C pending flag
+ (+) __HAL_I2C_ENABLE_IT: Enable the specified I2C interrupt
+ (+) __HAL_I2C_DISABLE_IT: Disable the specified I2C interrupt
+
+ *** Callback registration ***
+ =============================================
+ [..]
+ The compilation flag USE_HAL_I2C_REGISTER_CALLBACKS when set to 1
+ allows the user to configure dynamically the driver callbacks.
+ Use Functions HAL_I2C_RegisterCallback() or HAL_I2C_RegisterAddrCallback()
+ to register an interrupt callback.
+ [..]
+ Function HAL_I2C_RegisterCallback() allows to register following callbacks:
+ (+) MasterTxCpltCallback : callback for Master transmission end of transfer.
+ (+) MasterRxCpltCallback : callback for Master reception end of transfer.
+ (+) SlaveTxCpltCallback : callback for Slave transmission end of transfer.
+ (+) SlaveRxCpltCallback : callback for Slave reception end of transfer.
+ (+) ListenCpltCallback : callback for end of listen mode.
+ (+) MemTxCpltCallback : callback for Memory transmission end of transfer.
+ (+) MemRxCpltCallback : callback for Memory reception end of transfer.
+ (+) ErrorCallback : callback for error detection.
+ (+) AbortCpltCallback : callback for abort completion process.
+ (+) MspInitCallback : callback for Msp Init.
+ (+) MspDeInitCallback : callback for Msp DeInit.
+ This function takes as parameters the HAL peripheral handle, the Callback ID
+ and a pointer to the user callback function.
+ [..]
+ For specific callback AddrCallback use dedicated register callbacks : HAL_I2C_RegisterAddrCallback().
+ [..]
+ Use function HAL_I2C_UnRegisterCallback to reset a callback to the default
+ weak function.
+ HAL_I2C_UnRegisterCallback takes as parameters the HAL peripheral handle,
+ and the Callback ID.
+ This function allows to reset following callbacks:
+ (+) MasterTxCpltCallback : callback for Master transmission end of transfer.
+ (+) MasterRxCpltCallback : callback for Master reception end of transfer.
+ (+) SlaveTxCpltCallback : callback for Slave transmission end of transfer.
+ (+) SlaveRxCpltCallback : callback for Slave reception end of transfer.
+ (+) ListenCpltCallback : callback for end of listen mode.
+ (+) MemTxCpltCallback : callback for Memory transmission end of transfer.
+ (+) MemRxCpltCallback : callback for Memory reception end of transfer.
+ (+) ErrorCallback : callback for error detection.
+ (+) AbortCpltCallback : callback for abort completion process.
+ (+) MspInitCallback : callback for Msp Init.
+ (+) MspDeInitCallback : callback for Msp DeInit.
+ [..]
+ For callback AddrCallback use dedicated register callbacks : HAL_I2C_UnRegisterAddrCallback().
+ [..]
+ By default, after the HAL_I2C_Init() and when the state is HAL_I2C_STATE_RESET
+ all callbacks are set to the corresponding weak functions:
+ examples HAL_I2C_MasterTxCpltCallback(), HAL_I2C_MasterRxCpltCallback().
+ Exception done for MspInit and MspDeInit functions that are
+ reset to the legacy weak functions in the HAL_I2C_Init()/ HAL_I2C_DeInit() only when
+ these callbacks are null (not registered beforehand).
+ If MspInit or MspDeInit are not null, the HAL_I2C_Init()/ HAL_I2C_DeInit()
+ keep and use the user MspInit/MspDeInit callbacks (registered beforehand) whatever the state.
+ [..]
+ Callbacks can be registered/unregistered in HAL_I2C_STATE_READY state only.
+ Exception done MspInit/MspDeInit functions that can be registered/unregistered
+ in HAL_I2C_STATE_READY or HAL_I2C_STATE_RESET state,
+ thus registered (user) MspInit/DeInit callbacks can be used during the Init/DeInit.
+ Then, the user first registers the MspInit/MspDeInit user callbacks
+ using HAL_I2C_RegisterCallback() before calling HAL_I2C_DeInit()
+ or HAL_I2C_Init() function.
+ [..]
+ When the compilation flag USE_HAL_I2C_REGISTER_CALLBACKS is set to 0 or
+ not defined, the callback registration feature is not available and all callbacks
+ are set to the corresponding weak functions.
+
+ [..]
+ (@) You can refer to the I2C HAL driver header file for more useful macros
+
+ @endverbatim
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2016 STMicroelectronics.
+ * All rights reserved.
+ *
+ * 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 "stm32f0xx_hal.h"
+
+/** @addtogroup STM32F0xx_HAL_Driver
+ * @{
+ */
+
+/** @defgroup I2C I2C
+ * @brief I2C HAL module driver
+ * @{
+ */
+
+#ifdef HAL_I2C_MODULE_ENABLED
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+
+/** @defgroup I2C_Private_Define I2C Private Define
+ * @{
+ */
+#define TIMING_CLEAR_MASK (0xF0FFFFFFU) /*!< I2C TIMING clear register Mask */
+#define I2C_TIMEOUT_ADDR (10000U) /*!< 10 s */
+#define I2C_TIMEOUT_BUSY (25U) /*!< 25 ms */
+#define I2C_TIMEOUT_DIR (25U) /*!< 25 ms */
+#define I2C_TIMEOUT_RXNE (25U) /*!< 25 ms */
+#define I2C_TIMEOUT_STOPF (25U) /*!< 25 ms */
+#define I2C_TIMEOUT_TC (25U) /*!< 25 ms */
+#define I2C_TIMEOUT_TCR (25U) /*!< 25 ms */
+#define I2C_TIMEOUT_TXIS (25U) /*!< 25 ms */
+#define I2C_TIMEOUT_FLAG (25U) /*!< 25 ms */
+
+#define MAX_NBYTE_SIZE 255U
+#define SLAVE_ADDR_SHIFT 7U
+#define SLAVE_ADDR_MSK 0x06U
+
+/* Private define for @ref PreviousState usage */
+#define I2C_STATE_MSK ((uint32_t)((uint32_t)((uint32_t)HAL_I2C_STATE_BUSY_TX | \
+ (uint32_t)HAL_I2C_STATE_BUSY_RX) & \
+ (uint32_t)(~((uint32_t)HAL_I2C_STATE_READY))))
+/*!< Mask State define, keep only RX and TX bits */
+#define I2C_STATE_NONE ((uint32_t)(HAL_I2C_MODE_NONE))
+/*!< Default Value */
+#define I2C_STATE_MASTER_BUSY_TX ((uint32_t)(((uint32_t)HAL_I2C_STATE_BUSY_TX & I2C_STATE_MSK) | \
+ (uint32_t)HAL_I2C_MODE_MASTER))
+/*!< Master Busy TX, combinaison of State LSB and Mode enum */
+#define I2C_STATE_MASTER_BUSY_RX ((uint32_t)(((uint32_t)HAL_I2C_STATE_BUSY_RX & I2C_STATE_MSK) | \
+ (uint32_t)HAL_I2C_MODE_MASTER))
+/*!< Master Busy RX, combinaison of State LSB and Mode enum */
+#define I2C_STATE_SLAVE_BUSY_TX ((uint32_t)(((uint32_t)HAL_I2C_STATE_BUSY_TX & I2C_STATE_MSK) | \
+ (uint32_t)HAL_I2C_MODE_SLAVE))
+/*!< Slave Busy TX, combinaison of State LSB and Mode enum */
+#define I2C_STATE_SLAVE_BUSY_RX ((uint32_t)(((uint32_t)HAL_I2C_STATE_BUSY_RX & I2C_STATE_MSK) | \
+ (uint32_t)HAL_I2C_MODE_SLAVE))
+/*!< Slave Busy RX, combinaison of State LSB and Mode enum */
+#define I2C_STATE_MEM_BUSY_TX ((uint32_t)(((uint32_t)HAL_I2C_STATE_BUSY_TX & I2C_STATE_MSK) | \
+ (uint32_t)HAL_I2C_MODE_MEM))
+/*!< Memory Busy TX, combinaison of State LSB and Mode enum */
+#define I2C_STATE_MEM_BUSY_RX ((uint32_t)(((uint32_t)HAL_I2C_STATE_BUSY_RX & I2C_STATE_MSK) | \
+ (uint32_t)HAL_I2C_MODE_MEM))
+/*!< Memory Busy RX, combinaison of State LSB and Mode enum */
+
+
+/* Private define to centralize the enable/disable of Interrupts */
+#define I2C_XFER_TX_IT (uint16_t)(0x0001U) /*!< Bit field can be combinated with
+ @ref I2C_XFER_LISTEN_IT */
+#define I2C_XFER_RX_IT (uint16_t)(0x0002U) /*!< Bit field can be combinated with
+ @ref I2C_XFER_LISTEN_IT */
+#define I2C_XFER_LISTEN_IT (uint16_t)(0x8000U) /*!< Bit field can be combinated with @ref I2C_XFER_TX_IT
+ and @ref I2C_XFER_RX_IT */
+
+#define I2C_XFER_ERROR_IT (uint16_t)(0x0010U) /*!< Bit definition to manage addition of global Error
+ and NACK treatment */
+#define I2C_XFER_CPLT_IT (uint16_t)(0x0020U) /*!< Bit definition to manage only STOP evenement */
+#define I2C_XFER_RELOAD_IT (uint16_t)(0x0040U) /*!< Bit definition to manage only Reload of NBYTE */
+
+/* Private define Sequential Transfer Options default/reset value */
+#define I2C_NO_OPTION_FRAME (0xFFFF0000U)
+/**
+ * @}
+ */
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+
+/** @defgroup I2C_Private_Functions I2C Private Functions
+ * @{
+ */
+/* Private functions to handle DMA transfer */
+static void I2C_DMAMasterTransmitCplt(DMA_HandleTypeDef *hdma);
+static void I2C_DMAMasterReceiveCplt(DMA_HandleTypeDef *hdma);
+static void I2C_DMASlaveTransmitCplt(DMA_HandleTypeDef *hdma);
+static void I2C_DMASlaveReceiveCplt(DMA_HandleTypeDef *hdma);
+static void I2C_DMAError(DMA_HandleTypeDef *hdma);
+static void I2C_DMAAbort(DMA_HandleTypeDef *hdma);
+
+/* Private functions to handle IT transfer */
+static void I2C_ITAddrCplt(I2C_HandleTypeDef *hi2c, uint32_t ITFlags);
+static void I2C_ITMasterSeqCplt(I2C_HandleTypeDef *hi2c);
+static void I2C_ITSlaveSeqCplt(I2C_HandleTypeDef *hi2c);
+static void I2C_ITMasterCplt(I2C_HandleTypeDef *hi2c, uint32_t ITFlags);
+static void I2C_ITSlaveCplt(I2C_HandleTypeDef *hi2c, uint32_t ITFlags);
+static void I2C_ITListenCplt(I2C_HandleTypeDef *hi2c, uint32_t ITFlags);
+static void I2C_ITError(I2C_HandleTypeDef *hi2c, uint32_t ErrorCode);
+
+/* Private functions to handle IT transfer */
+static HAL_StatusTypeDef I2C_RequestMemoryWrite(I2C_HandleTypeDef *hi2c, uint16_t DevAddress,
+ uint16_t MemAddress, uint16_t MemAddSize, uint32_t Timeout,
+ uint32_t Tickstart);
+static HAL_StatusTypeDef I2C_RequestMemoryRead(I2C_HandleTypeDef *hi2c, uint16_t DevAddress,
+ uint16_t MemAddress, uint16_t MemAddSize, uint32_t Timeout,
+ uint32_t Tickstart);
+
+/* Private functions for I2C transfer IRQ handler */
+static HAL_StatusTypeDef I2C_Master_ISR_IT(struct __I2C_HandleTypeDef *hi2c, uint32_t ITFlags,
+ uint32_t ITSources);
+static HAL_StatusTypeDef I2C_Slave_ISR_IT(struct __I2C_HandleTypeDef *hi2c, uint32_t ITFlags,
+ uint32_t ITSources);
+static HAL_StatusTypeDef I2C_Master_ISR_DMA(struct __I2C_HandleTypeDef *hi2c, uint32_t ITFlags,
+ uint32_t ITSources);
+static HAL_StatusTypeDef I2C_Slave_ISR_DMA(struct __I2C_HandleTypeDef *hi2c, uint32_t ITFlags,
+ uint32_t ITSources);
+
+/* Private functions to handle flags during polling transfer */
+static HAL_StatusTypeDef I2C_WaitOnFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Flag, FlagStatus Status,
+ uint32_t Timeout, uint32_t Tickstart);
+static HAL_StatusTypeDef I2C_WaitOnTXISFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Timeout,
+ uint32_t Tickstart);
+static HAL_StatusTypeDef I2C_WaitOnRXNEFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Timeout,
+ uint32_t Tickstart);
+static HAL_StatusTypeDef I2C_WaitOnSTOPFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Timeout,
+ uint32_t Tickstart);
+static HAL_StatusTypeDef I2C_IsAcknowledgeFailed(I2C_HandleTypeDef *hi2c, uint32_t Timeout,
+ uint32_t Tickstart);
+
+/* Private functions to centralize the enable/disable of Interrupts */
+static void I2C_Enable_IRQ(I2C_HandleTypeDef *hi2c, uint16_t InterruptRequest);
+static void I2C_Disable_IRQ(I2C_HandleTypeDef *hi2c, uint16_t InterruptRequest);
+
+/* Private function to treat different error callback */
+static void I2C_TreatErrorCallback(I2C_HandleTypeDef *hi2c);
+
+/* Private function to flush TXDR register */
+static void I2C_Flush_TXDR(I2C_HandleTypeDef *hi2c);
+
+/* Private function to handle start, restart or stop a transfer */
+static void I2C_TransferConfig(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t Size, uint32_t Mode,
+ uint32_t Request);
+
+/* Private function to Convert Specific options */
+static void I2C_ConvertOtherXferOptions(I2C_HandleTypeDef *hi2c);
+/**
+ * @}
+ */
+
+/* Exported functions --------------------------------------------------------*/
+
+/** @defgroup I2C_Exported_Functions I2C Exported Functions
+ * @{
+ */
+
+/** @defgroup I2C_Exported_Functions_Group1 Initialization and de-initialization functions
+ * @brief Initialization and Configuration functions
+ *
+@verbatim
+ ===============================================================================
+ ##### Initialization and de-initialization functions #####
+ ===============================================================================
+ [..] This subsection provides a set of functions allowing to initialize and
+ deinitialize the I2Cx peripheral:
+
+ (+) User must Implement HAL_I2C_MspInit() function in which he configures
+ all related peripherals resources (CLOCK, GPIO, DMA, IT and NVIC ).
+
+ (+) Call the function HAL_I2C_Init() to configure the selected device with
+ the selected configuration:
+ (++) Clock Timing
+ (++) Own Address 1
+ (++) Addressing mode (Master, Slave)
+ (++) Dual Addressing mode
+ (++) Own Address 2
+ (++) Own Address 2 Mask
+ (++) General call mode
+ (++) Nostretch mode
+
+ (+) Call the function HAL_I2C_DeInit() to restore the default configuration
+ of the selected I2Cx peripheral.
+
+@endverbatim
+ * @{
+ */
+
+/**
+ * @brief Initializes the I2C according to the specified parameters
+ * in the I2C_InitTypeDef and initialize the associated handle.
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2C.
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_I2C_Init(I2C_HandleTypeDef *hi2c)
+{
+ /* Check the I2C handle allocation */
+ if (hi2c == NULL)
+ {
+ return HAL_ERROR;
+ }
+
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_INSTANCE(hi2c->Instance));
+ assert_param(IS_I2C_OWN_ADDRESS1(hi2c->Init.OwnAddress1));
+ assert_param(IS_I2C_ADDRESSING_MODE(hi2c->Init.AddressingMode));
+ assert_param(IS_I2C_DUAL_ADDRESS(hi2c->Init.DualAddressMode));
+ assert_param(IS_I2C_OWN_ADDRESS2(hi2c->Init.OwnAddress2));
+ assert_param(IS_I2C_OWN_ADDRESS2_MASK(hi2c->Init.OwnAddress2Masks));
+ assert_param(IS_I2C_GENERAL_CALL(hi2c->Init.GeneralCallMode));
+ assert_param(IS_I2C_NO_STRETCH(hi2c->Init.NoStretchMode));
+
+ if (hi2c->State == HAL_I2C_STATE_RESET)
+ {
+ /* Allocate lock resource and initialize it */
+ hi2c->Lock = HAL_UNLOCKED;
+
+#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1)
+ /* Init the I2C Callback settings */
+ hi2c->MasterTxCpltCallback = HAL_I2C_MasterTxCpltCallback; /* Legacy weak MasterTxCpltCallback */
+ hi2c->MasterRxCpltCallback = HAL_I2C_MasterRxCpltCallback; /* Legacy weak MasterRxCpltCallback */
+ hi2c->SlaveTxCpltCallback = HAL_I2C_SlaveTxCpltCallback; /* Legacy weak SlaveTxCpltCallback */
+ hi2c->SlaveRxCpltCallback = HAL_I2C_SlaveRxCpltCallback; /* Legacy weak SlaveRxCpltCallback */
+ hi2c->ListenCpltCallback = HAL_I2C_ListenCpltCallback; /* Legacy weak ListenCpltCallback */
+ hi2c->MemTxCpltCallback = HAL_I2C_MemTxCpltCallback; /* Legacy weak MemTxCpltCallback */
+ hi2c->MemRxCpltCallback = HAL_I2C_MemRxCpltCallback; /* Legacy weak MemRxCpltCallback */
+ hi2c->ErrorCallback = HAL_I2C_ErrorCallback; /* Legacy weak ErrorCallback */
+ hi2c->AbortCpltCallback = HAL_I2C_AbortCpltCallback; /* Legacy weak AbortCpltCallback */
+ hi2c->AddrCallback = HAL_I2C_AddrCallback; /* Legacy weak AddrCallback */
+
+ if (hi2c->MspInitCallback == NULL)
+ {
+ hi2c->MspInitCallback = HAL_I2C_MspInit; /* Legacy weak MspInit */
+ }
+
+ /* Init the low level hardware : GPIO, CLOCK, CORTEX...etc */
+ hi2c->MspInitCallback(hi2c);
+#else
+ /* Init the low level hardware : GPIO, CLOCK, CORTEX...etc */
+ HAL_I2C_MspInit(hi2c);
+#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */
+ }
+
+ hi2c->State = HAL_I2C_STATE_BUSY;
+
+ /* Disable the selected I2C peripheral */
+ __HAL_I2C_DISABLE(hi2c);
+
+ /*---------------------------- I2Cx TIMINGR Configuration ------------------*/
+ /* Configure I2Cx: Frequency range */
+ hi2c->Instance->TIMINGR = hi2c->Init.Timing & TIMING_CLEAR_MASK;
+
+ /*---------------------------- I2Cx OAR1 Configuration ---------------------*/
+ /* Disable Own Address1 before set the Own Address1 configuration */
+ hi2c->Instance->OAR1 &= ~I2C_OAR1_OA1EN;
+
+ /* Configure I2Cx: Own Address1 and ack own address1 mode */
+ if (hi2c->Init.AddressingMode == I2C_ADDRESSINGMODE_7BIT)
+ {
+ hi2c->Instance->OAR1 = (I2C_OAR1_OA1EN | hi2c->Init.OwnAddress1);
+ }
+ else /* I2C_ADDRESSINGMODE_10BIT */
+ {
+ hi2c->Instance->OAR1 = (I2C_OAR1_OA1EN | I2C_OAR1_OA1MODE | hi2c->Init.OwnAddress1);
+ }
+
+ /*---------------------------- I2Cx CR2 Configuration ----------------------*/
+ /* Configure I2Cx: Addressing Master mode */
+ if (hi2c->Init.AddressingMode == I2C_ADDRESSINGMODE_10BIT)
+ {
+ hi2c->Instance->CR2 = (I2C_CR2_ADD10);
+ }
+ /* Enable the AUTOEND by default, and enable NACK (should be disable only during Slave process */
+ hi2c->Instance->CR2 |= (I2C_CR2_AUTOEND | I2C_CR2_NACK);
+
+ /*---------------------------- I2Cx OAR2 Configuration ---------------------*/
+ /* Disable Own Address2 before set the Own Address2 configuration */
+ hi2c->Instance->OAR2 &= ~I2C_DUALADDRESS_ENABLE;
+
+ /* Configure I2Cx: Dual mode and Own Address2 */
+ hi2c->Instance->OAR2 = (hi2c->Init.DualAddressMode | hi2c->Init.OwnAddress2 | \
+ (hi2c->Init.OwnAddress2Masks << 8));
+
+ /*---------------------------- I2Cx CR1 Configuration ----------------------*/
+ /* Configure I2Cx: Generalcall and NoStretch mode */
+ hi2c->Instance->CR1 = (hi2c->Init.GeneralCallMode | hi2c->Init.NoStretchMode);
+
+ /* Enable the selected I2C peripheral */
+ __HAL_I2C_ENABLE(hi2c);
+
+ hi2c->ErrorCode = HAL_I2C_ERROR_NONE;
+ hi2c->State = HAL_I2C_STATE_READY;
+ hi2c->PreviousState = I2C_STATE_NONE;
+ hi2c->Mode = HAL_I2C_MODE_NONE;
+
+ return HAL_OK;
+}
+
+/**
+ * @brief DeInitialize the I2C peripheral.
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2C.
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_I2C_DeInit(I2C_HandleTypeDef *hi2c)
+{
+ /* Check the I2C handle allocation */
+ if (hi2c == NULL)
+ {
+ return HAL_ERROR;
+ }
+
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_INSTANCE(hi2c->Instance));
+
+ hi2c->State = HAL_I2C_STATE_BUSY;
+
+ /* Disable the I2C Peripheral Clock */
+ __HAL_I2C_DISABLE(hi2c);
+
+#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1)
+ if (hi2c->MspDeInitCallback == NULL)
+ {
+ hi2c->MspDeInitCallback = HAL_I2C_MspDeInit; /* Legacy weak MspDeInit */
+ }
+
+ /* DeInit the low level hardware: GPIO, CLOCK, NVIC */
+ hi2c->MspDeInitCallback(hi2c);
+#else
+ /* DeInit the low level hardware: GPIO, CLOCK, NVIC */
+ HAL_I2C_MspDeInit(hi2c);
+#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */
+
+ hi2c->ErrorCode = HAL_I2C_ERROR_NONE;
+ hi2c->State = HAL_I2C_STATE_RESET;
+ hi2c->PreviousState = I2C_STATE_NONE;
+ hi2c->Mode = HAL_I2C_MODE_NONE;
+
+ /* Release Lock */
+ __HAL_UNLOCK(hi2c);
+
+ return HAL_OK;
+}
+
+/**
+ * @brief Initialize the I2C MSP.
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2C.
+ * @retval None
+ */
+__weak void HAL_I2C_MspInit(I2C_HandleTypeDef *hi2c)
+{
+ /* Prevent unused argument(s) compilation warning */
+ UNUSED(hi2c);
+
+ /* NOTE : This function should not be modified, when the callback is needed,
+ the HAL_I2C_MspInit could be implemented in the user file
+ */
+}
+
+/**
+ * @brief DeInitialize the I2C MSP.
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2C.
+ * @retval None
+ */
+__weak void HAL_I2C_MspDeInit(I2C_HandleTypeDef *hi2c)
+{
+ /* Prevent unused argument(s) compilation warning */
+ UNUSED(hi2c);
+
+ /* NOTE : This function should not be modified, when the callback is needed,
+ the HAL_I2C_MspDeInit could be implemented in the user file
+ */
+}
+
+#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1)
+/**
+ * @brief Register a User I2C Callback
+ * To be used instead of the weak predefined callback
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2C.
+ * @param CallbackID ID of the callback to be registered
+ * This parameter can be one of the following values:
+ * @arg @ref HAL_I2C_MASTER_TX_COMPLETE_CB_ID Master Tx Transfer completed callback ID
+ * @arg @ref HAL_I2C_MASTER_RX_COMPLETE_CB_ID Master Rx Transfer completed callback ID
+ * @arg @ref HAL_I2C_SLAVE_TX_COMPLETE_CB_ID Slave Tx Transfer completed callback ID
+ * @arg @ref HAL_I2C_SLAVE_RX_COMPLETE_CB_ID Slave Rx Transfer completed callback ID
+ * @arg @ref HAL_I2C_LISTEN_COMPLETE_CB_ID Listen Complete callback ID
+ * @arg @ref HAL_I2C_MEM_TX_COMPLETE_CB_ID Memory Tx Transfer callback ID
+ * @arg @ref HAL_I2C_MEM_RX_COMPLETE_CB_ID Memory Rx Transfer completed callback ID
+ * @arg @ref HAL_I2C_ERROR_CB_ID Error callback ID
+ * @arg @ref HAL_I2C_ABORT_CB_ID Abort callback ID
+ * @arg @ref HAL_I2C_MSPINIT_CB_ID MspInit callback ID
+ * @arg @ref HAL_I2C_MSPDEINIT_CB_ID MspDeInit callback ID
+ * @param pCallback pointer to the Callback function
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_I2C_RegisterCallback(I2C_HandleTypeDef *hi2c, HAL_I2C_CallbackIDTypeDef CallbackID,
+ pI2C_CallbackTypeDef pCallback)
+{
+ HAL_StatusTypeDef status = HAL_OK;
+
+ if (pCallback == NULL)
+ {
+ /* Update the error code */
+ hi2c->ErrorCode |= HAL_I2C_ERROR_INVALID_CALLBACK;
+
+ return HAL_ERROR;
+ }
+ /* Process locked */
+ __HAL_LOCK(hi2c);
+
+ if (HAL_I2C_STATE_READY == hi2c->State)
+ {
+ switch (CallbackID)
+ {
+ case HAL_I2C_MASTER_TX_COMPLETE_CB_ID :
+ hi2c->MasterTxCpltCallback = pCallback;
+ break;
+
+ case HAL_I2C_MASTER_RX_COMPLETE_CB_ID :
+ hi2c->MasterRxCpltCallback = pCallback;
+ break;
+
+ case HAL_I2C_SLAVE_TX_COMPLETE_CB_ID :
+ hi2c->SlaveTxCpltCallback = pCallback;
+ break;
+
+ case HAL_I2C_SLAVE_RX_COMPLETE_CB_ID :
+ hi2c->SlaveRxCpltCallback = pCallback;
+ break;
+
+ case HAL_I2C_LISTEN_COMPLETE_CB_ID :
+ hi2c->ListenCpltCallback = pCallback;
+ break;
+
+ case HAL_I2C_MEM_TX_COMPLETE_CB_ID :
+ hi2c->MemTxCpltCallback = pCallback;
+ break;
+
+ case HAL_I2C_MEM_RX_COMPLETE_CB_ID :
+ hi2c->MemRxCpltCallback = pCallback;
+ break;
+
+ case HAL_I2C_ERROR_CB_ID :
+ hi2c->ErrorCallback = pCallback;
+ break;
+
+ case HAL_I2C_ABORT_CB_ID :
+ hi2c->AbortCpltCallback = pCallback;
+ break;
+
+ case HAL_I2C_MSPINIT_CB_ID :
+ hi2c->MspInitCallback = pCallback;
+ break;
+
+ case HAL_I2C_MSPDEINIT_CB_ID :
+ hi2c->MspDeInitCallback = pCallback;
+ break;
+
+ default :
+ /* Update the error code */
+ hi2c->ErrorCode |= HAL_I2C_ERROR_INVALID_CALLBACK;
+
+ /* Return error status */
+ status = HAL_ERROR;
+ break;
+ }
+ }
+ else if (HAL_I2C_STATE_RESET == hi2c->State)
+ {
+ switch (CallbackID)
+ {
+ case HAL_I2C_MSPINIT_CB_ID :
+ hi2c->MspInitCallback = pCallback;
+ break;
+
+ case HAL_I2C_MSPDEINIT_CB_ID :
+ hi2c->MspDeInitCallback = pCallback;
+ break;
+
+ default :
+ /* Update the error code */
+ hi2c->ErrorCode |= HAL_I2C_ERROR_INVALID_CALLBACK;
+
+ /* Return error status */
+ status = HAL_ERROR;
+ break;
+ }
+ }
+ else
+ {
+ /* Update the error code */
+ hi2c->ErrorCode |= HAL_I2C_ERROR_INVALID_CALLBACK;
+
+ /* Return error status */
+ status = HAL_ERROR;
+ }
+
+ /* Release Lock */
+ __HAL_UNLOCK(hi2c);
+ return status;
+}
+
+/**
+ * @brief Unregister an I2C Callback
+ * I2C callback is redirected to the weak predefined callback
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2C.
+ * @param CallbackID ID of the callback to be unregistered
+ * This parameter can be one of the following values:
+ * This parameter can be one of the following values:
+ * @arg @ref HAL_I2C_MASTER_TX_COMPLETE_CB_ID Master Tx Transfer completed callback ID
+ * @arg @ref HAL_I2C_MASTER_RX_COMPLETE_CB_ID Master Rx Transfer completed callback ID
+ * @arg @ref HAL_I2C_SLAVE_TX_COMPLETE_CB_ID Slave Tx Transfer completed callback ID
+ * @arg @ref HAL_I2C_SLAVE_RX_COMPLETE_CB_ID Slave Rx Transfer completed callback ID
+ * @arg @ref HAL_I2C_LISTEN_COMPLETE_CB_ID Listen Complete callback ID
+ * @arg @ref HAL_I2C_MEM_TX_COMPLETE_CB_ID Memory Tx Transfer callback ID
+ * @arg @ref HAL_I2C_MEM_RX_COMPLETE_CB_ID Memory Rx Transfer completed callback ID
+ * @arg @ref HAL_I2C_ERROR_CB_ID Error callback ID
+ * @arg @ref HAL_I2C_ABORT_CB_ID Abort callback ID
+ * @arg @ref HAL_I2C_MSPINIT_CB_ID MspInit callback ID
+ * @arg @ref HAL_I2C_MSPDEINIT_CB_ID MspDeInit callback ID
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_I2C_UnRegisterCallback(I2C_HandleTypeDef *hi2c, HAL_I2C_CallbackIDTypeDef CallbackID)
+{
+ HAL_StatusTypeDef status = HAL_OK;
+
+ /* Process locked */
+ __HAL_LOCK(hi2c);
+
+ if (HAL_I2C_STATE_READY == hi2c->State)
+ {
+ switch (CallbackID)
+ {
+ case HAL_I2C_MASTER_TX_COMPLETE_CB_ID :
+ hi2c->MasterTxCpltCallback = HAL_I2C_MasterTxCpltCallback; /* Legacy weak MasterTxCpltCallback */
+ break;
+
+ case HAL_I2C_MASTER_RX_COMPLETE_CB_ID :
+ hi2c->MasterRxCpltCallback = HAL_I2C_MasterRxCpltCallback; /* Legacy weak MasterRxCpltCallback */
+ break;
+
+ case HAL_I2C_SLAVE_TX_COMPLETE_CB_ID :
+ hi2c->SlaveTxCpltCallback = HAL_I2C_SlaveTxCpltCallback; /* Legacy weak SlaveTxCpltCallback */
+ break;
+
+ case HAL_I2C_SLAVE_RX_COMPLETE_CB_ID :
+ hi2c->SlaveRxCpltCallback = HAL_I2C_SlaveRxCpltCallback; /* Legacy weak SlaveRxCpltCallback */
+ break;
+
+ case HAL_I2C_LISTEN_COMPLETE_CB_ID :
+ hi2c->ListenCpltCallback = HAL_I2C_ListenCpltCallback; /* Legacy weak ListenCpltCallback */
+ break;
+
+ case HAL_I2C_MEM_TX_COMPLETE_CB_ID :
+ hi2c->MemTxCpltCallback = HAL_I2C_MemTxCpltCallback; /* Legacy weak MemTxCpltCallback */
+ break;
+
+ case HAL_I2C_MEM_RX_COMPLETE_CB_ID :
+ hi2c->MemRxCpltCallback = HAL_I2C_MemRxCpltCallback; /* Legacy weak MemRxCpltCallback */
+ break;
+
+ case HAL_I2C_ERROR_CB_ID :
+ hi2c->ErrorCallback = HAL_I2C_ErrorCallback; /* Legacy weak ErrorCallback */
+ break;
+
+ case HAL_I2C_ABORT_CB_ID :
+ hi2c->AbortCpltCallback = HAL_I2C_AbortCpltCallback; /* Legacy weak AbortCpltCallback */
+ break;
+
+ case HAL_I2C_MSPINIT_CB_ID :
+ hi2c->MspInitCallback = HAL_I2C_MspInit; /* Legacy weak MspInit */
+ break;
+
+ case HAL_I2C_MSPDEINIT_CB_ID :
+ hi2c->MspDeInitCallback = HAL_I2C_MspDeInit; /* Legacy weak MspDeInit */
+ break;
+
+ default :
+ /* Update the error code */
+ hi2c->ErrorCode |= HAL_I2C_ERROR_INVALID_CALLBACK;
+
+ /* Return error status */
+ status = HAL_ERROR;
+ break;
+ }
+ }
+ else if (HAL_I2C_STATE_RESET == hi2c->State)
+ {
+ switch (CallbackID)
+ {
+ case HAL_I2C_MSPINIT_CB_ID :
+ hi2c->MspInitCallback = HAL_I2C_MspInit; /* Legacy weak MspInit */
+ break;
+
+ case HAL_I2C_MSPDEINIT_CB_ID :
+ hi2c->MspDeInitCallback = HAL_I2C_MspDeInit; /* Legacy weak MspDeInit */
+ break;
+
+ default :
+ /* Update the error code */
+ hi2c->ErrorCode |= HAL_I2C_ERROR_INVALID_CALLBACK;
+
+ /* Return error status */
+ status = HAL_ERROR;
+ break;
+ }
+ }
+ else
+ {
+ /* Update the error code */
+ hi2c->ErrorCode |= HAL_I2C_ERROR_INVALID_CALLBACK;
+
+ /* Return error status */
+ status = HAL_ERROR;
+ }
+
+ /* Release Lock */
+ __HAL_UNLOCK(hi2c);
+ return status;
+}
+
+/**
+ * @brief Register the Slave Address Match I2C Callback
+ * To be used instead of the weak HAL_I2C_AddrCallback() predefined callback
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2C.
+ * @param pCallback pointer to the Address Match Callback function
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_I2C_RegisterAddrCallback(I2C_HandleTypeDef *hi2c, pI2C_AddrCallbackTypeDef pCallback)
+{
+ HAL_StatusTypeDef status = HAL_OK;
+
+ if (pCallback == NULL)
+ {
+ /* Update the error code */
+ hi2c->ErrorCode |= HAL_I2C_ERROR_INVALID_CALLBACK;
+
+ return HAL_ERROR;
+ }
+ /* Process locked */
+ __HAL_LOCK(hi2c);
+
+ if (HAL_I2C_STATE_READY == hi2c->State)
+ {
+ hi2c->AddrCallback = pCallback;
+ }
+ else
+ {
+ /* Update the error code */
+ hi2c->ErrorCode |= HAL_I2C_ERROR_INVALID_CALLBACK;
+
+ /* Return error status */
+ status = HAL_ERROR;
+ }
+
+ /* Release Lock */
+ __HAL_UNLOCK(hi2c);
+ return status;
+}
+
+/**
+ * @brief UnRegister the Slave Address Match I2C Callback
+ * Info Ready I2C Callback is redirected to the weak HAL_I2C_AddrCallback() predefined callback
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2C.
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_I2C_UnRegisterAddrCallback(I2C_HandleTypeDef *hi2c)
+{
+ HAL_StatusTypeDef status = HAL_OK;
+
+ /* Process locked */
+ __HAL_LOCK(hi2c);
+
+ if (HAL_I2C_STATE_READY == hi2c->State)
+ {
+ hi2c->AddrCallback = HAL_I2C_AddrCallback; /* Legacy weak AddrCallback */
+ }
+ else
+ {
+ /* Update the error code */
+ hi2c->ErrorCode |= HAL_I2C_ERROR_INVALID_CALLBACK;
+
+ /* Return error status */
+ status = HAL_ERROR;
+ }
+
+ /* Release Lock */
+ __HAL_UNLOCK(hi2c);
+ return status;
+}
+
+#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */
+
+/**
+ * @}
+ */
+
+/** @defgroup I2C_Exported_Functions_Group2 Input and Output operation functions
+ * @brief Data transfers functions
+ *
+@verbatim
+ ===============================================================================
+ ##### IO operation functions #####
+ ===============================================================================
+ [..]
+ This subsection provides a set of functions allowing to manage the I2C data
+ transfers.
+
+ (#) There are two modes of transfer:
+ (++) Blocking mode : The communication is performed in the polling mode.
+ The status of all data processing is returned by the same function
+ after finishing transfer.
+ (++) No-Blocking mode : The communication is performed using Interrupts
+ or DMA. These functions return the status of the transfer startup.
+ The end of the data processing will be indicated through the
+ dedicated I2C IRQ when using Interrupt mode or the DMA IRQ when
+ using DMA mode.
+
+ (#) Blocking mode functions are :
+ (++) HAL_I2C_Master_Transmit()
+ (++) HAL_I2C_Master_Receive()
+ (++) HAL_I2C_Slave_Transmit()
+ (++) HAL_I2C_Slave_Receive()
+ (++) HAL_I2C_Mem_Write()
+ (++) HAL_I2C_Mem_Read()
+ (++) HAL_I2C_IsDeviceReady()
+
+ (#) No-Blocking mode functions with Interrupt are :
+ (++) HAL_I2C_Master_Transmit_IT()
+ (++) HAL_I2C_Master_Receive_IT()
+ (++) HAL_I2C_Slave_Transmit_IT()
+ (++) HAL_I2C_Slave_Receive_IT()
+ (++) HAL_I2C_Mem_Write_IT()
+ (++) HAL_I2C_Mem_Read_IT()
+ (++) HAL_I2C_Master_Seq_Transmit_IT()
+ (++) HAL_I2C_Master_Seq_Receive_IT()
+ (++) HAL_I2C_Slave_Seq_Transmit_IT()
+ (++) HAL_I2C_Slave_Seq_Receive_IT()
+ (++) HAL_I2C_EnableListen_IT()
+ (++) HAL_I2C_DisableListen_IT()
+ (++) HAL_I2C_Master_Abort_IT()
+
+ (#) No-Blocking mode functions with DMA are :
+ (++) HAL_I2C_Master_Transmit_DMA()
+ (++) HAL_I2C_Master_Receive_DMA()
+ (++) HAL_I2C_Slave_Transmit_DMA()
+ (++) HAL_I2C_Slave_Receive_DMA()
+ (++) HAL_I2C_Mem_Write_DMA()
+ (++) HAL_I2C_Mem_Read_DMA()
+ (++) HAL_I2C_Master_Seq_Transmit_DMA()
+ (++) HAL_I2C_Master_Seq_Receive_DMA()
+ (++) HAL_I2C_Slave_Seq_Transmit_DMA()
+ (++) HAL_I2C_Slave_Seq_Receive_DMA()
+
+ (#) A set of Transfer Complete Callbacks are provided in non Blocking mode:
+ (++) HAL_I2C_MasterTxCpltCallback()
+ (++) HAL_I2C_MasterRxCpltCallback()
+ (++) HAL_I2C_SlaveTxCpltCallback()
+ (++) HAL_I2C_SlaveRxCpltCallback()
+ (++) HAL_I2C_MemTxCpltCallback()
+ (++) HAL_I2C_MemRxCpltCallback()
+ (++) HAL_I2C_AddrCallback()
+ (++) HAL_I2C_ListenCpltCallback()
+ (++) HAL_I2C_ErrorCallback()
+ (++) HAL_I2C_AbortCpltCallback()
+
+@endverbatim
+ * @{
+ */
+
+/**
+ * @brief Transmits in master mode an amount of data in blocking mode.
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2C.
+ * @param DevAddress Target device address: The device 7 bits address value
+ * in datasheet must be shifted to the left before calling the interface
+ * @param pData Pointer to data buffer
+ * @param Size Amount of data to be sent
+ * @param Timeout Timeout duration
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_I2C_Master_Transmit(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData,
+ uint16_t Size, uint32_t Timeout)
+{
+ uint32_t tickstart;
+
+ if (hi2c->State == HAL_I2C_STATE_READY)
+ {
+ /* Process Locked */
+ __HAL_LOCK(hi2c);
+
+ /* Init tickstart for timeout management*/
+ tickstart = HAL_GetTick();
+
+ if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BUSY, SET, I2C_TIMEOUT_BUSY, tickstart) != HAL_OK)
+ {
+ return HAL_ERROR;
+ }
+
+ hi2c->State = HAL_I2C_STATE_BUSY_TX;
+ hi2c->Mode = HAL_I2C_MODE_MASTER;
+ hi2c->ErrorCode = HAL_I2C_ERROR_NONE;
+
+ /* Prepare transfer parameters */
+ hi2c->pBuffPtr = pData;
+ hi2c->XferCount = Size;
+ hi2c->XferISR = NULL;
+
+ /* Send Slave Address */
+ /* Set NBYTES to write and reload if hi2c->XferCount > MAX_NBYTE_SIZE and generate RESTART */
+ if (hi2c->XferCount > MAX_NBYTE_SIZE)
+ {
+ hi2c->XferSize = MAX_NBYTE_SIZE;
+ I2C_TransferConfig(hi2c, DevAddress, (uint8_t)hi2c->XferSize, I2C_RELOAD_MODE,
+ I2C_GENERATE_START_WRITE);
+ }
+ else
+ {
+ hi2c->XferSize = hi2c->XferCount;
+ I2C_TransferConfig(hi2c, DevAddress, (uint8_t)hi2c->XferSize, I2C_AUTOEND_MODE,
+ I2C_GENERATE_START_WRITE);
+ }
+
+ while (hi2c->XferCount > 0U)
+ {
+ /* Wait until TXIS flag is set */
+ if (I2C_WaitOnTXISFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK)
+ {
+ return HAL_ERROR;
+ }
+ /* Write data to TXDR */
+ hi2c->Instance->TXDR = *hi2c->pBuffPtr;
+
+ /* Increment Buffer pointer */
+ hi2c->pBuffPtr++;
+
+ hi2c->XferCount--;
+ hi2c->XferSize--;
+
+ if ((hi2c->XferCount != 0U) && (hi2c->XferSize == 0U))
+ {
+ /* Wait until TCR flag is set */
+ if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_TCR, RESET, Timeout, tickstart) != HAL_OK)
+ {
+ return HAL_ERROR;
+ }
+
+ if (hi2c->XferCount > MAX_NBYTE_SIZE)
+ {
+ hi2c->XferSize = MAX_NBYTE_SIZE;
+ I2C_TransferConfig(hi2c, DevAddress, (uint8_t)hi2c->XferSize, I2C_RELOAD_MODE,
+ I2C_NO_STARTSTOP);
+ }
+ else
+ {
+ hi2c->XferSize = hi2c->XferCount;
+ I2C_TransferConfig(hi2c, DevAddress, (uint8_t)hi2c->XferSize, I2C_AUTOEND_MODE,
+ I2C_NO_STARTSTOP);
+ }
+ }
+ }
+
+ /* No need to Check TC flag, with AUTOEND mode the stop is automatically generated */
+ /* Wait until STOPF flag is set */
+ if (I2C_WaitOnSTOPFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK)
+ {
+ return HAL_ERROR;
+ }
+
+ /* Clear STOP Flag */
+ __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_STOPF);
+
+ /* Clear Configuration Register 2 */
+ I2C_RESET_CR2(hi2c);
+
+ hi2c->State = HAL_I2C_STATE_READY;
+ hi2c->Mode = HAL_I2C_MODE_NONE;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ return HAL_OK;
+ }
+ else
+ {
+ return HAL_BUSY;
+ }
+}
+
+/**
+ * @brief Receives in master mode an amount of data in blocking mode.
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2C.
+ * @param DevAddress Target device address: The device 7 bits address value
+ * in datasheet must be shifted to the left before calling the interface
+ * @param pData Pointer to data buffer
+ * @param Size Amount of data to be sent
+ * @param Timeout Timeout duration
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_I2C_Master_Receive(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData,
+ uint16_t Size, uint32_t Timeout)
+{
+ uint32_t tickstart;
+
+ if (hi2c->State == HAL_I2C_STATE_READY)
+ {
+ /* Process Locked */
+ __HAL_LOCK(hi2c);
+
+ /* Init tickstart for timeout management*/
+ tickstart = HAL_GetTick();
+
+ if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BUSY, SET, I2C_TIMEOUT_BUSY, tickstart) != HAL_OK)
+ {
+ return HAL_ERROR;
+ }
+
+ hi2c->State = HAL_I2C_STATE_BUSY_RX;
+ hi2c->Mode = HAL_I2C_MODE_MASTER;
+ hi2c->ErrorCode = HAL_I2C_ERROR_NONE;
+
+ /* Prepare transfer parameters */
+ hi2c->pBuffPtr = pData;
+ hi2c->XferCount = Size;
+ hi2c->XferISR = NULL;
+
+ /* Send Slave Address */
+ /* Set NBYTES to write and reload if hi2c->XferCount > MAX_NBYTE_SIZE and generate RESTART */
+ if (hi2c->XferCount > MAX_NBYTE_SIZE)
+ {
+ hi2c->XferSize = MAX_NBYTE_SIZE;
+ I2C_TransferConfig(hi2c, DevAddress, (uint8_t)hi2c->XferSize, I2C_RELOAD_MODE,
+ I2C_GENERATE_START_READ);
+ }
+ else
+ {
+ hi2c->XferSize = hi2c->XferCount;
+ I2C_TransferConfig(hi2c, DevAddress, (uint8_t)hi2c->XferSize, I2C_AUTOEND_MODE,
+ I2C_GENERATE_START_READ);
+ }
+
+ while (hi2c->XferCount > 0U)
+ {
+ /* Wait until RXNE flag is set */
+ if (I2C_WaitOnRXNEFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK)
+ {
+ return HAL_ERROR;
+ }
+
+ /* Read data from RXDR */
+ *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->RXDR;
+
+ /* Increment Buffer pointer */
+ hi2c->pBuffPtr++;
+
+ hi2c->XferSize--;
+ hi2c->XferCount--;
+
+ if ((hi2c->XferCount != 0U) && (hi2c->XferSize == 0U))
+ {
+ /* Wait until TCR flag is set */
+ if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_TCR, RESET, Timeout, tickstart) != HAL_OK)
+ {
+ return HAL_ERROR;
+ }
+
+ if (hi2c->XferCount > MAX_NBYTE_SIZE)
+ {
+ hi2c->XferSize = MAX_NBYTE_SIZE;
+ I2C_TransferConfig(hi2c, DevAddress, (uint8_t)hi2c->XferSize, I2C_RELOAD_MODE,
+ I2C_NO_STARTSTOP);
+ }
+ else
+ {
+ hi2c->XferSize = hi2c->XferCount;
+ I2C_TransferConfig(hi2c, DevAddress, (uint8_t)hi2c->XferSize, I2C_AUTOEND_MODE,
+ I2C_NO_STARTSTOP);
+ }
+ }
+ }
+
+ /* No need to Check TC flag, with AUTOEND mode the stop is automatically generated */
+ /* Wait until STOPF flag is set */
+ if (I2C_WaitOnSTOPFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK)
+ {
+ return HAL_ERROR;
+ }
+
+ /* Clear STOP Flag */
+ __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_STOPF);
+
+ /* Clear Configuration Register 2 */
+ I2C_RESET_CR2(hi2c);
+
+ hi2c->State = HAL_I2C_STATE_READY;
+ hi2c->Mode = HAL_I2C_MODE_NONE;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ return HAL_OK;
+ }
+ else
+ {
+ return HAL_BUSY;
+ }
+}
+
+/**
+ * @brief Transmits in slave mode an amount of data in blocking mode.
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2C.
+ * @param pData Pointer to data buffer
+ * @param Size Amount of data to be sent
+ * @param Timeout Timeout duration
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_I2C_Slave_Transmit(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size,
+ uint32_t Timeout)
+{
+ uint32_t tickstart;
+
+ if (hi2c->State == HAL_I2C_STATE_READY)
+ {
+ if ((pData == NULL) || (Size == 0U))
+ {
+ hi2c->ErrorCode = HAL_I2C_ERROR_INVALID_PARAM;
+ return HAL_ERROR;
+ }
+ /* Process Locked */
+ __HAL_LOCK(hi2c);
+
+ /* Init tickstart for timeout management*/
+ tickstart = HAL_GetTick();
+
+ hi2c->State = HAL_I2C_STATE_BUSY_TX;
+ hi2c->Mode = HAL_I2C_MODE_SLAVE;
+ hi2c->ErrorCode = HAL_I2C_ERROR_NONE;
+
+ /* Prepare transfer parameters */
+ hi2c->pBuffPtr = pData;
+ hi2c->XferCount = Size;
+ hi2c->XferISR = NULL;
+
+ /* Enable Address Acknowledge */
+ hi2c->Instance->CR2 &= ~I2C_CR2_NACK;
+
+ /* Wait until ADDR flag is set */
+ if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_ADDR, RESET, Timeout, tickstart) != HAL_OK)
+ {
+ /* Disable Address Acknowledge */
+ hi2c->Instance->CR2 |= I2C_CR2_NACK;
+ return HAL_ERROR;
+ }
+
+ /* Clear ADDR flag */
+ __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_ADDR);
+
+ /* If 10bit addressing mode is selected */
+ if (hi2c->Init.AddressingMode == I2C_ADDRESSINGMODE_10BIT)
+ {
+ /* Wait until ADDR flag is set */
+ if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_ADDR, RESET, Timeout, tickstart) != HAL_OK)
+ {
+ /* Disable Address Acknowledge */
+ hi2c->Instance->CR2 |= I2C_CR2_NACK;
+ return HAL_ERROR;
+ }
+
+ /* Clear ADDR flag */
+ __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_ADDR);
+ }
+
+ /* Wait until DIR flag is set Transmitter mode */
+ if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_DIR, RESET, Timeout, tickstart) != HAL_OK)
+ {
+ /* Disable Address Acknowledge */
+ hi2c->Instance->CR2 |= I2C_CR2_NACK;
+ return HAL_ERROR;
+ }
+
+ while (hi2c->XferCount > 0U)
+ {
+ /* Wait until TXIS flag is set */
+ if (I2C_WaitOnTXISFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK)
+ {
+ /* Disable Address Acknowledge */
+ hi2c->Instance->CR2 |= I2C_CR2_NACK;
+ return HAL_ERROR;
+ }
+
+ /* Write data to TXDR */
+ hi2c->Instance->TXDR = *hi2c->pBuffPtr;
+
+ /* Increment Buffer pointer */
+ hi2c->pBuffPtr++;
+
+ hi2c->XferCount--;
+ }
+
+ /* Wait until STOP flag is set */
+ if (I2C_WaitOnSTOPFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK)
+ {
+ /* Disable Address Acknowledge */
+ hi2c->Instance->CR2 |= I2C_CR2_NACK;
+
+ if (hi2c->ErrorCode == HAL_I2C_ERROR_AF)
+ {
+ /* Normal use case for Transmitter mode */
+ /* A NACK is generated to confirm the end of transfer */
+ hi2c->ErrorCode = HAL_I2C_ERROR_NONE;
+ }
+ else
+ {
+ return HAL_ERROR;
+ }
+ }
+
+ /* Clear STOP flag */
+ __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_STOPF);
+
+ /* Wait until BUSY flag is reset */
+ if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BUSY, SET, Timeout, tickstart) != HAL_OK)
+ {
+ /* Disable Address Acknowledge */
+ hi2c->Instance->CR2 |= I2C_CR2_NACK;
+ return HAL_ERROR;
+ }
+
+ /* Disable Address Acknowledge */
+ hi2c->Instance->CR2 |= I2C_CR2_NACK;
+
+ hi2c->State = HAL_I2C_STATE_READY;
+ hi2c->Mode = HAL_I2C_MODE_NONE;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ return HAL_OK;
+ }
+ else
+ {
+ return HAL_BUSY;
+ }
+}
+
+/**
+ * @brief Receive in slave mode an amount of data in blocking mode
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2C.
+ * @param pData Pointer to data buffer
+ * @param Size Amount of data to be sent
+ * @param Timeout Timeout duration
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_I2C_Slave_Receive(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size,
+ uint32_t Timeout)
+{
+ uint32_t tickstart;
+
+ if (hi2c->State == HAL_I2C_STATE_READY)
+ {
+ if ((pData == NULL) || (Size == 0U))
+ {
+ hi2c->ErrorCode = HAL_I2C_ERROR_INVALID_PARAM;
+ return HAL_ERROR;
+ }
+ /* Process Locked */
+ __HAL_LOCK(hi2c);
+
+ /* Init tickstart for timeout management*/
+ tickstart = HAL_GetTick();
+
+ hi2c->State = HAL_I2C_STATE_BUSY_RX;
+ hi2c->Mode = HAL_I2C_MODE_SLAVE;
+ hi2c->ErrorCode = HAL_I2C_ERROR_NONE;
+
+ /* Prepare transfer parameters */
+ hi2c->pBuffPtr = pData;
+ hi2c->XferCount = Size;
+ hi2c->XferISR = NULL;
+
+ /* Enable Address Acknowledge */
+ hi2c->Instance->CR2 &= ~I2C_CR2_NACK;
+
+ /* Wait until ADDR flag is set */
+ if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_ADDR, RESET, Timeout, tickstart) != HAL_OK)
+ {
+ /* Disable Address Acknowledge */
+ hi2c->Instance->CR2 |= I2C_CR2_NACK;
+ return HAL_ERROR;
+ }
+
+ /* Clear ADDR flag */
+ __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_ADDR);
+
+ /* Wait until DIR flag is reset Receiver mode */
+ if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_DIR, SET, Timeout, tickstart) != HAL_OK)
+ {
+ /* Disable Address Acknowledge */
+ hi2c->Instance->CR2 |= I2C_CR2_NACK;
+ return HAL_ERROR;
+ }
+
+ while (hi2c->XferCount > 0U)
+ {
+ /* Wait until RXNE flag is set */
+ if (I2C_WaitOnRXNEFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK)
+ {
+ /* Disable Address Acknowledge */
+ hi2c->Instance->CR2 |= I2C_CR2_NACK;
+
+ /* Store Last receive data if any */
+ if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_RXNE) == SET)
+ {
+ /* Read data from RXDR */
+ *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->RXDR;
+
+ /* Increment Buffer pointer */
+ hi2c->pBuffPtr++;
+
+ hi2c->XferCount--;
+ }
+
+ return HAL_ERROR;
+ }
+
+ /* Read data from RXDR */
+ *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->RXDR;
+
+ /* Increment Buffer pointer */
+ hi2c->pBuffPtr++;
+
+ hi2c->XferCount--;
+ }
+
+ /* Wait until STOP flag is set */
+ if (I2C_WaitOnSTOPFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK)
+ {
+ /* Disable Address Acknowledge */
+ hi2c->Instance->CR2 |= I2C_CR2_NACK;
+ return HAL_ERROR;
+ }
+
+ /* Clear STOP flag */
+ __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_STOPF);
+
+ /* Wait until BUSY flag is reset */
+ if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BUSY, SET, Timeout, tickstart) != HAL_OK)
+ {
+ /* Disable Address Acknowledge */
+ hi2c->Instance->CR2 |= I2C_CR2_NACK;
+ return HAL_ERROR;
+ }
+
+ /* Disable Address Acknowledge */
+ hi2c->Instance->CR2 |= I2C_CR2_NACK;
+
+ hi2c->State = HAL_I2C_STATE_READY;
+ hi2c->Mode = HAL_I2C_MODE_NONE;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ return HAL_OK;
+ }
+ else
+ {
+ return HAL_BUSY;
+ }
+}
+
+/**
+ * @brief Transmit in master mode an amount of data in non-blocking mode with Interrupt
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2C.
+ * @param DevAddress Target device address: The device 7 bits address value
+ * in datasheet must be shifted to the left before calling the interface
+ * @param pData Pointer to data buffer
+ * @param Size Amount of data to be sent
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_I2C_Master_Transmit_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData,
+ uint16_t Size)
+{
+ uint32_t xfermode;
+
+ if (hi2c->State == HAL_I2C_STATE_READY)
+ {
+ if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) == SET)
+ {
+ return HAL_BUSY;
+ }
+
+ /* Process Locked */
+ __HAL_LOCK(hi2c);
+
+ hi2c->State = HAL_I2C_STATE_BUSY_TX;
+ hi2c->Mode = HAL_I2C_MODE_MASTER;
+ hi2c->ErrorCode = HAL_I2C_ERROR_NONE;
+
+ /* Prepare transfer parameters */
+ hi2c->pBuffPtr = pData;
+ hi2c->XferCount = Size;
+ hi2c->XferOptions = I2C_NO_OPTION_FRAME;
+ hi2c->XferISR = I2C_Master_ISR_IT;
+
+ if (hi2c->XferCount > MAX_NBYTE_SIZE)
+ {
+ hi2c->XferSize = MAX_NBYTE_SIZE;
+ xfermode = I2C_RELOAD_MODE;
+ }
+ else
+ {
+ hi2c->XferSize = hi2c->XferCount;
+ xfermode = I2C_AUTOEND_MODE;
+ }
+
+ /* Send Slave Address */
+ /* Set NBYTES to write and reload if hi2c->XferCount > MAX_NBYTE_SIZE */
+ I2C_TransferConfig(hi2c, DevAddress, (uint8_t)hi2c->XferSize, xfermode, I2C_GENERATE_START_WRITE);
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ /* Note : The I2C interrupts must be enabled after unlocking current process
+ to avoid the risk of I2C interrupt handle execution before current
+ process unlock */
+
+ /* Enable ERR, TC, STOP, NACK, TXI interrupt */
+ /* possible to enable all of these */
+ /* I2C_IT_ERRI | I2C_IT_TCI | I2C_IT_STOPI | I2C_IT_NACKI |
+ I2C_IT_ADDRI | I2C_IT_RXI | I2C_IT_TXI */
+ I2C_Enable_IRQ(hi2c, I2C_XFER_TX_IT);
+
+ return HAL_OK;
+ }
+ else
+ {
+ return HAL_BUSY;
+ }
+}
+
+/**
+ * @brief Receive in master mode an amount of data in non-blocking mode with Interrupt
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2C.
+ * @param DevAddress Target device address: The device 7 bits address value
+ * in datasheet must be shifted to the left before calling the interface
+ * @param pData Pointer to data buffer
+ * @param Size Amount of data to be sent
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_I2C_Master_Receive_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData,
+ uint16_t Size)
+{
+ uint32_t xfermode;
+
+ if (hi2c->State == HAL_I2C_STATE_READY)
+ {
+ if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) == SET)
+ {
+ return HAL_BUSY;
+ }
+
+ /* Process Locked */
+ __HAL_LOCK(hi2c);
+
+ hi2c->State = HAL_I2C_STATE_BUSY_RX;
+ hi2c->Mode = HAL_I2C_MODE_MASTER;
+ hi2c->ErrorCode = HAL_I2C_ERROR_NONE;
+
+ /* Prepare transfer parameters */
+ hi2c->pBuffPtr = pData;
+ hi2c->XferCount = Size;
+ hi2c->XferOptions = I2C_NO_OPTION_FRAME;
+ hi2c->XferISR = I2C_Master_ISR_IT;
+
+ if (hi2c->XferCount > MAX_NBYTE_SIZE)
+ {
+ hi2c->XferSize = MAX_NBYTE_SIZE;
+ xfermode = I2C_RELOAD_MODE;
+ }
+ else
+ {
+ hi2c->XferSize = hi2c->XferCount;
+ xfermode = I2C_AUTOEND_MODE;
+ }
+
+ /* Send Slave Address */
+ /* Set NBYTES to write and reload if hi2c->XferCount > MAX_NBYTE_SIZE */
+ I2C_TransferConfig(hi2c, DevAddress, (uint8_t)hi2c->XferSize, xfermode, I2C_GENERATE_START_READ);
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ /* Note : The I2C interrupts must be enabled after unlocking current process
+ to avoid the risk of I2C interrupt handle execution before current
+ process unlock */
+
+ /* Enable ERR, TC, STOP, NACK, RXI interrupt */
+ /* possible to enable all of these */
+ /* I2C_IT_ERRI | I2C_IT_TCI | I2C_IT_STOPI | I2C_IT_NACKI |
+ I2C_IT_ADDRI | I2C_IT_RXI | I2C_IT_TXI */
+ I2C_Enable_IRQ(hi2c, I2C_XFER_RX_IT);
+
+ return HAL_OK;
+ }
+ else
+ {
+ return HAL_BUSY;
+ }
+}
+
+/**
+ * @brief Transmit in slave mode an amount of data in non-blocking mode with Interrupt
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2C.
+ * @param pData Pointer to data buffer
+ * @param Size Amount of data to be sent
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_I2C_Slave_Transmit_IT(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size)
+{
+ if (hi2c->State == HAL_I2C_STATE_READY)
+ {
+ /* Process Locked */
+ __HAL_LOCK(hi2c);
+
+ hi2c->State = HAL_I2C_STATE_BUSY_TX;
+ hi2c->Mode = HAL_I2C_MODE_SLAVE;
+ hi2c->ErrorCode = HAL_I2C_ERROR_NONE;
+
+ /* Enable Address Acknowledge */
+ hi2c->Instance->CR2 &= ~I2C_CR2_NACK;
+
+ /* Prepare transfer parameters */
+ hi2c->pBuffPtr = pData;
+ hi2c->XferCount = Size;
+ hi2c->XferSize = hi2c->XferCount;
+ hi2c->XferOptions = I2C_NO_OPTION_FRAME;
+ hi2c->XferISR = I2C_Slave_ISR_IT;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ /* Note : The I2C interrupts must be enabled after unlocking current process
+ to avoid the risk of I2C interrupt handle execution before current
+ process unlock */
+
+ /* Enable ERR, TC, STOP, NACK, TXI interrupt */
+ /* possible to enable all of these */
+ /* I2C_IT_ERRI | I2C_IT_TCI | I2C_IT_STOPI | I2C_IT_NACKI |
+ I2C_IT_ADDRI | I2C_IT_RXI | I2C_IT_TXI */
+ I2C_Enable_IRQ(hi2c, I2C_XFER_TX_IT | I2C_XFER_LISTEN_IT);
+
+ return HAL_OK;
+ }
+ else
+ {
+ return HAL_BUSY;
+ }
+}
+
+/**
+ * @brief Receive in slave mode an amount of data in non-blocking mode with Interrupt
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2C.
+ * @param pData Pointer to data buffer
+ * @param Size Amount of data to be sent
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_I2C_Slave_Receive_IT(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size)
+{
+ if (hi2c->State == HAL_I2C_STATE_READY)
+ {
+ /* Process Locked */
+ __HAL_LOCK(hi2c);
+
+ hi2c->State = HAL_I2C_STATE_BUSY_RX;
+ hi2c->Mode = HAL_I2C_MODE_SLAVE;
+ hi2c->ErrorCode = HAL_I2C_ERROR_NONE;
+
+ /* Enable Address Acknowledge */
+ hi2c->Instance->CR2 &= ~I2C_CR2_NACK;
+
+ /* Prepare transfer parameters */
+ hi2c->pBuffPtr = pData;
+ hi2c->XferCount = Size;
+ hi2c->XferSize = hi2c->XferCount;
+ hi2c->XferOptions = I2C_NO_OPTION_FRAME;
+ hi2c->XferISR = I2C_Slave_ISR_IT;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ /* Note : The I2C interrupts must be enabled after unlocking current process
+ to avoid the risk of I2C interrupt handle execution before current
+ process unlock */
+
+ /* Enable ERR, TC, STOP, NACK, RXI interrupt */
+ /* possible to enable all of these */
+ /* I2C_IT_ERRI | I2C_IT_TCI | I2C_IT_STOPI | I2C_IT_NACKI |
+ I2C_IT_ADDRI | I2C_IT_RXI | I2C_IT_TXI */
+ I2C_Enable_IRQ(hi2c, I2C_XFER_RX_IT | I2C_XFER_LISTEN_IT);
+
+ return HAL_OK;
+ }
+ else
+ {
+ return HAL_BUSY;
+ }
+}
+
+/**
+ * @brief Transmit in master mode an amount of data in non-blocking mode with DMA
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2C.
+ * @param DevAddress Target device address: The device 7 bits address value
+ * in datasheet must be shifted to the left before calling the interface
+ * @param pData Pointer to data buffer
+ * @param Size Amount of data to be sent
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_I2C_Master_Transmit_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData,
+ uint16_t Size)
+{
+ uint32_t xfermode;
+ HAL_StatusTypeDef dmaxferstatus;
+
+ if (hi2c->State == HAL_I2C_STATE_READY)
+ {
+ if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) == SET)
+ {
+ return HAL_BUSY;
+ }
+
+ /* Process Locked */
+ __HAL_LOCK(hi2c);
+
+ hi2c->State = HAL_I2C_STATE_BUSY_TX;
+ hi2c->Mode = HAL_I2C_MODE_MASTER;
+ hi2c->ErrorCode = HAL_I2C_ERROR_NONE;
+
+ /* Prepare transfer parameters */
+ hi2c->pBuffPtr = pData;
+ hi2c->XferCount = Size;
+ hi2c->XferOptions = I2C_NO_OPTION_FRAME;
+ hi2c->XferISR = I2C_Master_ISR_DMA;
+
+ if (hi2c->XferCount > MAX_NBYTE_SIZE)
+ {
+ hi2c->XferSize = MAX_NBYTE_SIZE;
+ xfermode = I2C_RELOAD_MODE;
+ }
+ else
+ {
+ hi2c->XferSize = hi2c->XferCount;
+ xfermode = I2C_AUTOEND_MODE;
+ }
+
+ if (hi2c->XferSize > 0U)
+ {
+ if (hi2c->hdmatx != NULL)
+ {
+ /* Set the I2C DMA transfer complete callback */
+ hi2c->hdmatx->XferCpltCallback = I2C_DMAMasterTransmitCplt;
+
+ /* Set the DMA error callback */
+ hi2c->hdmatx->XferErrorCallback = I2C_DMAError;
+
+ /* Set the unused DMA callbacks to NULL */
+ hi2c->hdmatx->XferHalfCpltCallback = NULL;
+ hi2c->hdmatx->XferAbortCallback = NULL;
+
+ /* Enable the DMA channel */
+ dmaxferstatus = HAL_DMA_Start_IT(hi2c->hdmatx, (uint32_t)pData, (uint32_t)&hi2c->Instance->TXDR,
+ hi2c->XferSize);
+ }
+ else
+ {
+ /* Update I2C state */
+ hi2c->State = HAL_I2C_STATE_READY;
+ hi2c->Mode = HAL_I2C_MODE_NONE;
+
+ /* Update I2C error code */
+ hi2c->ErrorCode |= HAL_I2C_ERROR_DMA_PARAM;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ return HAL_ERROR;
+ }
+
+ if (dmaxferstatus == HAL_OK)
+ {
+ /* Send Slave Address */
+ /* Set NBYTES to write and reload if hi2c->XferCount > MAX_NBYTE_SIZE and generate RESTART */
+ I2C_TransferConfig(hi2c, DevAddress, (uint8_t)hi2c->XferSize, xfermode, I2C_GENERATE_START_WRITE);
+
+ /* Update XferCount value */
+ hi2c->XferCount -= hi2c->XferSize;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ /* Note : The I2C interrupts must be enabled after unlocking current process
+ to avoid the risk of I2C interrupt handle execution before current
+ process unlock */
+ /* Enable ERR and NACK interrupts */
+ I2C_Enable_IRQ(hi2c, I2C_XFER_ERROR_IT);
+
+ /* Enable DMA Request */
+ hi2c->Instance->CR1 |= I2C_CR1_TXDMAEN;
+ }
+ else
+ {
+ /* Update I2C state */
+ hi2c->State = HAL_I2C_STATE_READY;
+ hi2c->Mode = HAL_I2C_MODE_NONE;
+
+ /* Update I2C error code */
+ hi2c->ErrorCode |= HAL_I2C_ERROR_DMA;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ return HAL_ERROR;
+ }
+ }
+ else
+ {
+ /* Update Transfer ISR function pointer */
+ hi2c->XferISR = I2C_Master_ISR_IT;
+
+ /* Send Slave Address */
+ /* Set NBYTES to write and generate START condition */
+ I2C_TransferConfig(hi2c, DevAddress, (uint8_t)hi2c->XferSize, I2C_AUTOEND_MODE,
+ I2C_GENERATE_START_WRITE);
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ /* Note : The I2C interrupts must be enabled after unlocking current process
+ to avoid the risk of I2C interrupt handle execution before current
+ process unlock */
+ /* Enable ERR, TC, STOP, NACK, TXI interrupt */
+ /* possible to enable all of these */
+ /* I2C_IT_ERRI | I2C_IT_TCI | I2C_IT_STOPI | I2C_IT_NACKI |
+ I2C_IT_ADDRI | I2C_IT_RXI | I2C_IT_TXI */
+ I2C_Enable_IRQ(hi2c, I2C_XFER_TX_IT);
+ }
+
+ return HAL_OK;
+ }
+ else
+ {
+ return HAL_BUSY;
+ }
+}
+
+/**
+ * @brief Receive in master mode an amount of data in non-blocking mode with DMA
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2C.
+ * @param DevAddress Target device address: The device 7 bits address value
+ * in datasheet must be shifted to the left before calling the interface
+ * @param pData Pointer to data buffer
+ * @param Size Amount of data to be sent
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_I2C_Master_Receive_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData,
+ uint16_t Size)
+{
+ uint32_t xfermode;
+ HAL_StatusTypeDef dmaxferstatus;
+
+ if (hi2c->State == HAL_I2C_STATE_READY)
+ {
+ if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) == SET)
+ {
+ return HAL_BUSY;
+ }
+
+ /* Process Locked */
+ __HAL_LOCK(hi2c);
+
+ hi2c->State = HAL_I2C_STATE_BUSY_RX;
+ hi2c->Mode = HAL_I2C_MODE_MASTER;
+ hi2c->ErrorCode = HAL_I2C_ERROR_NONE;
+
+ /* Prepare transfer parameters */
+ hi2c->pBuffPtr = pData;
+ hi2c->XferCount = Size;
+ hi2c->XferOptions = I2C_NO_OPTION_FRAME;
+ hi2c->XferISR = I2C_Master_ISR_DMA;
+
+ if (hi2c->XferCount > MAX_NBYTE_SIZE)
+ {
+ hi2c->XferSize = MAX_NBYTE_SIZE;
+ xfermode = I2C_RELOAD_MODE;
+ }
+ else
+ {
+ hi2c->XferSize = hi2c->XferCount;
+ xfermode = I2C_AUTOEND_MODE;
+ }
+
+ if (hi2c->XferSize > 0U)
+ {
+ if (hi2c->hdmarx != NULL)
+ {
+ /* Set the I2C DMA transfer complete callback */
+ hi2c->hdmarx->XferCpltCallback = I2C_DMAMasterReceiveCplt;
+
+ /* Set the DMA error callback */
+ hi2c->hdmarx->XferErrorCallback = I2C_DMAError;
+
+ /* Set the unused DMA callbacks to NULL */
+ hi2c->hdmarx->XferHalfCpltCallback = NULL;
+ hi2c->hdmarx->XferAbortCallback = NULL;
+
+ /* Enable the DMA channel */
+ dmaxferstatus = HAL_DMA_Start_IT(hi2c->hdmarx, (uint32_t)&hi2c->Instance->RXDR, (uint32_t)pData,
+ hi2c->XferSize);
+ }
+ else
+ {
+ /* Update I2C state */
+ hi2c->State = HAL_I2C_STATE_READY;
+ hi2c->Mode = HAL_I2C_MODE_NONE;
+
+ /* Update I2C error code */
+ hi2c->ErrorCode |= HAL_I2C_ERROR_DMA_PARAM;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ return HAL_ERROR;
+ }
+
+ if (dmaxferstatus == HAL_OK)
+ {
+ /* Send Slave Address */
+ /* Set NBYTES to read and reload if hi2c->XferCount > MAX_NBYTE_SIZE and generate RESTART */
+ I2C_TransferConfig(hi2c, DevAddress, (uint8_t)hi2c->XferSize, xfermode, I2C_GENERATE_START_READ);
+
+ /* Update XferCount value */
+ hi2c->XferCount -= hi2c->XferSize;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ /* Note : The I2C interrupts must be enabled after unlocking current process
+ to avoid the risk of I2C interrupt handle execution before current
+ process unlock */
+ /* Enable ERR and NACK interrupts */
+ I2C_Enable_IRQ(hi2c, I2C_XFER_ERROR_IT);
+
+ /* Enable DMA Request */
+ hi2c->Instance->CR1 |= I2C_CR1_RXDMAEN;
+ }
+ else
+ {
+ /* Update I2C state */
+ hi2c->State = HAL_I2C_STATE_READY;
+ hi2c->Mode = HAL_I2C_MODE_NONE;
+
+ /* Update I2C error code */
+ hi2c->ErrorCode |= HAL_I2C_ERROR_DMA;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ return HAL_ERROR;
+ }
+ }
+ else
+ {
+ /* Update Transfer ISR function pointer */
+ hi2c->XferISR = I2C_Master_ISR_IT;
+
+ /* Send Slave Address */
+ /* Set NBYTES to read and generate START condition */
+ I2C_TransferConfig(hi2c, DevAddress, (uint8_t)hi2c->XferSize, I2C_AUTOEND_MODE,
+ I2C_GENERATE_START_READ);
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ /* Note : The I2C interrupts must be enabled after unlocking current process
+ to avoid the risk of I2C interrupt handle execution before current
+ process unlock */
+ /* Enable ERR, TC, STOP, NACK, TXI interrupt */
+ /* possible to enable all of these */
+ /* I2C_IT_ERRI | I2C_IT_TCI | I2C_IT_STOPI | I2C_IT_NACKI |
+ I2C_IT_ADDRI | I2C_IT_RXI | I2C_IT_TXI */
+ I2C_Enable_IRQ(hi2c, I2C_XFER_TX_IT);
+ }
+
+ return HAL_OK;
+ }
+ else
+ {
+ return HAL_BUSY;
+ }
+}
+
+/**
+ * @brief Transmit in slave mode an amount of data in non-blocking mode with DMA
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2C.
+ * @param pData Pointer to data buffer
+ * @param Size Amount of data to be sent
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_I2C_Slave_Transmit_DMA(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size)
+{
+ HAL_StatusTypeDef dmaxferstatus;
+
+ if (hi2c->State == HAL_I2C_STATE_READY)
+ {
+ if ((pData == NULL) || (Size == 0U))
+ {
+ hi2c->ErrorCode = HAL_I2C_ERROR_INVALID_PARAM;
+ return HAL_ERROR;
+ }
+ /* Process Locked */
+ __HAL_LOCK(hi2c);
+
+ hi2c->State = HAL_I2C_STATE_BUSY_TX;
+ hi2c->Mode = HAL_I2C_MODE_SLAVE;
+ hi2c->ErrorCode = HAL_I2C_ERROR_NONE;
+
+ /* Prepare transfer parameters */
+ hi2c->pBuffPtr = pData;
+ hi2c->XferCount = Size;
+ hi2c->XferSize = hi2c->XferCount;
+ hi2c->XferOptions = I2C_NO_OPTION_FRAME;
+ hi2c->XferISR = I2C_Slave_ISR_DMA;
+
+ if (hi2c->hdmatx != NULL)
+ {
+ /* Set the I2C DMA transfer complete callback */
+ hi2c->hdmatx->XferCpltCallback = I2C_DMASlaveTransmitCplt;
+
+ /* Set the DMA error callback */
+ hi2c->hdmatx->XferErrorCallback = I2C_DMAError;
+
+ /* Set the unused DMA callbacks to NULL */
+ hi2c->hdmatx->XferHalfCpltCallback = NULL;
+ hi2c->hdmatx->XferAbortCallback = NULL;
+
+ /* Enable the DMA channel */
+ dmaxferstatus = HAL_DMA_Start_IT(hi2c->hdmatx, (uint32_t)pData, (uint32_t)&hi2c->Instance->TXDR,
+ hi2c->XferSize);
+ }
+ else
+ {
+ /* Update I2C state */
+ hi2c->State = HAL_I2C_STATE_LISTEN;
+ hi2c->Mode = HAL_I2C_MODE_NONE;
+
+ /* Update I2C error code */
+ hi2c->ErrorCode |= HAL_I2C_ERROR_DMA_PARAM;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ return HAL_ERROR;
+ }
+
+ if (dmaxferstatus == HAL_OK)
+ {
+ /* Enable Address Acknowledge */
+ hi2c->Instance->CR2 &= ~I2C_CR2_NACK;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ /* Note : The I2C interrupts must be enabled after unlocking current process
+ to avoid the risk of I2C interrupt handle execution before current
+ process unlock */
+ /* Enable ERR, STOP, NACK, ADDR interrupts */
+ I2C_Enable_IRQ(hi2c, I2C_XFER_LISTEN_IT);
+
+ /* Enable DMA Request */
+ hi2c->Instance->CR1 |= I2C_CR1_TXDMAEN;
+ }
+ else
+ {
+ /* Update I2C state */
+ hi2c->State = HAL_I2C_STATE_LISTEN;
+ hi2c->Mode = HAL_I2C_MODE_NONE;
+
+ /* Update I2C error code */
+ hi2c->ErrorCode |= HAL_I2C_ERROR_DMA;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ return HAL_ERROR;
+ }
+
+ return HAL_OK;
+ }
+ else
+ {
+ return HAL_BUSY;
+ }
+}
+
+/**
+ * @brief Receive in slave mode an amount of data in non-blocking mode with DMA
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2C.
+ * @param pData Pointer to data buffer
+ * @param Size Amount of data to be sent
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_I2C_Slave_Receive_DMA(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size)
+{
+ HAL_StatusTypeDef dmaxferstatus;
+
+ if (hi2c->State == HAL_I2C_STATE_READY)
+ {
+ if ((pData == NULL) || (Size == 0U))
+ {
+ hi2c->ErrorCode = HAL_I2C_ERROR_INVALID_PARAM;
+ return HAL_ERROR;
+ }
+ /* Process Locked */
+ __HAL_LOCK(hi2c);
+
+ hi2c->State = HAL_I2C_STATE_BUSY_RX;
+ hi2c->Mode = HAL_I2C_MODE_SLAVE;
+ hi2c->ErrorCode = HAL_I2C_ERROR_NONE;
+
+ /* Prepare transfer parameters */
+ hi2c->pBuffPtr = pData;
+ hi2c->XferCount = Size;
+ hi2c->XferSize = hi2c->XferCount;
+ hi2c->XferOptions = I2C_NO_OPTION_FRAME;
+ hi2c->XferISR = I2C_Slave_ISR_DMA;
+
+ if (hi2c->hdmarx != NULL)
+ {
+ /* Set the I2C DMA transfer complete callback */
+ hi2c->hdmarx->XferCpltCallback = I2C_DMASlaveReceiveCplt;
+
+ /* Set the DMA error callback */
+ hi2c->hdmarx->XferErrorCallback = I2C_DMAError;
+
+ /* Set the unused DMA callbacks to NULL */
+ hi2c->hdmarx->XferHalfCpltCallback = NULL;
+ hi2c->hdmarx->XferAbortCallback = NULL;
+
+ /* Enable the DMA channel */
+ dmaxferstatus = HAL_DMA_Start_IT(hi2c->hdmarx, (uint32_t)&hi2c->Instance->RXDR, (uint32_t)pData,
+ hi2c->XferSize);
+ }
+ else
+ {
+ /* Update I2C state */
+ hi2c->State = HAL_I2C_STATE_LISTEN;
+ hi2c->Mode = HAL_I2C_MODE_NONE;
+
+ /* Update I2C error code */
+ hi2c->ErrorCode |= HAL_I2C_ERROR_DMA_PARAM;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ return HAL_ERROR;
+ }
+
+ if (dmaxferstatus == HAL_OK)
+ {
+ /* Enable Address Acknowledge */
+ hi2c->Instance->CR2 &= ~I2C_CR2_NACK;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ /* Note : The I2C interrupts must be enabled after unlocking current process
+ to avoid the risk of I2C interrupt handle execution before current
+ process unlock */
+ /* Enable ERR, STOP, NACK, ADDR interrupts */
+ I2C_Enable_IRQ(hi2c, I2C_XFER_LISTEN_IT);
+
+ /* Enable DMA Request */
+ hi2c->Instance->CR1 |= I2C_CR1_RXDMAEN;
+ }
+ else
+ {
+ /* Update I2C state */
+ hi2c->State = HAL_I2C_STATE_LISTEN;
+ hi2c->Mode = HAL_I2C_MODE_NONE;
+
+ /* Update I2C error code */
+ hi2c->ErrorCode |= HAL_I2C_ERROR_DMA;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ return HAL_ERROR;
+ }
+
+ return HAL_OK;
+ }
+ else
+ {
+ return HAL_BUSY;
+ }
+}
+/**
+ * @brief Write an amount of data in blocking mode to a specific memory address
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2C.
+ * @param DevAddress Target device address: The device 7 bits address value
+ * in datasheet must be shifted to the left before calling the interface
+ * @param MemAddress Internal memory address
+ * @param MemAddSize Size of internal memory address
+ * @param pData Pointer to data buffer
+ * @param Size Amount of data to be sent
+ * @param Timeout Timeout duration
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_I2C_Mem_Write(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress,
+ uint16_t MemAddSize, uint8_t *pData, uint16_t Size, uint32_t Timeout)
+{
+ uint32_t tickstart;
+
+ /* Check the parameters */
+ assert_param(IS_I2C_MEMADD_SIZE(MemAddSize));
+
+ if (hi2c->State == HAL_I2C_STATE_READY)
+ {
+ if ((pData == NULL) || (Size == 0U))
+ {
+ hi2c->ErrorCode = HAL_I2C_ERROR_INVALID_PARAM;
+ return HAL_ERROR;
+ }
+
+ /* Process Locked */
+ __HAL_LOCK(hi2c);
+
+ /* Init tickstart for timeout management*/
+ tickstart = HAL_GetTick();
+
+ if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BUSY, SET, I2C_TIMEOUT_BUSY, tickstart) != HAL_OK)
+ {
+ return HAL_ERROR;
+ }
+
+ hi2c->State = HAL_I2C_STATE_BUSY_TX;
+ hi2c->Mode = HAL_I2C_MODE_MEM;
+ hi2c->ErrorCode = HAL_I2C_ERROR_NONE;
+
+ /* Prepare transfer parameters */
+ hi2c->pBuffPtr = pData;
+ hi2c->XferCount = Size;
+ hi2c->XferISR = NULL;
+
+ /* Send Slave Address and Memory Address */
+ if (I2C_RequestMemoryWrite(hi2c, DevAddress, MemAddress, MemAddSize, Timeout, tickstart) != HAL_OK)
+ {
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+ return HAL_ERROR;
+ }
+
+ /* Set NBYTES to write and reload if hi2c->XferCount > MAX_NBYTE_SIZE */
+ if (hi2c->XferCount > MAX_NBYTE_SIZE)
+ {
+ hi2c->XferSize = MAX_NBYTE_SIZE;
+ I2C_TransferConfig(hi2c, DevAddress, (uint8_t)hi2c->XferSize, I2C_RELOAD_MODE, I2C_NO_STARTSTOP);
+ }
+ else
+ {
+ hi2c->XferSize = hi2c->XferCount;
+ I2C_TransferConfig(hi2c, DevAddress, (uint8_t)hi2c->XferSize, I2C_AUTOEND_MODE, I2C_NO_STARTSTOP);
+ }
+
+ do
+ {
+ /* Wait until TXIS flag is set */
+ if (I2C_WaitOnTXISFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK)
+ {
+ return HAL_ERROR;
+ }
+
+ /* Write data to TXDR */
+ hi2c->Instance->TXDR = *hi2c->pBuffPtr;
+
+ /* Increment Buffer pointer */
+ hi2c->pBuffPtr++;
+
+ hi2c->XferCount--;
+ hi2c->XferSize--;
+
+ if ((hi2c->XferCount != 0U) && (hi2c->XferSize == 0U))
+ {
+ /* Wait until TCR flag is set */
+ if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_TCR, RESET, Timeout, tickstart) != HAL_OK)
+ {
+ return HAL_ERROR;
+ }
+
+ if (hi2c->XferCount > MAX_NBYTE_SIZE)
+ {
+ hi2c->XferSize = MAX_NBYTE_SIZE;
+ I2C_TransferConfig(hi2c, DevAddress, (uint8_t)hi2c->XferSize, I2C_RELOAD_MODE,
+ I2C_NO_STARTSTOP);
+ }
+ else
+ {
+ hi2c->XferSize = hi2c->XferCount;
+ I2C_TransferConfig(hi2c, DevAddress, (uint8_t)hi2c->XferSize, I2C_AUTOEND_MODE,
+ I2C_NO_STARTSTOP);
+ }
+ }
+
+ } while (hi2c->XferCount > 0U);
+
+ /* No need to Check TC flag, with AUTOEND mode the stop is automatically generated */
+ /* Wait until STOPF flag is reset */
+ if (I2C_WaitOnSTOPFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK)
+ {
+ return HAL_ERROR;
+ }
+
+ /* Clear STOP Flag */
+ __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_STOPF);
+
+ /* Clear Configuration Register 2 */
+ I2C_RESET_CR2(hi2c);
+
+ hi2c->State = HAL_I2C_STATE_READY;
+ hi2c->Mode = HAL_I2C_MODE_NONE;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ return HAL_OK;
+ }
+ else
+ {
+ return HAL_BUSY;
+ }
+}
+
+/**
+ * @brief Read an amount of data in blocking mode from a specific memory address
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2C.
+ * @param DevAddress Target device address: The device 7 bits address value
+ * in datasheet must be shifted to the left before calling the interface
+ * @param MemAddress Internal memory address
+ * @param MemAddSize Size of internal memory address
+ * @param pData Pointer to data buffer
+ * @param Size Amount of data to be sent
+ * @param Timeout Timeout duration
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_I2C_Mem_Read(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress,
+ uint16_t MemAddSize, uint8_t *pData, uint16_t Size, uint32_t Timeout)
+{
+ uint32_t tickstart;
+
+ /* Check the parameters */
+ assert_param(IS_I2C_MEMADD_SIZE(MemAddSize));
+
+ if (hi2c->State == HAL_I2C_STATE_READY)
+ {
+ if ((pData == NULL) || (Size == 0U))
+ {
+ hi2c->ErrorCode = HAL_I2C_ERROR_INVALID_PARAM;
+ return HAL_ERROR;
+ }
+
+ /* Process Locked */
+ __HAL_LOCK(hi2c);
+
+ /* Init tickstart for timeout management*/
+ tickstart = HAL_GetTick();
+
+ if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BUSY, SET, I2C_TIMEOUT_BUSY, tickstart) != HAL_OK)
+ {
+ return HAL_ERROR;
+ }
+
+ hi2c->State = HAL_I2C_STATE_BUSY_RX;
+ hi2c->Mode = HAL_I2C_MODE_MEM;
+ hi2c->ErrorCode = HAL_I2C_ERROR_NONE;
+
+ /* Prepare transfer parameters */
+ hi2c->pBuffPtr = pData;
+ hi2c->XferCount = Size;
+ hi2c->XferISR = NULL;
+
+ /* Send Slave Address and Memory Address */
+ if (I2C_RequestMemoryRead(hi2c, DevAddress, MemAddress, MemAddSize, Timeout, tickstart) != HAL_OK)
+ {
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+ return HAL_ERROR;
+ }
+
+ /* Send Slave Address */
+ /* Set NBYTES to write and reload if hi2c->XferCount > MAX_NBYTE_SIZE and generate RESTART */
+ if (hi2c->XferCount > MAX_NBYTE_SIZE)
+ {
+ hi2c->XferSize = MAX_NBYTE_SIZE;
+ I2C_TransferConfig(hi2c, DevAddress, (uint8_t)hi2c->XferSize, I2C_RELOAD_MODE,
+ I2C_GENERATE_START_READ);
+ }
+ else
+ {
+ hi2c->XferSize = hi2c->XferCount;
+ I2C_TransferConfig(hi2c, DevAddress, (uint8_t)hi2c->XferSize, I2C_AUTOEND_MODE,
+ I2C_GENERATE_START_READ);
+ }
+
+ do
+ {
+ /* Wait until RXNE flag is set */
+ if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_RXNE, RESET, Timeout, tickstart) != HAL_OK)
+ {
+ return HAL_ERROR;
+ }
+
+ /* Read data from RXDR */
+ *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->RXDR;
+
+ /* Increment Buffer pointer */
+ hi2c->pBuffPtr++;
+
+ hi2c->XferSize--;
+ hi2c->XferCount--;
+
+ if ((hi2c->XferCount != 0U) && (hi2c->XferSize == 0U))
+ {
+ /* Wait until TCR flag is set */
+ if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_TCR, RESET, Timeout, tickstart) != HAL_OK)
+ {
+ return HAL_ERROR;
+ }
+
+ if (hi2c->XferCount > MAX_NBYTE_SIZE)
+ {
+ hi2c->XferSize = MAX_NBYTE_SIZE;
+ I2C_TransferConfig(hi2c, DevAddress, (uint8_t) hi2c->XferSize, I2C_RELOAD_MODE,
+ I2C_NO_STARTSTOP);
+ }
+ else
+ {
+ hi2c->XferSize = hi2c->XferCount;
+ I2C_TransferConfig(hi2c, DevAddress, (uint8_t)hi2c->XferSize, I2C_AUTOEND_MODE,
+ I2C_NO_STARTSTOP);
+ }
+ }
+ } while (hi2c->XferCount > 0U);
+
+ /* No need to Check TC flag, with AUTOEND mode the stop is automatically generated */
+ /* Wait until STOPF flag is reset */
+ if (I2C_WaitOnSTOPFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK)
+ {
+ return HAL_ERROR;
+ }
+
+ /* Clear STOP Flag */
+ __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_STOPF);
+
+ /* Clear Configuration Register 2 */
+ I2C_RESET_CR2(hi2c);
+
+ hi2c->State = HAL_I2C_STATE_READY;
+ hi2c->Mode = HAL_I2C_MODE_NONE;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ return HAL_OK;
+ }
+ else
+ {
+ return HAL_BUSY;
+ }
+}
+/**
+ * @brief Write an amount of data in non-blocking mode with Interrupt to a specific memory address
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2C.
+ * @param DevAddress Target device address: The device 7 bits address value
+ * in datasheet must be shifted to the left before calling the interface
+ * @param MemAddress Internal memory address
+ * @param MemAddSize Size of internal memory address
+ * @param pData Pointer to data buffer
+ * @param Size Amount of data to be sent
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_I2C_Mem_Write_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress,
+ uint16_t MemAddSize, uint8_t *pData, uint16_t Size)
+{
+ uint32_t tickstart;
+ uint32_t xfermode;
+
+ /* Check the parameters */
+ assert_param(IS_I2C_MEMADD_SIZE(MemAddSize));
+
+ if (hi2c->State == HAL_I2C_STATE_READY)
+ {
+ if ((pData == NULL) || (Size == 0U))
+ {
+ hi2c->ErrorCode = HAL_I2C_ERROR_INVALID_PARAM;
+ return HAL_ERROR;
+ }
+
+ if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) == SET)
+ {
+ return HAL_BUSY;
+ }
+
+ /* Process Locked */
+ __HAL_LOCK(hi2c);
+
+ /* Init tickstart for timeout management*/
+ tickstart = HAL_GetTick();
+
+ hi2c->State = HAL_I2C_STATE_BUSY_TX;
+ hi2c->Mode = HAL_I2C_MODE_MEM;
+ hi2c->ErrorCode = HAL_I2C_ERROR_NONE;
+
+ /* Prepare transfer parameters */
+ hi2c->pBuffPtr = pData;
+ hi2c->XferCount = Size;
+ hi2c->XferOptions = I2C_NO_OPTION_FRAME;
+ hi2c->XferISR = I2C_Master_ISR_IT;
+
+ if (hi2c->XferCount > MAX_NBYTE_SIZE)
+ {
+ hi2c->XferSize = MAX_NBYTE_SIZE;
+ xfermode = I2C_RELOAD_MODE;
+ }
+ else
+ {
+ hi2c->XferSize = hi2c->XferCount;
+ xfermode = I2C_AUTOEND_MODE;
+ }
+
+ /* Send Slave Address and Memory Address */
+ if (I2C_RequestMemoryWrite(hi2c, DevAddress, MemAddress, MemAddSize, I2C_TIMEOUT_FLAG, tickstart)
+ != HAL_OK)
+ {
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+ return HAL_ERROR;
+ }
+
+ /* Set NBYTES to write and reload if hi2c->XferCount > MAX_NBYTE_SIZE and generate RESTART */
+ I2C_TransferConfig(hi2c, DevAddress, (uint8_t)hi2c->XferSize, xfermode, I2C_NO_STARTSTOP);
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ /* Note : The I2C interrupts must be enabled after unlocking current process
+ to avoid the risk of I2C interrupt handle execution before current
+ process unlock */
+
+ /* Enable ERR, TC, STOP, NACK, TXI interrupt */
+ /* possible to enable all of these */
+ /* I2C_IT_ERRI | I2C_IT_TCI | I2C_IT_STOPI | I2C_IT_NACKI |
+ I2C_IT_ADDRI | I2C_IT_RXI | I2C_IT_TXI */
+ I2C_Enable_IRQ(hi2c, I2C_XFER_TX_IT);
+
+ return HAL_OK;
+ }
+ else
+ {
+ return HAL_BUSY;
+ }
+}
+
+/**
+ * @brief Read an amount of data in non-blocking mode with Interrupt from a specific memory address
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2C.
+ * @param DevAddress Target device address: The device 7 bits address value
+ * in datasheet must be shifted to the left before calling the interface
+ * @param MemAddress Internal memory address
+ * @param MemAddSize Size of internal memory address
+ * @param pData Pointer to data buffer
+ * @param Size Amount of data to be sent
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_I2C_Mem_Read_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress,
+ uint16_t MemAddSize, uint8_t *pData, uint16_t Size)
+{
+ uint32_t tickstart;
+ uint32_t xfermode;
+
+ /* Check the parameters */
+ assert_param(IS_I2C_MEMADD_SIZE(MemAddSize));
+
+ if (hi2c->State == HAL_I2C_STATE_READY)
+ {
+ if ((pData == NULL) || (Size == 0U))
+ {
+ hi2c->ErrorCode = HAL_I2C_ERROR_INVALID_PARAM;
+ return HAL_ERROR;
+ }
+
+ if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) == SET)
+ {
+ return HAL_BUSY;
+ }
+
+ /* Process Locked */
+ __HAL_LOCK(hi2c);
+
+ /* Init tickstart for timeout management*/
+ tickstart = HAL_GetTick();
+
+ hi2c->State = HAL_I2C_STATE_BUSY_RX;
+ hi2c->Mode = HAL_I2C_MODE_MEM;
+ hi2c->ErrorCode = HAL_I2C_ERROR_NONE;
+
+ /* Prepare transfer parameters */
+ hi2c->pBuffPtr = pData;
+ hi2c->XferCount = Size;
+ hi2c->XferOptions = I2C_NO_OPTION_FRAME;
+ hi2c->XferISR = I2C_Master_ISR_IT;
+
+ if (hi2c->XferCount > MAX_NBYTE_SIZE)
+ {
+ hi2c->XferSize = MAX_NBYTE_SIZE;
+ xfermode = I2C_RELOAD_MODE;
+ }
+ else
+ {
+ hi2c->XferSize = hi2c->XferCount;
+ xfermode = I2C_AUTOEND_MODE;
+ }
+
+ /* Send Slave Address and Memory Address */
+ if (I2C_RequestMemoryRead(hi2c, DevAddress, MemAddress, MemAddSize, I2C_TIMEOUT_FLAG, tickstart) != HAL_OK)
+ {
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+ return HAL_ERROR;
+ }
+
+ /* Set NBYTES to write and reload if hi2c->XferCount > MAX_NBYTE_SIZE and generate RESTART */
+ I2C_TransferConfig(hi2c, DevAddress, (uint8_t)hi2c->XferSize, xfermode, I2C_GENERATE_START_READ);
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ /* Note : The I2C interrupts must be enabled after unlocking current process
+ to avoid the risk of I2C interrupt handle execution before current
+ process unlock */
+
+ /* Enable ERR, TC, STOP, NACK, RXI interrupt */
+ /* possible to enable all of these */
+ /* I2C_IT_ERRI | I2C_IT_TCI | I2C_IT_STOPI | I2C_IT_NACKI |
+ I2C_IT_ADDRI | I2C_IT_RXI | I2C_IT_TXI */
+ I2C_Enable_IRQ(hi2c, I2C_XFER_RX_IT);
+
+ return HAL_OK;
+ }
+ else
+ {
+ return HAL_BUSY;
+ }
+}
+/**
+ * @brief Write an amount of data in non-blocking mode with DMA to a specific memory address
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2C.
+ * @param DevAddress Target device address: The device 7 bits address value
+ * in datasheet must be shifted to the left before calling the interface
+ * @param MemAddress Internal memory address
+ * @param MemAddSize Size of internal memory address
+ * @param pData Pointer to data buffer
+ * @param Size Amount of data to be sent
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_I2C_Mem_Write_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress,
+ uint16_t MemAddSize, uint8_t *pData, uint16_t Size)
+{
+ uint32_t tickstart;
+ uint32_t xfermode;
+ HAL_StatusTypeDef dmaxferstatus;
+
+ /* Check the parameters */
+ assert_param(IS_I2C_MEMADD_SIZE(MemAddSize));
+
+ if (hi2c->State == HAL_I2C_STATE_READY)
+ {
+ if ((pData == NULL) || (Size == 0U))
+ {
+ hi2c->ErrorCode = HAL_I2C_ERROR_INVALID_PARAM;
+ return HAL_ERROR;
+ }
+
+ if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) == SET)
+ {
+ return HAL_BUSY;
+ }
+
+ /* Process Locked */
+ __HAL_LOCK(hi2c);
+
+ /* Init tickstart for timeout management*/
+ tickstart = HAL_GetTick();
+
+ hi2c->State = HAL_I2C_STATE_BUSY_TX;
+ hi2c->Mode = HAL_I2C_MODE_MEM;
+ hi2c->ErrorCode = HAL_I2C_ERROR_NONE;
+
+ /* Prepare transfer parameters */
+ hi2c->pBuffPtr = pData;
+ hi2c->XferCount = Size;
+ hi2c->XferOptions = I2C_NO_OPTION_FRAME;
+ hi2c->XferISR = I2C_Master_ISR_DMA;
+
+ if (hi2c->XferCount > MAX_NBYTE_SIZE)
+ {
+ hi2c->XferSize = MAX_NBYTE_SIZE;
+ xfermode = I2C_RELOAD_MODE;
+ }
+ else
+ {
+ hi2c->XferSize = hi2c->XferCount;
+ xfermode = I2C_AUTOEND_MODE;
+ }
+
+ /* Send Slave Address and Memory Address */
+ if (I2C_RequestMemoryWrite(hi2c, DevAddress, MemAddress, MemAddSize, I2C_TIMEOUT_FLAG, tickstart)
+ != HAL_OK)
+ {
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+ return HAL_ERROR;
+ }
+
+
+ if (hi2c->hdmatx != NULL)
+ {
+ /* Set the I2C DMA transfer complete callback */
+ hi2c->hdmatx->XferCpltCallback = I2C_DMAMasterTransmitCplt;
+
+ /* Set the DMA error callback */
+ hi2c->hdmatx->XferErrorCallback = I2C_DMAError;
+
+ /* Set the unused DMA callbacks to NULL */
+ hi2c->hdmatx->XferHalfCpltCallback = NULL;
+ hi2c->hdmatx->XferAbortCallback = NULL;
+
+ /* Enable the DMA channel */
+ dmaxferstatus = HAL_DMA_Start_IT(hi2c->hdmatx, (uint32_t)pData, (uint32_t)&hi2c->Instance->TXDR,
+ hi2c->XferSize);
+ }
+ else
+ {
+ /* Update I2C state */
+ hi2c->State = HAL_I2C_STATE_READY;
+ hi2c->Mode = HAL_I2C_MODE_NONE;
+
+ /* Update I2C error code */
+ hi2c->ErrorCode |= HAL_I2C_ERROR_DMA_PARAM;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ return HAL_ERROR;
+ }
+
+ if (dmaxferstatus == HAL_OK)
+ {
+ /* Send Slave Address */
+ /* Set NBYTES to write and reload if hi2c->XferCount > MAX_NBYTE_SIZE and generate RESTART */
+ I2C_TransferConfig(hi2c, DevAddress, (uint8_t)hi2c->XferSize, xfermode, I2C_NO_STARTSTOP);
+
+ /* Update XferCount value */
+ hi2c->XferCount -= hi2c->XferSize;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ /* Note : The I2C interrupts must be enabled after unlocking current process
+ to avoid the risk of I2C interrupt handle execution before current
+ process unlock */
+ /* Enable ERR and NACK interrupts */
+ I2C_Enable_IRQ(hi2c, I2C_XFER_ERROR_IT);
+
+ /* Enable DMA Request */
+ hi2c->Instance->CR1 |= I2C_CR1_TXDMAEN;
+ }
+ else
+ {
+ /* Update I2C state */
+ hi2c->State = HAL_I2C_STATE_READY;
+ hi2c->Mode = HAL_I2C_MODE_NONE;
+
+ /* Update I2C error code */
+ hi2c->ErrorCode |= HAL_I2C_ERROR_DMA;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ return HAL_ERROR;
+ }
+
+ return HAL_OK;
+ }
+ else
+ {
+ return HAL_BUSY;
+ }
+}
+
+/**
+ * @brief Reads an amount of data in non-blocking mode with DMA from a specific memory address.
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2C.
+ * @param DevAddress Target device address: The device 7 bits address value
+ * in datasheet must be shifted to the left before calling the interface
+ * @param MemAddress Internal memory address
+ * @param MemAddSize Size of internal memory address
+ * @param pData Pointer to data buffer
+ * @param Size Amount of data to be read
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_I2C_Mem_Read_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress,
+ uint16_t MemAddSize, uint8_t *pData, uint16_t Size)
+{
+ uint32_t tickstart;
+ uint32_t xfermode;
+ HAL_StatusTypeDef dmaxferstatus;
+
+ /* Check the parameters */
+ assert_param(IS_I2C_MEMADD_SIZE(MemAddSize));
+
+ if (hi2c->State == HAL_I2C_STATE_READY)
+ {
+ if ((pData == NULL) || (Size == 0U))
+ {
+ hi2c->ErrorCode = HAL_I2C_ERROR_INVALID_PARAM;
+ return HAL_ERROR;
+ }
+
+ if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) == SET)
+ {
+ return HAL_BUSY;
+ }
+
+ /* Process Locked */
+ __HAL_LOCK(hi2c);
+
+ /* Init tickstart for timeout management*/
+ tickstart = HAL_GetTick();
+
+ hi2c->State = HAL_I2C_STATE_BUSY_RX;
+ hi2c->Mode = HAL_I2C_MODE_MEM;
+ hi2c->ErrorCode = HAL_I2C_ERROR_NONE;
+
+ /* Prepare transfer parameters */
+ hi2c->pBuffPtr = pData;
+ hi2c->XferCount = Size;
+ hi2c->XferOptions = I2C_NO_OPTION_FRAME;
+ hi2c->XferISR = I2C_Master_ISR_DMA;
+
+ if (hi2c->XferCount > MAX_NBYTE_SIZE)
+ {
+ hi2c->XferSize = MAX_NBYTE_SIZE;
+ xfermode = I2C_RELOAD_MODE;
+ }
+ else
+ {
+ hi2c->XferSize = hi2c->XferCount;
+ xfermode = I2C_AUTOEND_MODE;
+ }
+
+ /* Send Slave Address and Memory Address */
+ if (I2C_RequestMemoryRead(hi2c, DevAddress, MemAddress, MemAddSize, I2C_TIMEOUT_FLAG, tickstart) != HAL_OK)
+ {
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+ return HAL_ERROR;
+ }
+
+ if (hi2c->hdmarx != NULL)
+ {
+ /* Set the I2C DMA transfer complete callback */
+ hi2c->hdmarx->XferCpltCallback = I2C_DMAMasterReceiveCplt;
+
+ /* Set the DMA error callback */
+ hi2c->hdmarx->XferErrorCallback = I2C_DMAError;
+
+ /* Set the unused DMA callbacks to NULL */
+ hi2c->hdmarx->XferHalfCpltCallback = NULL;
+ hi2c->hdmarx->XferAbortCallback = NULL;
+
+ /* Enable the DMA channel */
+ dmaxferstatus = HAL_DMA_Start_IT(hi2c->hdmarx, (uint32_t)&hi2c->Instance->RXDR, (uint32_t)pData,
+ hi2c->XferSize);
+ }
+ else
+ {
+ /* Update I2C state */
+ hi2c->State = HAL_I2C_STATE_READY;
+ hi2c->Mode = HAL_I2C_MODE_NONE;
+
+ /* Update I2C error code */
+ hi2c->ErrorCode |= HAL_I2C_ERROR_DMA_PARAM;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ return HAL_ERROR;
+ }
+
+ if (dmaxferstatus == HAL_OK)
+ {
+ /* Set NBYTES to write and reload if hi2c->XferCount > MAX_NBYTE_SIZE and generate RESTART */
+ I2C_TransferConfig(hi2c, DevAddress, (uint8_t)hi2c->XferSize, xfermode, I2C_GENERATE_START_READ);
+
+ /* Update XferCount value */
+ hi2c->XferCount -= hi2c->XferSize;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ /* Note : The I2C interrupts must be enabled after unlocking current process
+ to avoid the risk of I2C interrupt handle execution before current
+ process unlock */
+ /* Enable ERR and NACK interrupts */
+ I2C_Enable_IRQ(hi2c, I2C_XFER_ERROR_IT);
+
+ /* Enable DMA Request */
+ hi2c->Instance->CR1 |= I2C_CR1_RXDMAEN;
+ }
+ else
+ {
+ /* Update I2C state */
+ hi2c->State = HAL_I2C_STATE_READY;
+ hi2c->Mode = HAL_I2C_MODE_NONE;
+
+ /* Update I2C error code */
+ hi2c->ErrorCode |= HAL_I2C_ERROR_DMA;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ return HAL_ERROR;
+ }
+
+ return HAL_OK;
+ }
+ else
+ {
+ return HAL_BUSY;
+ }
+}
+
+/**
+ * @brief Checks if target device is ready for communication.
+ * @note This function is used with Memory devices
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2C.
+ * @param DevAddress Target device address: The device 7 bits address value
+ * in datasheet must be shifted to the left before calling the interface
+ * @param Trials Number of trials
+ * @param Timeout Timeout duration
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_I2C_IsDeviceReady(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint32_t Trials,
+ uint32_t Timeout)
+{
+ uint32_t tickstart;
+
+ __IO uint32_t I2C_Trials = 0UL;
+
+ FlagStatus tmp1;
+ FlagStatus tmp2;
+
+ if (hi2c->State == HAL_I2C_STATE_READY)
+ {
+ if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) == SET)
+ {
+ return HAL_BUSY;
+ }
+
+ /* Process Locked */
+ __HAL_LOCK(hi2c);
+
+ hi2c->State = HAL_I2C_STATE_BUSY;
+ hi2c->ErrorCode = HAL_I2C_ERROR_NONE;
+
+ do
+ {
+ /* Generate Start */
+ hi2c->Instance->CR2 = I2C_GENERATE_START(hi2c->Init.AddressingMode, DevAddress);
+
+ /* No need to Check TC flag, with AUTOEND mode the stop is automatically generated */
+ /* Wait until STOPF flag is set or a NACK flag is set*/
+ tickstart = HAL_GetTick();
+
+ tmp1 = __HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_STOPF);
+ tmp2 = __HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_AF);
+
+ while ((tmp1 == RESET) && (tmp2 == RESET))
+ {
+ if (Timeout != HAL_MAX_DELAY)
+ {
+ if (((HAL_GetTick() - tickstart) > Timeout) || (Timeout == 0U))
+ {
+ /* Update I2C state */
+ hi2c->State = HAL_I2C_STATE_READY;
+
+ /* Update I2C error code */
+ hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ return HAL_ERROR;
+ }
+ }
+
+ tmp1 = __HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_STOPF);
+ tmp2 = __HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_AF);
+ }
+
+ /* Check if the NACKF flag has not been set */
+ if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_AF) == RESET)
+ {
+ /* Wait until STOPF flag is reset */
+ if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_STOPF, RESET, Timeout, tickstart) != HAL_OK)
+ {
+ return HAL_ERROR;
+ }
+
+ /* Clear STOP Flag */
+ __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_STOPF);
+
+ /* Device is ready */
+ hi2c->State = HAL_I2C_STATE_READY;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ return HAL_OK;
+ }
+ else
+ {
+ /* Wait until STOPF flag is reset */
+ if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_STOPF, RESET, Timeout, tickstart) != HAL_OK)
+ {
+ return HAL_ERROR;
+ }
+
+ /* Clear NACK Flag */
+ __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_AF);
+
+ /* Clear STOP Flag, auto generated with autoend*/
+ __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_STOPF);
+ }
+
+ /* Check if the maximum allowed number of trials has been reached */
+ if (I2C_Trials == Trials)
+ {
+ /* Generate Stop */
+ hi2c->Instance->CR2 |= I2C_CR2_STOP;
+
+ /* Wait until STOPF flag is reset */
+ if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_STOPF, RESET, Timeout, tickstart) != HAL_OK)
+ {
+ return HAL_ERROR;
+ }
+
+ /* Clear STOP Flag */
+ __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_STOPF);
+ }
+
+ /* Increment Trials */
+ I2C_Trials++;
+ } while (I2C_Trials < Trials);
+
+ /* Update I2C state */
+ hi2c->State = HAL_I2C_STATE_READY;
+
+ /* Update I2C error code */
+ hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ return HAL_ERROR;
+ }
+ else
+ {
+ return HAL_BUSY;
+ }
+}
+
+/**
+ * @brief Sequential transmit in master I2C mode an amount of data in non-blocking mode with Interrupt.
+ * @note This interface allow to manage repeated start condition when a direction change during transfer
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2C.
+ * @param DevAddress Target device address: The device 7 bits address value
+ * in datasheet must be shifted to the left before calling the interface
+ * @param pData Pointer to data buffer
+ * @param Size Amount of data to be sent
+ * @param XferOptions Options of Transfer, value of @ref I2C_XFEROPTIONS
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_I2C_Master_Seq_Transmit_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData,
+ uint16_t Size, uint32_t XferOptions)
+{
+ uint32_t xfermode;
+ uint32_t xferrequest = I2C_GENERATE_START_WRITE;
+
+ /* Check the parameters */
+ assert_param(IS_I2C_TRANSFER_OPTIONS_REQUEST(XferOptions));
+
+ if (hi2c->State == HAL_I2C_STATE_READY)
+ {
+ /* Process Locked */
+ __HAL_LOCK(hi2c);
+
+ hi2c->State = HAL_I2C_STATE_BUSY_TX;
+ hi2c->Mode = HAL_I2C_MODE_MASTER;
+ hi2c->ErrorCode = HAL_I2C_ERROR_NONE;
+
+ /* Prepare transfer parameters */
+ hi2c->pBuffPtr = pData;
+ hi2c->XferCount = Size;
+ hi2c->XferOptions = XferOptions;
+ hi2c->XferISR = I2C_Master_ISR_IT;
+
+ /* If hi2c->XferCount > MAX_NBYTE_SIZE, use reload mode */
+ if (hi2c->XferCount > MAX_NBYTE_SIZE)
+ {
+ hi2c->XferSize = MAX_NBYTE_SIZE;
+ xfermode = I2C_RELOAD_MODE;
+ }
+ else
+ {
+ hi2c->XferSize = hi2c->XferCount;
+ xfermode = hi2c->XferOptions;
+ }
+
+ /* If transfer direction not change and there is no request to start another frame,
+ do not generate Restart Condition */
+ /* Mean Previous state is same as current state */
+ if ((hi2c->PreviousState == I2C_STATE_MASTER_BUSY_TX) && \
+ (IS_I2C_TRANSFER_OTHER_OPTIONS_REQUEST(XferOptions) == 0))
+ {
+ xferrequest = I2C_NO_STARTSTOP;
+ }
+ else
+ {
+ /* Convert OTHER_xxx XferOptions if any */
+ I2C_ConvertOtherXferOptions(hi2c);
+
+ /* Update xfermode accordingly if no reload is necessary */
+ if (hi2c->XferCount <= MAX_NBYTE_SIZE)
+ {
+ xfermode = hi2c->XferOptions;
+ }
+ }
+
+ /* Send Slave Address and set NBYTES to write */
+ I2C_TransferConfig(hi2c, DevAddress, (uint8_t)hi2c->XferSize, xfermode, xferrequest);
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ /* Note : The I2C interrupts must be enabled after unlocking current process
+ to avoid the risk of I2C interrupt handle execution before current
+ process unlock */
+ I2C_Enable_IRQ(hi2c, I2C_XFER_TX_IT);
+
+ return HAL_OK;
+ }
+ else
+ {
+ return HAL_BUSY;
+ }
+}
+
+/**
+ * @brief Sequential transmit in master I2C mode an amount of data in non-blocking mode with DMA.
+ * @note This interface allow to manage repeated start condition when a direction change during transfer
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2C.
+ * @param DevAddress Target device address: The device 7 bits address value
+ * in datasheet must be shifted to the left before calling the interface
+ * @param pData Pointer to data buffer
+ * @param Size Amount of data to be sent
+ * @param XferOptions Options of Transfer, value of @ref I2C_XFEROPTIONS
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_I2C_Master_Seq_Transmit_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData,
+ uint16_t Size, uint32_t XferOptions)
+{
+ uint32_t xfermode;
+ uint32_t xferrequest = I2C_GENERATE_START_WRITE;
+ HAL_StatusTypeDef dmaxferstatus;
+
+ /* Check the parameters */
+ assert_param(IS_I2C_TRANSFER_OPTIONS_REQUEST(XferOptions));
+
+ if (hi2c->State == HAL_I2C_STATE_READY)
+ {
+ /* Process Locked */
+ __HAL_LOCK(hi2c);
+
+ hi2c->State = HAL_I2C_STATE_BUSY_TX;
+ hi2c->Mode = HAL_I2C_MODE_MASTER;
+ hi2c->ErrorCode = HAL_I2C_ERROR_NONE;
+
+ /* Prepare transfer parameters */
+ hi2c->pBuffPtr = pData;
+ hi2c->XferCount = Size;
+ hi2c->XferOptions = XferOptions;
+ hi2c->XferISR = I2C_Master_ISR_DMA;
+
+ /* If hi2c->XferCount > MAX_NBYTE_SIZE, use reload mode */
+ if (hi2c->XferCount > MAX_NBYTE_SIZE)
+ {
+ hi2c->XferSize = MAX_NBYTE_SIZE;
+ xfermode = I2C_RELOAD_MODE;
+ }
+ else
+ {
+ hi2c->XferSize = hi2c->XferCount;
+ xfermode = hi2c->XferOptions;
+ }
+
+ /* If transfer direction not change and there is no request to start another frame,
+ do not generate Restart Condition */
+ /* Mean Previous state is same as current state */
+ if ((hi2c->PreviousState == I2C_STATE_MASTER_BUSY_TX) && \
+ (IS_I2C_TRANSFER_OTHER_OPTIONS_REQUEST(XferOptions) == 0))
+ {
+ xferrequest = I2C_NO_STARTSTOP;
+ }
+ else
+ {
+ /* Convert OTHER_xxx XferOptions if any */
+ I2C_ConvertOtherXferOptions(hi2c);
+
+ /* Update xfermode accordingly if no reload is necessary */
+ if (hi2c->XferCount <= MAX_NBYTE_SIZE)
+ {
+ xfermode = hi2c->XferOptions;
+ }
+ }
+
+ if (hi2c->XferSize > 0U)
+ {
+ if (hi2c->hdmatx != NULL)
+ {
+ /* Set the I2C DMA transfer complete callback */
+ hi2c->hdmatx->XferCpltCallback = I2C_DMAMasterTransmitCplt;
+
+ /* Set the DMA error callback */
+ hi2c->hdmatx->XferErrorCallback = I2C_DMAError;
+
+ /* Set the unused DMA callbacks to NULL */
+ hi2c->hdmatx->XferHalfCpltCallback = NULL;
+ hi2c->hdmatx->XferAbortCallback = NULL;
+
+ /* Enable the DMA channel */
+ dmaxferstatus = HAL_DMA_Start_IT(hi2c->hdmatx, (uint32_t)pData, (uint32_t)&hi2c->Instance->TXDR,
+ hi2c->XferSize);
+ }
+ else
+ {
+ /* Update I2C state */
+ hi2c->State = HAL_I2C_STATE_READY;
+ hi2c->Mode = HAL_I2C_MODE_NONE;
+
+ /* Update I2C error code */
+ hi2c->ErrorCode |= HAL_I2C_ERROR_DMA_PARAM;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ return HAL_ERROR;
+ }
+
+ if (dmaxferstatus == HAL_OK)
+ {
+ /* Send Slave Address and set NBYTES to write */
+ I2C_TransferConfig(hi2c, DevAddress, (uint8_t)hi2c->XferSize, xfermode, xferrequest);
+
+ /* Update XferCount value */
+ hi2c->XferCount -= hi2c->XferSize;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ /* Note : The I2C interrupts must be enabled after unlocking current process
+ to avoid the risk of I2C interrupt handle execution before current
+ process unlock */
+ /* Enable ERR and NACK interrupts */
+ I2C_Enable_IRQ(hi2c, I2C_XFER_ERROR_IT);
+
+ /* Enable DMA Request */
+ hi2c->Instance->CR1 |= I2C_CR1_TXDMAEN;
+ }
+ else
+ {
+ /* Update I2C state */
+ hi2c->State = HAL_I2C_STATE_READY;
+ hi2c->Mode = HAL_I2C_MODE_NONE;
+
+ /* Update I2C error code */
+ hi2c->ErrorCode |= HAL_I2C_ERROR_DMA;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ return HAL_ERROR;
+ }
+ }
+ else
+ {
+ /* Update Transfer ISR function pointer */
+ hi2c->XferISR = I2C_Master_ISR_IT;
+
+ /* Send Slave Address */
+ /* Set NBYTES to write and generate START condition */
+ I2C_TransferConfig(hi2c, DevAddress, (uint8_t)hi2c->XferSize, I2C_AUTOEND_MODE,
+ I2C_GENERATE_START_WRITE);
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ /* Note : The I2C interrupts must be enabled after unlocking current process
+ to avoid the risk of I2C interrupt handle execution before current
+ process unlock */
+ /* Enable ERR, TC, STOP, NACK, TXI interrupt */
+ /* possible to enable all of these */
+ /* I2C_IT_ERRI | I2C_IT_TCI | I2C_IT_STOPI | I2C_IT_NACKI |
+ I2C_IT_ADDRI | I2C_IT_RXI | I2C_IT_TXI */
+ I2C_Enable_IRQ(hi2c, I2C_XFER_TX_IT);
+ }
+
+ return HAL_OK;
+ }
+ else
+ {
+ return HAL_BUSY;
+ }
+}
+
+/**
+ * @brief Sequential receive in master I2C mode an amount of data in non-blocking mode with Interrupt
+ * @note This interface allow to manage repeated start condition when a direction change during transfer
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2C.
+ * @param DevAddress Target device address: The device 7 bits address value
+ * in datasheet must be shifted to the left before calling the interface
+ * @param pData Pointer to data buffer
+ * @param Size Amount of data to be sent
+ * @param XferOptions Options of Transfer, value of @ref I2C_XFEROPTIONS
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_I2C_Master_Seq_Receive_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData,
+ uint16_t Size, uint32_t XferOptions)
+{
+ uint32_t xfermode;
+ uint32_t xferrequest = I2C_GENERATE_START_READ;
+
+ /* Check the parameters */
+ assert_param(IS_I2C_TRANSFER_OPTIONS_REQUEST(XferOptions));
+
+ if (hi2c->State == HAL_I2C_STATE_READY)
+ {
+ /* Process Locked */
+ __HAL_LOCK(hi2c);
+
+ hi2c->State = HAL_I2C_STATE_BUSY_RX;
+ hi2c->Mode = HAL_I2C_MODE_MASTER;
+ hi2c->ErrorCode = HAL_I2C_ERROR_NONE;
+
+ /* Prepare transfer parameters */
+ hi2c->pBuffPtr = pData;
+ hi2c->XferCount = Size;
+ hi2c->XferOptions = XferOptions;
+ hi2c->XferISR = I2C_Master_ISR_IT;
+
+ /* If hi2c->XferCount > MAX_NBYTE_SIZE, use reload mode */
+ if (hi2c->XferCount > MAX_NBYTE_SIZE)
+ {
+ hi2c->XferSize = MAX_NBYTE_SIZE;
+ xfermode = I2C_RELOAD_MODE;
+ }
+ else
+ {
+ hi2c->XferSize = hi2c->XferCount;
+ xfermode = hi2c->XferOptions;
+ }
+
+ /* If transfer direction not change and there is no request to start another frame,
+ do not generate Restart Condition */
+ /* Mean Previous state is same as current state */
+ if ((hi2c->PreviousState == I2C_STATE_MASTER_BUSY_RX) && \
+ (IS_I2C_TRANSFER_OTHER_OPTIONS_REQUEST(XferOptions) == 0))
+ {
+ xferrequest = I2C_NO_STARTSTOP;
+ }
+ else
+ {
+ /* Convert OTHER_xxx XferOptions if any */
+ I2C_ConvertOtherXferOptions(hi2c);
+
+ /* Update xfermode accordingly if no reload is necessary */
+ if (hi2c->XferCount <= MAX_NBYTE_SIZE)
+ {
+ xfermode = hi2c->XferOptions;
+ }
+ }
+
+ /* Send Slave Address and set NBYTES to read */
+ I2C_TransferConfig(hi2c, DevAddress, (uint8_t)hi2c->XferSize, xfermode, xferrequest);
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ /* Note : The I2C interrupts must be enabled after unlocking current process
+ to avoid the risk of I2C interrupt handle execution before current
+ process unlock */
+ I2C_Enable_IRQ(hi2c, I2C_XFER_RX_IT);
+
+ return HAL_OK;
+ }
+ else
+ {
+ return HAL_BUSY;
+ }
+}
+
+/**
+ * @brief Sequential receive in master I2C mode an amount of data in non-blocking mode with DMA
+ * @note This interface allow to manage repeated start condition when a direction change during transfer
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2C.
+ * @param DevAddress Target device address: The device 7 bits address value
+ * in datasheet must be shifted to the left before calling the interface
+ * @param pData Pointer to data buffer
+ * @param Size Amount of data to be sent
+ * @param XferOptions Options of Transfer, value of @ref I2C_XFEROPTIONS
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_I2C_Master_Seq_Receive_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData,
+ uint16_t Size, uint32_t XferOptions)
+{
+ uint32_t xfermode;
+ uint32_t xferrequest = I2C_GENERATE_START_READ;
+ HAL_StatusTypeDef dmaxferstatus;
+
+ /* Check the parameters */
+ assert_param(IS_I2C_TRANSFER_OPTIONS_REQUEST(XferOptions));
+
+ if (hi2c->State == HAL_I2C_STATE_READY)
+ {
+ /* Process Locked */
+ __HAL_LOCK(hi2c);
+
+ hi2c->State = HAL_I2C_STATE_BUSY_RX;
+ hi2c->Mode = HAL_I2C_MODE_MASTER;
+ hi2c->ErrorCode = HAL_I2C_ERROR_NONE;
+
+ /* Prepare transfer parameters */
+ hi2c->pBuffPtr = pData;
+ hi2c->XferCount = Size;
+ hi2c->XferOptions = XferOptions;
+ hi2c->XferISR = I2C_Master_ISR_DMA;
+
+ /* If hi2c->XferCount > MAX_NBYTE_SIZE, use reload mode */
+ if (hi2c->XferCount > MAX_NBYTE_SIZE)
+ {
+ hi2c->XferSize = MAX_NBYTE_SIZE;
+ xfermode = I2C_RELOAD_MODE;
+ }
+ else
+ {
+ hi2c->XferSize = hi2c->XferCount;
+ xfermode = hi2c->XferOptions;
+ }
+
+ /* If transfer direction not change and there is no request to start another frame,
+ do not generate Restart Condition */
+ /* Mean Previous state is same as current state */
+ if ((hi2c->PreviousState == I2C_STATE_MASTER_BUSY_RX) && \
+ (IS_I2C_TRANSFER_OTHER_OPTIONS_REQUEST(XferOptions) == 0))
+ {
+ xferrequest = I2C_NO_STARTSTOP;
+ }
+ else
+ {
+ /* Convert OTHER_xxx XferOptions if any */
+ I2C_ConvertOtherXferOptions(hi2c);
+
+ /* Update xfermode accordingly if no reload is necessary */
+ if (hi2c->XferCount <= MAX_NBYTE_SIZE)
+ {
+ xfermode = hi2c->XferOptions;
+ }
+ }
+
+ if (hi2c->XferSize > 0U)
+ {
+ if (hi2c->hdmarx != NULL)
+ {
+ /* Set the I2C DMA transfer complete callback */
+ hi2c->hdmarx->XferCpltCallback = I2C_DMAMasterReceiveCplt;
+
+ /* Set the DMA error callback */
+ hi2c->hdmarx->XferErrorCallback = I2C_DMAError;
+
+ /* Set the unused DMA callbacks to NULL */
+ hi2c->hdmarx->XferHalfCpltCallback = NULL;
+ hi2c->hdmarx->XferAbortCallback = NULL;
+
+ /* Enable the DMA channel */
+ dmaxferstatus = HAL_DMA_Start_IT(hi2c->hdmarx, (uint32_t)&hi2c->Instance->RXDR, (uint32_t)pData,
+ hi2c->XferSize);
+ }
+ else
+ {
+ /* Update I2C state */
+ hi2c->State = HAL_I2C_STATE_READY;
+ hi2c->Mode = HAL_I2C_MODE_NONE;
+
+ /* Update I2C error code */
+ hi2c->ErrorCode |= HAL_I2C_ERROR_DMA_PARAM;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ return HAL_ERROR;
+ }
+
+ if (dmaxferstatus == HAL_OK)
+ {
+ /* Send Slave Address and set NBYTES to read */
+ I2C_TransferConfig(hi2c, DevAddress, (uint8_t)hi2c->XferSize, xfermode, xferrequest);
+
+ /* Update XferCount value */
+ hi2c->XferCount -= hi2c->XferSize;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ /* Note : The I2C interrupts must be enabled after unlocking current process
+ to avoid the risk of I2C interrupt handle execution before current
+ process unlock */
+ /* Enable ERR and NACK interrupts */
+ I2C_Enable_IRQ(hi2c, I2C_XFER_ERROR_IT);
+
+ /* Enable DMA Request */
+ hi2c->Instance->CR1 |= I2C_CR1_RXDMAEN;
+ }
+ else
+ {
+ /* Update I2C state */
+ hi2c->State = HAL_I2C_STATE_READY;
+ hi2c->Mode = HAL_I2C_MODE_NONE;
+
+ /* Update I2C error code */
+ hi2c->ErrorCode |= HAL_I2C_ERROR_DMA;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ return HAL_ERROR;
+ }
+ }
+ else
+ {
+ /* Update Transfer ISR function pointer */
+ hi2c->XferISR = I2C_Master_ISR_IT;
+
+ /* Send Slave Address */
+ /* Set NBYTES to read and generate START condition */
+ I2C_TransferConfig(hi2c, DevAddress, (uint8_t)hi2c->XferSize, I2C_AUTOEND_MODE,
+ I2C_GENERATE_START_READ);
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ /* Note : The I2C interrupts must be enabled after unlocking current process
+ to avoid the risk of I2C interrupt handle execution before current
+ process unlock */
+ /* Enable ERR, TC, STOP, NACK, TXI interrupt */
+ /* possible to enable all of these */
+ /* I2C_IT_ERRI | I2C_IT_TCI | I2C_IT_STOPI | I2C_IT_NACKI |
+ I2C_IT_ADDRI | I2C_IT_RXI | I2C_IT_TXI */
+ I2C_Enable_IRQ(hi2c, I2C_XFER_TX_IT);
+ }
+
+ return HAL_OK;
+ }
+ else
+ {
+ return HAL_BUSY;
+ }
+}
+
+/**
+ * @brief Sequential transmit in slave/device I2C mode an amount of data in non-blocking mode with Interrupt
+ * @note This interface allow to manage repeated start condition when a direction change during transfer
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2C.
+ * @param pData Pointer to data buffer
+ * @param Size Amount of data to be sent
+ * @param XferOptions Options of Transfer, value of @ref I2C_XFEROPTIONS
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_I2C_Slave_Seq_Transmit_IT(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size,
+ uint32_t XferOptions)
+{
+ /* Check the parameters */
+ assert_param(IS_I2C_TRANSFER_OPTIONS_REQUEST(XferOptions));
+
+ if (((uint32_t)hi2c->State & (uint32_t)HAL_I2C_STATE_LISTEN) == (uint32_t)HAL_I2C_STATE_LISTEN)
+ {
+ if ((pData == NULL) || (Size == 0U))
+ {
+ hi2c->ErrorCode = HAL_I2C_ERROR_INVALID_PARAM;
+ return HAL_ERROR;
+ }
+
+ /* Disable Interrupts, to prevent preemption during treatment in case of multicall */
+ I2C_Disable_IRQ(hi2c, I2C_XFER_LISTEN_IT | I2C_XFER_TX_IT);
+
+ /* Process Locked */
+ __HAL_LOCK(hi2c);
+
+ /* I2C cannot manage full duplex exchange so disable previous IT enabled if any */
+ /* and then toggle the HAL slave RX state to TX state */
+ if (hi2c->State == HAL_I2C_STATE_BUSY_RX_LISTEN)
+ {
+ /* Disable associated Interrupts */
+ I2C_Disable_IRQ(hi2c, I2C_XFER_RX_IT);
+
+ /* Abort DMA Xfer if any */
+ if ((hi2c->Instance->CR1 & I2C_CR1_RXDMAEN) == I2C_CR1_RXDMAEN)
+ {
+ hi2c->Instance->CR1 &= ~I2C_CR1_RXDMAEN;
+
+ if (hi2c->hdmarx != NULL)
+ {
+ /* Set the I2C DMA Abort callback :
+ will lead to call HAL_I2C_ErrorCallback() at end of DMA abort procedure */
+ hi2c->hdmarx->XferAbortCallback = I2C_DMAAbort;
+
+ /* Abort DMA RX */
+ if (HAL_DMA_Abort_IT(hi2c->hdmarx) != HAL_OK)
+ {
+ /* Call Directly XferAbortCallback function in case of error */
+ hi2c->hdmarx->XferAbortCallback(hi2c->hdmarx);
+ }
+ }
+ }
+ }
+
+ hi2c->State = HAL_I2C_STATE_BUSY_TX_LISTEN;
+ hi2c->Mode = HAL_I2C_MODE_SLAVE;
+ hi2c->ErrorCode = HAL_I2C_ERROR_NONE;
+
+ /* Enable Address Acknowledge */
+ hi2c->Instance->CR2 &= ~I2C_CR2_NACK;
+
+ /* Prepare transfer parameters */
+ hi2c->pBuffPtr = pData;
+ hi2c->XferCount = Size;
+ hi2c->XferSize = hi2c->XferCount;
+ hi2c->XferOptions = XferOptions;
+ hi2c->XferISR = I2C_Slave_ISR_IT;
+
+ if (I2C_GET_DIR(hi2c) == I2C_DIRECTION_RECEIVE)
+ {
+ /* Clear ADDR flag after prepare the transfer parameters */
+ /* This action will generate an acknowledge to the Master */
+ __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_ADDR);
+ }
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ /* Note : The I2C interrupts must be enabled after unlocking current process
+ to avoid the risk of I2C interrupt handle execution before current
+ process unlock */
+ /* REnable ADDR interrupt */
+ I2C_Enable_IRQ(hi2c, I2C_XFER_TX_IT | I2C_XFER_LISTEN_IT);
+
+ return HAL_OK;
+ }
+ else
+ {
+ return HAL_ERROR;
+ }
+}
+
+/**
+ * @brief Sequential transmit in slave/device I2C mode an amount of data in non-blocking mode with DMA
+ * @note This interface allow to manage repeated start condition when a direction change during transfer
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2C.
+ * @param pData Pointer to data buffer
+ * @param Size Amount of data to be sent
+ * @param XferOptions Options of Transfer, value of @ref I2C_XFEROPTIONS
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_I2C_Slave_Seq_Transmit_DMA(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size,
+ uint32_t XferOptions)
+{
+ HAL_StatusTypeDef dmaxferstatus;
+
+ /* Check the parameters */
+ assert_param(IS_I2C_TRANSFER_OPTIONS_REQUEST(XferOptions));
+
+ if (((uint32_t)hi2c->State & (uint32_t)HAL_I2C_STATE_LISTEN) == (uint32_t)HAL_I2C_STATE_LISTEN)
+ {
+ if ((pData == NULL) || (Size == 0U))
+ {
+ hi2c->ErrorCode = HAL_I2C_ERROR_INVALID_PARAM;
+ return HAL_ERROR;
+ }
+
+ /* Process Locked */
+ __HAL_LOCK(hi2c);
+
+ /* Disable Interrupts, to prevent preemption during treatment in case of multicall */
+ I2C_Disable_IRQ(hi2c, I2C_XFER_LISTEN_IT | I2C_XFER_TX_IT);
+
+ /* I2C cannot manage full duplex exchange so disable previous IT enabled if any */
+ /* and then toggle the HAL slave RX state to TX state */
+ if (hi2c->State == HAL_I2C_STATE_BUSY_RX_LISTEN)
+ {
+ /* Disable associated Interrupts */
+ I2C_Disable_IRQ(hi2c, I2C_XFER_RX_IT);
+
+ if ((hi2c->Instance->CR1 & I2C_CR1_RXDMAEN) == I2C_CR1_RXDMAEN)
+ {
+ /* Abort DMA Xfer if any */
+ if (hi2c->hdmarx != NULL)
+ {
+ hi2c->Instance->CR1 &= ~I2C_CR1_RXDMAEN;
+
+ /* Set the I2C DMA Abort callback :
+ will lead to call HAL_I2C_ErrorCallback() at end of DMA abort procedure */
+ hi2c->hdmarx->XferAbortCallback = I2C_DMAAbort;
+
+ /* Abort DMA RX */
+ if (HAL_DMA_Abort_IT(hi2c->hdmarx) != HAL_OK)
+ {
+ /* Call Directly XferAbortCallback function in case of error */
+ hi2c->hdmarx->XferAbortCallback(hi2c->hdmarx);
+ }
+ }
+ }
+ }
+ else if (hi2c->State == HAL_I2C_STATE_BUSY_TX_LISTEN)
+ {
+ if ((hi2c->Instance->CR1 & I2C_CR1_TXDMAEN) == I2C_CR1_TXDMAEN)
+ {
+ hi2c->Instance->CR1 &= ~I2C_CR1_TXDMAEN;
+
+ /* Abort DMA Xfer if any */
+ if (hi2c->hdmatx != NULL)
+ {
+ /* Set the I2C DMA Abort callback :
+ will lead to call HAL_I2C_ErrorCallback() at end of DMA abort procedure */
+ hi2c->hdmatx->XferAbortCallback = I2C_DMAAbort;
+
+ /* Abort DMA TX */
+ if (HAL_DMA_Abort_IT(hi2c->hdmatx) != HAL_OK)
+ {
+ /* Call Directly XferAbortCallback function in case of error */
+ hi2c->hdmatx->XferAbortCallback(hi2c->hdmatx);
+ }
+ }
+ }
+ }
+ else
+ {
+ /* Nothing to do */
+ }
+
+ hi2c->State = HAL_I2C_STATE_BUSY_TX_LISTEN;
+ hi2c->Mode = HAL_I2C_MODE_SLAVE;
+ hi2c->ErrorCode = HAL_I2C_ERROR_NONE;
+
+ /* Enable Address Acknowledge */
+ hi2c->Instance->CR2 &= ~I2C_CR2_NACK;
+
+ /* Prepare transfer parameters */
+ hi2c->pBuffPtr = pData;
+ hi2c->XferCount = Size;
+ hi2c->XferSize = hi2c->XferCount;
+ hi2c->XferOptions = XferOptions;
+ hi2c->XferISR = I2C_Slave_ISR_DMA;
+
+ if (hi2c->hdmatx != NULL)
+ {
+ /* Set the I2C DMA transfer complete callback */
+ hi2c->hdmatx->XferCpltCallback = I2C_DMASlaveTransmitCplt;
+
+ /* Set the DMA error callback */
+ hi2c->hdmatx->XferErrorCallback = I2C_DMAError;
+
+ /* Set the unused DMA callbacks to NULL */
+ hi2c->hdmatx->XferHalfCpltCallback = NULL;
+ hi2c->hdmatx->XferAbortCallback = NULL;
+
+ /* Enable the DMA channel */
+ dmaxferstatus = HAL_DMA_Start_IT(hi2c->hdmatx, (uint32_t)pData, (uint32_t)&hi2c->Instance->TXDR,
+ hi2c->XferSize);
+ }
+ else
+ {
+ /* Update I2C state */
+ hi2c->State = HAL_I2C_STATE_LISTEN;
+ hi2c->Mode = HAL_I2C_MODE_NONE;
+
+ /* Update I2C error code */
+ hi2c->ErrorCode |= HAL_I2C_ERROR_DMA_PARAM;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ return HAL_ERROR;
+ }
+
+ if (dmaxferstatus == HAL_OK)
+ {
+ /* Update XferCount value */
+ hi2c->XferCount -= hi2c->XferSize;
+
+ /* Reset XferSize */
+ hi2c->XferSize = 0;
+ }
+ else
+ {
+ /* Update I2C state */
+ hi2c->State = HAL_I2C_STATE_LISTEN;
+ hi2c->Mode = HAL_I2C_MODE_NONE;
+
+ /* Update I2C error code */
+ hi2c->ErrorCode |= HAL_I2C_ERROR_DMA;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ return HAL_ERROR;
+ }
+
+ if (I2C_GET_DIR(hi2c) == I2C_DIRECTION_RECEIVE)
+ {
+ /* Clear ADDR flag after prepare the transfer parameters */
+ /* This action will generate an acknowledge to the Master */
+ __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_ADDR);
+ }
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ /* Note : The I2C interrupts must be enabled after unlocking current process
+ to avoid the risk of I2C interrupt handle execution before current
+ process unlock */
+ /* Enable ERR, STOP, NACK, ADDR interrupts */
+ I2C_Enable_IRQ(hi2c, I2C_XFER_LISTEN_IT);
+
+ /* Enable DMA Request */
+ hi2c->Instance->CR1 |= I2C_CR1_TXDMAEN;
+
+ return HAL_OK;
+ }
+ else
+ {
+ return HAL_ERROR;
+ }
+}
+
+/**
+ * @brief Sequential receive in slave/device I2C mode an amount of data in non-blocking mode with Interrupt
+ * @note This interface allow to manage repeated start condition when a direction change during transfer
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2C.
+ * @param pData Pointer to data buffer
+ * @param Size Amount of data to be sent
+ * @param XferOptions Options of Transfer, value of @ref I2C_XFEROPTIONS
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_I2C_Slave_Seq_Receive_IT(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size,
+ uint32_t XferOptions)
+{
+ /* Check the parameters */
+ assert_param(IS_I2C_TRANSFER_OPTIONS_REQUEST(XferOptions));
+
+ if (((uint32_t)hi2c->State & (uint32_t)HAL_I2C_STATE_LISTEN) == (uint32_t)HAL_I2C_STATE_LISTEN)
+ {
+ if ((pData == NULL) || (Size == 0U))
+ {
+ hi2c->ErrorCode = HAL_I2C_ERROR_INVALID_PARAM;
+ return HAL_ERROR;
+ }
+
+ /* Disable Interrupts, to prevent preemption during treatment in case of multicall */
+ I2C_Disable_IRQ(hi2c, I2C_XFER_LISTEN_IT | I2C_XFER_RX_IT);
+
+ /* Process Locked */
+ __HAL_LOCK(hi2c);
+
+ /* I2C cannot manage full duplex exchange so disable previous IT enabled if any */
+ /* and then toggle the HAL slave TX state to RX state */
+ if (hi2c->State == HAL_I2C_STATE_BUSY_TX_LISTEN)
+ {
+ /* Disable associated Interrupts */
+ I2C_Disable_IRQ(hi2c, I2C_XFER_TX_IT);
+
+ if ((hi2c->Instance->CR1 & I2C_CR1_TXDMAEN) == I2C_CR1_TXDMAEN)
+ {
+ hi2c->Instance->CR1 &= ~I2C_CR1_TXDMAEN;
+
+ /* Abort DMA Xfer if any */
+ if (hi2c->hdmatx != NULL)
+ {
+ /* Set the I2C DMA Abort callback :
+ will lead to call HAL_I2C_ErrorCallback() at end of DMA abort procedure */
+ hi2c->hdmatx->XferAbortCallback = I2C_DMAAbort;
+
+ /* Abort DMA TX */
+ if (HAL_DMA_Abort_IT(hi2c->hdmatx) != HAL_OK)
+ {
+ /* Call Directly XferAbortCallback function in case of error */
+ hi2c->hdmatx->XferAbortCallback(hi2c->hdmatx);
+ }
+ }
+ }
+ }
+
+ hi2c->State = HAL_I2C_STATE_BUSY_RX_LISTEN;
+ hi2c->Mode = HAL_I2C_MODE_SLAVE;
+ hi2c->ErrorCode = HAL_I2C_ERROR_NONE;
+
+ /* Enable Address Acknowledge */
+ hi2c->Instance->CR2 &= ~I2C_CR2_NACK;
+
+ /* Prepare transfer parameters */
+ hi2c->pBuffPtr = pData;
+ hi2c->XferCount = Size;
+ hi2c->XferSize = hi2c->XferCount;
+ hi2c->XferOptions = XferOptions;
+ hi2c->XferISR = I2C_Slave_ISR_IT;
+
+ if (I2C_GET_DIR(hi2c) == I2C_DIRECTION_TRANSMIT)
+ {
+ /* Clear ADDR flag after prepare the transfer parameters */
+ /* This action will generate an acknowledge to the Master */
+ __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_ADDR);
+ }
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ /* Note : The I2C interrupts must be enabled after unlocking current process
+ to avoid the risk of I2C interrupt handle execution before current
+ process unlock */
+ /* REnable ADDR interrupt */
+ I2C_Enable_IRQ(hi2c, I2C_XFER_RX_IT | I2C_XFER_LISTEN_IT);
+
+ return HAL_OK;
+ }
+ else
+ {
+ return HAL_ERROR;
+ }
+}
+
+/**
+ * @brief Sequential receive in slave/device I2C mode an amount of data in non-blocking mode with DMA
+ * @note This interface allow to manage repeated start condition when a direction change during transfer
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2C.
+ * @param pData Pointer to data buffer
+ * @param Size Amount of data to be sent
+ * @param XferOptions Options of Transfer, value of @ref I2C_XFEROPTIONS
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_I2C_Slave_Seq_Receive_DMA(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size,
+ uint32_t XferOptions)
+{
+ HAL_StatusTypeDef dmaxferstatus;
+
+ /* Check the parameters */
+ assert_param(IS_I2C_TRANSFER_OPTIONS_REQUEST(XferOptions));
+
+ if (((uint32_t)hi2c->State & (uint32_t)HAL_I2C_STATE_LISTEN) == (uint32_t)HAL_I2C_STATE_LISTEN)
+ {
+ if ((pData == NULL) || (Size == 0U))
+ {
+ hi2c->ErrorCode = HAL_I2C_ERROR_INVALID_PARAM;
+ return HAL_ERROR;
+ }
+
+ /* Disable Interrupts, to prevent preemption during treatment in case of multicall */
+ I2C_Disable_IRQ(hi2c, I2C_XFER_LISTEN_IT | I2C_XFER_RX_IT);
+
+ /* Process Locked */
+ __HAL_LOCK(hi2c);
+
+ /* I2C cannot manage full duplex exchange so disable previous IT enabled if any */
+ /* and then toggle the HAL slave TX state to RX state */
+ if (hi2c->State == HAL_I2C_STATE_BUSY_TX_LISTEN)
+ {
+ /* Disable associated Interrupts */
+ I2C_Disable_IRQ(hi2c, I2C_XFER_TX_IT);
+
+ if ((hi2c->Instance->CR1 & I2C_CR1_TXDMAEN) == I2C_CR1_TXDMAEN)
+ {
+ /* Abort DMA Xfer if any */
+ if (hi2c->hdmatx != NULL)
+ {
+ hi2c->Instance->CR1 &= ~I2C_CR1_TXDMAEN;
+
+ /* Set the I2C DMA Abort callback :
+ will lead to call HAL_I2C_ErrorCallback() at end of DMA abort procedure */
+ hi2c->hdmatx->XferAbortCallback = I2C_DMAAbort;
+
+ /* Abort DMA TX */
+ if (HAL_DMA_Abort_IT(hi2c->hdmatx) != HAL_OK)
+ {
+ /* Call Directly XferAbortCallback function in case of error */
+ hi2c->hdmatx->XferAbortCallback(hi2c->hdmatx);
+ }
+ }
+ }
+ }
+ else if (hi2c->State == HAL_I2C_STATE_BUSY_RX_LISTEN)
+ {
+ if ((hi2c->Instance->CR1 & I2C_CR1_RXDMAEN) == I2C_CR1_RXDMAEN)
+ {
+ hi2c->Instance->CR1 &= ~I2C_CR1_RXDMAEN;
+
+ /* Abort DMA Xfer if any */
+ if (hi2c->hdmarx != NULL)
+ {
+ /* Set the I2C DMA Abort callback :
+ will lead to call HAL_I2C_ErrorCallback() at end of DMA abort procedure */
+ hi2c->hdmarx->XferAbortCallback = I2C_DMAAbort;
+
+ /* Abort DMA RX */
+ if (HAL_DMA_Abort_IT(hi2c->hdmarx) != HAL_OK)
+ {
+ /* Call Directly XferAbortCallback function in case of error */
+ hi2c->hdmarx->XferAbortCallback(hi2c->hdmarx);
+ }
+ }
+ }
+ }
+ else
+ {
+ /* Nothing to do */
+ }
+
+ hi2c->State = HAL_I2C_STATE_BUSY_RX_LISTEN;
+ hi2c->Mode = HAL_I2C_MODE_SLAVE;
+ hi2c->ErrorCode = HAL_I2C_ERROR_NONE;
+
+ /* Enable Address Acknowledge */
+ hi2c->Instance->CR2 &= ~I2C_CR2_NACK;
+
+ /* Prepare transfer parameters */
+ hi2c->pBuffPtr = pData;
+ hi2c->XferCount = Size;
+ hi2c->XferSize = hi2c->XferCount;
+ hi2c->XferOptions = XferOptions;
+ hi2c->XferISR = I2C_Slave_ISR_DMA;
+
+ if (hi2c->hdmarx != NULL)
+ {
+ /* Set the I2C DMA transfer complete callback */
+ hi2c->hdmarx->XferCpltCallback = I2C_DMASlaveReceiveCplt;
+
+ /* Set the DMA error callback */
+ hi2c->hdmarx->XferErrorCallback = I2C_DMAError;
+
+ /* Set the unused DMA callbacks to NULL */
+ hi2c->hdmarx->XferHalfCpltCallback = NULL;
+ hi2c->hdmarx->XferAbortCallback = NULL;
+
+ /* Enable the DMA channel */
+ dmaxferstatus = HAL_DMA_Start_IT(hi2c->hdmarx, (uint32_t)&hi2c->Instance->RXDR,
+ (uint32_t)pData, hi2c->XferSize);
+ }
+ else
+ {
+ /* Update I2C state */
+ hi2c->State = HAL_I2C_STATE_LISTEN;
+ hi2c->Mode = HAL_I2C_MODE_NONE;
+
+ /* Update I2C error code */
+ hi2c->ErrorCode |= HAL_I2C_ERROR_DMA_PARAM;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ return HAL_ERROR;
+ }
+
+ if (dmaxferstatus == HAL_OK)
+ {
+ /* Update XferCount value */
+ hi2c->XferCount -= hi2c->XferSize;
+
+ /* Reset XferSize */
+ hi2c->XferSize = 0;
+ }
+ else
+ {
+ /* Update I2C state */
+ hi2c->State = HAL_I2C_STATE_LISTEN;
+ hi2c->Mode = HAL_I2C_MODE_NONE;
+
+ /* Update I2C error code */
+ hi2c->ErrorCode |= HAL_I2C_ERROR_DMA;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ return HAL_ERROR;
+ }
+
+ if (I2C_GET_DIR(hi2c) == I2C_DIRECTION_TRANSMIT)
+ {
+ /* Clear ADDR flag after prepare the transfer parameters */
+ /* This action will generate an acknowledge to the Master */
+ __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_ADDR);
+ }
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ /* Note : The I2C interrupts must be enabled after unlocking current process
+ to avoid the risk of I2C interrupt handle execution before current
+ process unlock */
+ /* REnable ADDR interrupt */
+ I2C_Enable_IRQ(hi2c, I2C_XFER_RX_IT | I2C_XFER_LISTEN_IT);
+
+ /* Enable DMA Request */
+ hi2c->Instance->CR1 |= I2C_CR1_RXDMAEN;
+
+ return HAL_OK;
+ }
+ else
+ {
+ return HAL_ERROR;
+ }
+}
+
+/**
+ * @brief Enable the Address listen mode with Interrupt.
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2C.
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_I2C_EnableListen_IT(I2C_HandleTypeDef *hi2c)
+{
+ if (hi2c->State == HAL_I2C_STATE_READY)
+ {
+ hi2c->State = HAL_I2C_STATE_LISTEN;
+ hi2c->XferISR = I2C_Slave_ISR_IT;
+
+ /* Enable the Address Match interrupt */
+ I2C_Enable_IRQ(hi2c, I2C_XFER_LISTEN_IT);
+
+ return HAL_OK;
+ }
+ else
+ {
+ return HAL_BUSY;
+ }
+}
+
+/**
+ * @brief Disable the Address listen mode with Interrupt.
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2C
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_I2C_DisableListen_IT(I2C_HandleTypeDef *hi2c)
+{
+ /* Declaration of tmp to prevent undefined behavior of volatile usage */
+ uint32_t tmp;
+
+ /* Disable Address listen mode only if a transfer is not ongoing */
+ if (hi2c->State == HAL_I2C_STATE_LISTEN)
+ {
+ tmp = (uint32_t)(hi2c->State) & I2C_STATE_MSK;
+ hi2c->PreviousState = tmp | (uint32_t)(hi2c->Mode);
+ hi2c->State = HAL_I2C_STATE_READY;
+ hi2c->Mode = HAL_I2C_MODE_NONE;
+ hi2c->XferISR = NULL;
+
+ /* Disable the Address Match interrupt */
+ I2C_Disable_IRQ(hi2c, I2C_XFER_LISTEN_IT);
+
+ return HAL_OK;
+ }
+ else
+ {
+ return HAL_BUSY;
+ }
+}
+
+/**
+ * @brief Abort a master I2C IT or DMA process communication with Interrupt.
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2C.
+ * @param DevAddress Target device address: The device 7 bits address value
+ * in datasheet must be shifted to the left before calling the interface
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_I2C_Master_Abort_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress)
+{
+ if (hi2c->Mode == HAL_I2C_MODE_MASTER)
+ {
+ /* Process Locked */
+ __HAL_LOCK(hi2c);
+
+ /* Disable Interrupts and Store Previous state */
+ if (hi2c->State == HAL_I2C_STATE_BUSY_TX)
+ {
+ I2C_Disable_IRQ(hi2c, I2C_XFER_TX_IT);
+ hi2c->PreviousState = I2C_STATE_MASTER_BUSY_TX;
+ }
+ else if (hi2c->State == HAL_I2C_STATE_BUSY_RX)
+ {
+ I2C_Disable_IRQ(hi2c, I2C_XFER_RX_IT);
+ hi2c->PreviousState = I2C_STATE_MASTER_BUSY_RX;
+ }
+ else
+ {
+ /* Do nothing */
+ }
+
+ /* Set State at HAL_I2C_STATE_ABORT */
+ hi2c->State = HAL_I2C_STATE_ABORT;
+
+ /* Set NBYTES to 1 to generate a dummy read on I2C peripheral */
+ /* Set AUTOEND mode, this will generate a NACK then STOP condition to abort the current transfer */
+ I2C_TransferConfig(hi2c, DevAddress, 1, I2C_AUTOEND_MODE, I2C_GENERATE_STOP);
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ /* Note : The I2C interrupts must be enabled after unlocking current process
+ to avoid the risk of I2C interrupt handle execution before current
+ process unlock */
+ I2C_Enable_IRQ(hi2c, I2C_XFER_CPLT_IT);
+
+ return HAL_OK;
+ }
+ else
+ {
+ /* Wrong usage of abort function */
+ /* This function should be used only in case of abort monitored by master device */
+ return HAL_ERROR;
+ }
+}
+
+/**
+ * @}
+ */
+
+/** @defgroup I2C_IRQ_Handler_and_Callbacks IRQ Handler and Callbacks
+ * @{
+ */
+
+/**
+ * @brief This function handles I2C event interrupt request.
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2C.
+ * @retval None
+ */
+void HAL_I2C_EV_IRQHandler(I2C_HandleTypeDef *hi2c)
+{
+ /* Get current IT Flags and IT sources value */
+ uint32_t itflags = READ_REG(hi2c->Instance->ISR);
+ uint32_t itsources = READ_REG(hi2c->Instance->CR1);
+
+ /* I2C events treatment -------------------------------------*/
+ if (hi2c->XferISR != NULL)
+ {
+ hi2c->XferISR(hi2c, itflags, itsources);
+ }
+}
+
+/**
+ * @brief This function handles I2C error interrupt request.
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2C.
+ * @retval None
+ */
+void HAL_I2C_ER_IRQHandler(I2C_HandleTypeDef *hi2c)
+{
+ uint32_t itflags = READ_REG(hi2c->Instance->ISR);
+ uint32_t itsources = READ_REG(hi2c->Instance->CR1);
+ uint32_t tmperror;
+
+ /* I2C Bus error interrupt occurred ------------------------------------*/
+ if ((I2C_CHECK_FLAG(itflags, I2C_FLAG_BERR) != RESET) && \
+ (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_ERRI) != RESET))
+ {
+ hi2c->ErrorCode |= HAL_I2C_ERROR_BERR;
+
+ /* Clear BERR flag */
+ __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_BERR);
+ }
+
+ /* I2C Over-Run/Under-Run interrupt occurred ----------------------------------------*/
+ if ((I2C_CHECK_FLAG(itflags, I2C_FLAG_OVR) != RESET) && \
+ (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_ERRI) != RESET))
+ {
+ hi2c->ErrorCode |= HAL_I2C_ERROR_OVR;
+
+ /* Clear OVR flag */
+ __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_OVR);
+ }
+
+ /* I2C Arbitration Loss error interrupt occurred -------------------------------------*/
+ if ((I2C_CHECK_FLAG(itflags, I2C_FLAG_ARLO) != RESET) && \
+ (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_ERRI) != RESET))
+ {
+ hi2c->ErrorCode |= HAL_I2C_ERROR_ARLO;
+
+ /* Clear ARLO flag */
+ __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_ARLO);
+ }
+
+ /* Store current volatile hi2c->ErrorCode, misra rule */
+ tmperror = hi2c->ErrorCode;
+
+ /* Call the Error Callback in case of Error detected */
+ if ((tmperror & (HAL_I2C_ERROR_BERR | HAL_I2C_ERROR_OVR | HAL_I2C_ERROR_ARLO)) != HAL_I2C_ERROR_NONE)
+ {
+ I2C_ITError(hi2c, tmperror);
+ }
+}
+
+/**
+ * @brief Master Tx Transfer completed callback.
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2C.
+ * @retval None
+ */
+__weak void HAL_I2C_MasterTxCpltCallback(I2C_HandleTypeDef *hi2c)
+{
+ /* Prevent unused argument(s) compilation warning */
+ UNUSED(hi2c);
+
+ /* NOTE : This function should not be modified, when the callback is needed,
+ the HAL_I2C_MasterTxCpltCallback could be implemented in the user file
+ */
+}
+
+/**
+ * @brief Master Rx Transfer completed callback.
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2C.
+ * @retval None
+ */
+__weak void HAL_I2C_MasterRxCpltCallback(I2C_HandleTypeDef *hi2c)
+{
+ /* Prevent unused argument(s) compilation warning */
+ UNUSED(hi2c);
+
+ /* NOTE : This function should not be modified, when the callback is needed,
+ the HAL_I2C_MasterRxCpltCallback could be implemented in the user file
+ */
+}
+
+/** @brief Slave Tx Transfer completed callback.
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2C.
+ * @retval None
+ */
+__weak void HAL_I2C_SlaveTxCpltCallback(I2C_HandleTypeDef *hi2c)
+{
+ /* Prevent unused argument(s) compilation warning */
+ UNUSED(hi2c);
+
+ /* NOTE : This function should not be modified, when the callback is needed,
+ the HAL_I2C_SlaveTxCpltCallback could be implemented in the user file
+ */
+}
+
+/**
+ * @brief Slave Rx Transfer completed callback.
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2C.
+ * @retval None
+ */
+__weak void HAL_I2C_SlaveRxCpltCallback(I2C_HandleTypeDef *hi2c)
+{
+ /* Prevent unused argument(s) compilation warning */
+ UNUSED(hi2c);
+
+ /* NOTE : This function should not be modified, when the callback is needed,
+ the HAL_I2C_SlaveRxCpltCallback could be implemented in the user file
+ */
+}
+
+/**
+ * @brief Slave Address Match callback.
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2C.
+ * @param TransferDirection Master request Transfer Direction (Write/Read), value of @ref I2C_XFERDIRECTION
+ * @param AddrMatchCode Address Match Code
+ * @retval None
+ */
+__weak void HAL_I2C_AddrCallback(I2C_HandleTypeDef *hi2c, uint8_t TransferDirection, uint16_t AddrMatchCode)
+{
+ /* Prevent unused argument(s) compilation warning */
+ UNUSED(hi2c);
+ UNUSED(TransferDirection);
+ UNUSED(AddrMatchCode);
+
+ /* NOTE : This function should not be modified, when the callback is needed,
+ the HAL_I2C_AddrCallback() could be implemented in the user file
+ */
+}
+
+/**
+ * @brief Listen Complete callback.
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2C.
+ * @retval None
+ */
+__weak void HAL_I2C_ListenCpltCallback(I2C_HandleTypeDef *hi2c)
+{
+ /* Prevent unused argument(s) compilation warning */
+ UNUSED(hi2c);
+
+ /* NOTE : This function should not be modified, when the callback is needed,
+ the HAL_I2C_ListenCpltCallback() could be implemented in the user file
+ */
+}
+
+/**
+ * @brief Memory Tx Transfer completed callback.
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2C.
+ * @retval None
+ */
+__weak void HAL_I2C_MemTxCpltCallback(I2C_HandleTypeDef *hi2c)
+{
+ /* Prevent unused argument(s) compilation warning */
+ UNUSED(hi2c);
+
+ /* NOTE : This function should not be modified, when the callback is needed,
+ the HAL_I2C_MemTxCpltCallback could be implemented in the user file
+ */
+}
+
+/**
+ * @brief Memory Rx Transfer completed callback.
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2C.
+ * @retval None
+ */
+__weak void HAL_I2C_MemRxCpltCallback(I2C_HandleTypeDef *hi2c)
+{
+ /* Prevent unused argument(s) compilation warning */
+ UNUSED(hi2c);
+
+ /* NOTE : This function should not be modified, when the callback is needed,
+ the HAL_I2C_MemRxCpltCallback could be implemented in the user file
+ */
+}
+
+/**
+ * @brief I2C error callback.
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2C.
+ * @retval None
+ */
+__weak void HAL_I2C_ErrorCallback(I2C_HandleTypeDef *hi2c)
+{
+ /* Prevent unused argument(s) compilation warning */
+ UNUSED(hi2c);
+
+ /* NOTE : This function should not be modified, when the callback is needed,
+ the HAL_I2C_ErrorCallback could be implemented in the user file
+ */
+}
+
+/**
+ * @brief I2C abort callback.
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2C.
+ * @retval None
+ */
+__weak void HAL_I2C_AbortCpltCallback(I2C_HandleTypeDef *hi2c)
+{
+ /* Prevent unused argument(s) compilation warning */
+ UNUSED(hi2c);
+
+ /* NOTE : This function should not be modified, when the callback is needed,
+ the HAL_I2C_AbortCpltCallback could be implemented in the user file
+ */
+}
+
+/**
+ * @}
+ */
+
+/** @defgroup I2C_Exported_Functions_Group3 Peripheral State, Mode and Error functions
+ * @brief Peripheral State, Mode and Error functions
+ *
+@verbatim
+ ===============================================================================
+ ##### Peripheral State, Mode and Error functions #####
+ ===============================================================================
+ [..]
+ This subsection permit to get in run-time the status of the peripheral
+ and the data flow.
+
+@endverbatim
+ * @{
+ */
+
+/**
+ * @brief Return the I2C handle state.
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2C.
+ * @retval HAL state
+ */
+HAL_I2C_StateTypeDef HAL_I2C_GetState(I2C_HandleTypeDef *hi2c)
+{
+ /* Return I2C handle state */
+ return hi2c->State;
+}
+
+/**
+ * @brief Returns the I2C Master, Slave, Memory or no mode.
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for I2C module
+ * @retval HAL mode
+ */
+HAL_I2C_ModeTypeDef HAL_I2C_GetMode(I2C_HandleTypeDef *hi2c)
+{
+ return hi2c->Mode;
+}
+
+/**
+ * @brief Return the I2C error code.
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2C.
+ * @retval I2C Error Code
+ */
+uint32_t HAL_I2C_GetError(I2C_HandleTypeDef *hi2c)
+{
+ return hi2c->ErrorCode;
+}
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/** @addtogroup I2C_Private_Functions
+ * @{
+ */
+
+/**
+ * @brief Interrupt Sub-Routine which handle the Interrupt Flags Master Mode with Interrupt.
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2C.
+ * @param ITFlags Interrupt flags to handle.
+ * @param ITSources Interrupt sources enabled.
+ * @retval HAL status
+ */
+static HAL_StatusTypeDef I2C_Master_ISR_IT(struct __I2C_HandleTypeDef *hi2c, uint32_t ITFlags,
+ uint32_t ITSources)
+{
+ uint16_t devaddress;
+ uint32_t tmpITFlags = ITFlags;
+
+ /* Process Locked */
+ __HAL_LOCK(hi2c);
+
+ if ((I2C_CHECK_FLAG(tmpITFlags, I2C_FLAG_AF) != RESET) && \
+ (I2C_CHECK_IT_SOURCE(ITSources, I2C_IT_NACKI) != RESET))
+ {
+ /* Clear NACK Flag */
+ __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_AF);
+
+ /* Set corresponding Error Code */
+ /* No need to generate STOP, it is automatically done */
+ /* Error callback will be send during stop flag treatment */
+ hi2c->ErrorCode |= HAL_I2C_ERROR_AF;
+
+ /* Flush TX register */
+ I2C_Flush_TXDR(hi2c);
+ }
+ else if ((I2C_CHECK_FLAG(tmpITFlags, I2C_FLAG_RXNE) != RESET) && \
+ (I2C_CHECK_IT_SOURCE(ITSources, I2C_IT_RXI) != RESET))
+ {
+ /* Remove RXNE flag on temporary variable as read done */
+ tmpITFlags &= ~I2C_FLAG_RXNE;
+
+ /* Read data from RXDR */
+ *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->RXDR;
+
+ /* Increment Buffer pointer */
+ hi2c->pBuffPtr++;
+
+ hi2c->XferSize--;
+ hi2c->XferCount--;
+ }
+ else if ((I2C_CHECK_FLAG(tmpITFlags, I2C_FLAG_TXIS) != RESET) && \
+ (I2C_CHECK_IT_SOURCE(ITSources, I2C_IT_TXI) != RESET))
+ {
+ /* Write data to TXDR */
+ hi2c->Instance->TXDR = *hi2c->pBuffPtr;
+
+ /* Increment Buffer pointer */
+ hi2c->pBuffPtr++;
+
+ hi2c->XferSize--;
+ hi2c->XferCount--;
+ }
+ else if ((I2C_CHECK_FLAG(tmpITFlags, I2C_FLAG_TCR) != RESET) && \
+ (I2C_CHECK_IT_SOURCE(ITSources, I2C_IT_TCI) != RESET))
+ {
+ if ((hi2c->XferCount != 0U) && (hi2c->XferSize == 0U))
+ {
+ devaddress = (uint16_t)(hi2c->Instance->CR2 & I2C_CR2_SADD);
+
+ if (hi2c->XferCount > MAX_NBYTE_SIZE)
+ {
+ hi2c->XferSize = MAX_NBYTE_SIZE;
+ I2C_TransferConfig(hi2c, devaddress, (uint8_t)hi2c->XferSize, I2C_RELOAD_MODE, I2C_NO_STARTSTOP);
+ }
+ else
+ {
+ hi2c->XferSize = hi2c->XferCount;
+ if (hi2c->XferOptions != I2C_NO_OPTION_FRAME)
+ {
+ I2C_TransferConfig(hi2c, devaddress, (uint8_t)hi2c->XferSize,
+ hi2c->XferOptions, I2C_NO_STARTSTOP);
+ }
+ else
+ {
+ I2C_TransferConfig(hi2c, devaddress, (uint8_t)hi2c->XferSize,
+ I2C_AUTOEND_MODE, I2C_NO_STARTSTOP);
+ }
+ }
+ }
+ else
+ {
+ /* Call TxCpltCallback() if no stop mode is set */
+ if (I2C_GET_STOP_MODE(hi2c) != I2C_AUTOEND_MODE)
+ {
+ /* Call I2C Master Sequential complete process */
+ I2C_ITMasterSeqCplt(hi2c);
+ }
+ else
+ {
+ /* Wrong size Status regarding TCR flag event */
+ /* Call the corresponding callback to inform upper layer of End of Transfer */
+ I2C_ITError(hi2c, HAL_I2C_ERROR_SIZE);
+ }
+ }
+ }
+ else if ((I2C_CHECK_FLAG(tmpITFlags, I2C_FLAG_TC) != RESET) && \
+ (I2C_CHECK_IT_SOURCE(ITSources, I2C_IT_TCI) != RESET))
+ {
+ if (hi2c->XferCount == 0U)
+ {
+ if (I2C_GET_STOP_MODE(hi2c) != I2C_AUTOEND_MODE)
+ {
+ /* Generate a stop condition in case of no transfer option */
+ if (hi2c->XferOptions == I2C_NO_OPTION_FRAME)
+ {
+ /* Generate Stop */
+ hi2c->Instance->CR2 |= I2C_CR2_STOP;
+ }
+ else
+ {
+ /* Call I2C Master Sequential complete process */
+ I2C_ITMasterSeqCplt(hi2c);
+ }
+ }
+ }
+ else
+ {
+ /* Wrong size Status regarding TC flag event */
+ /* Call the corresponding callback to inform upper layer of End of Transfer */
+ I2C_ITError(hi2c, HAL_I2C_ERROR_SIZE);
+ }
+ }
+ else
+ {
+ /* Nothing to do */
+ }
+
+ if ((I2C_CHECK_FLAG(tmpITFlags, I2C_FLAG_STOPF) != RESET) && \
+ (I2C_CHECK_IT_SOURCE(ITSources, I2C_IT_STOPI) != RESET))
+ {
+ /* Call I2C Master complete process */
+ I2C_ITMasterCplt(hi2c, tmpITFlags);
+ }
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ return HAL_OK;
+}
+
+/**
+ * @brief Interrupt Sub-Routine which handle the Interrupt Flags Slave Mode with Interrupt.
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2C.
+ * @param ITFlags Interrupt flags to handle.
+ * @param ITSources Interrupt sources enabled.
+ * @retval HAL status
+ */
+static HAL_StatusTypeDef I2C_Slave_ISR_IT(struct __I2C_HandleTypeDef *hi2c, uint32_t ITFlags,
+ uint32_t ITSources)
+{
+ uint32_t tmpoptions = hi2c->XferOptions;
+ uint32_t tmpITFlags = ITFlags;
+
+ /* Process locked */
+ __HAL_LOCK(hi2c);
+
+ /* Check if STOPF is set */
+ if ((I2C_CHECK_FLAG(tmpITFlags, I2C_FLAG_STOPF) != RESET) && \
+ (I2C_CHECK_IT_SOURCE(ITSources, I2C_IT_STOPI) != RESET))
+ {
+ /* Call I2C Slave complete process */
+ I2C_ITSlaveCplt(hi2c, tmpITFlags);
+ }
+
+ if ((I2C_CHECK_FLAG(tmpITFlags, I2C_FLAG_AF) != RESET) && \
+ (I2C_CHECK_IT_SOURCE(ITSources, I2C_IT_NACKI) != RESET))
+ {
+ /* Check that I2C transfer finished */
+ /* if yes, normal use case, a NACK is sent by the MASTER when Transfer is finished */
+ /* Mean XferCount == 0*/
+ /* So clear Flag NACKF only */
+ if (hi2c->XferCount == 0U)
+ {
+ if ((hi2c->State == HAL_I2C_STATE_LISTEN) && (tmpoptions == I2C_FIRST_AND_LAST_FRAME))
+ /* Same action must be done for (tmpoptions == I2C_LAST_FRAME) which removed for
+ Warning[Pa134]: left and right operands are identical */
+ {
+ /* Call I2C Listen complete process */
+ I2C_ITListenCplt(hi2c, tmpITFlags);
+ }
+ else if ((hi2c->State == HAL_I2C_STATE_BUSY_TX_LISTEN) && (tmpoptions != I2C_NO_OPTION_FRAME))
+ {
+ /* Clear NACK Flag */
+ __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_AF);
+
+ /* Flush TX register */
+ I2C_Flush_TXDR(hi2c);
+
+ /* Last Byte is Transmitted */
+ /* Call I2C Slave Sequential complete process */
+ I2C_ITSlaveSeqCplt(hi2c);
+ }
+ else
+ {
+ /* Clear NACK Flag */
+ __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_AF);
+ }
+ }
+ else
+ {
+ /* if no, error use case, a Non-Acknowledge of last Data is generated by the MASTER*/
+ /* Clear NACK Flag */
+ __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_AF);
+
+ /* Set ErrorCode corresponding to a Non-Acknowledge */
+ hi2c->ErrorCode |= HAL_I2C_ERROR_AF;
+
+ if ((tmpoptions == I2C_FIRST_FRAME) || (tmpoptions == I2C_NEXT_FRAME))
+ {
+ /* Call the corresponding callback to inform upper layer of End of Transfer */
+ I2C_ITError(hi2c, hi2c->ErrorCode);
+ }
+ }
+ }
+ else if ((I2C_CHECK_FLAG(tmpITFlags, I2C_FLAG_RXNE) != RESET) && \
+ (I2C_CHECK_IT_SOURCE(ITSources, I2C_IT_RXI) != RESET))
+ {
+ if (hi2c->XferCount > 0U)
+ {
+ /* Read data from RXDR */
+ *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->RXDR;
+
+ /* Increment Buffer pointer */
+ hi2c->pBuffPtr++;
+
+ hi2c->XferSize--;
+ hi2c->XferCount--;
+ }
+
+ if ((hi2c->XferCount == 0U) && \
+ (tmpoptions != I2C_NO_OPTION_FRAME))
+ {
+ /* Call I2C Slave Sequential complete process */
+ I2C_ITSlaveSeqCplt(hi2c);
+ }
+ }
+ else if ((I2C_CHECK_FLAG(tmpITFlags, I2C_FLAG_ADDR) != RESET) && \
+ (I2C_CHECK_IT_SOURCE(ITSources, I2C_IT_ADDRI) != RESET))
+ {
+ I2C_ITAddrCplt(hi2c, tmpITFlags);
+ }
+ else if ((I2C_CHECK_FLAG(tmpITFlags, I2C_FLAG_TXIS) != RESET) && \
+ (I2C_CHECK_IT_SOURCE(ITSources, I2C_IT_TXI) != RESET))
+ {
+ /* Write data to TXDR only if XferCount not reach "0" */
+ /* A TXIS flag can be set, during STOP treatment */
+ /* Check if all Data have already been sent */
+ /* If it is the case, this last write in TXDR is not sent, correspond to a dummy TXIS event */
+ if (hi2c->XferCount > 0U)
+ {
+ /* Write data to TXDR */
+ hi2c->Instance->TXDR = *hi2c->pBuffPtr;
+
+ /* Increment Buffer pointer */
+ hi2c->pBuffPtr++;
+
+ hi2c->XferCount--;
+ hi2c->XferSize--;
+ }
+ else
+ {
+ if ((tmpoptions == I2C_NEXT_FRAME) || (tmpoptions == I2C_FIRST_FRAME))
+ {
+ /* Last Byte is Transmitted */
+ /* Call I2C Slave Sequential complete process */
+ I2C_ITSlaveSeqCplt(hi2c);
+ }
+ }
+ }
+ else
+ {
+ /* Nothing to do */
+ }
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ return HAL_OK;
+}
+
+/**
+ * @brief Interrupt Sub-Routine which handle the Interrupt Flags Master Mode with DMA.
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2C.
+ * @param ITFlags Interrupt flags to handle.
+ * @param ITSources Interrupt sources enabled.
+ * @retval HAL status
+ */
+static HAL_StatusTypeDef I2C_Master_ISR_DMA(struct __I2C_HandleTypeDef *hi2c, uint32_t ITFlags,
+ uint32_t ITSources)
+{
+ uint16_t devaddress;
+ uint32_t xfermode;
+
+ /* Process Locked */
+ __HAL_LOCK(hi2c);
+
+ if ((I2C_CHECK_FLAG(ITFlags, I2C_FLAG_AF) != RESET) && \
+ (I2C_CHECK_IT_SOURCE(ITSources, I2C_IT_NACKI) != RESET))
+ {
+ /* Clear NACK Flag */
+ __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_AF);
+
+ /* Set corresponding Error Code */
+ hi2c->ErrorCode |= HAL_I2C_ERROR_AF;
+
+ /* No need to generate STOP, it is automatically done */
+ /* But enable STOP interrupt, to treat it */
+ /* Error callback will be send during stop flag treatment */
+ I2C_Enable_IRQ(hi2c, I2C_XFER_CPLT_IT);
+
+ /* Flush TX register */
+ I2C_Flush_TXDR(hi2c);
+ }
+ else if ((I2C_CHECK_FLAG(ITFlags, I2C_FLAG_TCR) != RESET) && \
+ (I2C_CHECK_IT_SOURCE(ITSources, I2C_IT_TCI) != RESET))
+ {
+ /* Disable TC interrupt */
+ __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_TCI);
+
+ if (hi2c->XferCount != 0U)
+ {
+ /* Recover Slave address */
+ devaddress = (uint16_t)(hi2c->Instance->CR2 & I2C_CR2_SADD);
+
+ /* Prepare the new XferSize to transfer */
+ if (hi2c->XferCount > MAX_NBYTE_SIZE)
+ {
+ hi2c->XferSize = MAX_NBYTE_SIZE;
+ xfermode = I2C_RELOAD_MODE;
+ }
+ else
+ {
+ hi2c->XferSize = hi2c->XferCount;
+ if (hi2c->XferOptions != I2C_NO_OPTION_FRAME)
+ {
+ xfermode = hi2c->XferOptions;
+ }
+ else
+ {
+ xfermode = I2C_AUTOEND_MODE;
+ }
+ }
+
+ /* Set the new XferSize in Nbytes register */
+ I2C_TransferConfig(hi2c, devaddress, (uint8_t)hi2c->XferSize, xfermode, I2C_NO_STARTSTOP);
+
+ /* Update XferCount value */
+ hi2c->XferCount -= hi2c->XferSize;
+
+ /* Enable DMA Request */
+ if (hi2c->State == HAL_I2C_STATE_BUSY_RX)
+ {
+ hi2c->Instance->CR1 |= I2C_CR1_RXDMAEN;
+ }
+ else
+ {
+ hi2c->Instance->CR1 |= I2C_CR1_TXDMAEN;
+ }
+ }
+ else
+ {
+ /* Call TxCpltCallback() if no stop mode is set */
+ if (I2C_GET_STOP_MODE(hi2c) != I2C_AUTOEND_MODE)
+ {
+ /* Call I2C Master Sequential complete process */
+ I2C_ITMasterSeqCplt(hi2c);
+ }
+ else
+ {
+ /* Wrong size Status regarding TCR flag event */
+ /* Call the corresponding callback to inform upper layer of End of Transfer */
+ I2C_ITError(hi2c, HAL_I2C_ERROR_SIZE);
+ }
+ }
+ }
+ else if ((I2C_CHECK_FLAG(ITFlags, I2C_FLAG_TC) != RESET) && \
+ (I2C_CHECK_IT_SOURCE(ITSources, I2C_IT_TCI) != RESET))
+ {
+ if (hi2c->XferCount == 0U)
+ {
+ if (I2C_GET_STOP_MODE(hi2c) != I2C_AUTOEND_MODE)
+ {
+ /* Generate a stop condition in case of no transfer option */
+ if (hi2c->XferOptions == I2C_NO_OPTION_FRAME)
+ {
+ /* Generate Stop */
+ hi2c->Instance->CR2 |= I2C_CR2_STOP;
+ }
+ else
+ {
+ /* Call I2C Master Sequential complete process */
+ I2C_ITMasterSeqCplt(hi2c);
+ }
+ }
+ }
+ else
+ {
+ /* Wrong size Status regarding TC flag event */
+ /* Call the corresponding callback to inform upper layer of End of Transfer */
+ I2C_ITError(hi2c, HAL_I2C_ERROR_SIZE);
+ }
+ }
+ else if ((I2C_CHECK_FLAG(ITFlags, I2C_FLAG_STOPF) != RESET) && \
+ (I2C_CHECK_IT_SOURCE(ITSources, I2C_IT_STOPI) != RESET))
+ {
+ /* Call I2C Master complete process */
+ I2C_ITMasterCplt(hi2c, ITFlags);
+ }
+ else
+ {
+ /* Nothing to do */
+ }
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ return HAL_OK;
+}
+
+/**
+ * @brief Interrupt Sub-Routine which handle the Interrupt Flags Slave Mode with DMA.
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2C.
+ * @param ITFlags Interrupt flags to handle.
+ * @param ITSources Interrupt sources enabled.
+ * @retval HAL status
+ */
+static HAL_StatusTypeDef I2C_Slave_ISR_DMA(struct __I2C_HandleTypeDef *hi2c, uint32_t ITFlags,
+ uint32_t ITSources)
+{
+ uint32_t tmpoptions = hi2c->XferOptions;
+ uint32_t treatdmanack = 0U;
+ HAL_I2C_StateTypeDef tmpstate;
+
+ /* Process locked */
+ __HAL_LOCK(hi2c);
+
+ /* Check if STOPF is set */
+ if ((I2C_CHECK_FLAG(ITFlags, I2C_FLAG_STOPF) != RESET) && \
+ (I2C_CHECK_IT_SOURCE(ITSources, I2C_IT_STOPI) != RESET))
+ {
+ /* Call I2C Slave complete process */
+ I2C_ITSlaveCplt(hi2c, ITFlags);
+ }
+
+ if ((I2C_CHECK_FLAG(ITFlags, I2C_FLAG_AF) != RESET) && \
+ (I2C_CHECK_IT_SOURCE(ITSources, I2C_IT_NACKI) != RESET))
+ {
+ /* Check that I2C transfer finished */
+ /* if yes, normal use case, a NACK is sent by the MASTER when Transfer is finished */
+ /* Mean XferCount == 0 */
+ /* So clear Flag NACKF only */
+ if ((I2C_CHECK_IT_SOURCE(ITSources, I2C_CR1_TXDMAEN) != RESET) ||
+ (I2C_CHECK_IT_SOURCE(ITSources, I2C_CR1_RXDMAEN) != RESET))
+ {
+ /* Split check of hdmarx, for MISRA compliance */
+ if (hi2c->hdmarx != NULL)
+ {
+ if (I2C_CHECK_IT_SOURCE(ITSources, I2C_CR1_RXDMAEN) != RESET)
+ {
+ if (__HAL_DMA_GET_COUNTER(hi2c->hdmarx) == 0U)
+ {
+ treatdmanack = 1U;
+ }
+ }
+ }
+
+ /* Split check of hdmatx, for MISRA compliance */
+ if (hi2c->hdmatx != NULL)
+ {
+ if (I2C_CHECK_IT_SOURCE(ITSources, I2C_CR1_TXDMAEN) != RESET)
+ {
+ if (__HAL_DMA_GET_COUNTER(hi2c->hdmatx) == 0U)
+ {
+ treatdmanack = 1U;
+ }
+ }
+ }
+
+ if (treatdmanack == 1U)
+ {
+ if ((hi2c->State == HAL_I2C_STATE_LISTEN) && (tmpoptions == I2C_FIRST_AND_LAST_FRAME))
+ /* Same action must be done for (tmpoptions == I2C_LAST_FRAME) which removed for
+ Warning[Pa134]: left and right operands are identical */
+ {
+ /* Call I2C Listen complete process */
+ I2C_ITListenCplt(hi2c, ITFlags);
+ }
+ else if ((hi2c->State == HAL_I2C_STATE_BUSY_TX_LISTEN) && (tmpoptions != I2C_NO_OPTION_FRAME))
+ {
+ /* Clear NACK Flag */
+ __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_AF);
+
+ /* Flush TX register */
+ I2C_Flush_TXDR(hi2c);
+
+ /* Last Byte is Transmitted */
+ /* Call I2C Slave Sequential complete process */
+ I2C_ITSlaveSeqCplt(hi2c);
+ }
+ else
+ {
+ /* Clear NACK Flag */
+ __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_AF);
+ }
+ }
+ else
+ {
+ /* if no, error use case, a Non-Acknowledge of last Data is generated by the MASTER*/
+ /* Clear NACK Flag */
+ __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_AF);
+
+ /* Set ErrorCode corresponding to a Non-Acknowledge */
+ hi2c->ErrorCode |= HAL_I2C_ERROR_AF;
+
+ /* Store current hi2c->State, solve MISRA2012-Rule-13.5 */
+ tmpstate = hi2c->State;
+
+ if ((tmpoptions == I2C_FIRST_FRAME) || (tmpoptions == I2C_NEXT_FRAME))
+ {
+ if ((tmpstate == HAL_I2C_STATE_BUSY_TX) || (tmpstate == HAL_I2C_STATE_BUSY_TX_LISTEN))
+ {
+ hi2c->PreviousState = I2C_STATE_SLAVE_BUSY_TX;
+ }
+ else if ((tmpstate == HAL_I2C_STATE_BUSY_RX) || (tmpstate == HAL_I2C_STATE_BUSY_RX_LISTEN))
+ {
+ hi2c->PreviousState = I2C_STATE_SLAVE_BUSY_RX;
+ }
+ else
+ {
+ /* Do nothing */
+ }
+
+ /* Call the corresponding callback to inform upper layer of End of Transfer */
+ I2C_ITError(hi2c, hi2c->ErrorCode);
+ }
+ }
+ }
+ else
+ {
+ /* Only Clear NACK Flag, no DMA treatment is pending */
+ __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_AF);
+ }
+ }
+ else if ((I2C_CHECK_FLAG(ITFlags, I2C_FLAG_ADDR) != RESET) && \
+ (I2C_CHECK_IT_SOURCE(ITSources, I2C_IT_ADDRI) != RESET))
+ {
+ I2C_ITAddrCplt(hi2c, ITFlags);
+ }
+ else
+ {
+ /* Nothing to do */
+ }
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ return HAL_OK;
+}
+
+/**
+ * @brief Master sends target device address followed by internal memory address for write request.
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2C.
+ * @param DevAddress Target device address: The device 7 bits address value
+ * in datasheet must be shifted to the left before calling the interface
+ * @param MemAddress Internal memory address
+ * @param MemAddSize Size of internal memory address
+ * @param Timeout Timeout duration
+ * @param Tickstart Tick start value
+ * @retval HAL status
+ */
+static HAL_StatusTypeDef I2C_RequestMemoryWrite(I2C_HandleTypeDef *hi2c, uint16_t DevAddress,
+ uint16_t MemAddress, uint16_t MemAddSize, uint32_t Timeout,
+ uint32_t Tickstart)
+{
+ I2C_TransferConfig(hi2c, DevAddress, (uint8_t)MemAddSize, I2C_RELOAD_MODE, I2C_GENERATE_START_WRITE);
+
+ /* Wait until TXIS flag is set */
+ if (I2C_WaitOnTXISFlagUntilTimeout(hi2c, Timeout, Tickstart) != HAL_OK)
+ {
+ return HAL_ERROR;
+ }
+
+ /* If Memory address size is 8Bit */
+ if (MemAddSize == I2C_MEMADD_SIZE_8BIT)
+ {
+ /* Send Memory Address */
+ hi2c->Instance->TXDR = I2C_MEM_ADD_LSB(MemAddress);
+ }
+ /* If Memory address size is 16Bit */
+ else
+ {
+ /* Send MSB of Memory Address */
+ hi2c->Instance->TXDR = I2C_MEM_ADD_MSB(MemAddress);
+
+ /* Wait until TXIS flag is set */
+ if (I2C_WaitOnTXISFlagUntilTimeout(hi2c, Timeout, Tickstart) != HAL_OK)
+ {
+ return HAL_ERROR;
+ }
+
+ /* Send LSB of Memory Address */
+ hi2c->Instance->TXDR = I2C_MEM_ADD_LSB(MemAddress);
+ }
+
+ /* Wait until TCR flag is set */
+ if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_TCR, RESET, Timeout, Tickstart) != HAL_OK)
+ {
+ return HAL_ERROR;
+ }
+
+ return HAL_OK;
+}
+
+/**
+ * @brief Master sends target device address followed by internal memory address for read request.
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2C.
+ * @param DevAddress Target device address: The device 7 bits address value
+ * in datasheet must be shifted to the left before calling the interface
+ * @param MemAddress Internal memory address
+ * @param MemAddSize Size of internal memory address
+ * @param Timeout Timeout duration
+ * @param Tickstart Tick start value
+ * @retval HAL status
+ */
+static HAL_StatusTypeDef I2C_RequestMemoryRead(I2C_HandleTypeDef *hi2c, uint16_t DevAddress,
+ uint16_t MemAddress, uint16_t MemAddSize, uint32_t Timeout,
+ uint32_t Tickstart)
+{
+ I2C_TransferConfig(hi2c, DevAddress, (uint8_t)MemAddSize, I2C_SOFTEND_MODE, I2C_GENERATE_START_WRITE);
+
+ /* Wait until TXIS flag is set */
+ if (I2C_WaitOnTXISFlagUntilTimeout(hi2c, Timeout, Tickstart) != HAL_OK)
+ {
+ return HAL_ERROR;
+ }
+
+ /* If Memory address size is 8Bit */
+ if (MemAddSize == I2C_MEMADD_SIZE_8BIT)
+ {
+ /* Send Memory Address */
+ hi2c->Instance->TXDR = I2C_MEM_ADD_LSB(MemAddress);
+ }
+ /* If Memory address size is 16Bit */
+ else
+ {
+ /* Send MSB of Memory Address */
+ hi2c->Instance->TXDR = I2C_MEM_ADD_MSB(MemAddress);
+
+ /* Wait until TXIS flag is set */
+ if (I2C_WaitOnTXISFlagUntilTimeout(hi2c, Timeout, Tickstart) != HAL_OK)
+ {
+ return HAL_ERROR;
+ }
+
+ /* Send LSB of Memory Address */
+ hi2c->Instance->TXDR = I2C_MEM_ADD_LSB(MemAddress);
+ }
+
+ /* Wait until TC flag is set */
+ if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_TC, RESET, Timeout, Tickstart) != HAL_OK)
+ {
+ return HAL_ERROR;
+ }
+
+ return HAL_OK;
+}
+
+/**
+ * @brief I2C Address complete process callback.
+ * @param hi2c I2C handle.
+ * @param ITFlags Interrupt flags to handle.
+ * @retval None
+ */
+static void I2C_ITAddrCplt(I2C_HandleTypeDef *hi2c, uint32_t ITFlags)
+{
+ uint8_t transferdirection;
+ uint16_t slaveaddrcode;
+ uint16_t ownadd1code;
+ uint16_t ownadd2code;
+
+ /* Prevent unused argument(s) compilation warning */
+ UNUSED(ITFlags);
+
+ /* In case of Listen state, need to inform upper layer of address match code event */
+ if (((uint32_t)hi2c->State & (uint32_t)HAL_I2C_STATE_LISTEN) == (uint32_t)HAL_I2C_STATE_LISTEN)
+ {
+ transferdirection = I2C_GET_DIR(hi2c);
+ slaveaddrcode = I2C_GET_ADDR_MATCH(hi2c);
+ ownadd1code = I2C_GET_OWN_ADDRESS1(hi2c);
+ ownadd2code = I2C_GET_OWN_ADDRESS2(hi2c);
+
+ /* If 10bits addressing mode is selected */
+ if (hi2c->Init.AddressingMode == I2C_ADDRESSINGMODE_10BIT)
+ {
+ if ((slaveaddrcode & SLAVE_ADDR_MSK) == ((ownadd1code >> SLAVE_ADDR_SHIFT) & SLAVE_ADDR_MSK))
+ {
+ slaveaddrcode = ownadd1code;
+ hi2c->AddrEventCount++;
+ if (hi2c->AddrEventCount == 2U)
+ {
+ /* Reset Address Event counter */
+ hi2c->AddrEventCount = 0U;
+
+ /* Clear ADDR flag */
+ __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_ADDR);
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ /* Call Slave Addr callback */
+#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1)
+ hi2c->AddrCallback(hi2c, transferdirection, slaveaddrcode);
+#else
+ HAL_I2C_AddrCallback(hi2c, transferdirection, slaveaddrcode);
+#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */
+ }
+ }
+ else
+ {
+ slaveaddrcode = ownadd2code;
+
+ /* Disable ADDR Interrupts */
+ I2C_Disable_IRQ(hi2c, I2C_XFER_LISTEN_IT);
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ /* Call Slave Addr callback */
+#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1)
+ hi2c->AddrCallback(hi2c, transferdirection, slaveaddrcode);
+#else
+ HAL_I2C_AddrCallback(hi2c, transferdirection, slaveaddrcode);
+#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */
+ }
+ }
+ /* else 7 bits addressing mode is selected */
+ else
+ {
+ /* Disable ADDR Interrupts */
+ I2C_Disable_IRQ(hi2c, I2C_XFER_LISTEN_IT);
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ /* Call Slave Addr callback */
+#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1)
+ hi2c->AddrCallback(hi2c, transferdirection, slaveaddrcode);
+#else
+ HAL_I2C_AddrCallback(hi2c, transferdirection, slaveaddrcode);
+#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */
+ }
+ }
+ /* Else clear address flag only */
+ else
+ {
+ /* Clear ADDR flag */
+ __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_ADDR);
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+ }
+}
+
+/**
+ * @brief I2C Master sequential complete process.
+ * @param hi2c I2C handle.
+ * @retval None
+ */
+static void I2C_ITMasterSeqCplt(I2C_HandleTypeDef *hi2c)
+{
+ /* Reset I2C handle mode */
+ hi2c->Mode = HAL_I2C_MODE_NONE;
+
+ /* No Generate Stop, to permit restart mode */
+ /* The stop will be done at the end of transfer, when I2C_AUTOEND_MODE enable */
+ if (hi2c->State == HAL_I2C_STATE_BUSY_TX)
+ {
+ hi2c->State = HAL_I2C_STATE_READY;
+ hi2c->PreviousState = I2C_STATE_MASTER_BUSY_TX;
+ hi2c->XferISR = NULL;
+
+ /* Disable Interrupts */
+ I2C_Disable_IRQ(hi2c, I2C_XFER_TX_IT);
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ /* Call the corresponding callback to inform upper layer of End of Transfer */
+#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1)
+ hi2c->MasterTxCpltCallback(hi2c);
+#else
+ HAL_I2C_MasterTxCpltCallback(hi2c);
+#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */
+ }
+ /* hi2c->State == HAL_I2C_STATE_BUSY_RX */
+ else
+ {
+ hi2c->State = HAL_I2C_STATE_READY;
+ hi2c->PreviousState = I2C_STATE_MASTER_BUSY_RX;
+ hi2c->XferISR = NULL;
+
+ /* Disable Interrupts */
+ I2C_Disable_IRQ(hi2c, I2C_XFER_RX_IT);
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ /* Call the corresponding callback to inform upper layer of End of Transfer */
+#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1)
+ hi2c->MasterRxCpltCallback(hi2c);
+#else
+ HAL_I2C_MasterRxCpltCallback(hi2c);
+#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */
+ }
+}
+
+/**
+ * @brief I2C Slave sequential complete process.
+ * @param hi2c I2C handle.
+ * @retval None
+ */
+static void I2C_ITSlaveSeqCplt(I2C_HandleTypeDef *hi2c)
+{
+ uint32_t tmpcr1value = READ_REG(hi2c->Instance->CR1);
+
+ /* Reset I2C handle mode */
+ hi2c->Mode = HAL_I2C_MODE_NONE;
+
+ /* If a DMA is ongoing, Update handle size context */
+ if (I2C_CHECK_IT_SOURCE(tmpcr1value, I2C_CR1_TXDMAEN) != RESET)
+ {
+ /* Disable DMA Request */
+ hi2c->Instance->CR1 &= ~I2C_CR1_TXDMAEN;
+ }
+ else if (I2C_CHECK_IT_SOURCE(tmpcr1value, I2C_CR1_RXDMAEN) != RESET)
+ {
+ /* Disable DMA Request */
+ hi2c->Instance->CR1 &= ~I2C_CR1_RXDMAEN;
+ }
+ else
+ {
+ /* Do nothing */
+ }
+
+ if (hi2c->State == HAL_I2C_STATE_BUSY_TX_LISTEN)
+ {
+ /* Remove HAL_I2C_STATE_SLAVE_BUSY_TX, keep only HAL_I2C_STATE_LISTEN */
+ hi2c->State = HAL_I2C_STATE_LISTEN;
+ hi2c->PreviousState = I2C_STATE_SLAVE_BUSY_TX;
+
+ /* Disable Interrupts */
+ I2C_Disable_IRQ(hi2c, I2C_XFER_TX_IT);
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ /* Call the corresponding callback to inform upper layer of End of Transfer */
+#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1)
+ hi2c->SlaveTxCpltCallback(hi2c);
+#else
+ HAL_I2C_SlaveTxCpltCallback(hi2c);
+#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */
+ }
+
+ else if (hi2c->State == HAL_I2C_STATE_BUSY_RX_LISTEN)
+ {
+ /* Remove HAL_I2C_STATE_SLAVE_BUSY_RX, keep only HAL_I2C_STATE_LISTEN */
+ hi2c->State = HAL_I2C_STATE_LISTEN;
+ hi2c->PreviousState = I2C_STATE_SLAVE_BUSY_RX;
+
+ /* Disable Interrupts */
+ I2C_Disable_IRQ(hi2c, I2C_XFER_RX_IT);
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ /* Call the corresponding callback to inform upper layer of End of Transfer */
+#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1)
+ hi2c->SlaveRxCpltCallback(hi2c);
+#else
+ HAL_I2C_SlaveRxCpltCallback(hi2c);
+#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */
+ }
+ else
+ {
+ /* Nothing to do */
+ }
+}
+
+/**
+ * @brief I2C Master complete process.
+ * @param hi2c I2C handle.
+ * @param ITFlags Interrupt flags to handle.
+ * @retval None
+ */
+static void I2C_ITMasterCplt(I2C_HandleTypeDef *hi2c, uint32_t ITFlags)
+{
+ uint32_t tmperror;
+ uint32_t tmpITFlags = ITFlags;
+ __IO uint32_t tmpreg;
+
+ /* Clear STOP Flag */
+ __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_STOPF);
+
+ /* Disable Interrupts and Store Previous state */
+ if (hi2c->State == HAL_I2C_STATE_BUSY_TX)
+ {
+ I2C_Disable_IRQ(hi2c, I2C_XFER_TX_IT);
+ hi2c->PreviousState = I2C_STATE_MASTER_BUSY_TX;
+ }
+ else if (hi2c->State == HAL_I2C_STATE_BUSY_RX)
+ {
+ I2C_Disable_IRQ(hi2c, I2C_XFER_RX_IT);
+ hi2c->PreviousState = I2C_STATE_MASTER_BUSY_RX;
+ }
+ else
+ {
+ /* Do nothing */
+ }
+
+ /* Clear Configuration Register 2 */
+ I2C_RESET_CR2(hi2c);
+
+ /* Reset handle parameters */
+ hi2c->XferISR = NULL;
+ hi2c->XferOptions = I2C_NO_OPTION_FRAME;
+
+ if (I2C_CHECK_FLAG(tmpITFlags, I2C_FLAG_AF) != RESET)
+ {
+ /* Clear NACK Flag */
+ __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_AF);
+
+ /* Set acknowledge error code */
+ hi2c->ErrorCode |= HAL_I2C_ERROR_AF;
+ }
+
+ /* Fetch Last receive data if any */
+ if ((hi2c->State == HAL_I2C_STATE_ABORT) && (I2C_CHECK_FLAG(tmpITFlags, I2C_FLAG_RXNE) != RESET))
+ {
+ /* Read data from RXDR */
+ tmpreg = (uint8_t)hi2c->Instance->RXDR;
+ UNUSED(tmpreg);
+ }
+
+ /* Flush TX register */
+ I2C_Flush_TXDR(hi2c);
+
+ /* Store current volatile hi2c->ErrorCode, misra rule */
+ tmperror = hi2c->ErrorCode;
+
+ /* Call the corresponding callback to inform upper layer of End of Transfer */
+ if ((hi2c->State == HAL_I2C_STATE_ABORT) || (tmperror != HAL_I2C_ERROR_NONE))
+ {
+ /* Call the corresponding callback to inform upper layer of End of Transfer */
+ I2C_ITError(hi2c, hi2c->ErrorCode);
+ }
+ /* hi2c->State == HAL_I2C_STATE_BUSY_TX */
+ else if (hi2c->State == HAL_I2C_STATE_BUSY_TX)
+ {
+ hi2c->State = HAL_I2C_STATE_READY;
+ hi2c->PreviousState = I2C_STATE_NONE;
+
+ if (hi2c->Mode == HAL_I2C_MODE_MEM)
+ {
+ hi2c->Mode = HAL_I2C_MODE_NONE;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ /* Call the corresponding callback to inform upper layer of End of Transfer */
+#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1)
+ hi2c->MemTxCpltCallback(hi2c);
+#else
+ HAL_I2C_MemTxCpltCallback(hi2c);
+#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */
+ }
+ else
+ {
+ hi2c->Mode = HAL_I2C_MODE_NONE;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ /* Call the corresponding callback to inform upper layer of End of Transfer */
+#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1)
+ hi2c->MasterTxCpltCallback(hi2c);
+#else
+ HAL_I2C_MasterTxCpltCallback(hi2c);
+#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */
+ }
+ }
+ /* hi2c->State == HAL_I2C_STATE_BUSY_RX */
+ else if (hi2c->State == HAL_I2C_STATE_BUSY_RX)
+ {
+ hi2c->State = HAL_I2C_STATE_READY;
+ hi2c->PreviousState = I2C_STATE_NONE;
+
+ if (hi2c->Mode == HAL_I2C_MODE_MEM)
+ {
+ hi2c->Mode = HAL_I2C_MODE_NONE;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ /* Call the corresponding callback to inform upper layer of End of Transfer */
+#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1)
+ hi2c->MemRxCpltCallback(hi2c);
+#else
+ HAL_I2C_MemRxCpltCallback(hi2c);
+#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */
+ }
+ else
+ {
+ hi2c->Mode = HAL_I2C_MODE_NONE;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ /* Call the corresponding callback to inform upper layer of End of Transfer */
+#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1)
+ hi2c->MasterRxCpltCallback(hi2c);
+#else
+ HAL_I2C_MasterRxCpltCallback(hi2c);
+#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */
+ }
+ }
+ else
+ {
+ /* Nothing to do */
+ }
+}
+
+/**
+ * @brief I2C Slave complete process.
+ * @param hi2c I2C handle.
+ * @param ITFlags Interrupt flags to handle.
+ * @retval None
+ */
+static void I2C_ITSlaveCplt(I2C_HandleTypeDef *hi2c, uint32_t ITFlags)
+{
+ uint32_t tmpcr1value = READ_REG(hi2c->Instance->CR1);
+ uint32_t tmpITFlags = ITFlags;
+ HAL_I2C_StateTypeDef tmpstate = hi2c->State;
+
+ /* Clear STOP Flag */
+ __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_STOPF);
+
+ /* Disable Interrupts and Store Previous state */
+ if ((tmpstate == HAL_I2C_STATE_BUSY_TX) || (tmpstate == HAL_I2C_STATE_BUSY_TX_LISTEN))
+ {
+ I2C_Disable_IRQ(hi2c, I2C_XFER_LISTEN_IT | I2C_XFER_TX_IT);
+ hi2c->PreviousState = I2C_STATE_SLAVE_BUSY_TX;
+ }
+ else if ((tmpstate == HAL_I2C_STATE_BUSY_RX) || (tmpstate == HAL_I2C_STATE_BUSY_RX_LISTEN))
+ {
+ I2C_Disable_IRQ(hi2c, I2C_XFER_LISTEN_IT | I2C_XFER_RX_IT);
+ hi2c->PreviousState = I2C_STATE_SLAVE_BUSY_RX;
+ }
+ else
+ {
+ /* Do nothing */
+ }
+
+ /* Disable Address Acknowledge */
+ hi2c->Instance->CR2 |= I2C_CR2_NACK;
+
+ /* Clear Configuration Register 2 */
+ I2C_RESET_CR2(hi2c);
+
+ /* Flush TX register */
+ I2C_Flush_TXDR(hi2c);
+
+ /* If a DMA is ongoing, Update handle size context */
+ if (I2C_CHECK_IT_SOURCE(tmpcr1value, I2C_CR1_TXDMAEN) != RESET)
+ {
+ /* Disable DMA Request */
+ hi2c->Instance->CR1 &= ~I2C_CR1_TXDMAEN;
+
+ if (hi2c->hdmatx != NULL)
+ {
+ hi2c->XferCount = (uint16_t)__HAL_DMA_GET_COUNTER(hi2c->hdmatx);
+ }
+ }
+ else if (I2C_CHECK_IT_SOURCE(tmpcr1value, I2C_CR1_RXDMAEN) != RESET)
+ {
+ /* Disable DMA Request */
+ hi2c->Instance->CR1 &= ~I2C_CR1_RXDMAEN;
+
+ if (hi2c->hdmarx != NULL)
+ {
+ hi2c->XferCount = (uint16_t)__HAL_DMA_GET_COUNTER(hi2c->hdmarx);
+ }
+ }
+ else
+ {
+ /* Do nothing */
+ }
+
+ /* Store Last receive data if any */
+ if (I2C_CHECK_FLAG(tmpITFlags, I2C_FLAG_RXNE) != RESET)
+ {
+ /* Remove RXNE flag on temporary variable as read done */
+ tmpITFlags &= ~I2C_FLAG_RXNE;
+
+ /* Read data from RXDR */
+ *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->RXDR;
+
+ /* Increment Buffer pointer */
+ hi2c->pBuffPtr++;
+
+ if ((hi2c->XferSize > 0U))
+ {
+ hi2c->XferSize--;
+ hi2c->XferCount--;
+ }
+ }
+
+ /* All data are not transferred, so set error code accordingly */
+ if (hi2c->XferCount != 0U)
+ {
+ /* Set ErrorCode corresponding to a Non-Acknowledge */
+ hi2c->ErrorCode |= HAL_I2C_ERROR_AF;
+ }
+
+ hi2c->Mode = HAL_I2C_MODE_NONE;
+ hi2c->XferISR = NULL;
+
+ if (hi2c->ErrorCode != HAL_I2C_ERROR_NONE)
+ {
+ /* Call the corresponding callback to inform upper layer of End of Transfer */
+ I2C_ITError(hi2c, hi2c->ErrorCode);
+
+ /* Call the Listen Complete callback, to inform upper layer of the end of Listen usecase */
+ if (hi2c->State == HAL_I2C_STATE_LISTEN)
+ {
+ /* Call I2C Listen complete process */
+ I2C_ITListenCplt(hi2c, tmpITFlags);
+ }
+ }
+ else if (hi2c->XferOptions != I2C_NO_OPTION_FRAME)
+ {
+ /* Call the Sequential Complete callback, to inform upper layer of the end of Transfer */
+ I2C_ITSlaveSeqCplt(hi2c);
+
+ hi2c->XferOptions = I2C_NO_OPTION_FRAME;
+ hi2c->State = HAL_I2C_STATE_READY;
+ hi2c->PreviousState = I2C_STATE_NONE;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ /* Call the Listen Complete callback, to inform upper layer of the end of Listen usecase */
+#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1)
+ hi2c->ListenCpltCallback(hi2c);
+#else
+ HAL_I2C_ListenCpltCallback(hi2c);
+#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */
+ }
+ /* Call the corresponding callback to inform upper layer of End of Transfer */
+ else if (hi2c->State == HAL_I2C_STATE_BUSY_RX)
+ {
+ hi2c->State = HAL_I2C_STATE_READY;
+ hi2c->PreviousState = I2C_STATE_NONE;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ /* Call the corresponding callback to inform upper layer of End of Transfer */
+#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1)
+ hi2c->SlaveRxCpltCallback(hi2c);
+#else
+ HAL_I2C_SlaveRxCpltCallback(hi2c);
+#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */
+ }
+ else
+ {
+ hi2c->State = HAL_I2C_STATE_READY;
+ hi2c->PreviousState = I2C_STATE_NONE;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ /* Call the corresponding callback to inform upper layer of End of Transfer */
+#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1)
+ hi2c->SlaveTxCpltCallback(hi2c);
+#else
+ HAL_I2C_SlaveTxCpltCallback(hi2c);
+#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */
+ }
+}
+
+/**
+ * @brief I2C Listen complete process.
+ * @param hi2c I2C handle.
+ * @param ITFlags Interrupt flags to handle.
+ * @retval None
+ */
+static void I2C_ITListenCplt(I2C_HandleTypeDef *hi2c, uint32_t ITFlags)
+{
+ /* Reset handle parameters */
+ hi2c->XferOptions = I2C_NO_OPTION_FRAME;
+ hi2c->PreviousState = I2C_STATE_NONE;
+ hi2c->State = HAL_I2C_STATE_READY;
+ hi2c->Mode = HAL_I2C_MODE_NONE;
+ hi2c->XferISR = NULL;
+
+ /* Store Last receive data if any */
+ if (I2C_CHECK_FLAG(ITFlags, I2C_FLAG_RXNE) != RESET)
+ {
+ /* Read data from RXDR */
+ *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->RXDR;
+
+ /* Increment Buffer pointer */
+ hi2c->pBuffPtr++;
+
+ if ((hi2c->XferSize > 0U))
+ {
+ hi2c->XferSize--;
+ hi2c->XferCount--;
+
+ /* Set ErrorCode corresponding to a Non-Acknowledge */
+ hi2c->ErrorCode |= HAL_I2C_ERROR_AF;
+ }
+ }
+
+ /* Disable all Interrupts*/
+ I2C_Disable_IRQ(hi2c, I2C_XFER_LISTEN_IT | I2C_XFER_RX_IT | I2C_XFER_TX_IT);
+
+ /* Clear NACK Flag */
+ __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_AF);
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ /* Call the Listen Complete callback, to inform upper layer of the end of Listen usecase */
+#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1)
+ hi2c->ListenCpltCallback(hi2c);
+#else
+ HAL_I2C_ListenCpltCallback(hi2c);
+#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */
+}
+
+/**
+ * @brief I2C interrupts error process.
+ * @param hi2c I2C handle.
+ * @param ErrorCode Error code to handle.
+ * @retval None
+ */
+static void I2C_ITError(I2C_HandleTypeDef *hi2c, uint32_t ErrorCode)
+{
+ HAL_I2C_StateTypeDef tmpstate = hi2c->State;
+ uint32_t tmppreviousstate;
+
+ /* Reset handle parameters */
+ hi2c->Mode = HAL_I2C_MODE_NONE;
+ hi2c->XferOptions = I2C_NO_OPTION_FRAME;
+ hi2c->XferCount = 0U;
+
+ /* Set new error code */
+ hi2c->ErrorCode |= ErrorCode;
+
+ /* Disable Interrupts */
+ if ((tmpstate == HAL_I2C_STATE_LISTEN) ||
+ (tmpstate == HAL_I2C_STATE_BUSY_TX_LISTEN) ||
+ (tmpstate == HAL_I2C_STATE_BUSY_RX_LISTEN))
+ {
+ /* Disable all interrupts, except interrupts related to LISTEN state */
+ I2C_Disable_IRQ(hi2c, I2C_XFER_RX_IT | I2C_XFER_TX_IT);
+
+ /* keep HAL_I2C_STATE_LISTEN if set */
+ hi2c->State = HAL_I2C_STATE_LISTEN;
+ hi2c->XferISR = I2C_Slave_ISR_IT;
+ }
+ else
+ {
+ /* Disable all interrupts */
+ I2C_Disable_IRQ(hi2c, I2C_XFER_LISTEN_IT | I2C_XFER_RX_IT | I2C_XFER_TX_IT);
+
+ /* If state is an abort treatment on going, don't change state */
+ /* This change will be do later */
+ if (hi2c->State != HAL_I2C_STATE_ABORT)
+ {
+ /* Set HAL_I2C_STATE_READY */
+ hi2c->State = HAL_I2C_STATE_READY;
+ }
+ hi2c->XferISR = NULL;
+ }
+
+ /* Abort DMA TX transfer if any */
+ tmppreviousstate = hi2c->PreviousState;
+ if ((hi2c->hdmatx != NULL) && ((tmppreviousstate == I2C_STATE_MASTER_BUSY_TX) || \
+ (tmppreviousstate == I2C_STATE_SLAVE_BUSY_TX)))
+ {
+ if ((hi2c->Instance->CR1 & I2C_CR1_TXDMAEN) == I2C_CR1_TXDMAEN)
+ {
+ hi2c->Instance->CR1 &= ~I2C_CR1_TXDMAEN;
+ }
+
+ if (HAL_DMA_GetState(hi2c->hdmatx) != HAL_DMA_STATE_READY)
+ {
+ /* Set the I2C DMA Abort callback :
+ will lead to call HAL_I2C_ErrorCallback() at end of DMA abort procedure */
+ hi2c->hdmatx->XferAbortCallback = I2C_DMAAbort;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ /* Abort DMA TX */
+ if (HAL_DMA_Abort_IT(hi2c->hdmatx) != HAL_OK)
+ {
+ /* Call Directly XferAbortCallback function in case of error */
+ hi2c->hdmatx->XferAbortCallback(hi2c->hdmatx);
+ }
+ }
+ else
+ {
+ I2C_TreatErrorCallback(hi2c);
+ }
+ }
+ /* Abort DMA RX transfer if any */
+ else if ((hi2c->hdmarx != NULL) && ((tmppreviousstate == I2C_STATE_MASTER_BUSY_RX) || \
+ (tmppreviousstate == I2C_STATE_SLAVE_BUSY_RX)))
+ {
+ if ((hi2c->Instance->CR1 & I2C_CR1_RXDMAEN) == I2C_CR1_RXDMAEN)
+ {
+ hi2c->Instance->CR1 &= ~I2C_CR1_RXDMAEN;
+ }
+
+ if (HAL_DMA_GetState(hi2c->hdmarx) != HAL_DMA_STATE_READY)
+ {
+ /* Set the I2C DMA Abort callback :
+ will lead to call HAL_I2C_ErrorCallback() at end of DMA abort procedure */
+ hi2c->hdmarx->XferAbortCallback = I2C_DMAAbort;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ /* Abort DMA RX */
+ if (HAL_DMA_Abort_IT(hi2c->hdmarx) != HAL_OK)
+ {
+ /* Call Directly hi2c->hdmarx->XferAbortCallback function in case of error */
+ hi2c->hdmarx->XferAbortCallback(hi2c->hdmarx);
+ }
+ }
+ else
+ {
+ I2C_TreatErrorCallback(hi2c);
+ }
+ }
+ else
+ {
+ I2C_TreatErrorCallback(hi2c);
+ }
+}
+
+/**
+ * @brief I2C Error callback treatment.
+ * @param hi2c I2C handle.
+ * @retval None
+ */
+static void I2C_TreatErrorCallback(I2C_HandleTypeDef *hi2c)
+{
+ if (hi2c->State == HAL_I2C_STATE_ABORT)
+ {
+ hi2c->State = HAL_I2C_STATE_READY;
+ hi2c->PreviousState = I2C_STATE_NONE;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ /* Call the corresponding callback to inform upper layer of End of Transfer */
+#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1)
+ hi2c->AbortCpltCallback(hi2c);
+#else
+ HAL_I2C_AbortCpltCallback(hi2c);
+#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */
+ }
+ else
+ {
+ hi2c->PreviousState = I2C_STATE_NONE;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ /* Call the corresponding callback to inform upper layer of End of Transfer */
+#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1)
+ hi2c->ErrorCallback(hi2c);
+#else
+ HAL_I2C_ErrorCallback(hi2c);
+#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */
+ }
+}
+
+/**
+ * @brief I2C Tx data register flush process.
+ * @param hi2c I2C handle.
+ * @retval None
+ */
+static void I2C_Flush_TXDR(I2C_HandleTypeDef *hi2c)
+{
+ /* If a pending TXIS flag is set */
+ /* Write a dummy data in TXDR to clear it */
+ if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_TXIS) != RESET)
+ {
+ hi2c->Instance->TXDR = 0x00U;
+ }
+
+ /* Flush TX register if not empty */
+ if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_TXE) == RESET)
+ {
+ __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_TXE);
+ }
+}
+
+/**
+ * @brief DMA I2C master transmit process complete callback.
+ * @param hdma DMA handle
+ * @retval None
+ */
+static void I2C_DMAMasterTransmitCplt(DMA_HandleTypeDef *hdma)
+{
+ /* Derogation MISRAC2012-Rule-11.5 */
+ I2C_HandleTypeDef *hi2c = (I2C_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent);
+
+ /* Disable DMA Request */
+ hi2c->Instance->CR1 &= ~I2C_CR1_TXDMAEN;
+
+ /* If last transfer, enable STOP interrupt */
+ if (hi2c->XferCount == 0U)
+ {
+ /* Enable STOP interrupt */
+ I2C_Enable_IRQ(hi2c, I2C_XFER_CPLT_IT);
+ }
+ /* else prepare a new DMA transfer and enable TCReload interrupt */
+ else
+ {
+ /* Update Buffer pointer */
+ hi2c->pBuffPtr += hi2c->XferSize;
+
+ /* Set the XferSize to transfer */
+ if (hi2c->XferCount > MAX_NBYTE_SIZE)
+ {
+ hi2c->XferSize = MAX_NBYTE_SIZE;
+ }
+ else
+ {
+ hi2c->XferSize = hi2c->XferCount;
+ }
+
+ /* Enable the DMA channel */
+ if (HAL_DMA_Start_IT(hi2c->hdmatx, (uint32_t)hi2c->pBuffPtr, (uint32_t)&hi2c->Instance->TXDR,
+ hi2c->XferSize) != HAL_OK)
+ {
+ /* Call the corresponding callback to inform upper layer of End of Transfer */
+ I2C_ITError(hi2c, HAL_I2C_ERROR_DMA);
+ }
+ else
+ {
+ /* Enable TC interrupts */
+ I2C_Enable_IRQ(hi2c, I2C_XFER_RELOAD_IT);
+ }
+ }
+}
+
+/**
+ * @brief DMA I2C slave transmit process complete callback.
+ * @param hdma DMA handle
+ * @retval None
+ */
+static void I2C_DMASlaveTransmitCplt(DMA_HandleTypeDef *hdma)
+{
+ /* Derogation MISRAC2012-Rule-11.5 */
+ I2C_HandleTypeDef *hi2c = (I2C_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent);
+ uint32_t tmpoptions = hi2c->XferOptions;
+
+ if ((tmpoptions == I2C_NEXT_FRAME) || (tmpoptions == I2C_FIRST_FRAME))
+ {
+ /* Disable DMA Request */
+ hi2c->Instance->CR1 &= ~I2C_CR1_TXDMAEN;
+
+ /* Last Byte is Transmitted */
+ /* Call I2C Slave Sequential complete process */
+ I2C_ITSlaveSeqCplt(hi2c);
+ }
+ else
+ {
+ /* No specific action, Master fully manage the generation of STOP condition */
+ /* Mean that this generation can arrive at any time, at the end or during DMA process */
+ /* So STOP condition should be manage through Interrupt treatment */
+ }
+}
+
+/**
+ * @brief DMA I2C master receive process complete callback.
+ * @param hdma DMA handle
+ * @retval None
+ */
+static void I2C_DMAMasterReceiveCplt(DMA_HandleTypeDef *hdma)
+{
+ /* Derogation MISRAC2012-Rule-11.5 */
+ I2C_HandleTypeDef *hi2c = (I2C_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent);
+
+ /* Disable DMA Request */
+ hi2c->Instance->CR1 &= ~I2C_CR1_RXDMAEN;
+
+ /* If last transfer, enable STOP interrupt */
+ if (hi2c->XferCount == 0U)
+ {
+ /* Enable STOP interrupt */
+ I2C_Enable_IRQ(hi2c, I2C_XFER_CPLT_IT);
+ }
+ /* else prepare a new DMA transfer and enable TCReload interrupt */
+ else
+ {
+ /* Update Buffer pointer */
+ hi2c->pBuffPtr += hi2c->XferSize;
+
+ /* Set the XferSize to transfer */
+ if (hi2c->XferCount > MAX_NBYTE_SIZE)
+ {
+ hi2c->XferSize = MAX_NBYTE_SIZE;
+ }
+ else
+ {
+ hi2c->XferSize = hi2c->XferCount;
+ }
+
+ /* Enable the DMA channel */
+ if (HAL_DMA_Start_IT(hi2c->hdmarx, (uint32_t)&hi2c->Instance->RXDR, (uint32_t)hi2c->pBuffPtr,
+ hi2c->XferSize) != HAL_OK)
+ {
+ /* Call the corresponding callback to inform upper layer of End of Transfer */
+ I2C_ITError(hi2c, HAL_I2C_ERROR_DMA);
+ }
+ else
+ {
+ /* Enable TC interrupts */
+ I2C_Enable_IRQ(hi2c, I2C_XFER_RELOAD_IT);
+ }
+ }
+}
+
+/**
+ * @brief DMA I2C slave receive process complete callback.
+ * @param hdma DMA handle
+ * @retval None
+ */
+static void I2C_DMASlaveReceiveCplt(DMA_HandleTypeDef *hdma)
+{
+ /* Derogation MISRAC2012-Rule-11.5 */
+ I2C_HandleTypeDef *hi2c = (I2C_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent);
+ uint32_t tmpoptions = hi2c->XferOptions;
+
+ if ((__HAL_DMA_GET_COUNTER(hi2c->hdmarx) == 0U) && \
+ (tmpoptions != I2C_NO_OPTION_FRAME))
+ {
+ /* Disable DMA Request */
+ hi2c->Instance->CR1 &= ~I2C_CR1_RXDMAEN;
+
+ /* Call I2C Slave Sequential complete process */
+ I2C_ITSlaveSeqCplt(hi2c);
+ }
+ else
+ {
+ /* No specific action, Master fully manage the generation of STOP condition */
+ /* Mean that this generation can arrive at any time, at the end or during DMA process */
+ /* So STOP condition should be manage through Interrupt treatment */
+ }
+}
+
+/**
+ * @brief DMA I2C communication error callback.
+ * @param hdma DMA handle
+ * @retval None
+ */
+static void I2C_DMAError(DMA_HandleTypeDef *hdma)
+{
+ /* Derogation MISRAC2012-Rule-11.5 */
+ I2C_HandleTypeDef *hi2c = (I2C_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent);
+
+ /* Disable Acknowledge */
+ hi2c->Instance->CR2 |= I2C_CR2_NACK;
+
+ /* Call the corresponding callback to inform upper layer of End of Transfer */
+ I2C_ITError(hi2c, HAL_I2C_ERROR_DMA);
+}
+
+/**
+ * @brief DMA I2C communication abort callback
+ * (To be called at end of DMA Abort procedure).
+ * @param hdma DMA handle.
+ * @retval None
+ */
+static void I2C_DMAAbort(DMA_HandleTypeDef *hdma)
+{
+ /* Derogation MISRAC2012-Rule-11.5 */
+ I2C_HandleTypeDef *hi2c = (I2C_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent);
+
+ /* Reset AbortCpltCallback */
+ if (hi2c->hdmatx != NULL)
+ {
+ hi2c->hdmatx->XferAbortCallback = NULL;
+ }
+ if (hi2c->hdmarx != NULL)
+ {
+ hi2c->hdmarx->XferAbortCallback = NULL;
+ }
+
+ I2C_TreatErrorCallback(hi2c);
+}
+
+/**
+ * @brief This function handles I2C Communication Timeout.
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2C.
+ * @param Flag Specifies the I2C flag to check.
+ * @param Status The new Flag status (SET or RESET).
+ * @param Timeout Timeout duration
+ * @param Tickstart Tick start value
+ * @retval HAL status
+ */
+static HAL_StatusTypeDef I2C_WaitOnFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Flag, FlagStatus Status,
+ uint32_t Timeout, uint32_t Tickstart)
+{
+ while (__HAL_I2C_GET_FLAG(hi2c, Flag) == Status)
+ {
+ /* Check for the Timeout */
+ if (Timeout != HAL_MAX_DELAY)
+ {
+ if (((HAL_GetTick() - Tickstart) > Timeout) || (Timeout == 0U))
+ {
+ hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT;
+ hi2c->State = HAL_I2C_STATE_READY;
+ hi2c->Mode = HAL_I2C_MODE_NONE;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+ return HAL_ERROR;
+ }
+ }
+ }
+ return HAL_OK;
+}
+
+/**
+ * @brief This function handles I2C Communication Timeout for specific usage of TXIS flag.
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2C.
+ * @param Timeout Timeout duration
+ * @param Tickstart Tick start value
+ * @retval HAL status
+ */
+static HAL_StatusTypeDef I2C_WaitOnTXISFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Timeout,
+ uint32_t Tickstart)
+{
+ while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_TXIS) == RESET)
+ {
+ /* Check if a NACK is detected */
+ if (I2C_IsAcknowledgeFailed(hi2c, Timeout, Tickstart) != HAL_OK)
+ {
+ return HAL_ERROR;
+ }
+
+ /* Check for the Timeout */
+ if (Timeout != HAL_MAX_DELAY)
+ {
+ if (((HAL_GetTick() - Tickstart) > Timeout) || (Timeout == 0U))
+ {
+ hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT;
+ hi2c->State = HAL_I2C_STATE_READY;
+ hi2c->Mode = HAL_I2C_MODE_NONE;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ return HAL_ERROR;
+ }
+ }
+ }
+ return HAL_OK;
+}
+
+/**
+ * @brief This function handles I2C Communication Timeout for specific usage of STOP flag.
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2C.
+ * @param Timeout Timeout duration
+ * @param Tickstart Tick start value
+ * @retval HAL status
+ */
+static HAL_StatusTypeDef I2C_WaitOnSTOPFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Timeout,
+ uint32_t Tickstart)
+{
+ while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_STOPF) == RESET)
+ {
+ /* Check if a NACK is detected */
+ if (I2C_IsAcknowledgeFailed(hi2c, Timeout, Tickstart) != HAL_OK)
+ {
+ return HAL_ERROR;
+ }
+
+ /* Check for the Timeout */
+ if (((HAL_GetTick() - Tickstart) > Timeout) || (Timeout == 0U))
+ {
+ hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT;
+ hi2c->State = HAL_I2C_STATE_READY;
+ hi2c->Mode = HAL_I2C_MODE_NONE;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ return HAL_ERROR;
+ }
+ }
+ return HAL_OK;
+}
+
+/**
+ * @brief This function handles I2C Communication Timeout for specific usage of RXNE flag.
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2C.
+ * @param Timeout Timeout duration
+ * @param Tickstart Tick start value
+ * @retval HAL status
+ */
+static HAL_StatusTypeDef I2C_WaitOnRXNEFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Timeout,
+ uint32_t Tickstart)
+{
+ while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_RXNE) == RESET)
+ {
+ /* Check if a NACK is detected */
+ if (I2C_IsAcknowledgeFailed(hi2c, Timeout, Tickstart) != HAL_OK)
+ {
+ return HAL_ERROR;
+ }
+
+ /* Check if a STOPF is detected */
+ if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_STOPF) == SET)
+ {
+ /* Check if an RXNE is pending */
+ /* Store Last receive data if any */
+ if ((__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_RXNE) == SET) && (hi2c->XferSize > 0U))
+ {
+ /* Return HAL_OK */
+ /* The Reading of data from RXDR will be done in caller function */
+ return HAL_OK;
+ }
+ else
+ {
+ /* Clear STOP Flag */
+ __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_STOPF);
+
+ /* Clear Configuration Register 2 */
+ I2C_RESET_CR2(hi2c);
+
+ hi2c->ErrorCode = HAL_I2C_ERROR_NONE;
+ hi2c->State = HAL_I2C_STATE_READY;
+ hi2c->Mode = HAL_I2C_MODE_NONE;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ return HAL_ERROR;
+ }
+ }
+
+ /* Check for the Timeout */
+ if (((HAL_GetTick() - Tickstart) > Timeout) || (Timeout == 0U))
+ {
+ hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT;
+ hi2c->State = HAL_I2C_STATE_READY;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ return HAL_ERROR;
+ }
+ }
+ return HAL_OK;
+}
+
+/**
+ * @brief This function handles Acknowledge failed detection during an I2C Communication.
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2C.
+ * @param Timeout Timeout duration
+ * @param Tickstart Tick start value
+ * @retval HAL status
+ */
+static HAL_StatusTypeDef I2C_IsAcknowledgeFailed(I2C_HandleTypeDef *hi2c, uint32_t Timeout, uint32_t Tickstart)
+{
+ if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_AF) == SET)
+ {
+ /* In case of Soft End condition, generate the STOP condition */
+ if (I2C_GET_STOP_MODE(hi2c) != I2C_AUTOEND_MODE)
+ {
+ /* Generate Stop */
+ hi2c->Instance->CR2 |= I2C_CR2_STOP;
+ }
+ /* Wait until STOP Flag is reset */
+ /* AutoEnd should be initiate after AF */
+ while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_STOPF) == RESET)
+ {
+ /* Check for the Timeout */
+ if (Timeout != HAL_MAX_DELAY)
+ {
+ if (((HAL_GetTick() - Tickstart) > Timeout) || (Timeout == 0U))
+ {
+ hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT;
+ hi2c->State = HAL_I2C_STATE_READY;
+ hi2c->Mode = HAL_I2C_MODE_NONE;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ return HAL_ERROR;
+ }
+ }
+ }
+
+ /* Clear NACKF Flag */
+ __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_AF);
+
+ /* Clear STOP Flag */
+ __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_STOPF);
+
+ /* Flush TX register */
+ I2C_Flush_TXDR(hi2c);
+
+ /* Clear Configuration Register 2 */
+ I2C_RESET_CR2(hi2c);
+
+ hi2c->ErrorCode |= HAL_I2C_ERROR_AF;
+ hi2c->State = HAL_I2C_STATE_READY;
+ hi2c->Mode = HAL_I2C_MODE_NONE;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ return HAL_ERROR;
+ }
+ return HAL_OK;
+}
+
+/**
+ * @brief Handles I2Cx communication when starting transfer or during transfer (TC or TCR flag are set).
+ * @param hi2c I2C handle.
+ * @param DevAddress Specifies the slave address to be programmed.
+ * @param Size Specifies the number of bytes to be programmed.
+ * This parameter must be a value between 0 and 255.
+ * @param Mode New state of the I2C START condition generation.
+ * This parameter can be one of the following values:
+ * @arg @ref I2C_RELOAD_MODE Enable Reload mode .
+ * @arg @ref I2C_AUTOEND_MODE Enable Automatic end mode.
+ * @arg @ref I2C_SOFTEND_MODE Enable Software end mode.
+ * @param Request New state of the I2C START condition generation.
+ * This parameter can be one of the following values:
+ * @arg @ref I2C_NO_STARTSTOP Don't Generate stop and start condition.
+ * @arg @ref I2C_GENERATE_STOP Generate stop condition (Size should be set to 0).
+ * @arg @ref I2C_GENERATE_START_READ Generate Restart for read request.
+ * @arg @ref I2C_GENERATE_START_WRITE Generate Restart for write request.
+ * @retval None
+ */
+static void I2C_TransferConfig(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t Size, uint32_t Mode,
+ uint32_t Request)
+{
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_INSTANCE(hi2c->Instance));
+ assert_param(IS_TRANSFER_MODE(Mode));
+ assert_param(IS_TRANSFER_REQUEST(Request));
+
+ /* update CR2 register */
+ MODIFY_REG(hi2c->Instance->CR2,
+ ((I2C_CR2_SADD | I2C_CR2_NBYTES | I2C_CR2_RELOAD | I2C_CR2_AUTOEND | \
+ (I2C_CR2_RD_WRN & (uint32_t)(Request >> (31U - I2C_CR2_RD_WRN_Pos))) | \
+ I2C_CR2_START | I2C_CR2_STOP)), \
+ (uint32_t)(((uint32_t)DevAddress & I2C_CR2_SADD) | \
+ (((uint32_t)Size << I2C_CR2_NBYTES_Pos) & I2C_CR2_NBYTES) | \
+ (uint32_t)Mode | (uint32_t)Request));
+}
+
+/**
+ * @brief Manage the enabling of Interrupts.
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2C.
+ * @param InterruptRequest Value of @ref I2C_Interrupt_configuration_definition.
+ * @retval None
+ */
+static void I2C_Enable_IRQ(I2C_HandleTypeDef *hi2c, uint16_t InterruptRequest)
+{
+ uint32_t tmpisr = 0U;
+
+ if ((hi2c->XferISR == I2C_Master_ISR_DMA) || \
+ (hi2c->XferISR == I2C_Slave_ISR_DMA))
+ {
+ if ((InterruptRequest & I2C_XFER_LISTEN_IT) == I2C_XFER_LISTEN_IT)
+ {
+ /* Enable ERR, STOP, NACK and ADDR interrupts */
+ tmpisr |= I2C_IT_ADDRI | I2C_IT_STOPI | I2C_IT_NACKI | I2C_IT_ERRI;
+ }
+
+ if (InterruptRequest == I2C_XFER_ERROR_IT)
+ {
+ /* Enable ERR and NACK interrupts */
+ tmpisr |= I2C_IT_ERRI | I2C_IT_NACKI;
+ }
+
+ if (InterruptRequest == I2C_XFER_CPLT_IT)
+ {
+ /* Enable STOP interrupts */
+ tmpisr |= (I2C_IT_STOPI | I2C_IT_TCI);
+ }
+
+ if (InterruptRequest == I2C_XFER_RELOAD_IT)
+ {
+ /* Enable TC interrupts */
+ tmpisr |= I2C_IT_TCI;
+ }
+ }
+ else
+ {
+ if ((InterruptRequest & I2C_XFER_LISTEN_IT) == I2C_XFER_LISTEN_IT)
+ {
+ /* Enable ERR, STOP, NACK, and ADDR interrupts */
+ tmpisr |= I2C_IT_ADDRI | I2C_IT_STOPI | I2C_IT_NACKI | I2C_IT_ERRI;
+ }
+
+ if ((InterruptRequest & I2C_XFER_TX_IT) == I2C_XFER_TX_IT)
+ {
+ /* Enable ERR, TC, STOP, NACK and RXI interrupts */
+ tmpisr |= I2C_IT_ERRI | I2C_IT_TCI | I2C_IT_STOPI | I2C_IT_NACKI | I2C_IT_TXI;
+ }
+
+ if ((InterruptRequest & I2C_XFER_RX_IT) == I2C_XFER_RX_IT)
+ {
+ /* Enable ERR, TC, STOP, NACK and TXI interrupts */
+ tmpisr |= I2C_IT_ERRI | I2C_IT_TCI | I2C_IT_STOPI | I2C_IT_NACKI | I2C_IT_RXI;
+ }
+
+ if (InterruptRequest == I2C_XFER_CPLT_IT)
+ {
+ /* Enable STOP interrupts */
+ tmpisr |= I2C_IT_STOPI;
+ }
+ }
+
+ /* Enable interrupts only at the end */
+ /* to avoid the risk of I2C interrupt handle execution before */
+ /* all interrupts requested done */
+ __HAL_I2C_ENABLE_IT(hi2c, tmpisr);
+}
+
+/**
+ * @brief Manage the disabling of Interrupts.
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2C.
+ * @param InterruptRequest Value of @ref I2C_Interrupt_configuration_definition.
+ * @retval None
+ */
+static void I2C_Disable_IRQ(I2C_HandleTypeDef *hi2c, uint16_t InterruptRequest)
+{
+ uint32_t tmpisr = 0U;
+
+ if ((InterruptRequest & I2C_XFER_TX_IT) == I2C_XFER_TX_IT)
+ {
+ /* Disable TC and TXI interrupts */
+ tmpisr |= I2C_IT_TCI | I2C_IT_TXI;
+
+ if (((uint32_t)hi2c->State & (uint32_t)HAL_I2C_STATE_LISTEN) != (uint32_t)HAL_I2C_STATE_LISTEN)
+ {
+ /* Disable NACK and STOP interrupts */
+ tmpisr |= I2C_IT_STOPI | I2C_IT_NACKI | I2C_IT_ERRI;
+ }
+ }
+
+ if ((InterruptRequest & I2C_XFER_RX_IT) == I2C_XFER_RX_IT)
+ {
+ /* Disable TC and RXI interrupts */
+ tmpisr |= I2C_IT_TCI | I2C_IT_RXI;
+
+ if (((uint32_t)hi2c->State & (uint32_t)HAL_I2C_STATE_LISTEN) != (uint32_t)HAL_I2C_STATE_LISTEN)
+ {
+ /* Disable NACK and STOP interrupts */
+ tmpisr |= I2C_IT_STOPI | I2C_IT_NACKI | I2C_IT_ERRI;
+ }
+ }
+
+ if ((InterruptRequest & I2C_XFER_LISTEN_IT) == I2C_XFER_LISTEN_IT)
+ {
+ /* Disable ADDR, NACK and STOP interrupts */
+ tmpisr |= I2C_IT_ADDRI | I2C_IT_STOPI | I2C_IT_NACKI | I2C_IT_ERRI;
+ }
+
+ if (InterruptRequest == I2C_XFER_ERROR_IT)
+ {
+ /* Enable ERR and NACK interrupts */
+ tmpisr |= I2C_IT_ERRI | I2C_IT_NACKI;
+ }
+
+ if (InterruptRequest == I2C_XFER_CPLT_IT)
+ {
+ /* Enable STOP interrupts */
+ tmpisr |= I2C_IT_STOPI;
+ }
+
+ if (InterruptRequest == I2C_XFER_RELOAD_IT)
+ {
+ /* Enable TC interrupts */
+ tmpisr |= I2C_IT_TCI;
+ }
+
+ /* Disable interrupts only at the end */
+ /* to avoid a breaking situation like at "t" time */
+ /* all disable interrupts request are not done */
+ __HAL_I2C_DISABLE_IT(hi2c, tmpisr);
+}
+
+/**
+ * @brief Convert I2Cx OTHER_xxx XferOptions to functional XferOptions.
+ * @param hi2c I2C handle.
+ * @retval None
+ */
+static void I2C_ConvertOtherXferOptions(I2C_HandleTypeDef *hi2c)
+{
+ /* if user set XferOptions to I2C_OTHER_FRAME */
+ /* it request implicitly to generate a restart condition */
+ /* set XferOptions to I2C_FIRST_FRAME */
+ if (hi2c->XferOptions == I2C_OTHER_FRAME)
+ {
+ hi2c->XferOptions = I2C_FIRST_FRAME;
+ }
+ /* else if user set XferOptions to I2C_OTHER_AND_LAST_FRAME */
+ /* it request implicitly to generate a restart condition */
+ /* then generate a stop condition at the end of transfer */
+ /* set XferOptions to I2C_FIRST_AND_LAST_FRAME */
+ else if (hi2c->XferOptions == I2C_OTHER_AND_LAST_FRAME)
+ {
+ hi2c->XferOptions = I2C_FIRST_AND_LAST_FRAME;
+ }
+ else
+ {
+ /* Nothing to do */
+ }
+}
+
+/**
+ * @}
+ */
+
+#endif /* HAL_I2C_MODULE_ENABLED */
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_i2c_ex.c b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_i2c_ex.c
new file mode 100644
index 0000000..9000409
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_i2c_ex.c
@@ -0,0 +1,365 @@
+/**
+ ******************************************************************************
+ * @file stm32f0xx_hal_i2c_ex.c
+ * @author MCD Application Team
+ * @brief I2C Extended HAL module driver.
+ * This file provides firmware functions to manage the following
+ * functionalities of I2C Extended peripheral:
+ * + Filter Mode Functions
+ * + WakeUp Mode Functions
+ * + FastModePlus Functions
+ *
+ @verbatim
+ ==============================================================================
+ ##### I2C peripheral Extended features #####
+ ==============================================================================
+
+ [..] Comparing to other previous devices, the I2C interface for STM32F0xx
+ devices contains the following additional features
+
+ (+) Possibility to disable or enable Analog Noise Filter
+ (+) Use of a configured Digital Noise Filter
+ (+) Disable or enable wakeup from Stop mode(s)
+ (+) Disable or enable Fast Mode Plus
+
+ ##### How to use this driver #####
+ ==============================================================================
+ [..] This driver provides functions to configure Noise Filter and Wake Up Feature
+ (#) Configure I2C Analog noise filter using the function HAL_I2CEx_ConfigAnalogFilter()
+ (#) Configure I2C Digital noise filter using the function HAL_I2CEx_ConfigDigitalFilter()
+ (#) Configure the enable or disable of I2C Wake Up Mode using the functions :
+ (++) HAL_I2CEx_EnableWakeUp()
+ (++) HAL_I2CEx_DisableWakeUp()
+ (#) Configure the enable or disable of fast mode plus driving capability using the functions :
+ (++) HAL_I2CEx_EnableFastModePlus()
+ (++) HAL_I2CEx_DisableFastModePlus()
+ @endverbatim
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2016 STMicroelectronics.
+ * All rights reserved.
+ *
+ * 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 "stm32f0xx_hal.h"
+
+/** @addtogroup STM32F0xx_HAL_Driver
+ * @{
+ */
+
+/** @defgroup I2CEx I2CEx
+ * @brief I2C Extended HAL module driver
+ * @{
+ */
+
+#ifdef HAL_I2C_MODULE_ENABLED
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/** @defgroup I2CEx_Exported_Functions I2C Extended Exported Functions
+ * @{
+ */
+
+/** @defgroup I2CEx_Exported_Functions_Group1 Filter Mode Functions
+ * @brief Filter Mode Functions
+ *
+@verbatim
+ ===============================================================================
+ ##### Filter Mode Functions #####
+ ===============================================================================
+ [..] This section provides functions allowing to:
+ (+) Configure Noise Filters
+
+@endverbatim
+ * @{
+ */
+
+/**
+ * @brief Configure I2C Analog noise filter.
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2Cx peripheral.
+ * @param AnalogFilter New state of the Analog filter.
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_I2CEx_ConfigAnalogFilter(I2C_HandleTypeDef *hi2c, uint32_t AnalogFilter)
+{
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_INSTANCE(hi2c->Instance));
+ assert_param(IS_I2C_ANALOG_FILTER(AnalogFilter));
+
+ if (hi2c->State == HAL_I2C_STATE_READY)
+ {
+ /* Process Locked */
+ __HAL_LOCK(hi2c);
+
+ hi2c->State = HAL_I2C_STATE_BUSY;
+
+ /* Disable the selected I2C peripheral */
+ __HAL_I2C_DISABLE(hi2c);
+
+ /* Reset I2Cx ANOFF bit */
+ hi2c->Instance->CR1 &= ~(I2C_CR1_ANFOFF);
+
+ /* Set analog filter bit*/
+ hi2c->Instance->CR1 |= AnalogFilter;
+
+ __HAL_I2C_ENABLE(hi2c);
+
+ hi2c->State = HAL_I2C_STATE_READY;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ return HAL_OK;
+ }
+ else
+ {
+ return HAL_BUSY;
+ }
+}
+
+/**
+ * @brief Configure I2C Digital noise filter.
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2Cx peripheral.
+ * @param DigitalFilter Coefficient of digital noise filter between Min_Data=0x00 and Max_Data=0x0F.
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_I2CEx_ConfigDigitalFilter(I2C_HandleTypeDef *hi2c, uint32_t DigitalFilter)
+{
+ uint32_t tmpreg;
+
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_INSTANCE(hi2c->Instance));
+ assert_param(IS_I2C_DIGITAL_FILTER(DigitalFilter));
+
+ if (hi2c->State == HAL_I2C_STATE_READY)
+ {
+ /* Process Locked */
+ __HAL_LOCK(hi2c);
+
+ hi2c->State = HAL_I2C_STATE_BUSY;
+
+ /* Disable the selected I2C peripheral */
+ __HAL_I2C_DISABLE(hi2c);
+
+ /* Get the old register value */
+ tmpreg = hi2c->Instance->CR1;
+
+ /* Reset I2Cx DNF bits [11:8] */
+ tmpreg &= ~(I2C_CR1_DNF);
+
+ /* Set I2Cx DNF coefficient */
+ tmpreg |= DigitalFilter << 8U;
+
+ /* Store the new register value */
+ hi2c->Instance->CR1 = tmpreg;
+
+ __HAL_I2C_ENABLE(hi2c);
+
+ hi2c->State = HAL_I2C_STATE_READY;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ return HAL_OK;
+ }
+ else
+ {
+ return HAL_BUSY;
+ }
+}
+/**
+ * @}
+ */
+#if defined(I2C_CR1_WUPEN)
+
+/** @defgroup I2CEx_Exported_Functions_Group2 WakeUp Mode Functions
+ * @brief WakeUp Mode Functions
+ *
+@verbatim
+ ===============================================================================
+ ##### WakeUp Mode Functions #####
+ ===============================================================================
+ [..] This section provides functions allowing to:
+ (+) Configure Wake Up Feature
+
+@endverbatim
+ * @{
+ */
+
+/**
+ * @brief Enable I2C wakeup from Stop mode(s).
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2Cx peripheral.
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_I2CEx_EnableWakeUp(I2C_HandleTypeDef *hi2c)
+{
+ /* Check the parameters */
+ assert_param(IS_I2C_WAKEUP_FROMSTOP_INSTANCE(hi2c->Instance));
+
+ if (hi2c->State == HAL_I2C_STATE_READY)
+ {
+ /* Process Locked */
+ __HAL_LOCK(hi2c);
+
+ hi2c->State = HAL_I2C_STATE_BUSY;
+
+ /* Disable the selected I2C peripheral */
+ __HAL_I2C_DISABLE(hi2c);
+
+ /* Enable wakeup from stop mode */
+ hi2c->Instance->CR1 |= I2C_CR1_WUPEN;
+
+ __HAL_I2C_ENABLE(hi2c);
+
+ hi2c->State = HAL_I2C_STATE_READY;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ return HAL_OK;
+ }
+ else
+ {
+ return HAL_BUSY;
+ }
+}
+
+/**
+ * @brief Disable I2C wakeup from Stop mode(s).
+ * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
+ * the configuration information for the specified I2Cx peripheral.
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_I2CEx_DisableWakeUp(I2C_HandleTypeDef *hi2c)
+{
+ /* Check the parameters */
+ assert_param(IS_I2C_WAKEUP_FROMSTOP_INSTANCE(hi2c->Instance));
+
+ if (hi2c->State == HAL_I2C_STATE_READY)
+ {
+ /* Process Locked */
+ __HAL_LOCK(hi2c);
+
+ hi2c->State = HAL_I2C_STATE_BUSY;
+
+ /* Disable the selected I2C peripheral */
+ __HAL_I2C_DISABLE(hi2c);
+
+ /* Enable wakeup from stop mode */
+ hi2c->Instance->CR1 &= ~(I2C_CR1_WUPEN);
+
+ __HAL_I2C_ENABLE(hi2c);
+
+ hi2c->State = HAL_I2C_STATE_READY;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hi2c);
+
+ return HAL_OK;
+ }
+ else
+ {
+ return HAL_BUSY;
+ }
+}
+/**
+ * @}
+ */
+#endif /* I2C_CR1_WUPEN */
+
+/** @defgroup I2CEx_Exported_Functions_Group3 Fast Mode Plus Functions
+ * @brief Fast Mode Plus Functions
+ *
+@verbatim
+ ===============================================================================
+ ##### Fast Mode Plus Functions #####
+ ===============================================================================
+ [..] This section provides functions allowing to:
+ (+) Configure Fast Mode Plus
+
+@endverbatim
+ * @{
+ */
+
+/**
+ * @brief Enable the I2C fast mode plus driving capability.
+ * @param ConfigFastModePlus Selects the pin.
+ * This parameter can be one of the @ref I2CEx_FastModePlus values
+ * @note For I2C1, fast mode plus driving capability can be enabled on all selected
+ * I2C1 pins using I2C_FASTMODEPLUS_I2C1 parameter or independently
+ * on each one of the following pins PB6, PB7, PB8 and PB9.
+ * @note For remaining I2C1 pins (PA14, PA15...) fast mode plus driving capability
+ * can be enabled only by using I2C_FASTMODEPLUS_I2C1 parameter.
+ * @note For all I2C2 pins fast mode plus driving capability can be enabled
+ * only by using I2C_FASTMODEPLUS_I2C2 parameter.
+ * @retval None
+ */
+void HAL_I2CEx_EnableFastModePlus(uint32_t ConfigFastModePlus)
+{
+ /* Check the parameter */
+ assert_param(IS_I2C_FASTMODEPLUS(ConfigFastModePlus));
+
+ /* Enable SYSCFG clock */
+ __HAL_RCC_SYSCFG_CLK_ENABLE();
+
+ /* Enable fast mode plus driving capability for selected pin */
+ SET_BIT(SYSCFG->CFGR1, (uint32_t)ConfigFastModePlus);
+}
+
+/**
+ * @brief Disable the I2C fast mode plus driving capability.
+ * @param ConfigFastModePlus Selects the pin.
+ * This parameter can be one of the @ref I2CEx_FastModePlus values
+ * @note For I2C1, fast mode plus driving capability can be disabled on all selected
+ * I2C1 pins using I2C_FASTMODEPLUS_I2C1 parameter or independently
+ * on each one of the following pins PB6, PB7, PB8 and PB9.
+ * @note For remaining I2C1 pins (PA14, PA15...) fast mode plus driving capability
+ * can be disabled only by using I2C_FASTMODEPLUS_I2C1 parameter.
+ * @note For all I2C2 pins fast mode plus driving capability can be disabled
+ * only by using I2C_FASTMODEPLUS_I2C2 parameter.
+ * @retval None
+ */
+void HAL_I2CEx_DisableFastModePlus(uint32_t ConfigFastModePlus)
+{
+ /* Check the parameter */
+ assert_param(IS_I2C_FASTMODEPLUS(ConfigFastModePlus));
+
+ /* Enable SYSCFG clock */
+ __HAL_RCC_SYSCFG_CLK_ENABLE();
+
+ /* Disable fast mode plus driving capability for selected pin */
+ CLEAR_BIT(SYSCFG->CFGR1, (uint32_t)ConfigFastModePlus);
+}
+/**
+ * @}
+ */
+/**
+ * @}
+ */
+
+#endif /* HAL_I2C_MODULE_ENABLED */
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_pwr.c b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_pwr.c
new file mode 100644
index 0000000..435b265
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_pwr.c
@@ -0,0 +1,454 @@
+/**
+ ******************************************************************************
+ * @file stm32f0xx_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 function
+ * + Peripheral Control function
+ *
+ @verbatim
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2016 STMicroelectronics.
+ * All rights reserved.
+ *
+ * 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 "stm32f0xx_hal.h"
+
+/** @addtogroup STM32F0xx_HAL_Driver
+ * @{
+ */
+
+/** @defgroup PWR PWR
+ * @brief PWR HAL module driver
+ * @{
+ */
+
+#ifdef HAL_PWR_MODULE_ENABLED
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/** @defgroup PWR_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.
+ * @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 when present).
+ * @note If the HSE divided by 32 is used as the RTC clock, the
+ * Backup Domain Access should be kept enabled.
+ * @retval None
+ */
+void HAL_PWR_EnableBkUpAccess(void)
+{
+ PWR->CR |= (uint32_t)PWR_CR_DBP;
+}
+
+/**
+ * @brief Disables access to the backup domain (RTC registers, RTC
+ * backup data registers when present).
+ * @note If the HSE divided by 32 is used as the RTC clock, the
+ * Backup Domain Access should be kept enabled.
+ * @retval None
+ */
+void HAL_PWR_DisableBkUpAccess(void)
+{
+ PWR->CR &= ~((uint32_t)PWR_CR_DBP);
+}
+
+/**
+ * @}
+ */
+
+/** @defgroup PWR_Exported_Functions_Group2 Peripheral Control functions
+ * @brief Low Power modes configuration functions
+ *
+@verbatim
+
+ ===============================================================================
+ ##### Peripheral Control functions #####
+ ===============================================================================
+
+ *** WakeUp pin configuration ***
+ ================================
+ [..]
+ (+) WakeUp pin is used to wakeup the system from Standby mode. This pin is
+ forced in input pull down configuration and is active on rising edges.
+ (+) There are two WakeUp pins, and up to eight Wakeup pins on STM32F07x & STM32F09x devices.
+ (++)WakeUp Pin 1 on PA.00.
+ (++)WakeUp Pin 2 on PC.13.
+ (++)WakeUp Pin 3 on PE.06.(STM32F07x/STM32F09x)
+ (++)WakeUp Pin 4 on PA.02.(STM32F07x/STM32F09x)
+ (++)WakeUp Pin 5 on PC.05.(STM32F07x/STM32F09x)
+ (++)WakeUp Pin 6 on PB.05.(STM32F07x/STM32F09x)
+ (++)WakeUp Pin 7 on PB.15.(STM32F07x/STM32F09x)
+ (++)WakeUp Pin 8 on PF.02.(STM32F07x/STM32F09x)
+
+ *** Low Power modes configuration ***
+ =====================================
+ [..]
+ The devices feature 3 low-power modes:
+ (+) Sleep mode: Cortex-M0 core stopped, peripherals kept running.
+ (+) Stop mode: all clocks are stopped, regulator running, regulator
+ in low power mode
+ (+) Standby mode: 1.2V domain powered off (mode not available on STM32F0x8 devices).
+
+ *** 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.
+
+ *** Stop mode ***
+ =================
+ [..]
+ In Stop mode, all clocks in the 1.8V domain are stopped, the PLL, the HSI,
+ and the HSE RC oscillators are disabled. Internal SRAM and register contents
+ are preserved.
+ The voltage regulator can be configured either in normal or low-power mode.
+ To minimize the consumption.
+
+ (+) Entry:
+ The Stop mode is entered using the HAL_PWR_EnterSTOPMode(PWR_MAINREGULATOR_ON, PWR_STOPENTRY_WFI )
+ function with:
+ (++) Main regulator ON.
+ (++) Low Power regulator ON.
+ (++) PWR_STOPENTRY_WFI: enter STOP mode with WFI instruction
+ (++) PWR_STOPENTRY_WFE: enter STOP mode with WFE instruction
+ (+) Exit:
+ (++) Any EXTI Line (Internal or External) configured in Interrupt/Event mode.
+ (++) Some specific communication peripherals (CEC, USART, I2C) interrupts,
+ when programmed in wakeup mode (the peripheral must be
+ programmed in wakeup mode and the corresponding interrupt vector
+ must be enabled in the NVIC)
+
+ *** Standby mode ***
+ ====================
+ [..]
+ The Standby mode allows to achieve the lowest power consumption. It is based
+ on the Cortex-M0 deep sleep mode, with the voltage regulator disabled.
+ The 1.8V domain is consequently powered off. The PLL, 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.
+ The voltage regulator is OFF.
+
+ (+) Entry:
+ (++) The Standby mode is entered using the HAL_PWR_EnterSTANDBYMode() function.
+ (+) Exit:
+ (++) WKUP pin rising edge, RTC alarm (Alarm A), 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 and Standby modes
+
+ (++) To wake up from the Stop mode with an RTC alarm event, it is necessary to
+ configure the RTC to generate the RTC alarm using the HAL_RTC_SetAlarm_IT() function.
+
+ (++) To wake up from the Stop mode with an RTC Tamper or time stamp event, it
+ is necessary to configure the RTC to detect the tamper or time stamp event using the
+ HAL_RTC_SetTimeStamp_IT() or HAL_RTC_SetTamper_IT() functions.
+
+ (++) To wake up from the Stop mode with an RTC WakeUp event, it is necessary to
+ configure the RTC to generate the RTC WakeUp event using the HAL_RTC_SetWakeUpTimer_IT() function.
+
+ (+) Comparator auto-wakeup (AWU) from the Stop mode
+
+ (++) To wake up from the Stop mode with a comparator wakeup event, it is necessary to:
+ (+++) Configure the EXTI Line associated with the comparator (example EXTI Line 22 for comparator 2)
+ to be sensitive to to the selected edges (falling, rising or falling
+ and rising) (Interrupt or Event modes) using the EXTI_Init() function.
+ (+++) Configure the comparator to generate the event.
+@endverbatim
+ * @{
+ */
+
+/**
+ * @brief Enables the WakeUp PINx functionality.
+ * @param WakeUpPinx Specifies the Power Wake-Up pin to enable.
+ * This parameter can be value of :
+ * @ref PWREx_WakeUp_Pins
+ * @retval None
+ */
+void HAL_PWR_EnableWakeUpPin(uint32_t WakeUpPinx)
+{
+ /* Check the parameters */
+ assert_param(IS_PWR_WAKEUP_PIN(WakeUpPinx));
+ /* Enable the EWUPx pin */
+ SET_BIT(PWR->CSR, WakeUpPinx);
+}
+
+/**
+ * @brief Disables the WakeUp PINx functionality.
+ * @param WakeUpPinx Specifies the Power Wake-Up pin to disable.
+ * This parameter can be values of :
+ * @ref PWREx_WakeUp_Pins
+ * @retval None
+ */
+void HAL_PWR_DisableWakeUpPin(uint32_t WakeUpPinx)
+{
+ /* Check the parameters */
+ assert_param(IS_PWR_WAKEUP_PIN(WakeUpPinx));
+ /* Disable the EWUPx pin */
+ CLEAR_BIT(PWR->CSR, WakeUpPinx);
+}
+
+/**
+ * @brief Enters Sleep mode.
+ * @note In Sleep mode, all I/O pins keep the same state as in Run mode.
+ * @param Regulator Specifies the regulator state in SLEEP mode.
+ * On STM32F0 devices, this parameter is a dummy value and it is ignored
+ * as regulator can't be modified in this mode. Parameter is kept for platform
+ * compatibility.
+ * @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));
+
+ /* Clear SLEEPDEEP bit of Cortex System Control Register */
+ SCB->SCR &= (uint32_t)~((uint32_t)SCB_SCR_SLEEPDEEP_Msk);
+
+ /* Select SLEEP mode entry -------------------------------------------------*/
+ if(SLEEPEntry == PWR_SLEEPENTRY_WFI)
+ {
+ /* Request Wait For Interrupt */
+ __WFI();
+ }
+ else
+ {
+ /* Request Wait For Event */
+ __SEV();
+ __WFE();
+ __WFE();
+ }
+}
+
+/**
+ * @brief Enters STOP mode.
+ * @note In Stop mode, all I/O pins keep the same state as in Run mode.
+ * @note When exiting Stop mode by issuing an interrupt or a wakeup event,
+ * the HSI RC oscillator is selected as system clock.
+ * @note When the voltage regulator operates in low power mode, an additional
+ * startup delay is incurred when waking up from Stop mode.
+ * By keeping the internal regulator ON during Stop mode, the consumption
+ * is higher although the startup time is reduced.
+ * @param Regulator Specifies the regulator state in STOP mode.
+ * This parameter can be one of the following values:
+ * @arg PWR_MAINREGULATOR_ON: STOP mode with regulator ON
+ * @arg PWR_LOWPOWERREGULATOR_ON: STOP mode with low power regulator ON
+ * @param STOPEntry specifies if STOP mode in entered with WFI or WFE instruction.
+ * This parameter can be one of the following values:
+ * @arg PWR_STOPENTRY_WFI:Enter STOP mode with WFI instruction
+ * @arg PWR_STOPENTRY_WFE: Enter STOP mode with WFE instruction
+ * @retval None
+ */
+void HAL_PWR_EnterSTOPMode(uint32_t Regulator, uint8_t STOPEntry)
+{
+ uint32_t tmpreg = 0;
+
+ /* Check the parameters */
+ assert_param(IS_PWR_REGULATOR(Regulator));
+ assert_param(IS_PWR_STOP_ENTRY(STOPEntry));
+
+ /* Select the regulator state in STOP mode ---------------------------------*/
+ tmpreg = PWR->CR;
+
+ /* Clear PDDS and LPDS bits */
+ tmpreg &= (uint32_t)~(PWR_CR_PDDS | PWR_CR_LPDS);
+
+ /* Set LPDS bit according to Regulator value */
+ tmpreg |= Regulator;
+
+ /* Store the new value */
+ PWR->CR = tmpreg;
+
+ /* Set SLEEPDEEP bit of Cortex System Control Register */
+ SCB->SCR |= SCB_SCR_SLEEPDEEP_Msk;
+
+ /* Select STOP mode entry --------------------------------------------------*/
+ if(STOPEntry == PWR_STOPENTRY_WFI)
+ {
+ /* Request Wait For Interrupt */
+ __WFI();
+ }
+ else
+ {
+ /* Request Wait For Event */
+ __SEV();
+ __WFE();
+ __WFE();
+ }
+
+ /* Reset SLEEPDEEP bit of Cortex System Control Register */
+ SCB->SCR &= (uint32_t)~((uint32_t)SCB_SCR_SLEEPDEEP_Msk);
+}
+
+/**
+ * @brief Enters STANDBY mode.
+ * @note In Standby mode, all I/O pins are high impedance except for:
+ * - Reset pad (still available)
+ * - RTC alternate function pins if configured for tamper, time-stamp, RTC
+ * Alarm out, or RTC clock calibration out.
+ * - WKUP pins if enabled.
+ * STM32F0x8 devices, the Stop mode is available, but it is
+ * aningless to distinguish between voltage regulator in Low power
+ * mode and voltage regulator in Run mode because the regulator
+ * not used and the core is supplied directly from an external source.
+ * Consequently, the Standby mode is not available on those devices.
+ * @retval None
+ */
+void HAL_PWR_EnterSTANDBYMode(void)
+{
+ /* Select STANDBY mode */
+ PWR->CR |= (uint32_t)PWR_CR_PDDS;
+
+ /* Set SLEEPDEEP bit of Cortex System Control Register */
+ SCB->SCR |= SCB_SCR_SLEEPDEEP_Msk;
+
+ /* This option is used to ensure that store operations are completed */
+#if defined ( __CC_ARM)
+ __force_stores();
+#endif
+ /* Request Wait For Interrupt */
+ __WFI();
+}
+
+/**
+ * @brief 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 M4 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 M4 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));
+}
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+#endif /* HAL_PWR_MODULE_ENABLED */
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_pwr_ex.c b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_pwr_ex.c
new file mode 100644
index 0000000..c9b16dc
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_pwr_ex.c
@@ -0,0 +1,274 @@
+/**
+ ******************************************************************************
+ * @file stm32f0xx_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
+ *
+ * © Copyright (c) 2016 STMicroelectronics.
+ * All rights reserved.
+ *
+ * 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 "stm32f0xx_hal.h"
+
+/** @addtogroup STM32F0xx_HAL_Driver
+ * @{
+ */
+
+/** @defgroup PWREx PWREx
+ * @brief PWREx HAL module driver
+ * @{
+ */
+
+#ifdef HAL_PWR_MODULE_ENABLED
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/** @defgroup PWREx_Private_Constants PWREx Private Constants
+ * @{
+ */
+#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 -----------------------------------------------*/
+/* Exported functions ---------------------------------------------------------*/
+
+/** @defgroup PWREx_Exported_Functions PWREx Exported Functions
+ * @{
+ */
+
+/** @defgroup PWREx_Exported_Functions_Group1 Peripheral Extended Control Functions
+ * @brief Extended Peripheral Control functions
+ *
+@verbatim
+
+ ===============================================================================
+ ##### Peripheral extended 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).
+ (+) 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_ConfigPVD(), HAL_PWR_EnablePVD() functions.
+ (+) The PVD is stopped in Standby mode.
+ -@- PVD is not available on STM32F030x4/x6/x8
+
+ *** VDDIO2 Monitor Configuration ***
+ ====================================
+ [..]
+ (+) VDDIO2 monitor is used to monitor the VDDIO2 power supply by comparing it
+ to VREFInt Voltage
+ (+) This monitor is internally connected to the EXTI line31
+ and can generate an interrupt if enabled. This is done through
+ HAL_PWREx_EnableVddio2Monitor() function.
+ -@- VDDIO2 is available on STM32F07x/09x/04x
+
+@endverbatim
+ * @{
+ */
+
+#if defined (STM32F031x6) || defined (STM32F051x8) || \
+ defined (STM32F071xB) || defined (STM32F091xC) || \
+ defined (STM32F042x6) || defined (STM32F072xB)
+/**
+ * @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_EDGE();__HAL_PWR_PVD_EXTI_DISABLE_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)
+{
+ PWR->CR |= (uint32_t)PWR_CR_PVDE;
+}
+
+/**
+ * @brief Disables the Power Voltage Detector(PVD).
+ * @retval None
+ */
+void HAL_PWR_DisablePVD(void)
+{
+ PWR->CR &= ~((uint32_t)PWR_CR_PVDE);
+}
+
+/**
+ * @brief This function handles the PWR PVD interrupt request.
+ * @note This API should be called under the PVD_IRQHandler() or PVD_VDDIO2_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 /* defined (STM32F031x6) || defined (STM32F051x8) || */
+ /* defined (STM32F071xB) || defined (STM32F091xC) || */
+ /* defined (STM32F042x6) || defined (STM32F072xB) */
+
+#if defined (STM32F042x6) || defined (STM32F048xx) || \
+ defined (STM32F071xB) || defined (STM32F072xB) || defined (STM32F078xx) || \
+ defined (STM32F091xC) || defined (STM32F098xx)
+/**
+ * @brief Enable VDDIO2 monitor: enable Exti 31 and falling edge detection.
+ * @note If Exti 31 is enable correlty and VDDIO2 voltage goes below Vrefint,
+ an interrupt is generated Irq line 1.
+ NVIS has to be enable by user.
+ * @retval None
+ */
+void HAL_PWREx_EnableVddio2Monitor(void)
+{
+ __HAL_PWR_VDDIO2_EXTI_ENABLE_IT();
+ __HAL_PWR_VDDIO2_EXTI_ENABLE_FALLING_EDGE();
+}
+
+/**
+ * @brief Disable the Vddio2 Monitor.
+ * @retval None
+ */
+void HAL_PWREx_DisableVddio2Monitor(void)
+{
+ __HAL_PWR_VDDIO2_EXTI_DISABLE_IT();
+ __HAL_PWR_VDDIO2_EXTI_DISABLE_FALLING_EDGE();
+
+}
+
+/**
+ * @brief This function handles the PWR Vddio2 monitor interrupt request.
+ * @note This API should be called under the VDDIO2_IRQHandler() PVD_VDDIO2_IRQHandler().
+ * @retval None
+ */
+void HAL_PWREx_Vddio2Monitor_IRQHandler(void)
+{
+ /* Check PWR exti flag */
+ if(__HAL_PWR_VDDIO2_EXTI_GET_FLAG() != RESET)
+ {
+ /* PWR Vddio2 monitor interrupt user callback */
+ HAL_PWREx_Vddio2MonitorCallback();
+
+ /* Clear PWR Exti pending bit */
+ __HAL_PWR_VDDIO2_EXTI_CLEAR_FLAG();
+ }
+}
+
+/**
+ * @brief PWR Vddio2 Monitor interrupt callback
+ * @retval None
+ */
+__weak void HAL_PWREx_Vddio2MonitorCallback(void)
+{
+ /* NOTE : This function Should not be modified, when the callback is needed,
+ the HAL_PWREx_Vddio2MonitorCallback could be implemented in the user file
+ */
+}
+
+#endif /* defined (STM32F042x6) || defined (STM32F048xx) || \
+ defined (STM32F071xB) || defined (STM32F072xB) || defined (STM32F078xx) || \
+ defined (STM32F091xC) || defined (STM32F098xx) */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+#endif /* HAL_PWR_MODULE_ENABLED */
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_rcc.c b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_rcc.c
new file mode 100644
index 0000000..f5e477e
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_rcc.c
@@ -0,0 +1,1365 @@
+/**
+ ******************************************************************************
+ * @file stm32f0xx_hal_rcc.c
+ * @author MCD Application Team
+ * @brief RCC HAL module driver.
+ * This file provides firmware functions to manage the following
+ * functionalities of the Reset and Clock Control (RCC) peripheral:
+ * + Initialization and de-initialization functions
+ * + Peripheral Control functions
+ *
+ @verbatim
+ ==============================================================================
+ ##### RCC specific features #####
+ ==============================================================================
+ [..]
+ After reset the device is running from Internal High Speed oscillator
+ (HSI 8MHz) with Flash 0 wait state, Flash prefetch buffer is disabled,
+ and all peripherals are off except internal SRAM, Flash and JTAG.
+ (+) There is no prescaler on High speed (AHB) and Low speed (APB) buses;
+ all peripherals mapped on these buses are running at HSI speed.
+ (+) The clock for all peripherals is switched off, except the SRAM and FLASH.
+ (+) All GPIOs are in input floating state, except the JTAG pins which
+ are assigned to be used for debug purpose.
+ [..] Once the device started from reset, the user application has to:
+ (+) Configure the clock source to be used to drive the System clock
+ (if the application needs higher frequency/performance)
+ (+) Configure the System clock frequency and Flash settings
+ (+) Configure the AHB and APB buses prescalers
+ (+) Enable the clock for the peripheral(s) to be used
+ (+) Configure the clock source(s) for peripherals whose clocks are not
+ derived from the System clock (RTC, ADC, I2C, USART, TIM, USB FS, etc..)
+
+ ##### RCC Limitations #####
+ ==============================================================================
+ [..]
+ A delay between an RCC peripheral clock enable and the effective peripheral
+ enabling should be taken into account in order to manage the peripheral read/write
+ from/to registers.
+ (+) This delay depends on the peripheral mapping.
+ (++) AHB & APB peripherals, 1 dummy read is necessary
+
+ [..]
+ Workarounds:
+ (#) For AHB & APB peripherals, a dummy read to the peripheral register has been
+ inserted in each __HAL_RCC_PPP_CLK_ENABLE() macro.
+
+ @endverbatim
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2016 STMicroelectronics.
+ * All rights reserved.
+ *
+ * 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 "stm32f0xx_hal.h"
+
+/** @addtogroup STM32F0xx_HAL_Driver
+ * @{
+ */
+
+/** @defgroup RCC RCC
+* @brief RCC HAL module driver
+ * @{
+ */
+
+#ifdef HAL_RCC_MODULE_ENABLED
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/** @defgroup RCC_Private_Constants RCC Private Constants
+ * @{
+ */
+/**
+ * @}
+ */
+/* Private macro -------------------------------------------------------------*/
+/** @defgroup RCC_Private_Macros RCC Private Macros
+ * @{
+ */
+
+#define MCO1_CLK_ENABLE() __HAL_RCC_GPIOA_CLK_ENABLE()
+#define MCO1_GPIO_PORT GPIOA
+#define MCO1_PIN GPIO_PIN_8
+
+/**
+ * @}
+ */
+
+/* Private variables ---------------------------------------------------------*/
+/** @defgroup RCC_Private_Variables RCC Private Variables
+ * @{
+ */
+/**
+ * @}
+ */
+
+/* Private function prototypes -----------------------------------------------*/
+/* Exported functions ---------------------------------------------------------*/
+
+/** @defgroup RCC_Exported_Functions RCC Exported Functions
+ * @{
+ */
+
+/** @defgroup RCC_Exported_Functions_Group1 Initialization and de-initialization functions
+ * @brief Initialization and Configuration functions
+ *
+ @verbatim
+ ===============================================================================
+ ##### Initialization and de-initialization functions #####
+ ===============================================================================
+ [..]
+ This section provides functions allowing to configure the internal/external oscillators
+ (HSE, HSI, HSI14, HSI48, LSE, LSI, PLL, CSS and MCO) and the System buses clocks (SYSCLK,
+ AHB and APB1).
+
+ [..] Internal/external clock and PLL configuration
+ (#) HSI (high-speed internal), 8 MHz factory-trimmed RC used directly or through
+ the PLL as System clock source.
+ The HSI clock can be used also to clock the USART and I2C peripherals.
+
+ (#) HSI14 (high-speed internal), 14 MHz factory-trimmed RC used directly to clock
+ the ADC peripheral.
+
+ (#) LSI (low-speed internal), ~40 KHz low consumption RC used as IWDG and/or RTC
+ clock source.
+
+ (#) HSE (high-speed external), 4 to 32 MHz crystal oscillator used directly or
+ through the PLL as System clock source. Can be used also as RTC clock source.
+
+ (#) LSE (low-speed external), 32 KHz oscillator used as RTC clock source.
+
+ (#) PLL (clocked by HSI, HSI48 or HSE), featuring different output clocks:
+ (++) The first output is used to generate the high speed system clock (up to 48 MHz)
+ (++) The second output is used to generate the clock for the USB FS (48 MHz)
+ (++) The third output may be used to generate the clock for the TIM, I2C and USART
+ peripherals (up to 48 MHz)
+
+ (#) CSS (Clock security system), once enable using the macro __HAL_RCC_CSS_ENABLE()
+ and if a HSE clock failure occurs(HSE used directly or through PLL as System
+ clock source), the System clocks automatically switched to HSI and an interrupt
+ is generated if enabled. The interrupt is linked to the Cortex-M0 NMI
+ (Non-Maskable Interrupt) exception vector.
+
+ (#) MCO (microcontroller clock output), used to output SYSCLK, HSI, HSE, LSI, LSE or PLL
+ clock (divided by 2) output on pin (such as PA8 pin).
+
+ [..] System, AHB and APB buses clocks configuration
+ (#) Several clock sources can be used to drive the System clock (SYSCLK): HSI,
+ HSE and PLL.
+ The AHB clock (HCLK) is derived from System clock through configurable
+ prescaler and used to clock the CPU, memory and peripherals mapped
+ on AHB bus (DMA, GPIO...). APB1 (PCLK1) clock is derived
+ from AHB clock through configurable prescalers and used to clock
+ the peripherals mapped on these buses. You can use
+ "HAL_RCC_GetSysClockFreq()" function to retrieve the frequencies of these clocks.
+
+ (#) All the peripheral clocks are derived from the System clock (SYSCLK) except:
+ (++) The FLASH program/erase clock which is always HSI 8MHz clock.
+ (++) The USB 48 MHz clock which is derived from the PLL VCO clock.
+ (++) The USART clock which can be derived as well from HSI 8MHz, LSI or LSE.
+ (++) The I2C clock which can be derived as well from HSI 8MHz clock.
+ (++) The ADC clock which is derived from PLL output.
+ (++) The RTC clock which is derived from the LSE, LSI or 1 MHz HSE_RTC
+ (HSE divided by a programmable prescaler). The System clock (SYSCLK)
+ frequency must be higher or equal to the RTC clock frequency.
+ (++) IWDG clock which is always the LSI clock.
+
+ (#) For the STM32F0xx devices, the maximum frequency of the SYSCLK, HCLK and PCLK1 is 48 MHz,
+ Depending on the SYSCLK frequency, the flash latency should be adapted accordingly.
+
+ (#) After reset, the System clock source is the HSI (8 MHz) with 0 WS and
+ prefetch is disabled.
+ @endverbatim
+ * @{
+ */
+
+/*
+ Additional consideration on the SYSCLK based on Latency settings:
+ +-----------------------------------------------+
+ | Latency | SYSCLK clock frequency (MHz) |
+ |---------------|-------------------------------|
+ |0WS(1CPU cycle)| 0 < SYSCLK <= 24 |
+ |---------------|-------------------------------|
+ |1WS(2CPU cycle)| 24 < SYSCLK <= 48 |
+ +-----------------------------------------------+
+ */
+
+/**
+ * @brief Resets the RCC clock configuration to the default reset state.
+ * @note The default reset state of the clock configuration is given below:
+ * - HSI ON and used as system clock source
+ * - HSE and PLL OFF
+ * - AHB, APB1 prescaler set to 1.
+ * - CSS and MCO1 OFF
+ * - All interrupts disabled
+ * - All interrupt and reset flags cleared
+ * @note This function does not modify the configuration of the
+ * - Peripheral clocks
+ * - LSI, LSE and RTC clocks
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_RCC_DeInit(void)
+{
+ uint32_t tickstart;
+
+ /* Get Start Tick*/
+ tickstart = HAL_GetTick();
+
+ /* Set HSION bit, HSITRIM[4:0] bits to the reset value*/
+ SET_BIT(RCC->CR, RCC_CR_HSION | RCC_CR_HSITRIM_4);
+
+ /* Wait till HSI is ready */
+ while (READ_BIT(RCC->CR, RCC_CR_HSIRDY) == RESET)
+ {
+ if ((HAL_GetTick() - tickstart) > HSI_TIMEOUT_VALUE)
+ {
+ return HAL_TIMEOUT;
+ }
+ }
+
+ /* Reset SW[1:0], HPRE[3:0], PPRE[2:0] and MCOSEL[2:0] bits */
+ CLEAR_BIT(RCC->CFGR, RCC_CFGR_SW | RCC_CFGR_HPRE | RCC_CFGR_PPRE | RCC_CFGR_MCO);
+
+ /* Wait till HSI as SYSCLK status is enabled */
+ while (READ_BIT(RCC->CFGR, RCC_CFGR_SWS) != RESET)
+ {
+ if ((HAL_GetTick() - tickstart) > CLOCKSWITCH_TIMEOUT_VALUE)
+ {
+ return HAL_TIMEOUT;
+ }
+ }
+
+ /* Update the SystemCoreClock global variable for HSI as system clock source */
+ SystemCoreClock = HSI_VALUE;
+
+ /* Adapt Systick interrupt period */
+ if (HAL_InitTick(uwTickPrio) != HAL_OK)
+ {
+ return HAL_ERROR;
+ }
+
+ /* Reset HSEON, CSSON, PLLON bits */
+ CLEAR_BIT(RCC->CR, RCC_CR_PLLON | RCC_CR_CSSON | RCC_CR_HSEON);
+
+ /* Reset HSEBYP bit */
+ CLEAR_BIT(RCC->CR, RCC_CR_HSEBYP);
+
+ /* Get start tick */
+ tickstart = HAL_GetTick();
+
+ /* Wait till PLLRDY is cleared */
+ while(READ_BIT(RCC->CR, RCC_CR_PLLRDY) != RESET)
+ {
+ if((HAL_GetTick() - tickstart) > PLL_TIMEOUT_VALUE)
+ {
+ return HAL_TIMEOUT;
+ }
+ }
+
+ /* Reset CFGR register */
+ CLEAR_REG(RCC->CFGR);
+
+ /* Reset CFGR2 register */
+ CLEAR_REG(RCC->CFGR2);
+
+ /* Reset CFGR3 register */
+ CLEAR_REG(RCC->CFGR3);
+
+ /* Disable all interrupts */
+ CLEAR_REG(RCC->CIR);
+
+ /* Clear all reset flags */
+ __HAL_RCC_CLEAR_RESET_FLAGS();
+
+ return HAL_OK;
+}
+
+/**
+ * @brief Initializes the RCC Oscillators according to the specified parameters in the
+ * RCC_OscInitTypeDef.
+ * @param RCC_OscInitStruct pointer to an RCC_OscInitTypeDef structure that
+ * contains the configuration information for the RCC Oscillators.
+ * @note The PLL is not disabled when used as system clock.
+ * @note Transitions LSE Bypass to LSE On and LSE On to LSE Bypass are not
+ * supported by this macro. User should request a transition to LSE Off
+ * first and then LSE On or LSE Bypass.
+ * @note Transition HSE Bypass to HSE On and HSE On to HSE Bypass are not
+ * supported by this macro. User should request a transition to HSE Off
+ * first and then HSE On or HSE Bypass.
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_RCC_OscConfig(RCC_OscInitTypeDef *RCC_OscInitStruct)
+{
+ uint32_t tickstart;
+ uint32_t pll_config;
+ uint32_t pll_config2;
+
+ /* Check Null pointer */
+ if(RCC_OscInitStruct == NULL)
+ {
+ return HAL_ERROR;
+ }
+
+ /* Check the parameters */
+ assert_param(IS_RCC_OSCILLATORTYPE(RCC_OscInitStruct->OscillatorType));
+
+ /*------------------------------- HSE Configuration ------------------------*/
+ if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_HSE) == RCC_OSCILLATORTYPE_HSE)
+ {
+ /* Check the parameters */
+ assert_param(IS_RCC_HSE(RCC_OscInitStruct->HSEState));
+
+ /* When the HSE is used as system clock or clock source for PLL in these cases it is not allowed to be disabled */
+ if((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_SYSCLKSOURCE_STATUS_HSE)
+ || ((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_SYSCLKSOURCE_STATUS_PLLCLK) && (__HAL_RCC_GET_PLL_OSCSOURCE() == RCC_PLLSOURCE_HSE)))
+ {
+ if((__HAL_RCC_GET_FLAG(RCC_FLAG_HSERDY) != RESET) && (RCC_OscInitStruct->HSEState == RCC_HSE_OFF))
+ {
+ return HAL_ERROR;
+ }
+ }
+ else
+ {
+ /* Set the new HSE configuration ---------------------------------------*/
+ __HAL_RCC_HSE_CONFIG(RCC_OscInitStruct->HSEState);
+
+
+ /* Check the HSE State */
+ if(RCC_OscInitStruct->HSEState != RCC_HSE_OFF)
+ {
+ /* Get Start Tick */
+ tickstart = HAL_GetTick();
+
+ /* Wait till HSE is ready */
+ while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSERDY) == RESET)
+ {
+ if((HAL_GetTick() - tickstart ) > HSE_TIMEOUT_VALUE)
+ {
+ return HAL_TIMEOUT;
+ }
+ }
+ }
+ else
+ {
+ /* Get Start Tick */
+ tickstart = HAL_GetTick();
+
+ /* Wait till HSE is disabled */
+ while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSERDY) != RESET)
+ {
+ if((HAL_GetTick() - tickstart ) > HSE_TIMEOUT_VALUE)
+ {
+ return HAL_TIMEOUT;
+ }
+ }
+ }
+ }
+ }
+ /*----------------------------- HSI Configuration --------------------------*/
+ if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_HSI) == RCC_OSCILLATORTYPE_HSI)
+ {
+ /* Check the parameters */
+ assert_param(IS_RCC_HSI(RCC_OscInitStruct->HSIState));
+ assert_param(IS_RCC_CALIBRATION_VALUE(RCC_OscInitStruct->HSICalibrationValue));
+
+ /* Check if HSI is used as system clock or as PLL source when PLL is selected as system clock */
+ if((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_SYSCLKSOURCE_STATUS_HSI)
+ || ((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_SYSCLKSOURCE_STATUS_PLLCLK) && (__HAL_RCC_GET_PLL_OSCSOURCE() == RCC_PLLSOURCE_HSI)))
+ {
+ /* When HSI is used as system clock it will not disabled */
+ if((__HAL_RCC_GET_FLAG(RCC_FLAG_HSIRDY) != RESET) && (RCC_OscInitStruct->HSIState != RCC_HSI_ON))
+ {
+ return HAL_ERROR;
+ }
+ /* Otherwise, just the calibration is allowed */
+ else
+ {
+ /* Adjusts the Internal High Speed oscillator (HSI) calibration value.*/
+ __HAL_RCC_HSI_CALIBRATIONVALUE_ADJUST(RCC_OscInitStruct->HSICalibrationValue);
+ }
+ }
+ else
+ {
+ /* Check the HSI State */
+ if(RCC_OscInitStruct->HSIState != RCC_HSI_OFF)
+ {
+ /* Enable the Internal High Speed oscillator (HSI). */
+ __HAL_RCC_HSI_ENABLE();
+
+ /* Get Start Tick */
+ tickstart = HAL_GetTick();
+
+ /* Wait till HSI is ready */
+ while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSIRDY) == RESET)
+ {
+ if((HAL_GetTick() - tickstart ) > HSI_TIMEOUT_VALUE)
+ {
+ return HAL_TIMEOUT;
+ }
+ }
+
+ /* Adjusts the Internal High Speed oscillator (HSI) calibration value.*/
+ __HAL_RCC_HSI_CALIBRATIONVALUE_ADJUST(RCC_OscInitStruct->HSICalibrationValue);
+ }
+ else
+ {
+ /* Disable the Internal High Speed oscillator (HSI). */
+ __HAL_RCC_HSI_DISABLE();
+
+ /* Get Start Tick */
+ tickstart = HAL_GetTick();
+
+ /* Wait till HSI is disabled */
+ while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSIRDY) != RESET)
+ {
+ if((HAL_GetTick() - tickstart ) > HSI_TIMEOUT_VALUE)
+ {
+ return HAL_TIMEOUT;
+ }
+ }
+ }
+ }
+ }
+ /*------------------------------ LSI Configuration -------------------------*/
+ if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_LSI) == RCC_OSCILLATORTYPE_LSI)
+ {
+ /* Check the parameters */
+ assert_param(IS_RCC_LSI(RCC_OscInitStruct->LSIState));
+
+ /* Check the LSI State */
+ if(RCC_OscInitStruct->LSIState != RCC_LSI_OFF)
+ {
+ /* Enable the Internal Low Speed oscillator (LSI). */
+ __HAL_RCC_LSI_ENABLE();
+
+ /* Get Start Tick */
+ tickstart = HAL_GetTick();
+
+ /* Wait till LSI is ready */
+ while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSIRDY) == RESET)
+ {
+ if((HAL_GetTick() - tickstart ) > LSI_TIMEOUT_VALUE)
+ {
+ return HAL_TIMEOUT;
+ }
+ }
+ }
+ else
+ {
+ /* Disable the Internal Low Speed oscillator (LSI). */
+ __HAL_RCC_LSI_DISABLE();
+
+ /* Get Start Tick */
+ tickstart = HAL_GetTick();
+
+ /* Wait till LSI is disabled */
+ while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSIRDY) != RESET)
+ {
+ if((HAL_GetTick() - tickstart ) > LSI_TIMEOUT_VALUE)
+ {
+ return HAL_TIMEOUT;
+ }
+ }
+ }
+ }
+ /*------------------------------ LSE Configuration -------------------------*/
+ if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_LSE) == RCC_OSCILLATORTYPE_LSE)
+ {
+ FlagStatus pwrclkchanged = RESET;
+
+ /* Check the parameters */
+ assert_param(IS_RCC_LSE(RCC_OscInitStruct->LSEState));
+
+ /* Update LSE configuration in Backup Domain control register */
+ /* Requires to enable write access to Backup Domain of necessary */
+ if(__HAL_RCC_PWR_IS_CLK_DISABLED())
+ {
+ __HAL_RCC_PWR_CLK_ENABLE();
+ pwrclkchanged = SET;
+ }
+
+ if(HAL_IS_BIT_CLR(PWR->CR, PWR_CR_DBP))
+ {
+ /* Enable write access to Backup domain */
+ SET_BIT(PWR->CR, PWR_CR_DBP);
+
+ /* Wait for Backup domain Write protection disable */
+ tickstart = HAL_GetTick();
+
+ while(HAL_IS_BIT_CLR(PWR->CR, PWR_CR_DBP))
+ {
+ if((HAL_GetTick() - tickstart) > RCC_DBP_TIMEOUT_VALUE)
+ {
+ return HAL_TIMEOUT;
+ }
+ }
+ }
+
+ /* Set the new LSE configuration -----------------------------------------*/
+ __HAL_RCC_LSE_CONFIG(RCC_OscInitStruct->LSEState);
+ /* Check the LSE State */
+ if(RCC_OscInitStruct->LSEState != RCC_LSE_OFF)
+ {
+ /* Get Start Tick */
+ tickstart = HAL_GetTick();
+
+ /* Wait till LSE is ready */
+ while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) == RESET)
+ {
+ if((HAL_GetTick() - tickstart ) > RCC_LSE_TIMEOUT_VALUE)
+ {
+ return HAL_TIMEOUT;
+ }
+ }
+ }
+ else
+ {
+ /* Get Start Tick */
+ tickstart = HAL_GetTick();
+
+ /* Wait till LSE is disabled */
+ while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) != RESET)
+ {
+ if((HAL_GetTick() - tickstart ) > RCC_LSE_TIMEOUT_VALUE)
+ {
+ return HAL_TIMEOUT;
+ }
+ }
+ }
+
+ /* Require to disable power clock if necessary */
+ if(pwrclkchanged == SET)
+ {
+ __HAL_RCC_PWR_CLK_DISABLE();
+ }
+ }
+
+ /*----------------------------- HSI14 Configuration --------------------------*/
+ if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_HSI14) == RCC_OSCILLATORTYPE_HSI14)
+ {
+ /* Check the parameters */
+ assert_param(IS_RCC_HSI14(RCC_OscInitStruct->HSI14State));
+ assert_param(IS_RCC_CALIBRATION_VALUE(RCC_OscInitStruct->HSI14CalibrationValue));
+
+ /* Check the HSI14 State */
+ if(RCC_OscInitStruct->HSI14State == RCC_HSI14_ON)
+ {
+ /* Disable ADC control of the Internal High Speed oscillator HSI14 */
+ __HAL_RCC_HSI14ADC_DISABLE();
+
+ /* Enable the Internal High Speed oscillator (HSI). */
+ __HAL_RCC_HSI14_ENABLE();
+
+ /* Get Start Tick */
+ tickstart = HAL_GetTick();
+
+ /* Wait till HSI is ready */
+ while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSI14RDY) == RESET)
+ {
+ if((HAL_GetTick() - tickstart) > HSI14_TIMEOUT_VALUE)
+ {
+ return HAL_TIMEOUT;
+ }
+ }
+
+ /* Adjusts the Internal High Speed oscillator 14Mhz (HSI14) calibration value. */
+ __HAL_RCC_HSI14_CALIBRATIONVALUE_ADJUST(RCC_OscInitStruct->HSI14CalibrationValue);
+ }
+ else if(RCC_OscInitStruct->HSI14State == RCC_HSI14_ADC_CONTROL)
+ {
+ /* Enable ADC control of the Internal High Speed oscillator HSI14 */
+ __HAL_RCC_HSI14ADC_ENABLE();
+
+ /* Adjusts the Internal High Speed oscillator 14Mhz (HSI14) calibration value. */
+ __HAL_RCC_HSI14_CALIBRATIONVALUE_ADJUST(RCC_OscInitStruct->HSI14CalibrationValue);
+ }
+ else
+ {
+ /* Disable ADC control of the Internal High Speed oscillator HSI14 */
+ __HAL_RCC_HSI14ADC_DISABLE();
+
+ /* Disable the Internal High Speed oscillator (HSI). */
+ __HAL_RCC_HSI14_DISABLE();
+
+ /* Get Start Tick */
+ tickstart = HAL_GetTick();
+
+ /* Wait till HSI is ready */
+ while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSI14RDY) != RESET)
+ {
+ if((HAL_GetTick() - tickstart) > HSI14_TIMEOUT_VALUE)
+ {
+ return HAL_TIMEOUT;
+ }
+ }
+ }
+ }
+
+#if defined(RCC_HSI48_SUPPORT)
+ /*----------------------------- HSI48 Configuration --------------------------*/
+ if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_HSI48) == RCC_OSCILLATORTYPE_HSI48)
+ {
+ /* Check the parameters */
+ assert_param(IS_RCC_HSI48(RCC_OscInitStruct->HSI48State));
+
+ /* When the HSI48 is used as system clock it is not allowed to be disabled */
+ if((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_SYSCLKSOURCE_STATUS_HSI48) ||
+ ((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_SYSCLKSOURCE_STATUS_PLLCLK) && (__HAL_RCC_GET_PLL_OSCSOURCE() == RCC_PLLSOURCE_HSI48)))
+ {
+ if((__HAL_RCC_GET_FLAG(RCC_FLAG_HSI48RDY) != RESET) && (RCC_OscInitStruct->HSI48State != RCC_HSI48_ON))
+ {
+ return HAL_ERROR;
+ }
+ }
+ else
+ {
+ /* Check the HSI48 State */
+ if(RCC_OscInitStruct->HSI48State != RCC_HSI48_OFF)
+ {
+ /* Enable the Internal High Speed oscillator (HSI48). */
+ __HAL_RCC_HSI48_ENABLE();
+
+ /* Get Start Tick */
+ tickstart = HAL_GetTick();
+
+ /* Wait till HSI48 is ready */
+ while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSI48RDY) == RESET)
+ {
+ if((HAL_GetTick() - tickstart) > HSI48_TIMEOUT_VALUE)
+ {
+ return HAL_TIMEOUT;
+ }
+ }
+ }
+ else
+ {
+ /* Disable the Internal High Speed oscillator (HSI48). */
+ __HAL_RCC_HSI48_DISABLE();
+
+ /* Get Start Tick */
+ tickstart = HAL_GetTick();
+
+ /* Wait till HSI48 is ready */
+ while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSI48RDY) != RESET)
+ {
+ if((HAL_GetTick() - tickstart) > HSI48_TIMEOUT_VALUE)
+ {
+ return HAL_TIMEOUT;
+ }
+ }
+ }
+ }
+ }
+#endif /* RCC_HSI48_SUPPORT */
+
+ /*-------------------------------- PLL Configuration -----------------------*/
+ /* Check the parameters */
+ assert_param(IS_RCC_PLL(RCC_OscInitStruct->PLL.PLLState));
+ if ((RCC_OscInitStruct->PLL.PLLState) != RCC_PLL_NONE)
+ {
+ /* Check if the PLL is used as system clock or not */
+ if(__HAL_RCC_GET_SYSCLK_SOURCE() != RCC_SYSCLKSOURCE_STATUS_PLLCLK)
+ {
+ if((RCC_OscInitStruct->PLL.PLLState) == RCC_PLL_ON)
+ {
+ /* Check the parameters */
+ assert_param(IS_RCC_PLLSOURCE(RCC_OscInitStruct->PLL.PLLSource));
+ assert_param(IS_RCC_PLL_MUL(RCC_OscInitStruct->PLL.PLLMUL));
+ assert_param(IS_RCC_PREDIV(RCC_OscInitStruct->PLL.PREDIV));
+
+ /* Disable the main PLL. */
+ __HAL_RCC_PLL_DISABLE();
+
+ /* Get Start Tick */
+ tickstart = HAL_GetTick();
+
+ /* Wait till PLL is disabled */
+ while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) != RESET)
+ {
+ if((HAL_GetTick() - tickstart ) > PLL_TIMEOUT_VALUE)
+ {
+ return HAL_TIMEOUT;
+ }
+ }
+
+ /* Configure the main PLL clock source, predivider and multiplication factor. */
+ __HAL_RCC_PLL_CONFIG(RCC_OscInitStruct->PLL.PLLSource,
+ RCC_OscInitStruct->PLL.PREDIV,
+ RCC_OscInitStruct->PLL.PLLMUL);
+ /* Enable the main PLL. */
+ __HAL_RCC_PLL_ENABLE();
+
+ /* Get Start Tick */
+ tickstart = HAL_GetTick();
+
+ /* Wait till PLL is ready */
+ while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) == RESET)
+ {
+ if((HAL_GetTick() - tickstart ) > PLL_TIMEOUT_VALUE)
+ {
+ return HAL_TIMEOUT;
+ }
+ }
+ }
+ else
+ {
+ /* Disable the main PLL. */
+ __HAL_RCC_PLL_DISABLE();
+
+ /* Get Start Tick */
+ tickstart = HAL_GetTick();
+
+ /* Wait till PLL is disabled */
+ while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) != RESET)
+ {
+ if((HAL_GetTick() - tickstart ) > PLL_TIMEOUT_VALUE)
+ {
+ return HAL_TIMEOUT;
+ }
+ }
+ }
+ }
+ else
+ {
+ /* Check if there is a request to disable the PLL used as System clock source */
+ if((RCC_OscInitStruct->PLL.PLLState) == RCC_PLL_OFF)
+ {
+ return HAL_ERROR;
+ }
+ else
+ {
+ /* Do not return HAL_ERROR if request repeats the current configuration */
+ pll_config = RCC->CFGR;
+ pll_config2 = RCC->CFGR2;
+ if((READ_BIT(pll_config, RCC_CFGR_PLLSRC) != RCC_OscInitStruct->PLL.PLLSource) ||
+ (READ_BIT(pll_config2, RCC_CFGR2_PREDIV) != RCC_OscInitStruct->PLL.PREDIV) ||
+ (READ_BIT(pll_config, RCC_CFGR_PLLMUL) != RCC_OscInitStruct->PLL.PLLMUL))
+ {
+ return HAL_ERROR;
+ }
+ }
+ }
+ }
+
+ return HAL_OK;
+}
+
+/**
+ * @brief Initializes the CPU, AHB and APB buses clocks according to the specified
+ * parameters in the RCC_ClkInitStruct.
+ * @param RCC_ClkInitStruct pointer to an RCC_OscInitTypeDef structure that
+ * contains the configuration information for the RCC peripheral.
+ * @param FLatency FLASH Latency
+ * The value of this parameter depend on device used within the same series
+ * @note The SystemCoreClock CMSIS variable is used to store System Clock Frequency
+ * and updated by @ref HAL_RCC_GetHCLKFreq() function called within this function
+ *
+ * @note The HSI is used (enabled by hardware) as system clock source after
+ * start-up from Reset, wake-up from STOP and STANDBY mode, or in case
+ * of failure of the HSE used directly or indirectly as system clock
+ * (if the Clock Security System CSS is enabled).
+ *
+ * @note A switch from one clock source to another occurs only if the target
+ * clock source is ready (clock stable after start-up delay or PLL locked).
+ * If a clock source which is not yet ready is selected, the switch will
+ * occur when the clock source will be ready.
+ * You can use @ref HAL_RCC_GetClockConfig() function to know which clock is
+ * currently used as system clock source.
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_RCC_ClockConfig(RCC_ClkInitTypeDef *RCC_ClkInitStruct, uint32_t FLatency)
+{
+ uint32_t tickstart;
+
+ /* Check Null pointer */
+ if(RCC_ClkInitStruct == NULL)
+ {
+ return HAL_ERROR;
+ }
+
+ /* Check the parameters */
+ assert_param(IS_RCC_CLOCKTYPE(RCC_ClkInitStruct->ClockType));
+ assert_param(IS_FLASH_LATENCY(FLatency));
+
+ /* To correctly read data from FLASH memory, the number of wait states (LATENCY)
+ must be correctly programmed according to the frequency of the CPU clock
+ (HCLK) of the device. */
+
+ /* Increasing the number of wait states because of higher CPU frequency */
+ if(FLatency > __HAL_FLASH_GET_LATENCY())
+ {
+ /* Program the new number of wait states to the LATENCY bits in the FLASH_ACR register */
+ __HAL_FLASH_SET_LATENCY(FLatency);
+
+ /* Check that the new number of wait states is taken into account to access the Flash
+ memory by reading the FLASH_ACR register */
+ if(__HAL_FLASH_GET_LATENCY() != FLatency)
+ {
+ return HAL_ERROR;
+ }
+ }
+
+ /*-------------------------- HCLK Configuration --------------------------*/
+ if(((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_HCLK) == RCC_CLOCKTYPE_HCLK)
+ {
+ /* Set the highest APB divider in order to ensure that we do not go through
+ a non-spec phase whatever we decrease or increase HCLK. */
+ if(((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_PCLK1) == RCC_CLOCKTYPE_PCLK1)
+ {
+ MODIFY_REG(RCC->CFGR, RCC_CFGR_PPRE, RCC_HCLK_DIV16);
+ }
+
+ /* Set the new HCLK clock divider */
+ assert_param(IS_RCC_HCLK(RCC_ClkInitStruct->AHBCLKDivider));
+ MODIFY_REG(RCC->CFGR, RCC_CFGR_HPRE, RCC_ClkInitStruct->AHBCLKDivider);
+ }
+
+ /*------------------------- SYSCLK Configuration ---------------------------*/
+ if(((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_SYSCLK) == RCC_CLOCKTYPE_SYSCLK)
+ {
+ assert_param(IS_RCC_SYSCLKSOURCE(RCC_ClkInitStruct->SYSCLKSource));
+
+ /* HSE is selected as System Clock Source */
+ if(RCC_ClkInitStruct->SYSCLKSource == RCC_SYSCLKSOURCE_HSE)
+ {
+ /* Check the HSE ready flag */
+ if(__HAL_RCC_GET_FLAG(RCC_FLAG_HSERDY) == RESET)
+ {
+ return HAL_ERROR;
+ }
+ }
+ /* PLL is selected as System Clock Source */
+ else if(RCC_ClkInitStruct->SYSCLKSource == RCC_SYSCLKSOURCE_PLLCLK)
+ {
+ /* Check the PLL ready flag */
+ if(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) == RESET)
+ {
+ return HAL_ERROR;
+ }
+ }
+#if defined(RCC_CFGR_SWS_HSI48)
+ /* HSI48 is selected as System Clock Source */
+ else if(RCC_ClkInitStruct->SYSCLKSource == RCC_SYSCLKSOURCE_HSI48)
+ {
+ /* Check the HSI48 ready flag */
+ if(__HAL_RCC_GET_FLAG(RCC_FLAG_HSI48RDY) == RESET)
+ {
+ return HAL_ERROR;
+ }
+ }
+#endif /* RCC_CFGR_SWS_HSI48 */
+ /* HSI is selected as System Clock Source */
+ else
+ {
+ /* Check the HSI ready flag */
+ if(__HAL_RCC_GET_FLAG(RCC_FLAG_HSIRDY) == RESET)
+ {
+ return HAL_ERROR;
+ }
+ }
+ __HAL_RCC_SYSCLK_CONFIG(RCC_ClkInitStruct->SYSCLKSource);
+
+ /* Get Start Tick */
+ tickstart = HAL_GetTick();
+
+ while (__HAL_RCC_GET_SYSCLK_SOURCE() != (RCC_ClkInitStruct->SYSCLKSource << RCC_CFGR_SWS_Pos))
+ {
+ if((HAL_GetTick() - tickstart ) > CLOCKSWITCH_TIMEOUT_VALUE)
+ {
+ return HAL_TIMEOUT;
+ }
+ }
+ }
+
+ /* Decreasing the number of wait states because of lower CPU frequency */
+ if(FLatency < __HAL_FLASH_GET_LATENCY())
+ {
+ /* Program the new number of wait states to the LATENCY bits in the FLASH_ACR register */
+ __HAL_FLASH_SET_LATENCY(FLatency);
+
+ /* Check that the new number of wait states is taken into account to access the Flash
+ memory by reading the FLASH_ACR register */
+ if(__HAL_FLASH_GET_LATENCY() != FLatency)
+ {
+ return HAL_ERROR;
+ }
+ }
+
+ /*-------------------------- PCLK1 Configuration ---------------------------*/
+ if(((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_PCLK1) == RCC_CLOCKTYPE_PCLK1)
+ {
+ assert_param(IS_RCC_PCLK(RCC_ClkInitStruct->APB1CLKDivider));
+ MODIFY_REG(RCC->CFGR, RCC_CFGR_PPRE, RCC_ClkInitStruct->APB1CLKDivider);
+ }
+
+ /* Update the SystemCoreClock global variable */
+ SystemCoreClock = HAL_RCC_GetSysClockFreq() >> AHBPrescTable[(RCC->CFGR & RCC_CFGR_HPRE)>> RCC_CFGR_HPRE_BITNUMBER];
+
+ /* Configure the source of time base considering new system clocks settings*/
+ HAL_InitTick (TICK_INT_PRIORITY);
+
+ return HAL_OK;
+}
+
+/**
+ * @}
+ */
+
+/** @defgroup RCC_Exported_Functions_Group2 Peripheral Control functions
+ * @brief RCC clocks control functions
+ *
+ @verbatim
+ ===============================================================================
+ ##### Peripheral Control functions #####
+ ===============================================================================
+ [..]
+ This subsection provides a set of functions allowing to control the RCC Clocks
+ frequencies.
+
+ @endverbatim
+ * @{
+ */
+
+#if defined(RCC_CFGR_MCOPRE)
+/**
+ * @brief Selects the clock source to output on MCO pin.
+ * @note MCO pin should be configured in alternate function mode.
+ * @param RCC_MCOx specifies the output direction for the clock source.
+ * This parameter can be one of the following values:
+ * @arg @ref RCC_MCO1 Clock source to output on MCO1 pin(PA8).
+ * @param RCC_MCOSource specifies the clock source to output.
+ * This parameter can be one of the following values:
+ * @arg @ref RCC_MCO1SOURCE_NOCLOCK No clock selected
+ * @arg @ref RCC_MCO1SOURCE_SYSCLK System Clock selected as MCO clock
+ * @arg @ref RCC_MCO1SOURCE_HSI HSI selected as MCO clock
+ * @arg @ref RCC_MCO1SOURCE_HSE HSE selected as MCO clock
+ * @arg @ref RCC_MCO1SOURCE_LSI LSI selected as MCO clock
+ * @arg @ref RCC_MCO1SOURCE_LSE LSE selected as MCO clock
+ * @arg @ref RCC_MCO1SOURCE_HSI14 HSI14 selected as MCO clock
+ @if STM32F042x6
+ * @arg @ref RCC_MCO1SOURCE_HSI48 HSI48 selected as MCO clock
+ * @arg @ref RCC_MCO1SOURCE_PLLCLK PLLCLK selected as MCO clock
+ @elseif STM32F048xx
+ * @arg @ref RCC_MCO1SOURCE_HSI48 HSI48 selected as MCO clock
+ * @arg @ref RCC_MCO1SOURCE_PLLCLK PLLCLK selected as MCO clock
+ @elseif STM32F071xB
+ * @arg @ref RCC_MCO1SOURCE_HSI48 HSI48 selected as MCO clock
+ * @arg @ref RCC_MCO1SOURCE_PLLCLK PLLCLK selected as MCO clock
+ @elseif STM32F072xB
+ * @arg @ref RCC_MCO1SOURCE_HSI48 HSI48 selected as MCO clock
+ * @arg @ref RCC_MCO1SOURCE_PLLCLK PLLCLK selected as MCO clock
+ @elseif STM32F078xx
+ * @arg @ref RCC_MCO1SOURCE_HSI48 HSI48 selected as MCO clock
+ * @arg @ref RCC_MCO1SOURCE_PLLCLK PLLCLK selected as MCO clock
+ @elseif STM32F091xC
+ * @arg @ref RCC_MCO1SOURCE_HSI48 HSI48 selected as MCO clock
+ * @arg @ref RCC_MCO1SOURCE_PLLCLK PLLCLK selected as MCO clock
+ @elseif STM32F098xx
+ * @arg @ref RCC_MCO1SOURCE_HSI48 HSI48 selected as MCO clock
+ * @arg @ref RCC_MCO1SOURCE_PLLCLK PLLCLK selected as MCO clock
+ @elif STM32F030x6
+ * @arg @ref RCC_MCO1SOURCE_PLLCLK PLLCLK selected as MCO clock
+ @elif STM32F030xC
+ * @arg @ref RCC_MCO1SOURCE_PLLCLK PLLCLK selected as MCO clock
+ @elif STM32F031x6
+ * @arg @ref RCC_MCO1SOURCE_PLLCLK PLLCLK selected as MCO clock
+ @elif STM32F038xx
+ * @arg @ref RCC_MCO1SOURCE_PLLCLK PLLCLK selected as MCO clock
+ @elif STM32F070x6
+ * @arg @ref RCC_MCO1SOURCE_PLLCLK PLLCLK selected as MCO clock
+ @elif STM32F070xB
+ * @arg @ref RCC_MCO1SOURCE_PLLCLK PLLCLK selected as MCO clock
+ @endif
+ * @arg @ref RCC_MCO1SOURCE_PLLCLK_DIV2 PLLCLK Divided by 2 selected as MCO clock
+ * @param RCC_MCODiv specifies the MCO DIV.
+ * This parameter can be one of the following values:
+ * @arg @ref RCC_MCODIV_1 no division applied to MCO clock
+ * @arg @ref RCC_MCODIV_2 division by 2 applied to MCO clock
+ * @arg @ref RCC_MCODIV_4 division by 4 applied to MCO clock
+ * @arg @ref RCC_MCODIV_8 division by 8 applied to MCO clock
+ * @arg @ref RCC_MCODIV_16 division by 16 applied to MCO clock
+ * @arg @ref RCC_MCODIV_32 division by 32 applied to MCO clock
+ * @arg @ref RCC_MCODIV_64 division by 64 applied to MCO clock
+ * @arg @ref RCC_MCODIV_128 division by 128 applied to MCO clock
+ * @retval None
+ */
+#else
+/**
+ * @brief Selects the clock source to output on MCO pin.
+ * @note MCO pin should be configured in alternate function mode.
+ * @param RCC_MCOx specifies the output direction for the clock source.
+ * This parameter can be one of the following values:
+ * @arg @ref RCC_MCO1 Clock source to output on MCO1 pin(PA8).
+ * @param RCC_MCOSource specifies the clock source to output.
+ * This parameter can be one of the following values:
+ * @arg @ref RCC_MCO1SOURCE_NOCLOCK No clock selected as MCO clock
+ * @arg @ref RCC_MCO1SOURCE_SYSCLK System clock selected as MCO clock
+ * @arg @ref RCC_MCO1SOURCE_HSI HSI selected as MCO clock
+ * @arg @ref RCC_MCO1SOURCE_HSE HSE selected as MCO clock
+ * @arg @ref RCC_MCO1SOURCE_LSI LSI selected as MCO clock
+ * @arg @ref RCC_MCO1SOURCE_LSE LSE selected as MCO clock
+ * @arg @ref RCC_MCO1SOURCE_HSI14 HSI14 selected as MCO clock
+ * @arg @ref RCC_MCO1SOURCE_PLLCLK_DIV2 PLLCLK Divided by 2 selected as MCO clock
+ * @param RCC_MCODiv specifies the MCO DIV.
+ * This parameter can be one of the following values:
+ * @arg @ref RCC_MCODIV_1 no division applied to MCO clock
+ * @retval None
+ */
+#endif
+void HAL_RCC_MCOConfig(uint32_t RCC_MCOx, uint32_t RCC_MCOSource, uint32_t RCC_MCODiv)
+{
+ GPIO_InitTypeDef gpio;
+
+ /* Check the parameters */
+ assert_param(IS_RCC_MCO(RCC_MCOx));
+ assert_param(IS_RCC_MCODIV(RCC_MCODiv));
+ assert_param(IS_RCC_MCO1SOURCE(RCC_MCOSource));
+
+ /* Configure the MCO1 pin in alternate function mode */
+ gpio.Mode = GPIO_MODE_AF_PP;
+ gpio.Speed = GPIO_SPEED_FREQ_HIGH;
+ gpio.Pull = GPIO_NOPULL;
+ gpio.Pin = MCO1_PIN;
+ gpio.Alternate = GPIO_AF0_MCO;
+
+ /* MCO1 Clock Enable */
+ MCO1_CLK_ENABLE();
+
+ HAL_GPIO_Init(MCO1_GPIO_PORT, &gpio);
+
+ /* Configure the MCO clock source */
+ __HAL_RCC_MCO1_CONFIG(RCC_MCOSource, RCC_MCODiv);
+}
+
+/**
+ * @brief Enables the Clock Security System.
+ * @note If a failure is detected on the HSE oscillator clock, this oscillator
+ * is automatically disabled and an interrupt is generated to inform the
+ * software about the failure (Clock Security System Interrupt, CSSI),
+ * allowing the MCU to perform rescue operations. The CSSI is linked to
+ * the Cortex-M0 NMI (Non-Maskable Interrupt) exception vector.
+ * @retval None
+ */
+void HAL_RCC_EnableCSS(void)
+{
+ SET_BIT(RCC->CR, RCC_CR_CSSON) ;
+}
+
+/**
+ * @brief Disables the Clock Security System.
+ * @retval None
+ */
+void HAL_RCC_DisableCSS(void)
+{
+ CLEAR_BIT(RCC->CR, RCC_CR_CSSON) ;
+}
+
+/**
+ * @brief Returns the SYSCLK frequency
+ * @note The system frequency computed by this function is not the real
+ * frequency in the chip. It is calculated based on the predefined
+ * constant and the selected clock source:
+ * @note If SYSCLK source is HSI, function returns values based on HSI_VALUE(*)
+ * @note If SYSCLK source is HSE, function returns a value based on HSE_VALUE
+ * divided by PREDIV factor(**)
+ * @note If SYSCLK source is PLL, function returns a value based on HSE_VALUE
+ * divided by PREDIV factor(**) or depending on STM32F0xxxx devices either a value based
+ * on HSI_VALUE divided by 2 or HSI_VALUE divided by PREDIV factor(*) multiplied by the
+ * PLL factor.
+ * @note (*) HSI_VALUE is a constant defined in stm32f0xx_hal_conf.h file (default value
+ * 8 MHz) but the real value may vary depending on the variations
+ * in voltage and temperature.
+ * @note (**) HSE_VALUE is a constant defined in stm32f0xx_hal_conf.h file (default value
+ * 8 MHz), user has to ensure that HSE_VALUE is same as the real
+ * frequency of the crystal used. Otherwise, this function may
+ * have wrong result.
+ *
+ * @note The result of this function could be not correct when using fractional
+ * value for HSE crystal.
+ *
+ * @note This function can be used by the user application to compute the
+ * baud-rate for the communication peripherals or configure other parameters.
+ *
+ * @note Each time SYSCLK changes, this function must be called to update the
+ * right SYSCLK value. Otherwise, any configuration based on this function will be incorrect.
+ *
+ * @retval SYSCLK frequency
+ */
+uint32_t HAL_RCC_GetSysClockFreq(void)
+{
+ const uint8_t aPLLMULFactorTable[16] = { 2U, 3U, 4U, 5U, 6U, 7U, 8U, 9U,
+ 10U, 11U, 12U, 13U, 14U, 15U, 16U, 16U};
+ const uint8_t aPredivFactorTable[16] = { 1U, 2U, 3U, 4U, 5U, 6U, 7U, 8U,
+ 9U,10U, 11U, 12U, 13U, 14U, 15U, 16U};
+
+ uint32_t tmpreg = 0U, prediv = 0U, pllclk = 0U, pllmul = 0U;
+ uint32_t sysclockfreq = 0U;
+
+ tmpreg = RCC->CFGR;
+
+ /* Get SYSCLK source -------------------------------------------------------*/
+ switch (tmpreg & RCC_CFGR_SWS)
+ {
+ case RCC_SYSCLKSOURCE_STATUS_HSE: /* HSE used as system clock */
+ {
+ sysclockfreq = HSE_VALUE;
+ break;
+ }
+ case RCC_SYSCLKSOURCE_STATUS_PLLCLK: /* PLL used as system clock */
+ {
+ pllmul = aPLLMULFactorTable[(uint32_t)(tmpreg & RCC_CFGR_PLLMUL) >> RCC_CFGR_PLLMUL_BITNUMBER];
+ prediv = aPredivFactorTable[(uint32_t)(RCC->CFGR2 & RCC_CFGR2_PREDIV) >> RCC_CFGR2_PREDIV_BITNUMBER];
+ if ((tmpreg & RCC_CFGR_PLLSRC) == RCC_PLLSOURCE_HSE)
+ {
+ /* HSE used as PLL clock source : PLLCLK = HSE/PREDIV * PLLMUL */
+ pllclk = (uint32_t)((uint64_t) HSE_VALUE / (uint64_t) (prediv)) * ((uint64_t) pllmul);
+ }
+#if defined(RCC_CFGR_PLLSRC_HSI48_PREDIV)
+ else if ((tmpreg & RCC_CFGR_PLLSRC) == RCC_PLLSOURCE_HSI48)
+ {
+ /* HSI48 used as PLL clock source : PLLCLK = HSI48/PREDIV * PLLMUL */
+ pllclk = (uint32_t)((uint64_t) HSI48_VALUE / (uint64_t) (prediv)) * ((uint64_t) pllmul);
+ }
+#endif /* RCC_CFGR_PLLSRC_HSI48_PREDIV */
+ else
+ {
+#if (defined(STM32F042x6) || defined(STM32F048xx) || defined(STM32F070x6) || defined(STM32F071xB) || defined(STM32F072xB) || defined(STM32F078xx) || defined(STM32F070xB) || defined(STM32F091xC) || defined(STM32F098xx) || defined(STM32F030xC))
+ /* HSI used as PLL clock source : PLLCLK = HSI/PREDIV * PLLMUL */
+ pllclk = (uint32_t)((uint64_t) HSI_VALUE / (uint64_t) (prediv)) * ((uint64_t) pllmul);
+#else
+ /* HSI used as PLL clock source : PLLCLK = HSI/2 * PLLMUL */
+ pllclk = (uint32_t)((uint64_t) (HSI_VALUE >> 1U) * ((uint64_t) pllmul));
+#endif
+ }
+ sysclockfreq = pllclk;
+ break;
+ }
+#if defined(RCC_CFGR_SWS_HSI48)
+ case RCC_SYSCLKSOURCE_STATUS_HSI48: /* HSI48 used as system clock source */
+ {
+ sysclockfreq = HSI48_VALUE;
+ break;
+ }
+#endif /* RCC_CFGR_SWS_HSI48 */
+ case RCC_SYSCLKSOURCE_STATUS_HSI: /* HSI used as system clock source */
+ default: /* HSI used as system clock */
+ {
+ sysclockfreq = HSI_VALUE;
+ break;
+ }
+ }
+ return sysclockfreq;
+}
+
+/**
+ * @brief Returns the HCLK frequency
+ * @note Each time HCLK changes, this function must be called to update the
+ * right HCLK value. Otherwise, any configuration based on this function will be incorrect.
+ *
+ * @note The SystemCoreClock CMSIS variable is used to store System Clock Frequency
+ * and updated within this function
+ * @retval HCLK frequency
+ */
+uint32_t HAL_RCC_GetHCLKFreq(void)
+{
+ return SystemCoreClock;
+}
+
+/**
+ * @brief Returns the PCLK1 frequency
+ * @note Each time PCLK1 changes, this function must be called to update the
+ * right PCLK1 value. Otherwise, any configuration based on this function will be incorrect.
+ * @retval PCLK1 frequency
+ */
+uint32_t HAL_RCC_GetPCLK1Freq(void)
+{
+ /* Get HCLK source and Compute PCLK1 frequency ---------------------------*/
+ return (HAL_RCC_GetHCLKFreq() >> APBPrescTable[(RCC->CFGR & RCC_CFGR_PPRE) >> RCC_CFGR_PPRE_BITNUMBER]);
+}
+
+/**
+ * @brief Configures the RCC_OscInitStruct according to the internal
+ * RCC configuration registers.
+ * @param RCC_OscInitStruct pointer to an RCC_OscInitTypeDef structure that
+ * will be configured.
+ * @retval None
+ */
+void HAL_RCC_GetOscConfig(RCC_OscInitTypeDef *RCC_OscInitStruct)
+{
+ /* Check the parameters */
+ assert_param(RCC_OscInitStruct != NULL);
+
+ /* Set all possible values for the Oscillator type parameter ---------------*/
+ RCC_OscInitStruct->OscillatorType = RCC_OSCILLATORTYPE_HSE | RCC_OSCILLATORTYPE_HSI \
+ | RCC_OSCILLATORTYPE_LSE | RCC_OSCILLATORTYPE_LSI | RCC_OSCILLATORTYPE_HSI14;
+#if defined(RCC_HSI48_SUPPORT)
+ RCC_OscInitStruct->OscillatorType |= RCC_OSCILLATORTYPE_HSI48;
+#endif /* RCC_HSI48_SUPPORT */
+
+
+ /* Get the HSE configuration -----------------------------------------------*/
+ if((RCC->CR &RCC_CR_HSEBYP) == RCC_CR_HSEBYP)
+ {
+ RCC_OscInitStruct->HSEState = RCC_HSE_BYPASS;
+ }
+ else if((RCC->CR &RCC_CR_HSEON) == RCC_CR_HSEON)
+ {
+ RCC_OscInitStruct->HSEState = RCC_HSE_ON;
+ }
+ else
+ {
+ RCC_OscInitStruct->HSEState = RCC_HSE_OFF;
+ }
+
+ /* Get the HSI configuration -----------------------------------------------*/
+ if((RCC->CR &RCC_CR_HSION) == RCC_CR_HSION)
+ {
+ RCC_OscInitStruct->HSIState = RCC_HSI_ON;
+ }
+ else
+ {
+ RCC_OscInitStruct->HSIState = RCC_HSI_OFF;
+ }
+
+ RCC_OscInitStruct->HSICalibrationValue = (uint32_t)((RCC->CR &RCC_CR_HSITRIM) >> RCC_CR_HSITRIM_BitNumber);
+
+ /* Get the LSE configuration -----------------------------------------------*/
+ if((RCC->BDCR &RCC_BDCR_LSEBYP) == RCC_BDCR_LSEBYP)
+ {
+ RCC_OscInitStruct->LSEState = RCC_LSE_BYPASS;
+ }
+ else if((RCC->BDCR &RCC_BDCR_LSEON) == RCC_BDCR_LSEON)
+ {
+ RCC_OscInitStruct->LSEState = RCC_LSE_ON;
+ }
+ else
+ {
+ RCC_OscInitStruct->LSEState = RCC_LSE_OFF;
+ }
+
+ /* Get the LSI configuration -----------------------------------------------*/
+ if((RCC->CSR &RCC_CSR_LSION) == RCC_CSR_LSION)
+ {
+ RCC_OscInitStruct->LSIState = RCC_LSI_ON;
+ }
+ else
+ {
+ RCC_OscInitStruct->LSIState = RCC_LSI_OFF;
+ }
+
+ /* Get the HSI14 configuration -----------------------------------------------*/
+ if((RCC->CR2 & RCC_CR2_HSI14ON) == RCC_CR2_HSI14ON)
+ {
+ RCC_OscInitStruct->HSI14State = RCC_HSI_ON;
+ }
+ else
+ {
+ RCC_OscInitStruct->HSI14State = RCC_HSI_OFF;
+ }
+
+ RCC_OscInitStruct->HSI14CalibrationValue = (uint32_t)((RCC->CR2 & RCC_CR2_HSI14TRIM) >> RCC_HSI14TRIM_BIT_NUMBER);
+
+#if defined(RCC_HSI48_SUPPORT)
+ /* Get the HSI48 configuration if any-----------------------------------------*/
+ RCC_OscInitStruct->HSI48State = __HAL_RCC_GET_HSI48_STATE();
+#endif /* RCC_HSI48_SUPPORT */
+
+ /* Get the PLL configuration -----------------------------------------------*/
+ if((RCC->CR &RCC_CR_PLLON) == RCC_CR_PLLON)
+ {
+ RCC_OscInitStruct->PLL.PLLState = RCC_PLL_ON;
+ }
+ else
+ {
+ RCC_OscInitStruct->PLL.PLLState = RCC_PLL_OFF;
+ }
+ RCC_OscInitStruct->PLL.PLLSource = (uint32_t)(RCC->CFGR & RCC_CFGR_PLLSRC);
+ RCC_OscInitStruct->PLL.PLLMUL = (uint32_t)(RCC->CFGR & RCC_CFGR_PLLMUL);
+ RCC_OscInitStruct->PLL.PREDIV = (uint32_t)(RCC->CFGR2 & RCC_CFGR2_PREDIV);
+}
+
+/**
+ * @brief Get the RCC_ClkInitStruct according to the internal
+ * RCC configuration registers.
+ * @param RCC_ClkInitStruct pointer to an RCC_ClkInitTypeDef structure that
+ * contains the current clock configuration.
+ * @param pFLatency Pointer on the Flash Latency.
+ * @retval None
+ */
+void HAL_RCC_GetClockConfig(RCC_ClkInitTypeDef *RCC_ClkInitStruct, uint32_t *pFLatency)
+{
+ /* Check the parameters */
+ assert_param(RCC_ClkInitStruct != NULL);
+ assert_param(pFLatency != NULL);
+
+ /* Set all possible values for the Clock type parameter --------------------*/
+ RCC_ClkInitStruct->ClockType = RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_PCLK1;
+
+ /* Get the SYSCLK configuration --------------------------------------------*/
+ RCC_ClkInitStruct->SYSCLKSource = (uint32_t)(RCC->CFGR & RCC_CFGR_SW);
+
+ /* Get the HCLK configuration ----------------------------------------------*/
+ RCC_ClkInitStruct->AHBCLKDivider = (uint32_t)(RCC->CFGR & RCC_CFGR_HPRE);
+
+ /* Get the APB1 configuration ----------------------------------------------*/
+ RCC_ClkInitStruct->APB1CLKDivider = (uint32_t)(RCC->CFGR & RCC_CFGR_PPRE);
+ /* Get the Flash Wait State (Latency) configuration ------------------------*/
+ *pFLatency = __HAL_FLASH_GET_LATENCY();
+}
+
+/**
+ * @brief This function handles the RCC CSS interrupt request.
+ * @note This API should be called under the NMI_Handler().
+ * @retval None
+ */
+void HAL_RCC_NMI_IRQHandler(void)
+{
+ /* Check RCC CSSF flag */
+ if(__HAL_RCC_GET_IT(RCC_IT_CSS))
+ {
+ /* RCC Clock Security System interrupt user callback */
+ HAL_RCC_CSSCallback();
+
+ /* Clear RCC CSS pending bit */
+ __HAL_RCC_CLEAR_IT(RCC_IT_CSS);
+ }
+}
+
+/**
+ * @brief RCC Clock Security System interrupt callback
+ * @retval none
+ */
+__weak void HAL_RCC_CSSCallback(void)
+{
+ /* NOTE : This function Should not be modified, when the callback is needed,
+ the HAL_RCC_CSSCallback could be implemented in the user file
+ */
+}
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+#endif /* HAL_RCC_MODULE_ENABLED */
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_rcc_ex.c b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_rcc_ex.c
new file mode 100644
index 0000000..6aee903
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_rcc_ex.c
@@ -0,0 +1,964 @@
+/**
+ ******************************************************************************
+ * @file stm32f0xx_hal_rcc_ex.c
+ * @author MCD Application Team
+ * @brief Extended RCC HAL module driver.
+ * This file provides firmware functions to manage the following
+ * functionalities RCC extension peripheral:
+ * + Extended Peripheral Control functions
+ * + Extended Clock Recovery System Control functions
+ *
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2016 STMicroelectronics.
+ * All rights reserved.
+ *
+ * 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 "stm32f0xx_hal.h"
+
+/** @addtogroup STM32F0xx_HAL_Driver
+ * @{
+ */
+
+#ifdef HAL_RCC_MODULE_ENABLED
+
+/** @defgroup RCCEx RCCEx
+ * @brief RCC Extension HAL module driver.
+ * @{
+ */
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+#if defined(CRS)
+/** @defgroup RCCEx_Private_Constants RCCEx Private Constants
+ * @{
+ */
+/* Bit position in register */
+#define CRS_CFGR_FELIM_BITNUMBER 16
+#define CRS_CR_TRIM_BITNUMBER 8
+#define CRS_ISR_FECAP_BITNUMBER 16
+/**
+ * @}
+ */
+#endif /* CRS */
+
+/* Private macro -------------------------------------------------------------*/
+/** @defgroup RCCEx_Private_Macros RCCEx Private Macros
+ * @{
+ */
+/**
+ * @}
+ */
+
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/** @defgroup RCCEx_Exported_Functions RCCEx Exported Functions
+ * @{
+ */
+
+/** @defgroup RCCEx_Exported_Functions_Group1 Extended Peripheral Control functions
+ * @brief Extended Peripheral Control functions
+ *
+@verbatim
+ ===============================================================================
+ ##### Extended Peripheral Control functions #####
+ ===============================================================================
+ [..]
+ This subsection provides a set of functions allowing to control the RCC Clocks
+ frequencies.
+ [..]
+ (@) Important note: Care must be taken when HAL_RCCEx_PeriphCLKConfig() is used to
+ select the RTC clock source; in this case the Backup domain will be reset in
+ order to modify the RTC Clock source, as consequence RTC registers (including
+ the backup registers) are set to their reset values.
+
+@endverbatim
+ * @{
+ */
+
+/**
+ * @brief Initializes the RCC extended peripherals clocks according to the specified
+ * parameters in the RCC_PeriphCLKInitTypeDef.
+ * @param PeriphClkInit pointer to an RCC_PeriphCLKInitTypeDef structure that
+ * contains the configuration information for the Extended Peripherals clocks
+ * (USART, RTC, I2C, CEC and USB).
+ *
+ * @note Care must be taken when @ref HAL_RCCEx_PeriphCLKConfig() is used to select
+ * the RTC clock source; in this case the Backup domain will be reset in
+ * order to modify the RTC Clock source, as consequence RTC registers (including
+ * the backup registers) and RCC_BDCR register are set to their reset values.
+ *
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_RCCEx_PeriphCLKConfig(RCC_PeriphCLKInitTypeDef *PeriphClkInit)
+{
+ uint32_t tickstart = 0U;
+ uint32_t temp_reg = 0U;
+
+ /* Check the parameters */
+ assert_param(IS_RCC_PERIPHCLOCK(PeriphClkInit->PeriphClockSelection));
+
+ /*---------------------------- RTC configuration -------------------------------*/
+ if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_RTC) == (RCC_PERIPHCLK_RTC))
+ {
+ /* check for RTC Parameters used to output RTCCLK */
+ assert_param(IS_RCC_RTCCLKSOURCE(PeriphClkInit->RTCClockSelection));
+
+ FlagStatus pwrclkchanged = RESET;
+
+ /* As soon as function is called to change RTC clock source, activation of the
+ power domain is done. */
+ /* Requires to enable write access to Backup Domain of necessary */
+ if(__HAL_RCC_PWR_IS_CLK_DISABLED())
+ {
+ __HAL_RCC_PWR_CLK_ENABLE();
+ pwrclkchanged = SET;
+ }
+
+ if(HAL_IS_BIT_CLR(PWR->CR, PWR_CR_DBP))
+ {
+ /* Enable write access to Backup domain */
+ SET_BIT(PWR->CR, PWR_CR_DBP);
+
+ /* Wait for Backup domain Write protection disable */
+ tickstart = HAL_GetTick();
+
+ while(HAL_IS_BIT_CLR(PWR->CR, PWR_CR_DBP))
+ {
+ if((HAL_GetTick() - tickstart) > RCC_DBP_TIMEOUT_VALUE)
+ {
+ return HAL_TIMEOUT;
+ }
+ }
+ }
+
+ /* Reset the Backup domain only if the RTC Clock source selection is modified from reset value */
+ temp_reg = (RCC->BDCR & RCC_BDCR_RTCSEL);
+ if((temp_reg != 0x00000000U) && (temp_reg != (PeriphClkInit->RTCClockSelection & RCC_BDCR_RTCSEL)))
+ {
+ /* Store the content of BDCR register before the reset of Backup Domain */
+ temp_reg = (RCC->BDCR & ~(RCC_BDCR_RTCSEL));
+ /* RTC Clock selection can be changed only if the Backup Domain is reset */
+ __HAL_RCC_BACKUPRESET_FORCE();
+ __HAL_RCC_BACKUPRESET_RELEASE();
+ /* Restore the Content of BDCR register */
+ RCC->BDCR = temp_reg;
+
+ /* Wait for LSERDY if LSE was enabled */
+ if (HAL_IS_BIT_SET(temp_reg, RCC_BDCR_LSEON))
+ {
+ /* Get Start Tick */
+ tickstart = HAL_GetTick();
+
+ /* Wait till LSE is ready */
+ while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) == RESET)
+ {
+ if((HAL_GetTick() - tickstart) > RCC_LSE_TIMEOUT_VALUE)
+ {
+ return HAL_TIMEOUT;
+ }
+ }
+ }
+ }
+ __HAL_RCC_RTC_CONFIG(PeriphClkInit->RTCClockSelection);
+
+ /* Require to disable power clock if necessary */
+ if(pwrclkchanged == SET)
+ {
+ __HAL_RCC_PWR_CLK_DISABLE();
+ }
+ }
+
+ /*------------------------------- USART1 Configuration ------------------------*/
+ if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_USART1) == RCC_PERIPHCLK_USART1)
+ {
+ /* Check the parameters */
+ assert_param(IS_RCC_USART1CLKSOURCE(PeriphClkInit->Usart1ClockSelection));
+
+ /* Configure the USART1 clock source */
+ __HAL_RCC_USART1_CONFIG(PeriphClkInit->Usart1ClockSelection);
+ }
+
+#if defined(STM32F071xB) || defined(STM32F072xB) || defined(STM32F078xx)\
+ || defined(STM32F091xC) || defined(STM32F098xx)
+ /*----------------------------- USART2 Configuration --------------------------*/
+ if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_USART2) == RCC_PERIPHCLK_USART2)
+ {
+ /* Check the parameters */
+ assert_param(IS_RCC_USART2CLKSOURCE(PeriphClkInit->Usart2ClockSelection));
+
+ /* Configure the USART2 clock source */
+ __HAL_RCC_USART2_CONFIG(PeriphClkInit->Usart2ClockSelection);
+ }
+#endif /* STM32F071xB || STM32F072xB || STM32F078xx || */
+ /* STM32F091xC || STM32F098xx */
+
+#if defined(STM32F091xC) || defined(STM32F098xx)
+ /*----------------------------- USART3 Configuration --------------------------*/
+ if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_USART3) == RCC_PERIPHCLK_USART3)
+ {
+ /* Check the parameters */
+ assert_param(IS_RCC_USART3CLKSOURCE(PeriphClkInit->Usart3ClockSelection));
+
+ /* Configure the USART3 clock source */
+ __HAL_RCC_USART3_CONFIG(PeriphClkInit->Usart3ClockSelection);
+ }
+#endif /* STM32F091xC || STM32F098xx */
+
+ /*------------------------------ I2C1 Configuration ------------------------*/
+ if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2C1) == RCC_PERIPHCLK_I2C1)
+ {
+ /* Check the parameters */
+ assert_param(IS_RCC_I2C1CLKSOURCE(PeriphClkInit->I2c1ClockSelection));
+
+ /* Configure the I2C1 clock source */
+ __HAL_RCC_I2C1_CONFIG(PeriphClkInit->I2c1ClockSelection);
+ }
+
+#if defined(STM32F042x6) || defined(STM32F048xx) || defined(STM32F072xB) || defined(STM32F078xx) || defined(STM32F070xB) || defined(STM32F070x6)
+ /*------------------------------ USB Configuration ------------------------*/
+ if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_USB) == RCC_PERIPHCLK_USB)
+ {
+ /* Check the parameters */
+ assert_param(IS_RCC_USBCLKSOURCE(PeriphClkInit->UsbClockSelection));
+
+ /* Configure the USB clock source */
+ __HAL_RCC_USB_CONFIG(PeriphClkInit->UsbClockSelection);
+ }
+#endif /* STM32F042x6 || STM32F048xx || STM32F072xB || STM32F078xx || STM32F070xB || STM32F070x6 */
+
+#if defined(STM32F042x6) || defined(STM32F048xx)\
+ || defined(STM32F051x8) || defined(STM32F058xx)\
+ || defined(STM32F071xB) || defined(STM32F072xB) || defined(STM32F078xx)\
+ || defined(STM32F091xC) || defined(STM32F098xx)
+ /*------------------------------ CEC clock Configuration -------------------*/
+ if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_CEC) == RCC_PERIPHCLK_CEC)
+ {
+ /* Check the parameters */
+ assert_param(IS_RCC_CECCLKSOURCE(PeriphClkInit->CecClockSelection));
+
+ /* Configure the CEC clock source */
+ __HAL_RCC_CEC_CONFIG(PeriphClkInit->CecClockSelection);
+ }
+#endif /* STM32F042x6 || STM32F048xx || */
+ /* STM32F051x8 || STM32F058xx || */
+ /* STM32F071xB || STM32F072xB || STM32F078xx || */
+ /* STM32F091xC || STM32F098xx */
+
+ return HAL_OK;
+}
+
+/**
+ * @brief Get the RCC_ClkInitStruct according to the internal
+ * RCC configuration registers.
+ * @param PeriphClkInit pointer to an RCC_PeriphCLKInitTypeDef structure that
+ * returns the configuration information for the Extended Peripherals clocks
+ * (USART, RTC, I2C, CEC and USB).
+ * @retval None
+ */
+void HAL_RCCEx_GetPeriphCLKConfig(RCC_PeriphCLKInitTypeDef *PeriphClkInit)
+{
+ /* Set all possible values for the extended clock type parameter------------*/
+ /* Common part first */
+ PeriphClkInit->PeriphClockSelection = RCC_PERIPHCLK_USART1 | RCC_PERIPHCLK_I2C1 | RCC_PERIPHCLK_RTC;
+ /* Get the RTC configuration --------------------------------------------*/
+ PeriphClkInit->RTCClockSelection = __HAL_RCC_GET_RTC_SOURCE();
+ /* Get the USART1 clock configuration --------------------------------------------*/
+ PeriphClkInit->Usart1ClockSelection = __HAL_RCC_GET_USART1_SOURCE();
+ /* Get the I2C1 clock source -----------------------------------------------*/
+ PeriphClkInit->I2c1ClockSelection = __HAL_RCC_GET_I2C1_SOURCE();
+
+#if defined(STM32F071xB) || defined(STM32F072xB) || defined(STM32F078xx)\
+ || defined(STM32F091xC) || defined(STM32F098xx)
+ PeriphClkInit->PeriphClockSelection |= RCC_PERIPHCLK_USART2;
+ /* Get the USART2 clock source ---------------------------------------------*/
+ PeriphClkInit->Usart2ClockSelection = __HAL_RCC_GET_USART2_SOURCE();
+#endif /* STM32F071xB || STM32F072xB || STM32F078xx || */
+ /* STM32F091xC || STM32F098xx */
+
+#if defined(STM32F091xC) || defined(STM32F098xx)
+ PeriphClkInit->PeriphClockSelection |= RCC_PERIPHCLK_USART3;
+ /* Get the USART3 clock source ---------------------------------------------*/
+ PeriphClkInit->Usart3ClockSelection = __HAL_RCC_GET_USART3_SOURCE();
+#endif /* STM32F091xC || STM32F098xx */
+
+#if defined(STM32F042x6) || defined(STM32F048xx) || defined(STM32F072xB) || defined(STM32F078xx) || defined(STM32F070xB) || defined(STM32F070x6)
+ PeriphClkInit->PeriphClockSelection |= RCC_PERIPHCLK_USB;
+ /* Get the USB clock source ---------------------------------------------*/
+ PeriphClkInit->UsbClockSelection = __HAL_RCC_GET_USB_SOURCE();
+#endif /* STM32F042x6 || STM32F048xx || STM32F072xB || STM32F078xx || STM32F070xB || STM32F070x6 */
+
+#if defined(STM32F042x6) || defined(STM32F048xx)\
+ || defined(STM32F051x8) || defined(STM32F058xx)\
+ || defined(STM32F071xB) || defined(STM32F072xB) || defined(STM32F078xx)\
+ || defined(STM32F091xC) || defined(STM32F098xx)
+ PeriphClkInit->PeriphClockSelection |= RCC_PERIPHCLK_CEC;
+ /* Get the CEC clock source ------------------------------------------------*/
+ PeriphClkInit->CecClockSelection = __HAL_RCC_GET_CEC_SOURCE();
+#endif /* STM32F042x6 || STM32F048xx || */
+ /* STM32F051x8 || STM32F058xx || */
+ /* STM32F071xB || STM32F072xB || STM32F078xx || */
+ /* STM32F091xC || STM32F098xx */
+
+}
+
+/**
+ * @brief Returns the peripheral clock frequency
+ * @note Returns 0 if peripheral clock is unknown
+ * @param PeriphClk Peripheral clock identifier
+ * This parameter can be one of the following values:
+ * @arg @ref RCC_PERIPHCLK_RTC RTC peripheral clock
+ * @arg @ref RCC_PERIPHCLK_USART1 USART1 peripheral clock
+ * @arg @ref RCC_PERIPHCLK_I2C1 I2C1 peripheral clock
+ @if STM32F042x6
+ * @arg @ref RCC_PERIPHCLK_USB USB peripheral clock
+ * @arg @ref RCC_PERIPHCLK_CEC CEC peripheral clock
+ @endif
+ @if STM32F048xx
+ * @arg @ref RCC_PERIPHCLK_USB USB peripheral clock
+ * @arg @ref RCC_PERIPHCLK_CEC CEC peripheral clock
+ @endif
+ @if STM32F051x8
+ * @arg @ref RCC_PERIPHCLK_CEC CEC peripheral clock
+ @endif
+ @if STM32F058xx
+ * @arg @ref RCC_PERIPHCLK_CEC CEC peripheral clock
+ @endif
+ @if STM32F070x6
+ * @arg @ref RCC_PERIPHCLK_USB USB peripheral clock
+ @endif
+ @if STM32F070xB
+ * @arg @ref RCC_PERIPHCLK_USB USB peripheral clock
+ @endif
+ @if STM32F071xB
+ * @arg @ref RCC_PERIPHCLK_USART2 USART2 peripheral clock
+ * @arg @ref RCC_PERIPHCLK_CEC CEC peripheral clock
+ @endif
+ @if STM32F072xB
+ * @arg @ref RCC_PERIPHCLK_USART2 USART2 peripheral clock
+ * @arg @ref RCC_PERIPHCLK_USB USB peripheral clock
+ * @arg @ref RCC_PERIPHCLK_CEC CEC peripheral clock
+ @endif
+ @if STM32F078xx
+ * @arg @ref RCC_PERIPHCLK_USART2 USART2 peripheral clock
+ * @arg @ref RCC_PERIPHCLK_USB USB peripheral clock
+ * @arg @ref RCC_PERIPHCLK_CEC CEC peripheral clock
+ @endif
+ @if STM32F091xC
+ * @arg @ref RCC_PERIPHCLK_USART2 USART2 peripheral clock
+ * @arg @ref RCC_PERIPHCLK_USART3 USART2 peripheral clock
+ * @arg @ref RCC_PERIPHCLK_CEC CEC peripheral clock
+ @endif
+ @if STM32F098xx
+ * @arg @ref RCC_PERIPHCLK_USART2 USART2 peripheral clock
+ * @arg @ref RCC_PERIPHCLK_USART3 USART2 peripheral clock
+ * @arg @ref RCC_PERIPHCLK_CEC CEC peripheral clock
+ @endif
+ * @retval Frequency in Hz (0: means that no available frequency for the peripheral)
+ */
+uint32_t HAL_RCCEx_GetPeriphCLKFreq(uint32_t PeriphClk)
+{
+ /* frequency == 0 : means that no available frequency for the peripheral */
+ uint32_t frequency = 0U;
+
+ uint32_t srcclk = 0U;
+#if defined(USB)
+ uint32_t pllmull = 0U, pllsource = 0U, predivfactor = 0U;
+#endif /* USB */
+
+ /* Check the parameters */
+ assert_param(IS_RCC_PERIPHCLOCK(PeriphClk));
+
+ switch (PeriphClk)
+ {
+ case RCC_PERIPHCLK_RTC:
+ {
+ /* Get the current RTC source */
+ srcclk = __HAL_RCC_GET_RTC_SOURCE();
+
+ /* Check if LSE is ready and if RTC clock selection is LSE */
+ if ((srcclk == RCC_RTCCLKSOURCE_LSE) && (HAL_IS_BIT_SET(RCC->BDCR, RCC_BDCR_LSERDY)))
+ {
+ frequency = LSE_VALUE;
+ }
+ /* Check if LSI is ready and if RTC clock selection is LSI */
+ else if ((srcclk == RCC_RTCCLKSOURCE_LSI) && (HAL_IS_BIT_SET(RCC->CSR, RCC_CSR_LSIRDY)))
+ {
+ frequency = LSI_VALUE;
+ }
+ /* Check if HSE is ready and if RTC clock selection is HSI_DIV32*/
+ else if ((srcclk == RCC_RTCCLKSOURCE_HSE_DIV32) && (HAL_IS_BIT_SET(RCC->CR, RCC_CR_HSERDY)))
+ {
+ frequency = HSE_VALUE / 32U;
+ }
+ break;
+ }
+ case RCC_PERIPHCLK_USART1:
+ {
+ /* Get the current USART1 source */
+ srcclk = __HAL_RCC_GET_USART1_SOURCE();
+
+ /* Check if USART1 clock selection is PCLK1 */
+ if (srcclk == RCC_USART1CLKSOURCE_PCLK1)
+ {
+ frequency = HAL_RCC_GetPCLK1Freq();
+ }
+ /* Check if HSI is ready and if USART1 clock selection is HSI */
+ else if ((srcclk == RCC_USART1CLKSOURCE_HSI) && (HAL_IS_BIT_SET(RCC->CR, RCC_CR_HSIRDY)))
+ {
+ frequency = HSI_VALUE;
+ }
+ /* Check if USART1 clock selection is SYSCLK */
+ else if (srcclk == RCC_USART1CLKSOURCE_SYSCLK)
+ {
+ frequency = HAL_RCC_GetSysClockFreq();
+ }
+ /* Check if LSE is ready and if USART1 clock selection is LSE */
+ else if ((srcclk == RCC_USART1CLKSOURCE_LSE) && (HAL_IS_BIT_SET(RCC->BDCR, RCC_BDCR_LSERDY)))
+ {
+ frequency = LSE_VALUE;
+ }
+ break;
+ }
+#if defined(RCC_CFGR3_USART2SW)
+ case RCC_PERIPHCLK_USART2:
+ {
+ /* Get the current USART2 source */
+ srcclk = __HAL_RCC_GET_USART2_SOURCE();
+
+ /* Check if USART2 clock selection is PCLK1 */
+ if (srcclk == RCC_USART2CLKSOURCE_PCLK1)
+ {
+ frequency = HAL_RCC_GetPCLK1Freq();
+ }
+ /* Check if HSI is ready and if USART2 clock selection is HSI */
+ else if ((srcclk == RCC_USART2CLKSOURCE_HSI) && (HAL_IS_BIT_SET(RCC->CR, RCC_CR_HSIRDY)))
+ {
+ frequency = HSI_VALUE;
+ }
+ /* Check if USART2 clock selection is SYSCLK */
+ else if (srcclk == RCC_USART2CLKSOURCE_SYSCLK)
+ {
+ frequency = HAL_RCC_GetSysClockFreq();
+ }
+ /* Check if LSE is ready and if USART2 clock selection is LSE */
+ else if ((srcclk == RCC_USART2CLKSOURCE_LSE) && (HAL_IS_BIT_SET(RCC->BDCR, RCC_BDCR_LSERDY)))
+ {
+ frequency = LSE_VALUE;
+ }
+ break;
+ }
+#endif /* RCC_CFGR3_USART2SW */
+#if defined(RCC_CFGR3_USART3SW)
+ case RCC_PERIPHCLK_USART3:
+ {
+ /* Get the current USART3 source */
+ srcclk = __HAL_RCC_GET_USART3_SOURCE();
+
+ /* Check if USART3 clock selection is PCLK1 */
+ if (srcclk == RCC_USART3CLKSOURCE_PCLK1)
+ {
+ frequency = HAL_RCC_GetPCLK1Freq();
+ }
+ /* Check if HSI is ready and if USART3 clock selection is HSI */
+ else if ((srcclk == RCC_USART3CLKSOURCE_HSI) && (HAL_IS_BIT_SET(RCC->CR, RCC_CR_HSIRDY)))
+ {
+ frequency = HSI_VALUE;
+ }
+ /* Check if USART3 clock selection is SYSCLK */
+ else if (srcclk == RCC_USART3CLKSOURCE_SYSCLK)
+ {
+ frequency = HAL_RCC_GetSysClockFreq();
+ }
+ /* Check if LSE is ready and if USART3 clock selection is LSE */
+ else if ((srcclk == RCC_USART3CLKSOURCE_LSE) && (HAL_IS_BIT_SET(RCC->BDCR, RCC_BDCR_LSERDY)))
+ {
+ frequency = LSE_VALUE;
+ }
+ break;
+ }
+#endif /* RCC_CFGR3_USART3SW */
+ case RCC_PERIPHCLK_I2C1:
+ {
+ /* Get the current I2C1 source */
+ srcclk = __HAL_RCC_GET_I2C1_SOURCE();
+
+ /* Check if HSI is ready and if I2C1 clock selection is HSI */
+ if ((srcclk == RCC_I2C1CLKSOURCE_HSI) && (HAL_IS_BIT_SET(RCC->CR, RCC_CR_HSIRDY)))
+ {
+ frequency = HSI_VALUE;
+ }
+ /* Check if I2C1 clock selection is SYSCLK */
+ else if (srcclk == RCC_I2C1CLKSOURCE_SYSCLK)
+ {
+ frequency = HAL_RCC_GetSysClockFreq();
+ }
+ break;
+ }
+#if defined(USB)
+ case RCC_PERIPHCLK_USB:
+ {
+ /* Get the current USB source */
+ srcclk = __HAL_RCC_GET_USB_SOURCE();
+
+ /* Check if PLL is ready and if USB clock selection is PLL */
+ if ((srcclk == RCC_USBCLKSOURCE_PLL) && (HAL_IS_BIT_SET(RCC->CR, RCC_CR_PLLRDY)))
+ {
+ /* Get PLL clock source and multiplication factor ----------------------*/
+ pllmull = RCC->CFGR & RCC_CFGR_PLLMUL;
+ pllsource = RCC->CFGR & RCC_CFGR_PLLSRC;
+ pllmull = (pllmull >> RCC_CFGR_PLLMUL_BITNUMBER) + 2U;
+ predivfactor = (RCC->CFGR2 & RCC_CFGR2_PREDIV) + 1U;
+
+ if (pllsource == RCC_CFGR_PLLSRC_HSE_PREDIV)
+ {
+ /* HSE used as PLL clock source : frequency = HSE/PREDIV * PLLMUL */
+ frequency = (HSE_VALUE/predivfactor) * pllmull;
+ }
+#if defined(RCC_CR2_HSI48ON)
+ else if (pllsource == RCC_CFGR_PLLSRC_HSI48_PREDIV)
+ {
+ /* HSI48 used as PLL clock source : frequency = HSI48/PREDIV * PLLMUL */
+ frequency = (HSI48_VALUE / predivfactor) * pllmull;
+ }
+#endif /* RCC_CR2_HSI48ON */
+ else
+ {
+#if defined(STM32F042x6) || defined(STM32F048xx) || defined(STM32F078xx) || defined(STM32F072xB) || defined(STM32F070xB)
+ /* HSI used as PLL clock source : frequency = HSI/PREDIV * PLLMUL */
+ frequency = (HSI_VALUE / predivfactor) * pllmull;
+#else
+ /* HSI used as PLL clock source : frequency = HSI/2U * PLLMUL */
+ frequency = (HSI_VALUE >> 1U) * pllmull;
+#endif /* STM32F042x6 || STM32F048xx || STM32F072xB || STM32F078xx || STM32F070xB */
+ }
+ }
+#if defined(RCC_CR2_HSI48ON)
+ /* Check if HSI48 is ready and if USB clock selection is HSI48 */
+ else if ((srcclk == RCC_USBCLKSOURCE_HSI48) && (HAL_IS_BIT_SET(RCC->CR2, RCC_CR2_HSI48RDY)))
+ {
+ frequency = HSI48_VALUE;
+ }
+#endif /* RCC_CR2_HSI48ON */
+ break;
+ }
+#endif /* USB */
+#if defined(CEC)
+ case RCC_PERIPHCLK_CEC:
+ {
+ /* Get the current CEC source */
+ srcclk = __HAL_RCC_GET_CEC_SOURCE();
+
+ /* Check if HSI is ready and if CEC clock selection is HSI */
+ if ((srcclk == RCC_CECCLKSOURCE_HSI) && (HAL_IS_BIT_SET(RCC->CR, RCC_CR_HSIRDY)))
+ {
+ frequency = HSI_VALUE;
+ }
+ /* Check if LSE is ready and if CEC clock selection is LSE */
+ else if ((srcclk == RCC_CECCLKSOURCE_LSE) && (HAL_IS_BIT_SET(RCC->BDCR, RCC_BDCR_LSERDY)))
+ {
+ frequency = LSE_VALUE;
+ }
+ break;
+ }
+#endif /* CEC */
+ default:
+ {
+ break;
+ }
+ }
+ return(frequency);
+}
+
+/**
+ * @}
+ */
+
+#if defined(CRS)
+
+/** @defgroup RCCEx_Exported_Functions_Group3 Extended Clock Recovery System Control functions
+ * @brief Extended Clock Recovery System Control functions
+ *
+@verbatim
+ ===============================================================================
+ ##### Extended Clock Recovery System Control functions #####
+ ===============================================================================
+ [..]
+ For devices with Clock Recovery System feature (CRS), RCC Extension HAL driver can be used as follows:
+
+ (#) In System clock config, HSI48 needs to be enabled
+
+ (#) Enable CRS clock in IP MSP init which will use CRS functions
+
+ (#) Call CRS functions as follows:
+ (##) Prepare synchronization configuration necessary for HSI48 calibration
+ (+++) Default values can be set for frequency Error Measurement (reload and error limit)
+ and also HSI48 oscillator smooth trimming.
+ (+++) Macro __HAL_RCC_CRS_RELOADVALUE_CALCULATE can be also used to calculate
+ directly reload value with target and synchronization frequencies values
+ (##) Call function HAL_RCCEx_CRSConfig which
+ (+++) Reset CRS registers to their default values.
+ (+++) Configure CRS registers with synchronization configuration
+ (+++) Enable automatic calibration and frequency error counter feature
+ Note: When using USB LPM (Link Power Management) and the device is in Sleep mode, the
+ periodic USB SOF will not be generated by the host. No SYNC signal will therefore be
+ provided to the CRS to calibrate the HSI48 on the run. To guarantee the required clock
+ precision after waking up from Sleep mode, the LSE or reference clock on the GPIOs
+ should be used as SYNC signal.
+
+ (##) A polling function is provided to wait for complete synchronization
+ (+++) Call function HAL_RCCEx_CRSWaitSynchronization()
+ (+++) According to CRS status, user can decide to adjust again the calibration or continue
+ application if synchronization is OK
+
+ (#) User can retrieve information related to synchronization in calling function
+ HAL_RCCEx_CRSGetSynchronizationInfo()
+
+ (#) Regarding synchronization status and synchronization information, user can try a new calibration
+ in changing synchronization configuration and call again HAL_RCCEx_CRSConfig.
+ Note: When the SYNC event is detected during the downcounting phase (before reaching the zero value),
+ it means that the actual frequency is lower than the target (and so, that the TRIM value should be
+ incremented), while when it is detected during the upcounting phase it means that the actual frequency
+ is higher (and that the TRIM value should be decremented).
+
+ (#) In interrupt mode, user can resort to the available macros (__HAL_RCC_CRS_XXX_IT). Interrupts will go
+ through CRS Handler (RCC_IRQn/RCC_IRQHandler)
+ (++) Call function HAL_RCCEx_CRSConfig()
+ (++) Enable RCC_IRQn (thanks to NVIC functions)
+ (++) Enable CRS interrupt (__HAL_RCC_CRS_ENABLE_IT)
+ (++) Implement CRS status management in the following user callbacks called from
+ HAL_RCCEx_CRS_IRQHandler():
+ (+++) HAL_RCCEx_CRS_SyncOkCallback()
+ (+++) HAL_RCCEx_CRS_SyncWarnCallback()
+ (+++) HAL_RCCEx_CRS_ExpectedSyncCallback()
+ (+++) HAL_RCCEx_CRS_ErrorCallback()
+
+ (#) To force a SYNC EVENT, user can use the function HAL_RCCEx_CRSSoftwareSynchronizationGenerate().
+ This function can be called before calling HAL_RCCEx_CRSConfig (for instance in Systick handler)
+
+@endverbatim
+ * @{
+ */
+
+/**
+ * @brief Start automatic synchronization for polling mode
+ * @param pInit Pointer on RCC_CRSInitTypeDef structure
+ * @retval None
+ */
+void HAL_RCCEx_CRSConfig(RCC_CRSInitTypeDef *pInit)
+{
+ uint32_t value = 0U;
+
+ /* Check the parameters */
+ assert_param(IS_RCC_CRS_SYNC_DIV(pInit->Prescaler));
+ assert_param(IS_RCC_CRS_SYNC_SOURCE(pInit->Source));
+ assert_param(IS_RCC_CRS_SYNC_POLARITY(pInit->Polarity));
+ assert_param(IS_RCC_CRS_RELOADVALUE(pInit->ReloadValue));
+ assert_param(IS_RCC_CRS_ERRORLIMIT(pInit->ErrorLimitValue));
+ assert_param(IS_RCC_CRS_HSI48CALIBRATION(pInit->HSI48CalibrationValue));
+
+ /* CONFIGURATION */
+
+ /* Before configuration, reset CRS registers to their default values*/
+ __HAL_RCC_CRS_FORCE_RESET();
+ __HAL_RCC_CRS_RELEASE_RESET();
+
+ /* Set the SYNCDIV[2:0] bits according to Prescaler value */
+ /* Set the SYNCSRC[1:0] bits according to Source value */
+ /* Set the SYNCSPOL bit according to Polarity value */
+ value = (pInit->Prescaler | pInit->Source | pInit->Polarity);
+ /* Set the RELOAD[15:0] bits according to ReloadValue value */
+ value |= pInit->ReloadValue;
+ /* Set the FELIM[7:0] bits according to ErrorLimitValue value */
+ value |= (pInit->ErrorLimitValue << CRS_CFGR_FELIM_BITNUMBER);
+ WRITE_REG(CRS->CFGR, value);
+
+ /* Adjust HSI48 oscillator smooth trimming */
+ /* Set the TRIM[5:0] bits according to RCC_CRS_HSI48CalibrationValue value */
+ MODIFY_REG(CRS->CR, CRS_CR_TRIM, (pInit->HSI48CalibrationValue << CRS_CR_TRIM_BITNUMBER));
+
+ /* START AUTOMATIC SYNCHRONIZATION*/
+
+ /* Enable Automatic trimming & Frequency error counter */
+ SET_BIT(CRS->CR, CRS_CR_AUTOTRIMEN | CRS_CR_CEN);
+}
+
+/**
+ * @brief Generate the software synchronization event
+ * @retval None
+ */
+void HAL_RCCEx_CRSSoftwareSynchronizationGenerate(void)
+{
+ SET_BIT(CRS->CR, CRS_CR_SWSYNC);
+}
+
+/**
+ * @brief Return synchronization info
+ * @param pSynchroInfo Pointer on RCC_CRSSynchroInfoTypeDef structure
+ * @retval None
+ */
+void HAL_RCCEx_CRSGetSynchronizationInfo(RCC_CRSSynchroInfoTypeDef *pSynchroInfo)
+{
+ /* Check the parameter */
+ assert_param(pSynchroInfo != NULL);
+
+ /* Get the reload value */
+ pSynchroInfo->ReloadValue = (uint32_t)(READ_BIT(CRS->CFGR, CRS_CFGR_RELOAD));
+
+ /* Get HSI48 oscillator smooth trimming */
+ pSynchroInfo->HSI48CalibrationValue = (uint32_t)(READ_BIT(CRS->CR, CRS_CR_TRIM) >> CRS_CR_TRIM_BITNUMBER);
+
+ /* Get Frequency error capture */
+ pSynchroInfo->FreqErrorCapture = (uint32_t)(READ_BIT(CRS->ISR, CRS_ISR_FECAP) >> CRS_ISR_FECAP_BITNUMBER);
+
+ /* Get Frequency error direction */
+ pSynchroInfo->FreqErrorDirection = (uint32_t)(READ_BIT(CRS->ISR, CRS_ISR_FEDIR));
+}
+
+/**
+* @brief Wait for CRS Synchronization status.
+* @param Timeout Duration of the timeout
+* @note Timeout is based on the maximum time to receive a SYNC event based on synchronization
+* frequency.
+* @note If Timeout set to HAL_MAX_DELAY, HAL_TIMEOUT will be never returned.
+* @retval Combination of Synchronization status
+* This parameter can be a combination of the following values:
+* @arg @ref RCC_CRS_TIMEOUT
+* @arg @ref RCC_CRS_SYNCOK
+* @arg @ref RCC_CRS_SYNCWARN
+* @arg @ref RCC_CRS_SYNCERR
+* @arg @ref RCC_CRS_SYNCMISS
+* @arg @ref RCC_CRS_TRIMOVF
+*/
+uint32_t HAL_RCCEx_CRSWaitSynchronization(uint32_t Timeout)
+{
+ uint32_t crsstatus = RCC_CRS_NONE;
+ uint32_t tickstart = 0U;
+
+ /* Get timeout */
+ tickstart = HAL_GetTick();
+
+ /* Wait for CRS flag or timeout detection */
+ do
+ {
+ if(Timeout != HAL_MAX_DELAY)
+ {
+ if((Timeout == 0U) || ((HAL_GetTick() - tickstart) > Timeout))
+ {
+ crsstatus = RCC_CRS_TIMEOUT;
+ }
+ }
+ /* Check CRS SYNCOK flag */
+ if(__HAL_RCC_CRS_GET_FLAG(RCC_CRS_FLAG_SYNCOK))
+ {
+ /* CRS SYNC event OK */
+ crsstatus |= RCC_CRS_SYNCOK;
+
+ /* Clear CRS SYNC event OK bit */
+ __HAL_RCC_CRS_CLEAR_FLAG(RCC_CRS_FLAG_SYNCOK);
+ }
+
+ /* Check CRS SYNCWARN flag */
+ if(__HAL_RCC_CRS_GET_FLAG(RCC_CRS_FLAG_SYNCWARN))
+ {
+ /* CRS SYNC warning */
+ crsstatus |= RCC_CRS_SYNCWARN;
+
+ /* Clear CRS SYNCWARN bit */
+ __HAL_RCC_CRS_CLEAR_FLAG(RCC_CRS_FLAG_SYNCWARN);
+ }
+
+ /* Check CRS TRIM overflow flag */
+ if(__HAL_RCC_CRS_GET_FLAG(RCC_CRS_FLAG_TRIMOVF))
+ {
+ /* CRS SYNC Error */
+ crsstatus |= RCC_CRS_TRIMOVF;
+
+ /* Clear CRS Error bit */
+ __HAL_RCC_CRS_CLEAR_FLAG(RCC_CRS_FLAG_TRIMOVF);
+ }
+
+ /* Check CRS Error flag */
+ if(__HAL_RCC_CRS_GET_FLAG(RCC_CRS_FLAG_SYNCERR))
+ {
+ /* CRS SYNC Error */
+ crsstatus |= RCC_CRS_SYNCERR;
+
+ /* Clear CRS Error bit */
+ __HAL_RCC_CRS_CLEAR_FLAG(RCC_CRS_FLAG_SYNCERR);
+ }
+
+ /* Check CRS SYNC Missed flag */
+ if(__HAL_RCC_CRS_GET_FLAG(RCC_CRS_FLAG_SYNCMISS))
+ {
+ /* CRS SYNC Missed */
+ crsstatus |= RCC_CRS_SYNCMISS;
+
+ /* Clear CRS SYNC Missed bit */
+ __HAL_RCC_CRS_CLEAR_FLAG(RCC_CRS_FLAG_SYNCMISS);
+ }
+
+ /* Check CRS Expected SYNC flag */
+ if(__HAL_RCC_CRS_GET_FLAG(RCC_CRS_FLAG_ESYNC))
+ {
+ /* frequency error counter reached a zero value */
+ __HAL_RCC_CRS_CLEAR_FLAG(RCC_CRS_FLAG_ESYNC);
+ }
+ } while(RCC_CRS_NONE == crsstatus);
+
+ return crsstatus;
+}
+
+/**
+ * @brief Handle the Clock Recovery System interrupt request.
+ * @retval None
+ */
+void HAL_RCCEx_CRS_IRQHandler(void)
+{
+ uint32_t crserror = RCC_CRS_NONE;
+ /* Get current IT flags and IT sources values */
+ uint32_t itflags = READ_REG(CRS->ISR);
+ uint32_t itsources = READ_REG(CRS->CR);
+
+ /* Check CRS SYNCOK flag */
+ if(((itflags & RCC_CRS_FLAG_SYNCOK) != RESET) && ((itsources & RCC_CRS_IT_SYNCOK) != RESET))
+ {
+ /* Clear CRS SYNC event OK flag */
+ WRITE_REG(CRS->ICR, CRS_ICR_SYNCOKC);
+
+ /* user callback */
+ HAL_RCCEx_CRS_SyncOkCallback();
+ }
+ /* Check CRS SYNCWARN flag */
+ else if(((itflags & RCC_CRS_FLAG_SYNCWARN) != RESET) && ((itsources & RCC_CRS_IT_SYNCWARN) != RESET))
+ {
+ /* Clear CRS SYNCWARN flag */
+ WRITE_REG(CRS->ICR, CRS_ICR_SYNCWARNC);
+
+ /* user callback */
+ HAL_RCCEx_CRS_SyncWarnCallback();
+ }
+ /* Check CRS Expected SYNC flag */
+ else if(((itflags & RCC_CRS_FLAG_ESYNC) != RESET) && ((itsources & RCC_CRS_IT_ESYNC) != RESET))
+ {
+ /* frequency error counter reached a zero value */
+ WRITE_REG(CRS->ICR, CRS_ICR_ESYNCC);
+
+ /* user callback */
+ HAL_RCCEx_CRS_ExpectedSyncCallback();
+ }
+ /* Check CRS Error flags */
+ else
+ {
+ if(((itflags & RCC_CRS_FLAG_ERR) != RESET) && ((itsources & RCC_CRS_IT_ERR) != RESET))
+ {
+ if((itflags & RCC_CRS_FLAG_SYNCERR) != RESET)
+ {
+ crserror |= RCC_CRS_SYNCERR;
+ }
+ if((itflags & RCC_CRS_FLAG_SYNCMISS) != RESET)
+ {
+ crserror |= RCC_CRS_SYNCMISS;
+ }
+ if((itflags & RCC_CRS_FLAG_TRIMOVF) != RESET)
+ {
+ crserror |= RCC_CRS_TRIMOVF;
+ }
+
+ /* Clear CRS Error flags */
+ WRITE_REG(CRS->ICR, CRS_ICR_ERRC);
+
+ /* user error callback */
+ HAL_RCCEx_CRS_ErrorCallback(crserror);
+ }
+ }
+}
+
+/**
+ * @brief RCCEx Clock Recovery System SYNCOK interrupt callback.
+ * @retval none
+ */
+__weak void HAL_RCCEx_CRS_SyncOkCallback(void)
+{
+ /* NOTE : This function should not be modified, when the callback is needed,
+ the @ref HAL_RCCEx_CRS_SyncOkCallback should be implemented in the user file
+ */
+}
+
+/**
+ * @brief RCCEx Clock Recovery System SYNCWARN interrupt callback.
+ * @retval none
+ */
+__weak void HAL_RCCEx_CRS_SyncWarnCallback(void)
+{
+ /* NOTE : This function should not be modified, when the callback is needed,
+ the @ref HAL_RCCEx_CRS_SyncWarnCallback should be implemented in the user file
+ */
+}
+
+/**
+ * @brief RCCEx Clock Recovery System Expected SYNC interrupt callback.
+ * @retval none
+ */
+__weak void HAL_RCCEx_CRS_ExpectedSyncCallback(void)
+{
+ /* NOTE : This function should not be modified, when the callback is needed,
+ the @ref HAL_RCCEx_CRS_ExpectedSyncCallback should be implemented in the user file
+ */
+}
+
+/**
+ * @brief RCCEx Clock Recovery System Error interrupt callback.
+ * @param Error Combination of Error status.
+ * This parameter can be a combination of the following values:
+ * @arg @ref RCC_CRS_SYNCERR
+ * @arg @ref RCC_CRS_SYNCMISS
+ * @arg @ref RCC_CRS_TRIMOVF
+ * @retval none
+ */
+__weak void HAL_RCCEx_CRS_ErrorCallback(uint32_t Error)
+{
+ /* Prevent unused argument(s) compilation warning */
+ UNUSED(Error);
+
+ /* NOTE : This function should not be modified, when the callback is needed,
+ the @ref HAL_RCCEx_CRS_ErrorCallback should be implemented in the user file
+ */
+}
+
+/**
+ * @}
+ */
+
+#endif /* CRS */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+#endif /* HAL_RCC_MODULE_ENABLED */
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_spi.c b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_spi.c
new file mode 100644
index 0000000..2ddf042
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_spi.c
@@ -0,0 +1,4404 @@
+/**
+ ******************************************************************************
+ * @file stm32f0xx_hal_spi.c
+ * @author MCD Application Team
+ * @brief SPI HAL module driver.
+ * This file provides firmware functions to manage the following
+ * functionalities of the Serial Peripheral Interface (SPI) peripheral:
+ * + Initialization and de-initialization functions
+ * + IO operation functions
+ * + Peripheral Control functions
+ * + Peripheral State functions
+ *
+ @verbatim
+ ==============================================================================
+ ##### How to use this driver #####
+ ==============================================================================
+ [..]
+ The SPI HAL driver can be used as follows:
+
+ (#) Declare a SPI_HandleTypeDef handle structure, for example:
+ SPI_HandleTypeDef hspi;
+
+ (#)Initialize the SPI low level resources by implementing the HAL_SPI_MspInit() API:
+ (##) Enable the SPIx interface clock
+ (##) SPI pins configuration
+ (+++) Enable the clock for the SPI GPIOs
+ (+++) Configure these SPI pins as alternate function push-pull
+ (##) NVIC configuration if you need to use interrupt process
+ (+++) Configure the SPIx interrupt priority
+ (+++) Enable the NVIC SPI IRQ handle
+ (##) DMA Configuration if you need to use DMA process
+ (+++) Declare a DMA_HandleTypeDef handle structure for the transmit or receive Stream/Channel
+ (+++) Enable the DMAx clock
+ (+++) Configure the DMA handle parameters
+ (+++) Configure the DMA Tx or Rx Stream/Channel
+ (+++) Associate the initialized hdma_tx(or _rx) handle to the hspi DMA Tx or Rx handle
+ (+++) Configure the priority and enable the NVIC for the transfer complete interrupt on the DMA Tx or Rx Stream/Channel
+
+ (#) Program the Mode, BidirectionalMode , Data size, Baudrate Prescaler, NSS
+ management, Clock polarity and phase, FirstBit and CRC configuration in the hspi Init structure.
+
+ (#) Initialize the SPI registers by calling the HAL_SPI_Init() API:
+ (++) This API configures also the low level Hardware GPIO, CLOCK, CORTEX...etc)
+ by calling the customized HAL_SPI_MspInit() API.
+ [..]
+ Circular mode restriction:
+ (#) The DMA circular mode cannot be used when the SPI is configured in these modes:
+ (##) Master 2Lines RxOnly
+ (##) Master 1Line Rx
+ (#) The CRC feature is not managed when the DMA circular mode is enabled
+ (#) When the SPI DMA Pause/Stop features are used, we must use the following APIs
+ the HAL_SPI_DMAPause()/ HAL_SPI_DMAStop() only under the SPI callbacks
+ [..]
+ Master Receive mode restriction:
+ (#) In Master unidirectional receive-only mode (MSTR =1, BIDIMODE=0, RXONLY=1) or
+ bidirectional receive mode (MSTR=1, BIDIMODE=1, BIDIOE=0), to ensure that the SPI
+ does not initiate a new transfer the following procedure has to be respected:
+ (##) HAL_SPI_DeInit()
+ (##) HAL_SPI_Init()
+ [..]
+ Callback registration:
+
+ (#) The compilation flag USE_HAL_SPI_REGISTER_CALLBACKS when set to 1U
+ allows the user to configure dynamically the driver callbacks.
+ Use Functions HAL_SPI_RegisterCallback() to register an interrupt callback.
+
+ Function HAL_SPI_RegisterCallback() allows to register following callbacks:
+ (++) TxCpltCallback : SPI Tx Completed callback
+ (++) RxCpltCallback : SPI Rx Completed callback
+ (++) TxRxCpltCallback : SPI TxRx Completed callback
+ (++) TxHalfCpltCallback : SPI Tx Half Completed callback
+ (++) RxHalfCpltCallback : SPI Rx Half Completed callback
+ (++) TxRxHalfCpltCallback : SPI TxRx Half Completed callback
+ (++) ErrorCallback : SPI Error callback
+ (++) AbortCpltCallback : SPI Abort callback
+ (++) MspInitCallback : SPI Msp Init callback
+ (++) MspDeInitCallback : SPI Msp DeInit callback
+ This function takes as parameters the HAL peripheral handle, the Callback ID
+ and a pointer to the user callback function.
+
+
+ (#) Use function HAL_SPI_UnRegisterCallback to reset a callback to the default
+ weak function.
+ HAL_SPI_UnRegisterCallback takes as parameters the HAL peripheral handle,
+ and the Callback ID.
+ This function allows to reset following callbacks:
+ (++) TxCpltCallback : SPI Tx Completed callback
+ (++) RxCpltCallback : SPI Rx Completed callback
+ (++) TxRxCpltCallback : SPI TxRx Completed callback
+ (++) TxHalfCpltCallback : SPI Tx Half Completed callback
+ (++) RxHalfCpltCallback : SPI Rx Half Completed callback
+ (++) TxRxHalfCpltCallback : SPI TxRx Half Completed callback
+ (++) ErrorCallback : SPI Error callback
+ (++) AbortCpltCallback : SPI Abort callback
+ (++) MspInitCallback : SPI Msp Init callback
+ (++) MspDeInitCallback : SPI Msp DeInit callback
+
+ [..]
+ By default, after the HAL_SPI_Init() and when the state is HAL_SPI_STATE_RESET
+ all callbacks are set to the corresponding weak functions:
+ examples HAL_SPI_MasterTxCpltCallback(), HAL_SPI_MasterRxCpltCallback().
+ Exception done for MspInit and MspDeInit functions that are
+ reset to the legacy weak functions in the HAL_SPI_Init()/ HAL_SPI_DeInit() only when
+ these callbacks are null (not registered beforehand).
+ If MspInit or MspDeInit are not null, the HAL_SPI_Init()/ HAL_SPI_DeInit()
+ keep and use the user MspInit/MspDeInit callbacks (registered beforehand) whatever the state.
+
+ [..]
+ Callbacks can be registered/unregistered in HAL_SPI_STATE_READY state only.
+ Exception done MspInit/MspDeInit functions that can be registered/unregistered
+ in HAL_SPI_STATE_READY or HAL_SPI_STATE_RESET state,
+ thus registered (user) MspInit/DeInit callbacks can be used during the Init/DeInit.
+ Then, the user first registers the MspInit/MspDeInit user callbacks
+ using HAL_SPI_RegisterCallback() before calling HAL_SPI_DeInit()
+ or HAL_SPI_Init() function.
+
+ [..]
+ When the compilation define USE_HAL_PPP_REGISTER_CALLBACKS is set to 0 or
+ not defined, the callback registering feature is not available
+ and weak (surcharged) callbacks are used.
+
+ [..]
+ Using the HAL it is not possible to reach all supported SPI frequency with the different SPI Modes,
+ the following table resume the max SPI frequency reached with data size 8bits/16bits,
+ according to frequency of the APBx Peripheral Clock (fPCLK) used by the SPI instance.
+
+ @endverbatim
+
+ Additional table :
+
+ DataSize = SPI_DATASIZE_8BIT:
+ +----------------------------------------------------------------------------------------------+
+ | | | 2Lines Fullduplex | 2Lines RxOnly | 1Line |
+ | Process | Transfer mode |---------------------|----------------------|----------------------|
+ | | | Master | Slave | Master | Slave | Master | Slave |
+ |==============================================================================================|
+ | T | Polling | Fpclk/4 | Fpclk/8 | NA | NA | NA | NA |
+ | X |----------------|----------|----------|-----------|----------|-----------|----------|
+ | / | Interrupt | Fpclk/4 | Fpclk/16 | NA | NA | NA | NA |
+ | R |----------------|----------|----------|-----------|----------|-----------|----------|
+ | X | DMA | Fpclk/2 | Fpclk/2 | NA | NA | NA | NA |
+ |=========|================|==========|==========|===========|==========|===========|==========|
+ | | Polling | Fpclk/4 | Fpclk/8 | Fpclk/16 | Fpclk/8 | Fpclk/8 | Fpclk/8 |
+ | |----------------|----------|----------|-----------|----------|-----------|----------|
+ | R | Interrupt | Fpclk/8 | Fpclk/16 | Fpclk/8 | Fpclk/8 | Fpclk/8 | Fpclk/4 |
+ | X |----------------|----------|----------|-----------|----------|-----------|----------|
+ | | DMA | Fpclk/4 | Fpclk/2 | Fpclk/2 | Fpclk/16 | Fpclk/2 | Fpclk/16 |
+ |=========|================|==========|==========|===========|==========|===========|==========|
+ | | Polling | Fpclk/8 | Fpclk/2 | NA | NA | Fpclk/8 | Fpclk/8 |
+ | |----------------|----------|----------|-----------|----------|-----------|----------|
+ | T | Interrupt | Fpclk/2 | Fpclk/4 | NA | NA | Fpclk/16 | Fpclk/8 |
+ | X |----------------|----------|----------|-----------|----------|-----------|----------|
+ | | DMA | Fpclk/2 | Fpclk/2 | NA | NA | Fpclk/8 | Fpclk/16 |
+ +----------------------------------------------------------------------------------------------+
+
+ DataSize = SPI_DATASIZE_16BIT:
+ +----------------------------------------------------------------------------------------------+
+ | | | 2Lines Fullduplex | 2Lines RxOnly | 1Line |
+ | Process | Transfer mode |---------------------|----------------------|----------------------|
+ | | | Master | Slave | Master | Slave | Master | Slave |
+ |==============================================================================================|
+ | T | Polling | Fpclk/4 | Fpclk/8 | NA | NA | NA | NA |
+ | X |----------------|----------|----------|-----------|----------|-----------|----------|
+ | / | Interrupt | Fpclk/4 | Fpclk/16 | NA | NA | NA | NA |
+ | R |----------------|----------|----------|-----------|----------|-----------|----------|
+ | X | DMA | Fpclk/2 | Fpclk/2 | NA | NA | NA | NA |
+ |=========|================|==========|==========|===========|==========|===========|==========|
+ | | Polling | Fpclk/4 | Fpclk/8 | Fpclk/16 | Fpclk/8 | Fpclk/8 | Fpclk/8 |
+ | |----------------|----------|----------|-----------|----------|-----------|----------|
+ | R | Interrupt | Fpclk/8 | Fpclk/16 | Fpclk/8 | Fpclk/8 | Fpclk/8 | Fpclk/4 |
+ | X |----------------|----------|----------|-----------|----------|-----------|----------|
+ | | DMA | Fpclk/4 | Fpclk/2 | Fpclk/2 | Fpclk/16 | Fpclk/2 | Fpclk/16 |
+ |=========|================|==========|==========|===========|==========|===========|==========|
+ | | Polling | Fpclk/8 | Fpclk/2 | NA | NA | Fpclk/8 | Fpclk/8 |
+ | |----------------|----------|----------|-----------|----------|-----------|----------|
+ | T | Interrupt | Fpclk/2 | Fpclk/4 | NA | NA | Fpclk/16 | Fpclk/8 |
+ | X |----------------|----------|----------|-----------|----------|-----------|----------|
+ | | DMA | Fpclk/2 | Fpclk/2 | NA | NA | Fpclk/8 | Fpclk/16 |
+ +----------------------------------------------------------------------------------------------+
+ @note The max SPI frequency depend on SPI data size (4bits, 5bits,..., 8bits,...15bits, 16bits),
+ SPI mode(2 Lines fullduplex, 2 lines RxOnly, 1 line TX/RX) and Process mode (Polling, IT, DMA).
+ @note
+ (#) TX/RX processes are HAL_SPI_TransmitReceive(), HAL_SPI_TransmitReceive_IT() and HAL_SPI_TransmitReceive_DMA()
+ (#) RX processes are HAL_SPI_Receive(), HAL_SPI_Receive_IT() and HAL_SPI_Receive_DMA()
+ (#) TX processes are HAL_SPI_Transmit(), HAL_SPI_Transmit_IT() and HAL_SPI_Transmit_DMA()
+
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2016 STMicroelectronics.
+ * All rights reserved.
+ *
+ * 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 "stm32f0xx_hal.h"
+
+/** @addtogroup STM32F0xx_HAL_Driver
+ * @{
+ */
+
+/** @defgroup SPI SPI
+ * @brief SPI HAL module driver
+ * @{
+ */
+#ifdef HAL_SPI_MODULE_ENABLED
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private defines -----------------------------------------------------------*/
+/** @defgroup SPI_Private_Constants SPI Private Constants
+ * @{
+ */
+#define SPI_DEFAULT_TIMEOUT 100U
+/**
+ * @}
+ */
+
+/* Private macros ------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/** @defgroup SPI_Private_Functions SPI Private Functions
+ * @{
+ */
+static void SPI_DMATransmitCplt(DMA_HandleTypeDef *hdma);
+static void SPI_DMAReceiveCplt(DMA_HandleTypeDef *hdma);
+static void SPI_DMATransmitReceiveCplt(DMA_HandleTypeDef *hdma);
+static void SPI_DMAHalfTransmitCplt(DMA_HandleTypeDef *hdma);
+static void SPI_DMAHalfReceiveCplt(DMA_HandleTypeDef *hdma);
+static void SPI_DMAHalfTransmitReceiveCplt(DMA_HandleTypeDef *hdma);
+static void SPI_DMAError(DMA_HandleTypeDef *hdma);
+static void SPI_DMAAbortOnError(DMA_HandleTypeDef *hdma);
+static void SPI_DMATxAbortCallback(DMA_HandleTypeDef *hdma);
+static void SPI_DMARxAbortCallback(DMA_HandleTypeDef *hdma);
+static HAL_StatusTypeDef SPI_WaitFlagStateUntilTimeout(SPI_HandleTypeDef *hspi, uint32_t Flag, FlagStatus State,
+ uint32_t Timeout, uint32_t Tickstart);
+static HAL_StatusTypeDef SPI_WaitFifoStateUntilTimeout(SPI_HandleTypeDef *hspi, uint32_t Fifo, uint32_t State,
+ uint32_t Timeout, uint32_t Tickstart);
+static void SPI_TxISR_8BIT(struct __SPI_HandleTypeDef *hspi);
+static void SPI_TxISR_16BIT(struct __SPI_HandleTypeDef *hspi);
+static void SPI_RxISR_8BIT(struct __SPI_HandleTypeDef *hspi);
+static void SPI_RxISR_16BIT(struct __SPI_HandleTypeDef *hspi);
+static void SPI_2linesRxISR_8BIT(struct __SPI_HandleTypeDef *hspi);
+static void SPI_2linesTxISR_8BIT(struct __SPI_HandleTypeDef *hspi);
+static void SPI_2linesTxISR_16BIT(struct __SPI_HandleTypeDef *hspi);
+static void SPI_2linesRxISR_16BIT(struct __SPI_HandleTypeDef *hspi);
+#if (USE_SPI_CRC != 0U)
+static void SPI_RxISR_8BITCRC(struct __SPI_HandleTypeDef *hspi);
+static void SPI_RxISR_16BITCRC(struct __SPI_HandleTypeDef *hspi);
+static void SPI_2linesRxISR_8BITCRC(struct __SPI_HandleTypeDef *hspi);
+static void SPI_2linesRxISR_16BITCRC(struct __SPI_HandleTypeDef *hspi);
+#endif /* USE_SPI_CRC */
+static void SPI_AbortRx_ISR(SPI_HandleTypeDef *hspi);
+static void SPI_AbortTx_ISR(SPI_HandleTypeDef *hspi);
+static void SPI_CloseRxTx_ISR(SPI_HandleTypeDef *hspi);
+static void SPI_CloseRx_ISR(SPI_HandleTypeDef *hspi);
+static void SPI_CloseTx_ISR(SPI_HandleTypeDef *hspi);
+static HAL_StatusTypeDef SPI_EndRxTransaction(SPI_HandleTypeDef *hspi, uint32_t Timeout, uint32_t Tickstart);
+static HAL_StatusTypeDef SPI_EndRxTxTransaction(SPI_HandleTypeDef *hspi, uint32_t Timeout, uint32_t Tickstart);
+/**
+ * @}
+ */
+
+/* Exported functions --------------------------------------------------------*/
+/** @defgroup SPI_Exported_Functions SPI Exported Functions
+ * @{
+ */
+
+/** @defgroup SPI_Exported_Functions_Group1 Initialization and de-initialization functions
+ * @brief Initialization and Configuration functions
+ *
+@verbatim
+ ===============================================================================
+ ##### Initialization and de-initialization functions #####
+ ===============================================================================
+ [..] This subsection provides a set of functions allowing to initialize and
+ de-initialize the SPIx peripheral:
+
+ (+) User must implement HAL_SPI_MspInit() function in which he configures
+ all related peripherals resources (CLOCK, GPIO, DMA, IT and NVIC ).
+
+ (+) Call the function HAL_SPI_Init() to configure the selected device with
+ the selected configuration:
+ (++) Mode
+ (++) Direction
+ (++) Data Size
+ (++) Clock Polarity and Phase
+ (++) NSS Management
+ (++) BaudRate Prescaler
+ (++) FirstBit
+ (++) TIMode
+ (++) CRC Calculation
+ (++) CRC Polynomial if CRC enabled
+ (++) CRC Length, used only with Data8 and Data16
+ (++) FIFO reception threshold
+
+ (+) Call the function HAL_SPI_DeInit() to restore the default configuration
+ of the selected SPIx peripheral.
+
+@endverbatim
+ * @{
+ */
+
+/**
+ * @brief Initialize the SPI according to the specified parameters
+ * in the SPI_InitTypeDef and initialize the associated handle.
+ * @param hspi pointer to a SPI_HandleTypeDef structure that contains
+ * the configuration information for SPI module.
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_SPI_Init(SPI_HandleTypeDef *hspi)
+{
+ uint32_t frxth;
+
+ /* Check the SPI handle allocation */
+ if (hspi == NULL)
+ {
+ return HAL_ERROR;
+ }
+
+ /* Check the parameters */
+ assert_param(IS_SPI_ALL_INSTANCE(hspi->Instance));
+ assert_param(IS_SPI_MODE(hspi->Init.Mode));
+ assert_param(IS_SPI_DIRECTION(hspi->Init.Direction));
+ assert_param(IS_SPI_DATASIZE(hspi->Init.DataSize));
+ assert_param(IS_SPI_NSS(hspi->Init.NSS));
+ assert_param(IS_SPI_NSSP(hspi->Init.NSSPMode));
+ assert_param(IS_SPI_BAUDRATE_PRESCALER(hspi->Init.BaudRatePrescaler));
+ assert_param(IS_SPI_FIRST_BIT(hspi->Init.FirstBit));
+ assert_param(IS_SPI_TIMODE(hspi->Init.TIMode));
+ if (hspi->Init.TIMode == SPI_TIMODE_DISABLE)
+ {
+ assert_param(IS_SPI_CPOL(hspi->Init.CLKPolarity));
+ assert_param(IS_SPI_CPHA(hspi->Init.CLKPhase));
+
+ if (hspi->Init.Mode == SPI_MODE_MASTER)
+ {
+ assert_param(IS_SPI_BAUDRATE_PRESCALER(hspi->Init.BaudRatePrescaler));
+ }
+ else
+ {
+ /* Baudrate prescaler not use in Motoraola Slave mode. force to default value */
+ hspi->Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_2;
+ }
+ }
+ else
+ {
+ assert_param(IS_SPI_BAUDRATE_PRESCALER(hspi->Init.BaudRatePrescaler));
+
+ /* Force polarity and phase to TI protocaol requirements */
+ hspi->Init.CLKPolarity = SPI_POLARITY_LOW;
+ hspi->Init.CLKPhase = SPI_PHASE_1EDGE;
+ }
+#if (USE_SPI_CRC != 0U)
+ assert_param(IS_SPI_CRC_CALCULATION(hspi->Init.CRCCalculation));
+ if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
+ {
+ assert_param(IS_SPI_CRC_POLYNOMIAL(hspi->Init.CRCPolynomial));
+ assert_param(IS_SPI_CRC_LENGTH(hspi->Init.CRCLength));
+ }
+#else
+ hspi->Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE;
+#endif /* USE_SPI_CRC */
+
+ if (hspi->State == HAL_SPI_STATE_RESET)
+ {
+ /* Allocate lock resource and initialize it */
+ hspi->Lock = HAL_UNLOCKED;
+
+#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U)
+ /* Init the SPI Callback settings */
+ hspi->TxCpltCallback = HAL_SPI_TxCpltCallback; /* Legacy weak TxCpltCallback */
+ hspi->RxCpltCallback = HAL_SPI_RxCpltCallback; /* Legacy weak RxCpltCallback */
+ hspi->TxRxCpltCallback = HAL_SPI_TxRxCpltCallback; /* Legacy weak TxRxCpltCallback */
+ hspi->TxHalfCpltCallback = HAL_SPI_TxHalfCpltCallback; /* Legacy weak TxHalfCpltCallback */
+ hspi->RxHalfCpltCallback = HAL_SPI_RxHalfCpltCallback; /* Legacy weak RxHalfCpltCallback */
+ hspi->TxRxHalfCpltCallback = HAL_SPI_TxRxHalfCpltCallback; /* Legacy weak TxRxHalfCpltCallback */
+ hspi->ErrorCallback = HAL_SPI_ErrorCallback; /* Legacy weak ErrorCallback */
+ hspi->AbortCpltCallback = HAL_SPI_AbortCpltCallback; /* Legacy weak AbortCpltCallback */
+
+ if (hspi->MspInitCallback == NULL)
+ {
+ hspi->MspInitCallback = HAL_SPI_MspInit; /* Legacy weak MspInit */
+ }
+
+ /* Init the low level hardware : GPIO, CLOCK, NVIC... */
+ hspi->MspInitCallback(hspi);
+#else
+ /* Init the low level hardware : GPIO, CLOCK, NVIC... */
+ HAL_SPI_MspInit(hspi);
+#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */
+ }
+
+ hspi->State = HAL_SPI_STATE_BUSY;
+
+ /* Disable the selected SPI peripheral */
+ __HAL_SPI_DISABLE(hspi);
+
+ /* Align by default the rs fifo threshold on the data size */
+ if (hspi->Init.DataSize > SPI_DATASIZE_8BIT)
+ {
+ frxth = SPI_RXFIFO_THRESHOLD_HF;
+ }
+ else
+ {
+ frxth = SPI_RXFIFO_THRESHOLD_QF;
+ }
+
+ /* CRC calculation is valid only for 16Bit and 8 Bit */
+ if ((hspi->Init.DataSize != SPI_DATASIZE_16BIT) && (hspi->Init.DataSize != SPI_DATASIZE_8BIT))
+ {
+ /* CRC must be disabled */
+ hspi->Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE;
+ }
+
+ /*----------------------- SPIx CR1 & CR2 Configuration ---------------------*/
+ /* Configure : SPI Mode, Communication Mode, Clock polarity and phase, NSS management,
+ Communication speed, First bit and CRC calculation state */
+ WRITE_REG(hspi->Instance->CR1, ((hspi->Init.Mode & (SPI_CR1_MSTR | SPI_CR1_SSI)) |
+ (hspi->Init.Direction & (SPI_CR1_RXONLY | SPI_CR1_BIDIMODE)) |
+ (hspi->Init.CLKPolarity & SPI_CR1_CPOL) |
+ (hspi->Init.CLKPhase & SPI_CR1_CPHA) |
+ (hspi->Init.NSS & SPI_CR1_SSM) |
+ (hspi->Init.BaudRatePrescaler & SPI_CR1_BR_Msk) |
+ (hspi->Init.FirstBit & SPI_CR1_LSBFIRST) |
+ (hspi->Init.CRCCalculation & SPI_CR1_CRCEN)));
+#if (USE_SPI_CRC != 0U)
+ /*---------------------------- SPIx CRCL Configuration -------------------*/
+ if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
+ {
+ /* Align the CRC Length on the data size */
+ if (hspi->Init.CRCLength == SPI_CRC_LENGTH_DATASIZE)
+ {
+ /* CRC Length aligned on the data size : value set by default */
+ if (hspi->Init.DataSize > SPI_DATASIZE_8BIT)
+ {
+ hspi->Init.CRCLength = SPI_CRC_LENGTH_16BIT;
+ }
+ else
+ {
+ hspi->Init.CRCLength = SPI_CRC_LENGTH_8BIT;
+ }
+ }
+
+ /* Configure : CRC Length */
+ if (hspi->Init.CRCLength == SPI_CRC_LENGTH_16BIT)
+ {
+ SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCL);
+ }
+ }
+#endif /* USE_SPI_CRC */
+
+ /* Configure : NSS management, TI Mode, NSS Pulse, Data size and Rx Fifo threshold */
+ WRITE_REG(hspi->Instance->CR2, (((hspi->Init.NSS >> 16U) & SPI_CR2_SSOE) |
+ (hspi->Init.TIMode & SPI_CR2_FRF) |
+ (hspi->Init.NSSPMode & SPI_CR2_NSSP) |
+ (hspi->Init.DataSize & SPI_CR2_DS_Msk) |
+ (frxth & SPI_CR2_FRXTH)));
+
+#if (USE_SPI_CRC != 0U)
+ /*---------------------------- SPIx CRCPOLY Configuration ------------------*/
+ /* Configure : CRC Polynomial */
+ if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
+ {
+ WRITE_REG(hspi->Instance->CRCPR, (hspi->Init.CRCPolynomial & SPI_CRCPR_CRCPOLY_Msk));
+ }
+#endif /* USE_SPI_CRC */
+
+#if defined(SPI_I2SCFGR_I2SMOD)
+ /* Activate the SPI mode (Make sure that I2SMOD bit in I2SCFGR register is reset) */
+ CLEAR_BIT(hspi->Instance->I2SCFGR, SPI_I2SCFGR_I2SMOD);
+#endif /* SPI_I2SCFGR_I2SMOD */
+
+ hspi->ErrorCode = HAL_SPI_ERROR_NONE;
+ hspi->State = HAL_SPI_STATE_READY;
+
+ return HAL_OK;
+}
+
+/**
+ * @brief De-Initialize the SPI peripheral.
+ * @param hspi pointer to a SPI_HandleTypeDef structure that contains
+ * the configuration information for SPI module.
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_SPI_DeInit(SPI_HandleTypeDef *hspi)
+{
+ /* Check the SPI handle allocation */
+ if (hspi == NULL)
+ {
+ return HAL_ERROR;
+ }
+
+ /* Check SPI Instance parameter */
+ assert_param(IS_SPI_ALL_INSTANCE(hspi->Instance));
+
+ hspi->State = HAL_SPI_STATE_BUSY;
+
+ /* Disable the SPI Peripheral Clock */
+ __HAL_SPI_DISABLE(hspi);
+
+#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U)
+ if (hspi->MspDeInitCallback == NULL)
+ {
+ hspi->MspDeInitCallback = HAL_SPI_MspDeInit; /* Legacy weak MspDeInit */
+ }
+
+ /* DeInit the low level hardware: GPIO, CLOCK, NVIC... */
+ hspi->MspDeInitCallback(hspi);
+#else
+ /* DeInit the low level hardware: GPIO, CLOCK, NVIC... */
+ HAL_SPI_MspDeInit(hspi);
+#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */
+
+ hspi->ErrorCode = HAL_SPI_ERROR_NONE;
+ hspi->State = HAL_SPI_STATE_RESET;
+
+ /* Release Lock */
+ __HAL_UNLOCK(hspi);
+
+ return HAL_OK;
+}
+
+/**
+ * @brief Initialize the SPI MSP.
+ * @param hspi pointer to a SPI_HandleTypeDef structure that contains
+ * the configuration information for SPI module.
+ * @retval None
+ */
+__weak void HAL_SPI_MspInit(SPI_HandleTypeDef *hspi)
+{
+ /* Prevent unused argument(s) compilation warning */
+ UNUSED(hspi);
+
+ /* NOTE : This function should not be modified, when the callback is needed,
+ the HAL_SPI_MspInit should be implemented in the user file
+ */
+}
+
+/**
+ * @brief De-Initialize the SPI MSP.
+ * @param hspi pointer to a SPI_HandleTypeDef structure that contains
+ * the configuration information for SPI module.
+ * @retval None
+ */
+__weak void HAL_SPI_MspDeInit(SPI_HandleTypeDef *hspi)
+{
+ /* Prevent unused argument(s) compilation warning */
+ UNUSED(hspi);
+
+ /* NOTE : This function should not be modified, when the callback is needed,
+ the HAL_SPI_MspDeInit should be implemented in the user file
+ */
+}
+
+#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U)
+/**
+ * @brief Register a User SPI Callback
+ * To be used instead of the weak predefined callback
+ * @param hspi Pointer to a SPI_HandleTypeDef structure that contains
+ * the configuration information for the specified SPI.
+ * @param CallbackID ID of the callback to be registered
+ * @param pCallback pointer to the Callback function
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_SPI_RegisterCallback(SPI_HandleTypeDef *hspi, HAL_SPI_CallbackIDTypeDef CallbackID,
+ pSPI_CallbackTypeDef pCallback)
+{
+ HAL_StatusTypeDef status = HAL_OK;
+
+ if (pCallback == NULL)
+ {
+ /* Update the error code */
+ hspi->ErrorCode |= HAL_SPI_ERROR_INVALID_CALLBACK;
+
+ return HAL_ERROR;
+ }
+ /* Process locked */
+ __HAL_LOCK(hspi);
+
+ if (HAL_SPI_STATE_READY == hspi->State)
+ {
+ switch (CallbackID)
+ {
+ case HAL_SPI_TX_COMPLETE_CB_ID :
+ hspi->TxCpltCallback = pCallback;
+ break;
+
+ case HAL_SPI_RX_COMPLETE_CB_ID :
+ hspi->RxCpltCallback = pCallback;
+ break;
+
+ case HAL_SPI_TX_RX_COMPLETE_CB_ID :
+ hspi->TxRxCpltCallback = pCallback;
+ break;
+
+ case HAL_SPI_TX_HALF_COMPLETE_CB_ID :
+ hspi->TxHalfCpltCallback = pCallback;
+ break;
+
+ case HAL_SPI_RX_HALF_COMPLETE_CB_ID :
+ hspi->RxHalfCpltCallback = pCallback;
+ break;
+
+ case HAL_SPI_TX_RX_HALF_COMPLETE_CB_ID :
+ hspi->TxRxHalfCpltCallback = pCallback;
+ break;
+
+ case HAL_SPI_ERROR_CB_ID :
+ hspi->ErrorCallback = pCallback;
+ break;
+
+ case HAL_SPI_ABORT_CB_ID :
+ hspi->AbortCpltCallback = pCallback;
+ break;
+
+ case HAL_SPI_MSPINIT_CB_ID :
+ hspi->MspInitCallback = pCallback;
+ break;
+
+ case HAL_SPI_MSPDEINIT_CB_ID :
+ hspi->MspDeInitCallback = pCallback;
+ break;
+
+ default :
+ /* Update the error code */
+ SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_INVALID_CALLBACK);
+
+ /* Return error status */
+ status = HAL_ERROR;
+ break;
+ }
+ }
+ else if (HAL_SPI_STATE_RESET == hspi->State)
+ {
+ switch (CallbackID)
+ {
+ case HAL_SPI_MSPINIT_CB_ID :
+ hspi->MspInitCallback = pCallback;
+ break;
+
+ case HAL_SPI_MSPDEINIT_CB_ID :
+ hspi->MspDeInitCallback = pCallback;
+ break;
+
+ default :
+ /* Update the error code */
+ SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_INVALID_CALLBACK);
+
+ /* Return error status */
+ status = HAL_ERROR;
+ break;
+ }
+ }
+ else
+ {
+ /* Update the error code */
+ SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_INVALID_CALLBACK);
+
+ /* Return error status */
+ status = HAL_ERROR;
+ }
+
+ /* Release Lock */
+ __HAL_UNLOCK(hspi);
+ return status;
+}
+
+/**
+ * @brief Unregister an SPI Callback
+ * SPI callback is redirected to the weak predefined callback
+ * @param hspi Pointer to a SPI_HandleTypeDef structure that contains
+ * the configuration information for the specified SPI.
+ * @param CallbackID ID of the callback to be unregistered
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_SPI_UnRegisterCallback(SPI_HandleTypeDef *hspi, HAL_SPI_CallbackIDTypeDef CallbackID)
+{
+ HAL_StatusTypeDef status = HAL_OK;
+
+ /* Process locked */
+ __HAL_LOCK(hspi);
+
+ if (HAL_SPI_STATE_READY == hspi->State)
+ {
+ switch (CallbackID)
+ {
+ case HAL_SPI_TX_COMPLETE_CB_ID :
+ hspi->TxCpltCallback = HAL_SPI_TxCpltCallback; /* Legacy weak TxCpltCallback */
+ break;
+
+ case HAL_SPI_RX_COMPLETE_CB_ID :
+ hspi->RxCpltCallback = HAL_SPI_RxCpltCallback; /* Legacy weak RxCpltCallback */
+ break;
+
+ case HAL_SPI_TX_RX_COMPLETE_CB_ID :
+ hspi->TxRxCpltCallback = HAL_SPI_TxRxCpltCallback; /* Legacy weak TxRxCpltCallback */
+ break;
+
+ case HAL_SPI_TX_HALF_COMPLETE_CB_ID :
+ hspi->TxHalfCpltCallback = HAL_SPI_TxHalfCpltCallback; /* Legacy weak TxHalfCpltCallback */
+ break;
+
+ case HAL_SPI_RX_HALF_COMPLETE_CB_ID :
+ hspi->RxHalfCpltCallback = HAL_SPI_RxHalfCpltCallback; /* Legacy weak RxHalfCpltCallback */
+ break;
+
+ case HAL_SPI_TX_RX_HALF_COMPLETE_CB_ID :
+ hspi->TxRxHalfCpltCallback = HAL_SPI_TxRxHalfCpltCallback; /* Legacy weak TxRxHalfCpltCallback */
+ break;
+
+ case HAL_SPI_ERROR_CB_ID :
+ hspi->ErrorCallback = HAL_SPI_ErrorCallback; /* Legacy weak ErrorCallback */
+ break;
+
+ case HAL_SPI_ABORT_CB_ID :
+ hspi->AbortCpltCallback = HAL_SPI_AbortCpltCallback; /* Legacy weak AbortCpltCallback */
+ break;
+
+ case HAL_SPI_MSPINIT_CB_ID :
+ hspi->MspInitCallback = HAL_SPI_MspInit; /* Legacy weak MspInit */
+ break;
+
+ case HAL_SPI_MSPDEINIT_CB_ID :
+ hspi->MspDeInitCallback = HAL_SPI_MspDeInit; /* Legacy weak MspDeInit */
+ break;
+
+ default :
+ /* Update the error code */
+ SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_INVALID_CALLBACK);
+
+ /* Return error status */
+ status = HAL_ERROR;
+ break;
+ }
+ }
+ else if (HAL_SPI_STATE_RESET == hspi->State)
+ {
+ switch (CallbackID)
+ {
+ case HAL_SPI_MSPINIT_CB_ID :
+ hspi->MspInitCallback = HAL_SPI_MspInit; /* Legacy weak MspInit */
+ break;
+
+ case HAL_SPI_MSPDEINIT_CB_ID :
+ hspi->MspDeInitCallback = HAL_SPI_MspDeInit; /* Legacy weak MspDeInit */
+ break;
+
+ default :
+ /* Update the error code */
+ SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_INVALID_CALLBACK);
+
+ /* Return error status */
+ status = HAL_ERROR;
+ break;
+ }
+ }
+ else
+ {
+ /* Update the error code */
+ SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_INVALID_CALLBACK);
+
+ /* Return error status */
+ status = HAL_ERROR;
+ }
+
+ /* Release Lock */
+ __HAL_UNLOCK(hspi);
+ return status;
+}
+#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */
+/**
+ * @}
+ */
+
+/** @defgroup SPI_Exported_Functions_Group2 IO operation functions
+ * @brief Data transfers functions
+ *
+@verbatim
+ ==============================================================================
+ ##### IO operation functions #####
+ ===============================================================================
+ [..]
+ This subsection provides a set of functions allowing to manage the SPI
+ data transfers.
+
+ [..] The SPI supports master and slave mode :
+
+ (#) There are two modes of transfer:
+ (++) Blocking mode: The communication is performed in polling mode.
+ The HAL status of all data processing is returned by the same function
+ after finishing transfer.
+ (++) No-Blocking mode: The communication is performed using Interrupts
+ or DMA, These APIs return the HAL status.
+ The end of the data processing will be indicated through the
+ dedicated SPI IRQ when using Interrupt mode or the DMA IRQ when
+ using DMA mode.
+ The HAL_SPI_TxCpltCallback(), HAL_SPI_RxCpltCallback() and HAL_SPI_TxRxCpltCallback() user callbacks
+ will be executed respectively at the end of the transmit or Receive process
+ The HAL_SPI_ErrorCallback()user callback will be executed when a communication error is detected
+
+ (#) APIs provided for these 2 transfer modes (Blocking mode or Non blocking mode using either Interrupt or DMA)
+ exist for 1Line (simplex) and 2Lines (full duplex) modes.
+
+@endverbatim
+ * @{
+ */
+
+/**
+ * @brief Transmit an amount of data in blocking mode.
+ * @param hspi pointer to a SPI_HandleTypeDef structure that contains
+ * the configuration information for SPI module.
+ * @param pData pointer to data buffer
+ * @param Size amount of data to be sent
+ * @param Timeout Timeout duration
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_SPI_Transmit(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size, uint32_t Timeout)
+{
+ uint32_t tickstart;
+ HAL_StatusTypeDef errorcode = HAL_OK;
+ uint16_t initial_TxXferCount;
+
+ /* Check Direction parameter */
+ assert_param(IS_SPI_DIRECTION_2LINES_OR_1LINE(hspi->Init.Direction));
+
+ /* Process Locked */
+ __HAL_LOCK(hspi);
+
+ /* Init tickstart for timeout management*/
+ tickstart = HAL_GetTick();
+ initial_TxXferCount = Size;
+
+ if (hspi->State != HAL_SPI_STATE_READY)
+ {
+ errorcode = HAL_BUSY;
+ goto error;
+ }
+
+ if ((pData == NULL) || (Size == 0U))
+ {
+ errorcode = HAL_ERROR;
+ goto error;
+ }
+
+ /* Set the transaction information */
+ hspi->State = HAL_SPI_STATE_BUSY_TX;
+ hspi->ErrorCode = HAL_SPI_ERROR_NONE;
+ hspi->pTxBuffPtr = (uint8_t *)pData;
+ hspi->TxXferSize = Size;
+ hspi->TxXferCount = Size;
+
+ /*Init field not used in handle to zero */
+ hspi->pRxBuffPtr = (uint8_t *)NULL;
+ hspi->RxXferSize = 0U;
+ hspi->RxXferCount = 0U;
+ hspi->TxISR = NULL;
+ hspi->RxISR = NULL;
+
+ /* Configure communication direction : 1Line */
+ if (hspi->Init.Direction == SPI_DIRECTION_1LINE)
+ {
+ /* Disable SPI Peripheral before set 1Line direction (BIDIOE bit) */
+ __HAL_SPI_DISABLE(hspi);
+ SPI_1LINE_TX(hspi);
+ }
+
+#if (USE_SPI_CRC != 0U)
+ /* Reset CRC Calculation */
+ if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
+ {
+ SPI_RESET_CRC(hspi);
+ }
+#endif /* USE_SPI_CRC */
+
+ /* Check if the SPI is already enabled */
+ if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE)
+ {
+ /* Enable SPI peripheral */
+ __HAL_SPI_ENABLE(hspi);
+ }
+
+ /* Transmit data in 16 Bit mode */
+ if (hspi->Init.DataSize > SPI_DATASIZE_8BIT)
+ {
+ if ((hspi->Init.Mode == SPI_MODE_SLAVE) || (initial_TxXferCount == 0x01U))
+ {
+ hspi->Instance->DR = *((uint16_t *)hspi->pTxBuffPtr);
+ hspi->pTxBuffPtr += sizeof(uint16_t);
+ hspi->TxXferCount--;
+ }
+ /* Transmit data in 16 Bit mode */
+ while (hspi->TxXferCount > 0U)
+ {
+ /* Wait until TXE flag is set to send data */
+ if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_TXE))
+ {
+ hspi->Instance->DR = *((uint16_t *)hspi->pTxBuffPtr);
+ hspi->pTxBuffPtr += sizeof(uint16_t);
+ hspi->TxXferCount--;
+ }
+ else
+ {
+ /* Timeout management */
+ if ((((HAL_GetTick() - tickstart) >= Timeout) && (Timeout != HAL_MAX_DELAY)) || (Timeout == 0U))
+ {
+ errorcode = HAL_TIMEOUT;
+ goto error;
+ }
+ }
+ }
+ }
+ /* Transmit data in 8 Bit mode */
+ else
+ {
+ if ((hspi->Init.Mode == SPI_MODE_SLAVE) || (initial_TxXferCount == 0x01U))
+ {
+ *((__IO uint8_t *)&hspi->Instance->DR) = (*hspi->pTxBuffPtr);
+ hspi->pTxBuffPtr += sizeof(uint8_t);
+ hspi->TxXferCount--;
+ }
+ while (hspi->TxXferCount > 0U)
+ {
+ /* Wait until TXE flag is set to send data */
+ if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_TXE))
+ {
+ *((__IO uint8_t *)&hspi->Instance->DR) = (*hspi->pTxBuffPtr);
+ hspi->pTxBuffPtr += sizeof(uint8_t);
+ hspi->TxXferCount--;
+ }
+ else
+ {
+ /* Timeout management */
+ if ((((HAL_GetTick() - tickstart) >= Timeout) && (Timeout != HAL_MAX_DELAY)) || (Timeout == 0U))
+ {
+ errorcode = HAL_TIMEOUT;
+ goto error;
+ }
+ }
+ }
+ }
+#if (USE_SPI_CRC != 0U)
+ /* Enable CRC Transmission */
+ if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
+ {
+ SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT);
+ }
+#endif /* USE_SPI_CRC */
+
+ /* Check the end of the transaction */
+ if (SPI_EndRxTxTransaction(hspi, Timeout, tickstart) != HAL_OK)
+ {
+ hspi->ErrorCode = HAL_SPI_ERROR_FLAG;
+ }
+
+ /* Clear overrun flag in 2 Lines communication mode because received is not read */
+ if (hspi->Init.Direction == SPI_DIRECTION_2LINES)
+ {
+ __HAL_SPI_CLEAR_OVRFLAG(hspi);
+ }
+
+ if (hspi->ErrorCode != HAL_SPI_ERROR_NONE)
+ {
+ errorcode = HAL_ERROR;
+ }
+
+error:
+ hspi->State = HAL_SPI_STATE_READY;
+ /* Process Unlocked */
+ __HAL_UNLOCK(hspi);
+ return errorcode;
+}
+
+/**
+ * @brief Receive an amount of data in blocking mode.
+ * @param hspi pointer to a SPI_HandleTypeDef structure that contains
+ * the configuration information for SPI module.
+ * @param pData pointer to data buffer
+ * @param Size amount of data to be received
+ * @param Timeout Timeout duration
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_SPI_Receive(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size, uint32_t Timeout)
+{
+#if (USE_SPI_CRC != 0U)
+ __IO uint32_t tmpreg = 0U;
+ __IO uint8_t * ptmpreg8;
+ __IO uint8_t tmpreg8 = 0;
+#endif /* USE_SPI_CRC */
+ uint32_t tickstart;
+ HAL_StatusTypeDef errorcode = HAL_OK;
+
+ if ((hspi->Init.Mode == SPI_MODE_MASTER) && (hspi->Init.Direction == SPI_DIRECTION_2LINES))
+ {
+ hspi->State = HAL_SPI_STATE_BUSY_RX;
+ /* Call transmit-receive function to send Dummy data on Tx line and generate clock on CLK line */
+ return HAL_SPI_TransmitReceive(hspi, pData, pData, Size, Timeout);
+ }
+
+ /* Process Locked */
+ __HAL_LOCK(hspi);
+
+ /* Init tickstart for timeout management*/
+ tickstart = HAL_GetTick();
+
+ if (hspi->State != HAL_SPI_STATE_READY)
+ {
+ errorcode = HAL_BUSY;
+ goto error;
+ }
+
+ if ((pData == NULL) || (Size == 0U))
+ {
+ errorcode = HAL_ERROR;
+ goto error;
+ }
+
+ /* Set the transaction information */
+ hspi->State = HAL_SPI_STATE_BUSY_RX;
+ hspi->ErrorCode = HAL_SPI_ERROR_NONE;
+ hspi->pRxBuffPtr = (uint8_t *)pData;
+ hspi->RxXferSize = Size;
+ hspi->RxXferCount = Size;
+
+ /*Init field not used in handle to zero */
+ hspi->pTxBuffPtr = (uint8_t *)NULL;
+ hspi->TxXferSize = 0U;
+ hspi->TxXferCount = 0U;
+ hspi->RxISR = NULL;
+ hspi->TxISR = NULL;
+
+#if (USE_SPI_CRC != 0U)
+ /* Reset CRC Calculation */
+ if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
+ {
+ SPI_RESET_CRC(hspi);
+ /* this is done to handle the CRCNEXT before the latest data */
+ hspi->RxXferCount--;
+ }
+#endif /* USE_SPI_CRC */
+
+ /* Set the Rx Fifo threshold */
+ if (hspi->Init.DataSize > SPI_DATASIZE_8BIT)
+ {
+ /* Set RX Fifo threshold according the reception data length: 16bit */
+ CLEAR_BIT(hspi->Instance->CR2, SPI_RXFIFO_THRESHOLD);
+ }
+ else
+ {
+ /* Set RX Fifo threshold according the reception data length: 8bit */
+ SET_BIT(hspi->Instance->CR2, SPI_RXFIFO_THRESHOLD);
+ }
+
+ /* Configure communication direction: 1Line */
+ if (hspi->Init.Direction == SPI_DIRECTION_1LINE)
+ {
+ /* Disable SPI Peripheral before set 1Line direction (BIDIOE bit) */
+ __HAL_SPI_DISABLE(hspi);
+ SPI_1LINE_RX(hspi);
+ }
+
+ /* Check if the SPI is already enabled */
+ if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE)
+ {
+ /* Enable SPI peripheral */
+ __HAL_SPI_ENABLE(hspi);
+ }
+
+ /* Receive data in 8 Bit mode */
+ if (hspi->Init.DataSize <= SPI_DATASIZE_8BIT)
+ {
+ /* Transfer loop */
+ while (hspi->RxXferCount > 0U)
+ {
+ /* Check the RXNE flag */
+ if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_RXNE))
+ {
+ /* read the received data */
+ (* (uint8_t *)hspi->pRxBuffPtr) = *(__IO uint8_t *)&hspi->Instance->DR;
+ hspi->pRxBuffPtr += sizeof(uint8_t);
+ hspi->RxXferCount--;
+ }
+ else
+ {
+ /* Timeout management */
+ if ((((HAL_GetTick() - tickstart) >= Timeout) && (Timeout != HAL_MAX_DELAY)) || (Timeout == 0U))
+ {
+ errorcode = HAL_TIMEOUT;
+ goto error;
+ }
+ }
+ }
+ }
+ else
+ {
+ /* Transfer loop */
+ while (hspi->RxXferCount > 0U)
+ {
+ /* Check the RXNE flag */
+ if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_RXNE))
+ {
+ *((uint16_t *)hspi->pRxBuffPtr) = (uint16_t)hspi->Instance->DR;
+ hspi->pRxBuffPtr += sizeof(uint16_t);
+ hspi->RxXferCount--;
+ }
+ else
+ {
+ /* Timeout management */
+ if ((((HAL_GetTick() - tickstart) >= Timeout) && (Timeout != HAL_MAX_DELAY)) || (Timeout == 0U))
+ {
+ errorcode = HAL_TIMEOUT;
+ goto error;
+ }
+ }
+ }
+ }
+
+#if (USE_SPI_CRC != 0U)
+ /* Handle the CRC Transmission */
+ if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
+ {
+ /* freeze the CRC before the latest data */
+ SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT);
+
+ /* Read the latest data */
+ if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_RXNE, SET, Timeout, tickstart) != HAL_OK)
+ {
+ /* the latest data has not been received */
+ errorcode = HAL_TIMEOUT;
+ goto error;
+ }
+
+ /* Receive last data in 16 Bit mode */
+ if (hspi->Init.DataSize > SPI_DATASIZE_8BIT)
+ {
+ *((uint16_t *)hspi->pRxBuffPtr) = (uint16_t)hspi->Instance->DR;
+ }
+ /* Receive last data in 8 Bit mode */
+ else
+ {
+ (*(uint8_t *)hspi->pRxBuffPtr) = *(__IO uint8_t *)&hspi->Instance->DR;
+ }
+
+ /* Wait the CRC data */
+ if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_RXNE, SET, Timeout, tickstart) != HAL_OK)
+ {
+ SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC);
+ errorcode = HAL_TIMEOUT;
+ goto error;
+ }
+
+ /* Read CRC to Flush DR and RXNE flag */
+ if (hspi->Init.DataSize == SPI_DATASIZE_16BIT)
+ {
+ /* Read 16bit CRC */
+ tmpreg = READ_REG(hspi->Instance->DR);
+ /* To avoid GCC warning */
+ UNUSED(tmpreg);
+ }
+ else
+ {
+ /* Initialize the 8bit temporary pointer */
+ ptmpreg8 = (__IO uint8_t *)&hspi->Instance->DR;
+ /* Read 8bit CRC */
+ tmpreg8 = *ptmpreg8;
+ /* To avoid GCC warning */
+ UNUSED(tmpreg8);
+
+ if ((hspi->Init.DataSize == SPI_DATASIZE_8BIT) && (hspi->Init.CRCLength == SPI_CRC_LENGTH_16BIT))
+ {
+ if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_RXNE, SET, Timeout, tickstart) != HAL_OK)
+ {
+ /* Error on the CRC reception */
+ SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC);
+ errorcode = HAL_TIMEOUT;
+ goto error;
+ }
+ /* Read 8bit CRC again in case of 16bit CRC in 8bit Data mode */
+ tmpreg8 = *ptmpreg8;
+ /* To avoid GCC warning */
+ UNUSED(tmpreg8);
+ }
+ }
+ }
+#endif /* USE_SPI_CRC */
+
+ /* Check the end of the transaction */
+ if (SPI_EndRxTransaction(hspi, Timeout, tickstart) != HAL_OK)
+ {
+ hspi->ErrorCode = HAL_SPI_ERROR_FLAG;
+ }
+
+#if (USE_SPI_CRC != 0U)
+ /* Check if CRC error occurred */
+ if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_CRCERR))
+ {
+ SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC);
+ __HAL_SPI_CLEAR_CRCERRFLAG(hspi);
+ }
+#endif /* USE_SPI_CRC */
+
+ if (hspi->ErrorCode != HAL_SPI_ERROR_NONE)
+ {
+ errorcode = HAL_ERROR;
+ }
+
+error :
+ hspi->State = HAL_SPI_STATE_READY;
+ __HAL_UNLOCK(hspi);
+ return errorcode;
+}
+
+/**
+ * @brief Transmit and Receive an amount of data in blocking mode.
+ * @param hspi pointer to a SPI_HandleTypeDef structure that contains
+ * the configuration information for SPI module.
+ * @param pTxData pointer to transmission data buffer
+ * @param pRxData pointer to reception data buffer
+ * @param Size amount of data to be sent and received
+ * @param Timeout Timeout duration
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_SPI_TransmitReceive(SPI_HandleTypeDef *hspi, uint8_t *pTxData, uint8_t *pRxData, uint16_t Size,
+ uint32_t Timeout)
+{
+ uint16_t initial_TxXferCount;
+ uint32_t tmp_mode;
+ HAL_SPI_StateTypeDef tmp_state;
+ uint32_t tickstart;
+#if (USE_SPI_CRC != 0U)
+ __IO uint32_t tmpreg = 0U;
+ uint32_t spi_cr1;
+ uint32_t spi_cr2;
+ __IO uint8_t * ptmpreg8;
+ __IO uint8_t tmpreg8 = 0;
+#endif /* USE_SPI_CRC */
+
+ /* Variable used to alternate Rx and Tx during transfer */
+ uint32_t txallowed = 1U;
+ HAL_StatusTypeDef errorcode = HAL_OK;
+
+ /* Check Direction parameter */
+ assert_param(IS_SPI_DIRECTION_2LINES(hspi->Init.Direction));
+
+ /* Process Locked */
+ __HAL_LOCK(hspi);
+
+ /* Init tickstart for timeout management*/
+ tickstart = HAL_GetTick();
+
+ /* Init temporary variables */
+ tmp_state = hspi->State;
+ tmp_mode = hspi->Init.Mode;
+ initial_TxXferCount = Size;
+#if (USE_SPI_CRC != 0U)
+ spi_cr1 = READ_REG(hspi->Instance->CR1);
+ spi_cr2 = READ_REG(hspi->Instance->CR2);
+#endif /* USE_SPI_CRC */
+
+ if (!((tmp_state == HAL_SPI_STATE_READY) || \
+ ((tmp_mode == SPI_MODE_MASTER) && (hspi->Init.Direction == SPI_DIRECTION_2LINES) && (tmp_state == HAL_SPI_STATE_BUSY_RX))))
+ {
+ errorcode = HAL_BUSY;
+ goto error;
+ }
+
+ if ((pTxData == NULL) || (pRxData == NULL) || (Size == 0U))
+ {
+ errorcode = HAL_ERROR;
+ goto error;
+ }
+
+ /* Don't overwrite in case of HAL_SPI_STATE_BUSY_RX */
+ if (hspi->State != HAL_SPI_STATE_BUSY_RX)
+ {
+ hspi->State = HAL_SPI_STATE_BUSY_TX_RX;
+ }
+
+ /* Set the transaction information */
+ hspi->ErrorCode = HAL_SPI_ERROR_NONE;
+ hspi->pRxBuffPtr = (uint8_t *)pRxData;
+ hspi->RxXferCount = Size;
+ hspi->RxXferSize = Size;
+ hspi->pTxBuffPtr = (uint8_t *)pTxData;
+ hspi->TxXferCount = Size;
+ hspi->TxXferSize = Size;
+
+ /*Init field not used in handle to zero */
+ hspi->RxISR = NULL;
+ hspi->TxISR = NULL;
+
+#if (USE_SPI_CRC != 0U)
+ /* Reset CRC Calculation */
+ if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
+ {
+ SPI_RESET_CRC(hspi);
+ }
+#endif /* USE_SPI_CRC */
+
+ /* Set the Rx Fifo threshold */
+ if (hspi->Init.DataSize > SPI_DATASIZE_8BIT)
+ {
+ /* Set fiforxthreshold according the reception data length: 16bit */
+ CLEAR_BIT(hspi->Instance->CR2, SPI_RXFIFO_THRESHOLD);
+ }
+ else
+ {
+ /* Set fiforxthreshold according the reception data length: 8bit */
+ SET_BIT(hspi->Instance->CR2, SPI_RXFIFO_THRESHOLD);
+ }
+
+ /* Check if the SPI is already enabled */
+ if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE)
+ {
+ /* Enable SPI peripheral */
+ __HAL_SPI_ENABLE(hspi);
+ }
+
+ /* Transmit and Receive data in 16 Bit mode */
+ if (hspi->Init.DataSize > SPI_DATASIZE_8BIT)
+ {
+ if ((hspi->Init.Mode == SPI_MODE_SLAVE) || (initial_TxXferCount == 0x01U))
+ {
+ hspi->Instance->DR = *((uint16_t *)hspi->pTxBuffPtr);
+ hspi->pTxBuffPtr += sizeof(uint16_t);
+ hspi->TxXferCount--;
+ }
+ while ((hspi->TxXferCount > 0U) || (hspi->RxXferCount > 0U))
+ {
+ /* Check TXE flag */
+ if ((__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_TXE)) && (hspi->TxXferCount > 0U) && (txallowed == 1U))
+ {
+ hspi->Instance->DR = *((uint16_t *)hspi->pTxBuffPtr);
+ hspi->pTxBuffPtr += sizeof(uint16_t);
+ hspi->TxXferCount--;
+ /* Next Data is a reception (Rx). Tx not allowed */
+ txallowed = 0U;
+
+#if (USE_SPI_CRC != 0U)
+ /* Enable CRC Transmission */
+ if ((hspi->TxXferCount == 0U) && (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE))
+ {
+ /* Set NSS Soft to received correctly the CRC on slave mode with NSS pulse activated */
+ if ((READ_BIT(spi_cr1, SPI_CR1_MSTR) == 0U) && (READ_BIT(spi_cr2, SPI_CR2_NSSP) == SPI_CR2_NSSP))
+ {
+ SET_BIT(hspi->Instance->CR1, SPI_CR1_SSM);
+ }
+ SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT);
+ }
+#endif /* USE_SPI_CRC */
+ }
+
+ /* Check RXNE flag */
+ if ((__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_RXNE)) && (hspi->RxXferCount > 0U))
+ {
+ *((uint16_t *)hspi->pRxBuffPtr) = (uint16_t)hspi->Instance->DR;
+ hspi->pRxBuffPtr += sizeof(uint16_t);
+ hspi->RxXferCount--;
+ /* Next Data is a Transmission (Tx). Tx is allowed */
+ txallowed = 1U;
+ }
+ if (((HAL_GetTick() - tickstart) >= Timeout) && (Timeout != HAL_MAX_DELAY))
+ {
+ errorcode = HAL_TIMEOUT;
+ goto error;
+ }
+ }
+ }
+ /* Transmit and Receive data in 8 Bit mode */
+ else
+ {
+ if ((hspi->Init.Mode == SPI_MODE_SLAVE) || (initial_TxXferCount == 0x01U))
+ {
+ *((__IO uint8_t *)&hspi->Instance->DR) = (*hspi->pTxBuffPtr);
+ hspi->pTxBuffPtr += sizeof(uint8_t);
+ hspi->TxXferCount--;
+ }
+ while ((hspi->TxXferCount > 0U) || (hspi->RxXferCount > 0U))
+ {
+ /* Check TXE flag */
+ if ((__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_TXE)) && (hspi->TxXferCount > 0U) && (txallowed == 1U))
+ {
+ *(__IO uint8_t *)&hspi->Instance->DR = (*hspi->pTxBuffPtr);
+ hspi->pTxBuffPtr++;
+ hspi->TxXferCount--;
+ /* Next Data is a reception (Rx). Tx not allowed */
+ txallowed = 0U;
+
+#if (USE_SPI_CRC != 0U)
+ /* Enable CRC Transmission */
+ if ((hspi->TxXferCount == 0U) && (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE))
+ {
+ /* Set NSS Soft to received correctly the CRC on slave mode with NSS pulse activated */
+ if ((READ_BIT(spi_cr1, SPI_CR1_MSTR) == 0U) && (READ_BIT(spi_cr2, SPI_CR2_NSSP) == SPI_CR2_NSSP))
+ {
+ SET_BIT(hspi->Instance->CR1, SPI_CR1_SSM);
+ }
+ SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT);
+ }
+#endif /* USE_SPI_CRC */
+ }
+
+ /* Wait until RXNE flag is reset */
+ if ((__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_RXNE)) && (hspi->RxXferCount > 0U))
+ {
+ (*(uint8_t *)hspi->pRxBuffPtr) = *(__IO uint8_t *)&hspi->Instance->DR;
+ hspi->pRxBuffPtr++;
+ hspi->RxXferCount--;
+ /* Next Data is a Transmission (Tx). Tx is allowed */
+ txallowed = 1U;
+ }
+ if ((((HAL_GetTick() - tickstart) >= Timeout) && ((Timeout != HAL_MAX_DELAY))) || (Timeout == 0U))
+ {
+ errorcode = HAL_TIMEOUT;
+ goto error;
+ }
+ }
+ }
+
+#if (USE_SPI_CRC != 0U)
+ /* Read CRC from DR to close CRC calculation process */
+ if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
+ {
+ /* Wait until TXE flag */
+ if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_RXNE, SET, Timeout, tickstart) != HAL_OK)
+ {
+ /* Error on the CRC reception */
+ SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC);
+ errorcode = HAL_TIMEOUT;
+ goto error;
+ }
+ /* Read CRC */
+ if (hspi->Init.DataSize == SPI_DATASIZE_16BIT)
+ {
+ /* Read 16bit CRC */
+ tmpreg = READ_REG(hspi->Instance->DR);
+ /* To avoid GCC warning */
+ UNUSED(tmpreg);
+ }
+ else
+ {
+ /* Initialize the 8bit temporary pointer */
+ ptmpreg8 = (__IO uint8_t *)&hspi->Instance->DR;
+ /* Read 8bit CRC */
+ tmpreg8 = *ptmpreg8;
+ /* To avoid GCC warning */
+ UNUSED(tmpreg8);
+
+ if (hspi->Init.CRCLength == SPI_CRC_LENGTH_16BIT)
+ {
+ if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_RXNE, SET, Timeout, tickstart) != HAL_OK)
+ {
+ /* Error on the CRC reception */
+ SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC);
+ errorcode = HAL_TIMEOUT;
+ goto error;
+ }
+ /* Read 8bit CRC again in case of 16bit CRC in 8bit Data mode */
+ tmpreg8 = *ptmpreg8;
+ /* To avoid GCC warning */
+ UNUSED(tmpreg8);
+ }
+ }
+ }
+
+ /* Check if CRC error occurred */
+ if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_CRCERR))
+ {
+ SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC);
+ /* Clear CRC Flag */
+ __HAL_SPI_CLEAR_CRCERRFLAG(hspi);
+
+ errorcode = HAL_ERROR;
+ }
+#endif /* USE_SPI_CRC */
+
+ /* Check the end of the transaction */
+ if (SPI_EndRxTxTransaction(hspi, Timeout, tickstart) != HAL_OK)
+ {
+ errorcode = HAL_ERROR;
+ hspi->ErrorCode = HAL_SPI_ERROR_FLAG;
+ }
+
+error :
+ hspi->State = HAL_SPI_STATE_READY;
+ __HAL_UNLOCK(hspi);
+ return errorcode;
+}
+
+/**
+ * @brief Transmit an amount of data in non-blocking mode with Interrupt.
+ * @param hspi pointer to a SPI_HandleTypeDef structure that contains
+ * the configuration information for SPI module.
+ * @param pData pointer to data buffer
+ * @param Size amount of data to be sent
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_SPI_Transmit_IT(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size)
+{
+ HAL_StatusTypeDef errorcode = HAL_OK;
+
+ /* Check Direction parameter */
+ assert_param(IS_SPI_DIRECTION_2LINES_OR_1LINE(hspi->Init.Direction));
+
+ /* Process Locked */
+ __HAL_LOCK(hspi);
+
+ if ((pData == NULL) || (Size == 0U))
+ {
+ errorcode = HAL_ERROR;
+ goto error;
+ }
+
+ if (hspi->State != HAL_SPI_STATE_READY)
+ {
+ errorcode = HAL_BUSY;
+ goto error;
+ }
+
+ /* Set the transaction information */
+ hspi->State = HAL_SPI_STATE_BUSY_TX;
+ hspi->ErrorCode = HAL_SPI_ERROR_NONE;
+ hspi->pTxBuffPtr = (uint8_t *)pData;
+ hspi->TxXferSize = Size;
+ hspi->TxXferCount = Size;
+
+ /* Init field not used in handle to zero */
+ hspi->pRxBuffPtr = (uint8_t *)NULL;
+ hspi->RxXferSize = 0U;
+ hspi->RxXferCount = 0U;
+ hspi->RxISR = NULL;
+
+ /* Set the function for IT treatment */
+ if (hspi->Init.DataSize > SPI_DATASIZE_8BIT)
+ {
+ hspi->TxISR = SPI_TxISR_16BIT;
+ }
+ else
+ {
+ hspi->TxISR = SPI_TxISR_8BIT;
+ }
+
+ /* Configure communication direction : 1Line */
+ if (hspi->Init.Direction == SPI_DIRECTION_1LINE)
+ {
+ /* Disable SPI Peripheral before set 1Line direction (BIDIOE bit) */
+ __HAL_SPI_DISABLE(hspi);
+ SPI_1LINE_TX(hspi);
+ }
+
+#if (USE_SPI_CRC != 0U)
+ /* Reset CRC Calculation */
+ if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
+ {
+ SPI_RESET_CRC(hspi);
+ }
+#endif /* USE_SPI_CRC */
+
+ /* Enable TXE and ERR interrupt */
+ __HAL_SPI_ENABLE_IT(hspi, (SPI_IT_TXE | SPI_IT_ERR));
+
+
+ /* Check if the SPI is already enabled */
+ if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE)
+ {
+ /* Enable SPI peripheral */
+ __HAL_SPI_ENABLE(hspi);
+ }
+
+error :
+ __HAL_UNLOCK(hspi);
+ return errorcode;
+}
+
+/**
+ * @brief Receive an amount of data in non-blocking mode with Interrupt.
+ * @param hspi pointer to a SPI_HandleTypeDef structure that contains
+ * the configuration information for SPI module.
+ * @param pData pointer to data buffer
+ * @param Size amount of data to be sent
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_SPI_Receive_IT(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size)
+{
+ HAL_StatusTypeDef errorcode = HAL_OK;
+
+ if ((hspi->Init.Direction == SPI_DIRECTION_2LINES) && (hspi->Init.Mode == SPI_MODE_MASTER))
+ {
+ hspi->State = HAL_SPI_STATE_BUSY_RX;
+ /* Call transmit-receive function to send Dummy data on Tx line and generate clock on CLK line */
+ return HAL_SPI_TransmitReceive_IT(hspi, pData, pData, Size);
+ }
+
+ /* Process Locked */
+ __HAL_LOCK(hspi);
+
+ if (hspi->State != HAL_SPI_STATE_READY)
+ {
+ errorcode = HAL_BUSY;
+ goto error;
+ }
+
+ if ((pData == NULL) || (Size == 0U))
+ {
+ errorcode = HAL_ERROR;
+ goto error;
+ }
+
+ /* Set the transaction information */
+ hspi->State = HAL_SPI_STATE_BUSY_RX;
+ hspi->ErrorCode = HAL_SPI_ERROR_NONE;
+ hspi->pRxBuffPtr = (uint8_t *)pData;
+ hspi->RxXferSize = Size;
+ hspi->RxXferCount = Size;
+
+ /* Init field not used in handle to zero */
+ hspi->pTxBuffPtr = (uint8_t *)NULL;
+ hspi->TxXferSize = 0U;
+ hspi->TxXferCount = 0U;
+ hspi->TxISR = NULL;
+
+ /* Check the data size to adapt Rx threshold and the set the function for IT treatment */
+ if (hspi->Init.DataSize > SPI_DATASIZE_8BIT)
+ {
+ /* Set RX Fifo threshold according the reception data length: 16 bit */
+ CLEAR_BIT(hspi->Instance->CR2, SPI_RXFIFO_THRESHOLD);
+ hspi->RxISR = SPI_RxISR_16BIT;
+ }
+ else
+ {
+ /* Set RX Fifo threshold according the reception data length: 8 bit */
+ SET_BIT(hspi->Instance->CR2, SPI_RXFIFO_THRESHOLD);
+ hspi->RxISR = SPI_RxISR_8BIT;
+ }
+
+ /* Configure communication direction : 1Line */
+ if (hspi->Init.Direction == SPI_DIRECTION_1LINE)
+ {
+ /* Disable SPI Peripheral before set 1Line direction (BIDIOE bit) */
+ __HAL_SPI_DISABLE(hspi);
+ SPI_1LINE_RX(hspi);
+ }
+
+#if (USE_SPI_CRC != 0U)
+ /* Reset CRC Calculation */
+ if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
+ {
+ hspi->CRCSize = 1U;
+ if ((hspi->Init.DataSize <= SPI_DATASIZE_8BIT) && (hspi->Init.CRCLength == SPI_CRC_LENGTH_16BIT))
+ {
+ hspi->CRCSize = 2U;
+ }
+ SPI_RESET_CRC(hspi);
+ }
+ else
+ {
+ hspi->CRCSize = 0U;
+ }
+#endif /* USE_SPI_CRC */
+
+ /* Enable TXE and ERR interrupt */
+ __HAL_SPI_ENABLE_IT(hspi, (SPI_IT_RXNE | SPI_IT_ERR));
+
+ /* Note : The SPI must be enabled after unlocking current process
+ to avoid the risk of SPI interrupt handle execution before current
+ process unlock */
+
+ /* Check if the SPI is already enabled */
+ if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE)
+ {
+ /* Enable SPI peripheral */
+ __HAL_SPI_ENABLE(hspi);
+ }
+
+error :
+ /* Process Unlocked */
+ __HAL_UNLOCK(hspi);
+ return errorcode;
+}
+
+/**
+ * @brief Transmit and Receive an amount of data in non-blocking mode with Interrupt.
+ * @param hspi pointer to a SPI_HandleTypeDef structure that contains
+ * the configuration information for SPI module.
+ * @param pTxData pointer to transmission data buffer
+ * @param pRxData pointer to reception data buffer
+ * @param Size amount of data to be sent and received
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_SPI_TransmitReceive_IT(SPI_HandleTypeDef *hspi, uint8_t *pTxData, uint8_t *pRxData, uint16_t Size)
+{
+ uint32_t tmp_mode;
+ HAL_SPI_StateTypeDef tmp_state;
+ HAL_StatusTypeDef errorcode = HAL_OK;
+
+ /* Check Direction parameter */
+ assert_param(IS_SPI_DIRECTION_2LINES(hspi->Init.Direction));
+
+ /* Process locked */
+ __HAL_LOCK(hspi);
+
+ /* Init temporary variables */
+ tmp_state = hspi->State;
+ tmp_mode = hspi->Init.Mode;
+
+ if (!((tmp_state == HAL_SPI_STATE_READY) || \
+ ((tmp_mode == SPI_MODE_MASTER) && (hspi->Init.Direction == SPI_DIRECTION_2LINES) && (tmp_state == HAL_SPI_STATE_BUSY_RX))))
+ {
+ errorcode = HAL_BUSY;
+ goto error;
+ }
+
+ if ((pTxData == NULL) || (pRxData == NULL) || (Size == 0U))
+ {
+ errorcode = HAL_ERROR;
+ goto error;
+ }
+
+ /* Don't overwrite in case of HAL_SPI_STATE_BUSY_RX */
+ if (hspi->State != HAL_SPI_STATE_BUSY_RX)
+ {
+ hspi->State = HAL_SPI_STATE_BUSY_TX_RX;
+ }
+
+ /* Set the transaction information */
+ hspi->ErrorCode = HAL_SPI_ERROR_NONE;
+ hspi->pTxBuffPtr = (uint8_t *)pTxData;
+ hspi->TxXferSize = Size;
+ hspi->TxXferCount = Size;
+ hspi->pRxBuffPtr = (uint8_t *)pRxData;
+ hspi->RxXferSize = Size;
+ hspi->RxXferCount = Size;
+
+ /* Set the function for IT treatment */
+ if (hspi->Init.DataSize > SPI_DATASIZE_8BIT)
+ {
+ hspi->RxISR = SPI_2linesRxISR_16BIT;
+ hspi->TxISR = SPI_2linesTxISR_16BIT;
+ }
+ else
+ {
+ hspi->RxISR = SPI_2linesRxISR_8BIT;
+ hspi->TxISR = SPI_2linesTxISR_8BIT;
+ }
+
+#if (USE_SPI_CRC != 0U)
+ /* Reset CRC Calculation */
+ if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
+ {
+ hspi->CRCSize = 1U;
+ if ((hspi->Init.DataSize <= SPI_DATASIZE_8BIT) && (hspi->Init.CRCLength == SPI_CRC_LENGTH_16BIT))
+ {
+ hspi->CRCSize = 2U;
+ }
+ SPI_RESET_CRC(hspi);
+ }
+ else
+ {
+ hspi->CRCSize = 0U;
+ }
+#endif /* USE_SPI_CRC */
+
+ /* Check if packing mode is enabled and if there is more than 2 data to receive */
+ if ((hspi->Init.DataSize > SPI_DATASIZE_8BIT) || (Size >= 2U))
+ {
+ /* Set RX Fifo threshold according the reception data length: 16 bit */
+ CLEAR_BIT(hspi->Instance->CR2, SPI_RXFIFO_THRESHOLD);
+ }
+ else
+ {
+ /* Set RX Fifo threshold according the reception data length: 8 bit */
+ SET_BIT(hspi->Instance->CR2, SPI_RXFIFO_THRESHOLD);
+ }
+
+ /* Enable TXE, RXNE and ERR interrupt */
+ __HAL_SPI_ENABLE_IT(hspi, (SPI_IT_TXE | SPI_IT_RXNE | SPI_IT_ERR));
+
+ /* Check if the SPI is already enabled */
+ if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE)
+ {
+ /* Enable SPI peripheral */
+ __HAL_SPI_ENABLE(hspi);
+ }
+
+error :
+ /* Process Unlocked */
+ __HAL_UNLOCK(hspi);
+ return errorcode;
+}
+
+/**
+ * @brief Transmit an amount of data in non-blocking mode with DMA.
+ * @param hspi pointer to a SPI_HandleTypeDef structure that contains
+ * the configuration information for SPI module.
+ * @param pData pointer to data buffer
+ * @param Size amount of data to be sent
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_SPI_Transmit_DMA(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size)
+{
+ HAL_StatusTypeDef errorcode = HAL_OK;
+
+ /* Check tx dma handle */
+ assert_param(IS_SPI_DMA_HANDLE(hspi->hdmatx));
+
+ /* Check Direction parameter */
+ assert_param(IS_SPI_DIRECTION_2LINES_OR_1LINE(hspi->Init.Direction));
+
+ /* Process Locked */
+ __HAL_LOCK(hspi);
+
+ if (hspi->State != HAL_SPI_STATE_READY)
+ {
+ errorcode = HAL_BUSY;
+ goto error;
+ }
+
+ if ((pData == NULL) || (Size == 0U))
+ {
+ errorcode = HAL_ERROR;
+ goto error;
+ }
+
+ /* Set the transaction information */
+ hspi->State = HAL_SPI_STATE_BUSY_TX;
+ hspi->ErrorCode = HAL_SPI_ERROR_NONE;
+ hspi->pTxBuffPtr = (uint8_t *)pData;
+ hspi->TxXferSize = Size;
+ hspi->TxXferCount = Size;
+
+ /* Init field not used in handle to zero */
+ hspi->pRxBuffPtr = (uint8_t *)NULL;
+ hspi->TxISR = NULL;
+ hspi->RxISR = NULL;
+ hspi->RxXferSize = 0U;
+ hspi->RxXferCount = 0U;
+
+ /* Configure communication direction : 1Line */
+ if (hspi->Init.Direction == SPI_DIRECTION_1LINE)
+ {
+ /* Disable SPI Peripheral before set 1Line direction (BIDIOE bit) */
+ __HAL_SPI_DISABLE(hspi);
+ SPI_1LINE_TX(hspi);
+ }
+
+#if (USE_SPI_CRC != 0U)
+ /* Reset CRC Calculation */
+ if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
+ {
+ SPI_RESET_CRC(hspi);
+ }
+#endif /* USE_SPI_CRC */
+
+ /* Set the SPI TxDMA Half transfer complete callback */
+ hspi->hdmatx->XferHalfCpltCallback = SPI_DMAHalfTransmitCplt;
+
+ /* Set the SPI TxDMA transfer complete callback */
+ hspi->hdmatx->XferCpltCallback = SPI_DMATransmitCplt;
+
+ /* Set the DMA error callback */
+ hspi->hdmatx->XferErrorCallback = SPI_DMAError;
+
+ /* Set the DMA AbortCpltCallback */
+ hspi->hdmatx->XferAbortCallback = NULL;
+
+ CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_LDMATX);
+ /* Packing mode is enabled only if the DMA setting is HALWORD */
+ if ((hspi->Init.DataSize <= SPI_DATASIZE_8BIT) && (hspi->hdmatx->Init.MemDataAlignment == DMA_MDATAALIGN_HALFWORD))
+ {
+ /* Check the even/odd of the data size + crc if enabled */
+ if ((hspi->TxXferCount & 0x1U) == 0U)
+ {
+ CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_LDMATX);
+ hspi->TxXferCount = (hspi->TxXferCount >> 1U);
+ }
+ else
+ {
+ SET_BIT(hspi->Instance->CR2, SPI_CR2_LDMATX);
+ hspi->TxXferCount = (hspi->TxXferCount >> 1U) + 1U;
+ }
+ }
+
+ /* Enable the Tx DMA Stream/Channel */
+ if (HAL_OK != HAL_DMA_Start_IT(hspi->hdmatx, (uint32_t)hspi->pTxBuffPtr, (uint32_t)&hspi->Instance->DR,
+ hspi->TxXferCount))
+ {
+ /* Update SPI error code */
+ SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_DMA);
+ errorcode = HAL_ERROR;
+
+ hspi->State = HAL_SPI_STATE_READY;
+ goto error;
+ }
+
+ /* Check if the SPI is already enabled */
+ if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE)
+ {
+ /* Enable SPI peripheral */
+ __HAL_SPI_ENABLE(hspi);
+ }
+
+ /* Enable the SPI Error Interrupt Bit */
+ __HAL_SPI_ENABLE_IT(hspi, (SPI_IT_ERR));
+
+ /* Enable Tx DMA Request */
+ SET_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN);
+
+error :
+ /* Process Unlocked */
+ __HAL_UNLOCK(hspi);
+ return errorcode;
+}
+
+/**
+ * @brief Receive an amount of data in non-blocking mode with DMA.
+ * @note In case of MASTER mode and SPI_DIRECTION_2LINES direction, hdmatx shall be defined.
+ * @param hspi pointer to a SPI_HandleTypeDef structure that contains
+ * the configuration information for SPI module.
+ * @param pData pointer to data buffer
+ * @note When the CRC feature is enabled the pData Length must be Size + 1.
+ * @param Size amount of data to be sent
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_SPI_Receive_DMA(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size)
+{
+ HAL_StatusTypeDef errorcode = HAL_OK;
+
+ /* Check rx dma handle */
+ assert_param(IS_SPI_DMA_HANDLE(hspi->hdmarx));
+
+ if ((hspi->Init.Direction == SPI_DIRECTION_2LINES) && (hspi->Init.Mode == SPI_MODE_MASTER))
+ {
+ hspi->State = HAL_SPI_STATE_BUSY_RX;
+
+ /* Check tx dma handle */
+ assert_param(IS_SPI_DMA_HANDLE(hspi->hdmatx));
+
+ /* Call transmit-receive function to send Dummy data on Tx line and generate clock on CLK line */
+ return HAL_SPI_TransmitReceive_DMA(hspi, pData, pData, Size);
+ }
+
+ /* Process Locked */
+ __HAL_LOCK(hspi);
+
+ if (hspi->State != HAL_SPI_STATE_READY)
+ {
+ errorcode = HAL_BUSY;
+ goto error;
+ }
+
+ if ((pData == NULL) || (Size == 0U))
+ {
+ errorcode = HAL_ERROR;
+ goto error;
+ }
+
+ /* Set the transaction information */
+ hspi->State = HAL_SPI_STATE_BUSY_RX;
+ hspi->ErrorCode = HAL_SPI_ERROR_NONE;
+ hspi->pRxBuffPtr = (uint8_t *)pData;
+ hspi->RxXferSize = Size;
+ hspi->RxXferCount = Size;
+
+ /*Init field not used in handle to zero */
+ hspi->RxISR = NULL;
+ hspi->TxISR = NULL;
+ hspi->TxXferSize = 0U;
+ hspi->TxXferCount = 0U;
+
+ /* Configure communication direction : 1Line */
+ if (hspi->Init.Direction == SPI_DIRECTION_1LINE)
+ {
+ /* Disable SPI Peripheral before set 1Line direction (BIDIOE bit) */
+ __HAL_SPI_DISABLE(hspi);
+ SPI_1LINE_RX(hspi);
+ }
+
+#if (USE_SPI_CRC != 0U)
+ /* Reset CRC Calculation */
+ if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
+ {
+ SPI_RESET_CRC(hspi);
+ }
+#endif /* USE_SPI_CRC */
+
+#if defined (STM32F030x6) || defined (STM32F030x8) || defined (STM32F031x6)|| defined (STM32F038xx) || defined (STM32F051x8) || defined (STM32F058xx)
+ /* Packing mode management is enabled by the DMA settings */
+ if ((hspi->Init.DataSize <= SPI_DATASIZE_8BIT) && (hspi->hdmarx->Init.MemDataAlignment == DMA_MDATAALIGN_HALFWORD))
+ {
+ /* Restriction the DMA data received is not allowed in this mode */
+ errorcode = HAL_ERROR;
+ goto error;
+ }
+#endif /* STM32F030x6 || STM32F030x8 || STM32F031x6 || STM32F038xx || STM32F051x8 || STM32F058xx */
+
+ CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_LDMARX);
+ if (hspi->Init.DataSize > SPI_DATASIZE_8BIT)
+ {
+ /* Set RX Fifo threshold according the reception data length: 16bit */
+ CLEAR_BIT(hspi->Instance->CR2, SPI_RXFIFO_THRESHOLD);
+ }
+ else
+ {
+ /* Set RX Fifo threshold according the reception data length: 8bit */
+ SET_BIT(hspi->Instance->CR2, SPI_RXFIFO_THRESHOLD);
+
+ if (hspi->hdmarx->Init.MemDataAlignment == DMA_MDATAALIGN_HALFWORD)
+ {
+ /* Set RX Fifo threshold according the reception data length: 16bit */
+ CLEAR_BIT(hspi->Instance->CR2, SPI_RXFIFO_THRESHOLD);
+
+ if ((hspi->RxXferCount & 0x1U) == 0x0U)
+ {
+ CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_LDMARX);
+ hspi->RxXferCount = hspi->RxXferCount >> 1U;
+ }
+ else
+ {
+ SET_BIT(hspi->Instance->CR2, SPI_CR2_LDMARX);
+ hspi->RxXferCount = (hspi->RxXferCount >> 1U) + 1U;
+ }
+ }
+ }
+
+ /* Set the SPI RxDMA Half transfer complete callback */
+ hspi->hdmarx->XferHalfCpltCallback = SPI_DMAHalfReceiveCplt;
+
+ /* Set the SPI Rx DMA transfer complete callback */
+ hspi->hdmarx->XferCpltCallback = SPI_DMAReceiveCplt;
+
+ /* Set the DMA error callback */
+ hspi->hdmarx->XferErrorCallback = SPI_DMAError;
+
+ /* Set the DMA AbortCpltCallback */
+ hspi->hdmarx->XferAbortCallback = NULL;
+
+ /* Enable the Rx DMA Stream/Channel */
+ if (HAL_OK != HAL_DMA_Start_IT(hspi->hdmarx, (uint32_t)&hspi->Instance->DR, (uint32_t)hspi->pRxBuffPtr,
+ hspi->RxXferCount))
+ {
+ /* Update SPI error code */
+ SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_DMA);
+ errorcode = HAL_ERROR;
+
+ hspi->State = HAL_SPI_STATE_READY;
+ goto error;
+ }
+
+ /* Check if the SPI is already enabled */
+ if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE)
+ {
+ /* Enable SPI peripheral */
+ __HAL_SPI_ENABLE(hspi);
+ }
+
+ /* Enable the SPI Error Interrupt Bit */
+ __HAL_SPI_ENABLE_IT(hspi, (SPI_IT_ERR));
+
+ /* Enable Rx DMA Request */
+ SET_BIT(hspi->Instance->CR2, SPI_CR2_RXDMAEN);
+
+error:
+ /* Process Unlocked */
+ __HAL_UNLOCK(hspi);
+ return errorcode;
+}
+
+/**
+ * @brief Transmit and Receive an amount of data in non-blocking mode with DMA.
+ * @param hspi pointer to a SPI_HandleTypeDef structure that contains
+ * the configuration information for SPI module.
+ * @param pTxData pointer to transmission data buffer
+ * @param pRxData pointer to reception data buffer
+ * @note When the CRC feature is enabled the pRxData Length must be Size + 1
+ * @param Size amount of data to be sent
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_SPI_TransmitReceive_DMA(SPI_HandleTypeDef *hspi, uint8_t *pTxData, uint8_t *pRxData,
+ uint16_t Size)
+{
+ uint32_t tmp_mode;
+ HAL_SPI_StateTypeDef tmp_state;
+ HAL_StatusTypeDef errorcode = HAL_OK;
+
+ /* Check rx & tx dma handles */
+ assert_param(IS_SPI_DMA_HANDLE(hspi->hdmarx));
+ assert_param(IS_SPI_DMA_HANDLE(hspi->hdmatx));
+
+ /* Check Direction parameter */
+ assert_param(IS_SPI_DIRECTION_2LINES(hspi->Init.Direction));
+
+ /* Process locked */
+ __HAL_LOCK(hspi);
+
+ /* Init temporary variables */
+ tmp_state = hspi->State;
+ tmp_mode = hspi->Init.Mode;
+
+ if (!((tmp_state == HAL_SPI_STATE_READY) ||
+ ((tmp_mode == SPI_MODE_MASTER) && (hspi->Init.Direction == SPI_DIRECTION_2LINES) && (tmp_state == HAL_SPI_STATE_BUSY_RX))))
+ {
+ errorcode = HAL_BUSY;
+ goto error;
+ }
+
+ if ((pTxData == NULL) || (pRxData == NULL) || (Size == 0U))
+ {
+ errorcode = HAL_ERROR;
+ goto error;
+ }
+
+ /* Don't overwrite in case of HAL_SPI_STATE_BUSY_RX */
+ if (hspi->State != HAL_SPI_STATE_BUSY_RX)
+ {
+ hspi->State = HAL_SPI_STATE_BUSY_TX_RX;
+ }
+
+ /* Set the transaction information */
+ hspi->ErrorCode = HAL_SPI_ERROR_NONE;
+ hspi->pTxBuffPtr = (uint8_t *)pTxData;
+ hspi->TxXferSize = Size;
+ hspi->TxXferCount = Size;
+ hspi->pRxBuffPtr = (uint8_t *)pRxData;
+ hspi->RxXferSize = Size;
+ hspi->RxXferCount = Size;
+
+ /* Init field not used in handle to zero */
+ hspi->RxISR = NULL;
+ hspi->TxISR = NULL;
+
+#if (USE_SPI_CRC != 0U)
+ /* Reset CRC Calculation */
+ if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
+ {
+ SPI_RESET_CRC(hspi);
+ }
+#endif /* USE_SPI_CRC */
+
+#if defined (STM32F030x6) || defined (STM32F030x8) || defined (STM32F031x6) || defined (STM32F038xx) || defined (STM32F051x8) || defined (STM32F058xx)
+ /* Packing mode management is enabled by the DMA settings */
+ if ((hspi->Init.DataSize <= SPI_DATASIZE_8BIT) && (hspi->hdmarx->Init.MemDataAlignment == DMA_MDATAALIGN_HALFWORD))
+ {
+ /* Restriction the DMA data received is not allowed in this mode */
+ errorcode = HAL_ERROR;
+ goto error;
+ }
+#endif /* STM32F030x6 || STM32F030x8 || STM32F031x6 || STM32F038xx || STM32F051x8 || STM32F058xx */
+
+ /* Reset the threshold bit */
+ CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_LDMATX | SPI_CR2_LDMARX);
+
+ /* The packing mode management is enabled by the DMA settings according the spi data size */
+ if (hspi->Init.DataSize > SPI_DATASIZE_8BIT)
+ {
+ /* Set fiforxthreshold according the reception data length: 16bit */
+ CLEAR_BIT(hspi->Instance->CR2, SPI_RXFIFO_THRESHOLD);
+ }
+ else
+ {
+ /* Set RX Fifo threshold according the reception data length: 8bit */
+ SET_BIT(hspi->Instance->CR2, SPI_RXFIFO_THRESHOLD);
+
+ if (hspi->hdmatx->Init.MemDataAlignment == DMA_MDATAALIGN_HALFWORD)
+ {
+ if ((hspi->TxXferSize & 0x1U) == 0x0U)
+ {
+ CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_LDMATX);
+ hspi->TxXferCount = hspi->TxXferCount >> 1U;
+ }
+ else
+ {
+ SET_BIT(hspi->Instance->CR2, SPI_CR2_LDMATX);
+ hspi->TxXferCount = (hspi->TxXferCount >> 1U) + 1U;
+ }
+ }
+
+ if (hspi->hdmarx->Init.MemDataAlignment == DMA_MDATAALIGN_HALFWORD)
+ {
+ /* Set RX Fifo threshold according the reception data length: 16bit */
+ CLEAR_BIT(hspi->Instance->CR2, SPI_RXFIFO_THRESHOLD);
+
+ if ((hspi->RxXferCount & 0x1U) == 0x0U)
+ {
+ CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_LDMARX);
+ hspi->RxXferCount = hspi->RxXferCount >> 1U;
+ }
+ else
+ {
+ SET_BIT(hspi->Instance->CR2, SPI_CR2_LDMARX);
+ hspi->RxXferCount = (hspi->RxXferCount >> 1U) + 1U;
+ }
+ }
+ }
+
+ /* Check if we are in Rx only or in Rx/Tx Mode and configure the DMA transfer complete callback */
+ if (hspi->State == HAL_SPI_STATE_BUSY_RX)
+ {
+ /* Set the SPI Rx DMA Half transfer complete callback */
+ hspi->hdmarx->XferHalfCpltCallback = SPI_DMAHalfReceiveCplt;
+ hspi->hdmarx->XferCpltCallback = SPI_DMAReceiveCplt;
+ }
+ else
+ {
+ /* Set the SPI Tx/Rx DMA Half transfer complete callback */
+ hspi->hdmarx->XferHalfCpltCallback = SPI_DMAHalfTransmitReceiveCplt;
+ hspi->hdmarx->XferCpltCallback = SPI_DMATransmitReceiveCplt;
+ }
+
+ /* Set the DMA error callback */
+ hspi->hdmarx->XferErrorCallback = SPI_DMAError;
+
+ /* Set the DMA AbortCpltCallback */
+ hspi->hdmarx->XferAbortCallback = NULL;
+
+ /* Enable the Rx DMA Stream/Channel */
+ if (HAL_OK != HAL_DMA_Start_IT(hspi->hdmarx, (uint32_t)&hspi->Instance->DR, (uint32_t)hspi->pRxBuffPtr,
+ hspi->RxXferCount))
+ {
+ /* Update SPI error code */
+ SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_DMA);
+ errorcode = HAL_ERROR;
+
+ hspi->State = HAL_SPI_STATE_READY;
+ goto error;
+ }
+
+ /* Enable Rx DMA Request */
+ SET_BIT(hspi->Instance->CR2, SPI_CR2_RXDMAEN);
+
+ /* Set the SPI Tx DMA transfer complete callback as NULL because the communication closing
+ is performed in DMA reception complete callback */
+ hspi->hdmatx->XferHalfCpltCallback = NULL;
+ hspi->hdmatx->XferCpltCallback = NULL;
+ hspi->hdmatx->XferErrorCallback = NULL;
+ hspi->hdmatx->XferAbortCallback = NULL;
+
+ /* Enable the Tx DMA Stream/Channel */
+ if (HAL_OK != HAL_DMA_Start_IT(hspi->hdmatx, (uint32_t)hspi->pTxBuffPtr, (uint32_t)&hspi->Instance->DR,
+ hspi->TxXferCount))
+ {
+ /* Update SPI error code */
+ SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_DMA);
+ errorcode = HAL_ERROR;
+
+ hspi->State = HAL_SPI_STATE_READY;
+ goto error;
+ }
+
+ /* Check if the SPI is already enabled */
+ if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE)
+ {
+ /* Enable SPI peripheral */
+ __HAL_SPI_ENABLE(hspi);
+ }
+ /* Enable the SPI Error Interrupt Bit */
+ __HAL_SPI_ENABLE_IT(hspi, (SPI_IT_ERR));
+
+ /* Enable Tx DMA Request */
+ SET_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN);
+
+error :
+ /* Process Unlocked */
+ __HAL_UNLOCK(hspi);
+ return errorcode;
+}
+
+/**
+ * @brief Abort ongoing transfer (blocking mode).
+ * @param hspi SPI handle.
+ * @note This procedure could be used for aborting any ongoing transfer (Tx and Rx),
+ * started in Interrupt or DMA mode.
+ * This procedure performs following operations :
+ * - Disable SPI Interrupts (depending of transfer direction)
+ * - Disable the DMA transfer in the peripheral register (if enabled)
+ * - Abort DMA transfer by calling HAL_DMA_Abort (in case of transfer in DMA mode)
+ * - Set handle State to READY
+ * @note This procedure is executed in blocking mode : when exiting function, Abort is considered as completed.
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_SPI_Abort(SPI_HandleTypeDef *hspi)
+{
+ HAL_StatusTypeDef errorcode;
+ __IO uint32_t count;
+ __IO uint32_t resetcount;
+
+ /* Initialized local variable */
+ errorcode = HAL_OK;
+ resetcount = SPI_DEFAULT_TIMEOUT * (SystemCoreClock / 24U / 1000U);
+ count = resetcount;
+
+ /* Clear ERRIE interrupt to avoid error interrupts generation during Abort procedure */
+ CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_ERRIE);
+
+ /* Disable TXEIE, RXNEIE and ERRIE(mode fault event, overrun error, TI frame error) interrupts */
+ if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_TXEIE))
+ {
+ hspi->TxISR = SPI_AbortTx_ISR;
+ /* Wait HAL_SPI_STATE_ABORT state */
+ do
+ {
+ if (count == 0U)
+ {
+ SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_ABORT);
+ break;
+ }
+ count--;
+ } while (hspi->State != HAL_SPI_STATE_ABORT);
+ /* Reset Timeout Counter */
+ count = resetcount;
+ }
+
+ if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_RXNEIE))
+ {
+ hspi->RxISR = SPI_AbortRx_ISR;
+ /* Wait HAL_SPI_STATE_ABORT state */
+ do
+ {
+ if (count == 0U)
+ {
+ SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_ABORT);
+ break;
+ }
+ count--;
+ } while (hspi->State != HAL_SPI_STATE_ABORT);
+ /* Reset Timeout Counter */
+ count = resetcount;
+ }
+
+ /* Disable the SPI DMA Tx request if enabled */
+ if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_TXDMAEN))
+ {
+ /* Abort the SPI DMA Tx Stream/Channel : use blocking DMA Abort API (no callback) */
+ if (hspi->hdmatx != NULL)
+ {
+ /* Set the SPI DMA Abort callback :
+ will lead to call HAL_SPI_AbortCpltCallback() at end of DMA abort procedure */
+ hspi->hdmatx->XferAbortCallback = NULL;
+
+ /* Abort DMA Tx Handle linked to SPI Peripheral */
+ if (HAL_DMA_Abort(hspi->hdmatx) != HAL_OK)
+ {
+ hspi->ErrorCode = HAL_SPI_ERROR_ABORT;
+ }
+
+ /* Disable Tx DMA Request */
+ CLEAR_BIT(hspi->Instance->CR2, (SPI_CR2_TXDMAEN));
+
+ if (SPI_EndRxTxTransaction(hspi, SPI_DEFAULT_TIMEOUT, HAL_GetTick()) != HAL_OK)
+ {
+ hspi->ErrorCode = HAL_SPI_ERROR_ABORT;
+ }
+
+ /* Disable SPI Peripheral */
+ __HAL_SPI_DISABLE(hspi);
+
+ /* Empty the FRLVL fifo */
+ if (SPI_WaitFifoStateUntilTimeout(hspi, SPI_FLAG_FRLVL, SPI_FRLVL_EMPTY, SPI_DEFAULT_TIMEOUT, HAL_GetTick()) != HAL_OK)
+ {
+ hspi->ErrorCode = HAL_SPI_ERROR_ABORT;
+ }
+ }
+ }
+
+ /* Disable the SPI DMA Rx request if enabled */
+ if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_RXDMAEN))
+ {
+ /* Abort the SPI DMA Rx Stream/Channel : use blocking DMA Abort API (no callback) */
+ if (hspi->hdmarx != NULL)
+ {
+ /* Set the SPI DMA Abort callback :
+ will lead to call HAL_SPI_AbortCpltCallback() at end of DMA abort procedure */
+ hspi->hdmarx->XferAbortCallback = NULL;
+
+ /* Abort DMA Rx Handle linked to SPI Peripheral */
+ if (HAL_DMA_Abort(hspi->hdmarx) != HAL_OK)
+ {
+ hspi->ErrorCode = HAL_SPI_ERROR_ABORT;
+ }
+
+ /* Disable peripheral */
+ __HAL_SPI_DISABLE(hspi);
+
+ /* Control the BSY flag */
+ if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_BSY, RESET, SPI_DEFAULT_TIMEOUT, HAL_GetTick()) != HAL_OK)
+ {
+ hspi->ErrorCode = HAL_SPI_ERROR_ABORT;
+ }
+
+ /* Empty the FRLVL fifo */
+ if (SPI_WaitFifoStateUntilTimeout(hspi, SPI_FLAG_FRLVL, SPI_FRLVL_EMPTY, SPI_DEFAULT_TIMEOUT, HAL_GetTick()) != HAL_OK)
+ {
+ hspi->ErrorCode = HAL_SPI_ERROR_ABORT;
+ }
+
+ /* Disable Rx DMA Request */
+ CLEAR_BIT(hspi->Instance->CR2, (SPI_CR2_RXDMAEN));
+ }
+ }
+ /* Reset Tx and Rx transfer counters */
+ hspi->RxXferCount = 0U;
+ hspi->TxXferCount = 0U;
+
+ /* Check error during Abort procedure */
+ if (hspi->ErrorCode == HAL_SPI_ERROR_ABORT)
+ {
+ /* return HAL_Error in case of error during Abort procedure */
+ errorcode = HAL_ERROR;
+ }
+ else
+ {
+ /* Reset errorCode */
+ hspi->ErrorCode = HAL_SPI_ERROR_NONE;
+ }
+
+ /* Clear the Error flags in the SR register */
+ __HAL_SPI_CLEAR_OVRFLAG(hspi);
+ __HAL_SPI_CLEAR_FREFLAG(hspi);
+
+ /* Restore hspi->state to ready */
+ hspi->State = HAL_SPI_STATE_READY;
+
+ return errorcode;
+}
+
+/**
+ * @brief Abort ongoing transfer (Interrupt mode).
+ * @param hspi SPI handle.
+ * @note This procedure could be used for aborting any ongoing transfer (Tx and Rx),
+ * started in Interrupt or DMA mode.
+ * This procedure performs following operations :
+ * - Disable SPI Interrupts (depending of transfer direction)
+ * - Disable the DMA transfer in the peripheral register (if enabled)
+ * - Abort DMA transfer by calling HAL_DMA_Abort_IT (in case of transfer in DMA mode)
+ * - Set handle State to READY
+ * - At abort completion, call user abort complete callback
+ * @note This procedure is executed in Interrupt mode, meaning that abort procedure could be
+ * considered as completed only when user abort complete callback is executed (not when exiting function).
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_SPI_Abort_IT(SPI_HandleTypeDef *hspi)
+{
+ HAL_StatusTypeDef errorcode;
+ uint32_t abortcplt ;
+ __IO uint32_t count;
+ __IO uint32_t resetcount;
+
+ /* Initialized local variable */
+ errorcode = HAL_OK;
+ abortcplt = 1U;
+ resetcount = SPI_DEFAULT_TIMEOUT * (SystemCoreClock / 24U / 1000U);
+ count = resetcount;
+
+ /* Clear ERRIE interrupt to avoid error interrupts generation during Abort procedure */
+ CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_ERRIE);
+
+ /* Change Rx and Tx Irq Handler to Disable TXEIE, RXNEIE and ERRIE interrupts */
+ if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_TXEIE))
+ {
+ hspi->TxISR = SPI_AbortTx_ISR;
+ /* Wait HAL_SPI_STATE_ABORT state */
+ do
+ {
+ if (count == 0U)
+ {
+ SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_ABORT);
+ break;
+ }
+ count--;
+ } while (hspi->State != HAL_SPI_STATE_ABORT);
+ /* Reset Timeout Counter */
+ count = resetcount;
+ }
+
+ if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_RXNEIE))
+ {
+ hspi->RxISR = SPI_AbortRx_ISR;
+ /* Wait HAL_SPI_STATE_ABORT state */
+ do
+ {
+ if (count == 0U)
+ {
+ SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_ABORT);
+ break;
+ }
+ count--;
+ } while (hspi->State != HAL_SPI_STATE_ABORT);
+ /* Reset Timeout Counter */
+ count = resetcount;
+ }
+
+ /* If DMA Tx and/or DMA Rx Handles are associated to SPI Handle, DMA Abort complete callbacks should be initialised
+ before any call to DMA Abort functions */
+ /* DMA Tx Handle is valid */
+ if (hspi->hdmatx != NULL)
+ {
+ /* Set DMA Abort Complete callback if UART DMA Tx request if enabled.
+ Otherwise, set it to NULL */
+ if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_TXDMAEN))
+ {
+ hspi->hdmatx->XferAbortCallback = SPI_DMATxAbortCallback;
+ }
+ else
+ {
+ hspi->hdmatx->XferAbortCallback = NULL;
+ }
+ }
+ /* DMA Rx Handle is valid */
+ if (hspi->hdmarx != NULL)
+ {
+ /* Set DMA Abort Complete callback if UART DMA Rx request if enabled.
+ Otherwise, set it to NULL */
+ if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_RXDMAEN))
+ {
+ hspi->hdmarx->XferAbortCallback = SPI_DMARxAbortCallback;
+ }
+ else
+ {
+ hspi->hdmarx->XferAbortCallback = NULL;
+ }
+ }
+
+ /* Disable the SPI DMA Tx request if enabled */
+ if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_TXDMAEN))
+ {
+ /* Abort the SPI DMA Tx Stream/Channel */
+ if (hspi->hdmatx != NULL)
+ {
+ /* Abort DMA Tx Handle linked to SPI Peripheral */
+ if (HAL_DMA_Abort_IT(hspi->hdmatx) != HAL_OK)
+ {
+ hspi->hdmatx->XferAbortCallback = NULL;
+ hspi->ErrorCode = HAL_SPI_ERROR_ABORT;
+ }
+ else
+ {
+ abortcplt = 0U;
+ }
+ }
+ }
+ /* Disable the SPI DMA Rx request if enabled */
+ if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_RXDMAEN))
+ {
+ /* Abort the SPI DMA Rx Stream/Channel */
+ if (hspi->hdmarx != NULL)
+ {
+ /* Abort DMA Rx Handle linked to SPI Peripheral */
+ if (HAL_DMA_Abort_IT(hspi->hdmarx) != HAL_OK)
+ {
+ hspi->hdmarx->XferAbortCallback = NULL;
+ hspi->ErrorCode = HAL_SPI_ERROR_ABORT;
+ }
+ else
+ {
+ abortcplt = 0U;
+ }
+ }
+ }
+
+ if (abortcplt == 1U)
+ {
+ /* Reset Tx and Rx transfer counters */
+ hspi->RxXferCount = 0U;
+ hspi->TxXferCount = 0U;
+
+ /* Check error during Abort procedure */
+ if (hspi->ErrorCode == HAL_SPI_ERROR_ABORT)
+ {
+ /* return HAL_Error in case of error during Abort procedure */
+ errorcode = HAL_ERROR;
+ }
+ else
+ {
+ /* Reset errorCode */
+ hspi->ErrorCode = HAL_SPI_ERROR_NONE;
+ }
+
+ /* Clear the Error flags in the SR register */
+ __HAL_SPI_CLEAR_OVRFLAG(hspi);
+ __HAL_SPI_CLEAR_FREFLAG(hspi);
+
+ /* Restore hspi->State to Ready */
+ hspi->State = HAL_SPI_STATE_READY;
+
+ /* As no DMA to be aborted, call directly user Abort complete callback */
+#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U)
+ hspi->AbortCpltCallback(hspi);
+#else
+ HAL_SPI_AbortCpltCallback(hspi);
+#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */
+ }
+
+ return errorcode;
+}
+
+/**
+ * @brief Pause the DMA Transfer.
+ * @param hspi pointer to a SPI_HandleTypeDef structure that contains
+ * the configuration information for the specified SPI module.
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_SPI_DMAPause(SPI_HandleTypeDef *hspi)
+{
+ /* Process Locked */
+ __HAL_LOCK(hspi);
+
+ /* Disable the SPI DMA Tx & Rx requests */
+ CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN | SPI_CR2_RXDMAEN);
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hspi);
+
+ return HAL_OK;
+}
+
+/**
+ * @brief Resume the DMA Transfer.
+ * @param hspi pointer to a SPI_HandleTypeDef structure that contains
+ * the configuration information for the specified SPI module.
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_SPI_DMAResume(SPI_HandleTypeDef *hspi)
+{
+ /* Process Locked */
+ __HAL_LOCK(hspi);
+
+ /* Enable the SPI DMA Tx & Rx requests */
+ SET_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN | SPI_CR2_RXDMAEN);
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hspi);
+
+ return HAL_OK;
+}
+
+/**
+ * @brief Stop the DMA Transfer.
+ * @param hspi pointer to a SPI_HandleTypeDef structure that contains
+ * the configuration information for the specified SPI module.
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_SPI_DMAStop(SPI_HandleTypeDef *hspi)
+{
+ HAL_StatusTypeDef errorcode = HAL_OK;
+ /* The Lock is not implemented on this API to allow the user application
+ to call the HAL SPI API under callbacks HAL_SPI_TxCpltCallback() or HAL_SPI_RxCpltCallback() or HAL_SPI_TxRxCpltCallback():
+ when calling HAL_DMA_Abort() API the DMA TX/RX Transfer complete interrupt is generated
+ and the correspond call back is executed HAL_SPI_TxCpltCallback() or HAL_SPI_RxCpltCallback() or HAL_SPI_TxRxCpltCallback()
+ */
+
+ /* Abort the SPI DMA tx Stream/Channel */
+ if (hspi->hdmatx != NULL)
+ {
+ if (HAL_OK != HAL_DMA_Abort(hspi->hdmatx))
+ {
+ SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_DMA);
+ errorcode = HAL_ERROR;
+ }
+ }
+ /* Abort the SPI DMA rx Stream/Channel */
+ if (hspi->hdmarx != NULL)
+ {
+ if (HAL_OK != HAL_DMA_Abort(hspi->hdmarx))
+ {
+ SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_DMA);
+ errorcode = HAL_ERROR;
+ }
+ }
+
+ /* Disable the SPI DMA Tx & Rx requests */
+ CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN | SPI_CR2_RXDMAEN);
+ hspi->State = HAL_SPI_STATE_READY;
+ return errorcode;
+}
+
+/**
+ * @brief Handle SPI interrupt request.
+ * @param hspi pointer to a SPI_HandleTypeDef structure that contains
+ * the configuration information for the specified SPI module.
+ * @retval None
+ */
+void HAL_SPI_IRQHandler(SPI_HandleTypeDef *hspi)
+{
+ uint32_t itsource = hspi->Instance->CR2;
+ uint32_t itflag = hspi->Instance->SR;
+
+ /* SPI in mode Receiver ----------------------------------------------------*/
+ if ((SPI_CHECK_FLAG(itflag, SPI_FLAG_OVR) == RESET) &&
+ (SPI_CHECK_FLAG(itflag, SPI_FLAG_RXNE) != RESET) && (SPI_CHECK_IT_SOURCE(itsource, SPI_IT_RXNE) != RESET))
+ {
+ hspi->RxISR(hspi);
+ return;
+ }
+
+ /* SPI in mode Transmitter -------------------------------------------------*/
+ if ((SPI_CHECK_FLAG(itflag, SPI_FLAG_TXE) != RESET) && (SPI_CHECK_IT_SOURCE(itsource, SPI_IT_TXE) != RESET))
+ {
+ hspi->TxISR(hspi);
+ return;
+ }
+
+ /* SPI in Error Treatment --------------------------------------------------*/
+ if (((SPI_CHECK_FLAG(itflag, SPI_FLAG_MODF) != RESET) || (SPI_CHECK_FLAG(itflag, SPI_FLAG_OVR) != RESET)
+ || (SPI_CHECK_FLAG(itflag, SPI_FLAG_FRE) != RESET)) && (SPI_CHECK_IT_SOURCE(itsource, SPI_IT_ERR) != RESET))
+ {
+ /* SPI Overrun error interrupt occurred ----------------------------------*/
+ if (SPI_CHECK_FLAG(itflag, SPI_FLAG_OVR) != RESET)
+ {
+ if (hspi->State != HAL_SPI_STATE_BUSY_TX)
+ {
+ SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_OVR);
+ __HAL_SPI_CLEAR_OVRFLAG(hspi);
+ }
+ else
+ {
+ __HAL_SPI_CLEAR_OVRFLAG(hspi);
+ return;
+ }
+ }
+
+ /* SPI Mode Fault error interrupt occurred -------------------------------*/
+ if (SPI_CHECK_FLAG(itflag, SPI_FLAG_MODF) != RESET)
+ {
+ SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_MODF);
+ __HAL_SPI_CLEAR_MODFFLAG(hspi);
+ }
+
+ /* SPI Frame error interrupt occurred ------------------------------------*/
+ if (SPI_CHECK_FLAG(itflag, SPI_FLAG_FRE) != RESET)
+ {
+ SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FRE);
+ __HAL_SPI_CLEAR_FREFLAG(hspi);
+ }
+
+ if (hspi->ErrorCode != HAL_SPI_ERROR_NONE)
+ {
+ /* Disable all interrupts */
+ __HAL_SPI_DISABLE_IT(hspi, SPI_IT_RXNE | SPI_IT_TXE | SPI_IT_ERR);
+
+ hspi->State = HAL_SPI_STATE_READY;
+ /* Disable the SPI DMA requests if enabled */
+ if ((HAL_IS_BIT_SET(itsource, SPI_CR2_TXDMAEN)) || (HAL_IS_BIT_SET(itsource, SPI_CR2_RXDMAEN)))
+ {
+ CLEAR_BIT(hspi->Instance->CR2, (SPI_CR2_TXDMAEN | SPI_CR2_RXDMAEN));
+
+ /* Abort the SPI DMA Rx channel */
+ if (hspi->hdmarx != NULL)
+ {
+ /* Set the SPI DMA Abort callback :
+ will lead to call HAL_SPI_ErrorCallback() at end of DMA abort procedure */
+ hspi->hdmarx->XferAbortCallback = SPI_DMAAbortOnError;
+ if (HAL_OK != HAL_DMA_Abort_IT(hspi->hdmarx))
+ {
+ SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_ABORT);
+ }
+ }
+ /* Abort the SPI DMA Tx channel */
+ if (hspi->hdmatx != NULL)
+ {
+ /* Set the SPI DMA Abort callback :
+ will lead to call HAL_SPI_ErrorCallback() at end of DMA abort procedure */
+ hspi->hdmatx->XferAbortCallback = SPI_DMAAbortOnError;
+ if (HAL_OK != HAL_DMA_Abort_IT(hspi->hdmatx))
+ {
+ SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_ABORT);
+ }
+ }
+ }
+ else
+ {
+ /* Call user error callback */
+#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U)
+ hspi->ErrorCallback(hspi);
+#else
+ HAL_SPI_ErrorCallback(hspi);
+#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */
+ }
+ }
+ return;
+ }
+}
+
+/**
+ * @brief Tx Transfer completed callback.
+ * @param hspi pointer to a SPI_HandleTypeDef structure that contains
+ * the configuration information for SPI module.
+ * @retval None
+ */
+__weak void HAL_SPI_TxCpltCallback(SPI_HandleTypeDef *hspi)
+{
+ /* Prevent unused argument(s) compilation warning */
+ UNUSED(hspi);
+
+ /* NOTE : This function should not be modified, when the callback is needed,
+ the HAL_SPI_TxCpltCallback should be implemented in the user file
+ */
+}
+
+/**
+ * @brief Rx Transfer completed callback.
+ * @param hspi pointer to a SPI_HandleTypeDef structure that contains
+ * the configuration information for SPI module.
+ * @retval None
+ */
+__weak void HAL_SPI_RxCpltCallback(SPI_HandleTypeDef *hspi)
+{
+ /* Prevent unused argument(s) compilation warning */
+ UNUSED(hspi);
+
+ /* NOTE : This function should not be modified, when the callback is needed,
+ the HAL_SPI_RxCpltCallback should be implemented in the user file
+ */
+}
+
+/**
+ * @brief Tx and Rx Transfer completed callback.
+ * @param hspi pointer to a SPI_HandleTypeDef structure that contains
+ * the configuration information for SPI module.
+ * @retval None
+ */
+__weak void HAL_SPI_TxRxCpltCallback(SPI_HandleTypeDef *hspi)
+{
+ /* Prevent unused argument(s) compilation warning */
+ UNUSED(hspi);
+
+ /* NOTE : This function should not be modified, when the callback is needed,
+ the HAL_SPI_TxRxCpltCallback should be implemented in the user file
+ */
+}
+
+/**
+ * @brief Tx Half Transfer completed callback.
+ * @param hspi pointer to a SPI_HandleTypeDef structure that contains
+ * the configuration information for SPI module.
+ * @retval None
+ */
+__weak void HAL_SPI_TxHalfCpltCallback(SPI_HandleTypeDef *hspi)
+{
+ /* Prevent unused argument(s) compilation warning */
+ UNUSED(hspi);
+
+ /* NOTE : This function should not be modified, when the callback is needed,
+ the HAL_SPI_TxHalfCpltCallback should be implemented in the user file
+ */
+}
+
+/**
+ * @brief Rx Half Transfer completed callback.
+ * @param hspi pointer to a SPI_HandleTypeDef structure that contains
+ * the configuration information for SPI module.
+ * @retval None
+ */
+__weak void HAL_SPI_RxHalfCpltCallback(SPI_HandleTypeDef *hspi)
+{
+ /* Prevent unused argument(s) compilation warning */
+ UNUSED(hspi);
+
+ /* NOTE : This function should not be modified, when the callback is needed,
+ the HAL_SPI_RxHalfCpltCallback() should be implemented in the user file
+ */
+}
+
+/**
+ * @brief Tx and Rx Half Transfer callback.
+ * @param hspi pointer to a SPI_HandleTypeDef structure that contains
+ * the configuration information for SPI module.
+ * @retval None
+ */
+__weak void HAL_SPI_TxRxHalfCpltCallback(SPI_HandleTypeDef *hspi)
+{
+ /* Prevent unused argument(s) compilation warning */
+ UNUSED(hspi);
+
+ /* NOTE : This function should not be modified, when the callback is needed,
+ the HAL_SPI_TxRxHalfCpltCallback() should be implemented in the user file
+ */
+}
+
+/**
+ * @brief SPI error callback.
+ * @param hspi pointer to a SPI_HandleTypeDef structure that contains
+ * the configuration information for SPI module.
+ * @retval None
+ */
+__weak void HAL_SPI_ErrorCallback(SPI_HandleTypeDef *hspi)
+{
+ /* Prevent unused argument(s) compilation warning */
+ UNUSED(hspi);
+
+ /* NOTE : This function should not be modified, when the callback is needed,
+ the HAL_SPI_ErrorCallback should be implemented in the user file
+ */
+ /* NOTE : The ErrorCode parameter in the hspi handle is updated by the SPI processes
+ and user can use HAL_SPI_GetError() API to check the latest error occurred
+ */
+}
+
+/**
+ * @brief SPI Abort Complete callback.
+ * @param hspi SPI handle.
+ * @retval None
+ */
+__weak void HAL_SPI_AbortCpltCallback(SPI_HandleTypeDef *hspi)
+{
+ /* Prevent unused argument(s) compilation warning */
+ UNUSED(hspi);
+
+ /* NOTE : This function should not be modified, when the callback is needed,
+ the HAL_SPI_AbortCpltCallback can be implemented in the user file.
+ */
+}
+
+/**
+ * @}
+ */
+
+/** @defgroup SPI_Exported_Functions_Group3 Peripheral State and Errors functions
+ * @brief SPI control functions
+ *
+@verbatim
+ ===============================================================================
+ ##### Peripheral State and Errors functions #####
+ ===============================================================================
+ [..]
+ This subsection provides a set of functions allowing to control the SPI.
+ (+) HAL_SPI_GetState() API can be helpful to check in run-time the state of the SPI peripheral
+ (+) HAL_SPI_GetError() check in run-time Errors occurring during communication
+@endverbatim
+ * @{
+ */
+
+/**
+ * @brief Return the SPI handle state.
+ * @param hspi pointer to a SPI_HandleTypeDef structure that contains
+ * the configuration information for SPI module.
+ * @retval SPI state
+ */
+HAL_SPI_StateTypeDef HAL_SPI_GetState(SPI_HandleTypeDef *hspi)
+{
+ /* Return SPI handle state */
+ return hspi->State;
+}
+
+/**
+ * @brief Return the SPI error code.
+ * @param hspi pointer to a SPI_HandleTypeDef structure that contains
+ * the configuration information for SPI module.
+ * @retval SPI error code in bitmap format
+ */
+uint32_t HAL_SPI_GetError(SPI_HandleTypeDef *hspi)
+{
+ /* Return SPI ErrorCode */
+ return hspi->ErrorCode;
+}
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/** @addtogroup SPI_Private_Functions
+ * @brief Private functions
+ * @{
+ */
+
+/**
+ * @brief DMA SPI transmit process complete callback.
+ * @param hdma pointer to a DMA_HandleTypeDef structure that contains
+ * the configuration information for the specified DMA module.
+ * @retval None
+ */
+static void SPI_DMATransmitCplt(DMA_HandleTypeDef *hdma)
+{
+ SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent); /* Derogation MISRAC2012-Rule-11.5 */
+ uint32_t tickstart;
+
+ /* Init tickstart for timeout management*/
+ tickstart = HAL_GetTick();
+
+ /* DMA Normal Mode */
+ if ((hdma->Instance->CCR & DMA_CCR_CIRC) != DMA_CCR_CIRC)
+ {
+ /* Disable ERR interrupt */
+ __HAL_SPI_DISABLE_IT(hspi, SPI_IT_ERR);
+
+ /* Disable Tx DMA Request */
+ CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN);
+
+ /* Check the end of the transaction */
+ if (SPI_EndRxTxTransaction(hspi, SPI_DEFAULT_TIMEOUT, tickstart) != HAL_OK)
+ {
+ SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG);
+ }
+
+ /* Clear overrun flag in 2 Lines communication mode because received data is not read */
+ if (hspi->Init.Direction == SPI_DIRECTION_2LINES)
+ {
+ __HAL_SPI_CLEAR_OVRFLAG(hspi);
+ }
+
+ hspi->TxXferCount = 0U;
+ hspi->State = HAL_SPI_STATE_READY;
+
+ if (hspi->ErrorCode != HAL_SPI_ERROR_NONE)
+ {
+ /* Call user error callback */
+#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U)
+ hspi->ErrorCallback(hspi);
+#else
+ HAL_SPI_ErrorCallback(hspi);
+#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */
+ return;
+ }
+ }
+ /* Call user Tx complete callback */
+#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U)
+ hspi->TxCpltCallback(hspi);
+#else
+ HAL_SPI_TxCpltCallback(hspi);
+#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */
+}
+
+/**
+ * @brief DMA SPI receive process complete callback.
+ * @param hdma pointer to a DMA_HandleTypeDef structure that contains
+ * the configuration information for the specified DMA module.
+ * @retval None
+ */
+static void SPI_DMAReceiveCplt(DMA_HandleTypeDef *hdma)
+{
+ SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent); /* Derogation MISRAC2012-Rule-11.5 */
+ uint32_t tickstart;
+#if (USE_SPI_CRC != 0U)
+ __IO uint32_t tmpreg = 0U;
+ __IO uint8_t * ptmpreg8;
+ __IO uint8_t tmpreg8 = 0;
+#endif /* USE_SPI_CRC */
+
+ /* Init tickstart for timeout management*/
+ tickstart = HAL_GetTick();
+
+ /* DMA Normal Mode */
+ if ((hdma->Instance->CCR & DMA_CCR_CIRC) != DMA_CCR_CIRC)
+ {
+ /* Disable ERR interrupt */
+ __HAL_SPI_DISABLE_IT(hspi, SPI_IT_ERR);
+
+#if (USE_SPI_CRC != 0U)
+ /* CRC handling */
+ if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
+ {
+ /* Wait until RXNE flag */
+ if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_RXNE, SET, SPI_DEFAULT_TIMEOUT, tickstart) != HAL_OK)
+ {
+ /* Error on the CRC reception */
+ SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC);
+ }
+ /* Read CRC */
+ if (hspi->Init.DataSize > SPI_DATASIZE_8BIT)
+ {
+ /* Read 16bit CRC */
+ tmpreg = READ_REG(hspi->Instance->DR);
+ /* To avoid GCC warning */
+ UNUSED(tmpreg);
+ }
+ else
+ {
+ /* Initialize the 8bit temporary pointer */
+ ptmpreg8 = (__IO uint8_t *)&hspi->Instance->DR;
+ /* Read 8bit CRC */
+ tmpreg8 = *ptmpreg8;
+ /* To avoid GCC warning */
+ UNUSED(tmpreg8);
+
+ if (hspi->Init.CRCLength == SPI_CRC_LENGTH_16BIT)
+ {
+ if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_RXNE, SET, SPI_DEFAULT_TIMEOUT, tickstart) != HAL_OK)
+ {
+ /* Error on the CRC reception */
+ SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC);
+ }
+ /* Read 8bit CRC again in case of 16bit CRC in 8bit Data mode */
+ tmpreg8 = *ptmpreg8;
+ /* To avoid GCC warning */
+ UNUSED(tmpreg8);
+ }
+ }
+ }
+#endif /* USE_SPI_CRC */
+
+ /* Check if we are in Master RX 2 line mode */
+ if ((hspi->Init.Direction == SPI_DIRECTION_2LINES) && (hspi->Init.Mode == SPI_MODE_MASTER))
+ {
+ /* Disable Rx/Tx DMA Request (done by default to handle the case master rx direction 2 lines) */
+ CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN | SPI_CR2_RXDMAEN);
+ }
+ else
+ {
+ /* Normal case */
+ CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_RXDMAEN);
+ }
+
+ /* Check the end of the transaction */
+ if (SPI_EndRxTransaction(hspi, SPI_DEFAULT_TIMEOUT, tickstart) != HAL_OK)
+ {
+ hspi->ErrorCode = HAL_SPI_ERROR_FLAG;
+ }
+
+ hspi->RxXferCount = 0U;
+ hspi->State = HAL_SPI_STATE_READY;
+
+#if (USE_SPI_CRC != 0U)
+ /* Check if CRC error occurred */
+ if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_CRCERR))
+ {
+ SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC);
+ __HAL_SPI_CLEAR_CRCERRFLAG(hspi);
+ }
+#endif /* USE_SPI_CRC */
+
+ if (hspi->ErrorCode != HAL_SPI_ERROR_NONE)
+ {
+ /* Call user error callback */
+#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U)
+ hspi->ErrorCallback(hspi);
+#else
+ HAL_SPI_ErrorCallback(hspi);
+#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */
+ return;
+ }
+ }
+ /* Call user Rx complete callback */
+#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U)
+ hspi->RxCpltCallback(hspi);
+#else
+ HAL_SPI_RxCpltCallback(hspi);
+#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */
+}
+
+/**
+ * @brief DMA SPI transmit receive process complete callback.
+ * @param hdma pointer to a DMA_HandleTypeDef structure that contains
+ * the configuration information for the specified DMA module.
+ * @retval None
+ */
+static void SPI_DMATransmitReceiveCplt(DMA_HandleTypeDef *hdma)
+{
+ SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent); /* Derogation MISRAC2012-Rule-11.5 */
+ uint32_t tickstart;
+#if (USE_SPI_CRC != 0U)
+ __IO uint32_t tmpreg = 0U;
+ __IO uint8_t * ptmpreg8;
+ __IO uint8_t tmpreg8 = 0;
+#endif /* USE_SPI_CRC */
+
+ /* Init tickstart for timeout management*/
+ tickstart = HAL_GetTick();
+
+ /* DMA Normal Mode */
+ if ((hdma->Instance->CCR & DMA_CCR_CIRC) != DMA_CCR_CIRC)
+ {
+ /* Disable ERR interrupt */
+ __HAL_SPI_DISABLE_IT(hspi, SPI_IT_ERR);
+
+#if (USE_SPI_CRC != 0U)
+ /* CRC handling */
+ if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
+ {
+ if ((hspi->Init.DataSize == SPI_DATASIZE_8BIT) && (hspi->Init.CRCLength == SPI_CRC_LENGTH_8BIT))
+ {
+ if (SPI_WaitFifoStateUntilTimeout(hspi, SPI_FLAG_FRLVL, SPI_FRLVL_QUARTER_FULL, SPI_DEFAULT_TIMEOUT,
+ tickstart) != HAL_OK)
+ {
+ /* Error on the CRC reception */
+ SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC);
+ }
+ /* Initialize the 8bit temporary pointer */
+ ptmpreg8 = (__IO uint8_t *)&hspi->Instance->DR;
+ /* Read 8bit CRC */
+ tmpreg8 = *ptmpreg8;
+ /* To avoid GCC warning */
+ UNUSED(tmpreg8);
+ }
+ else
+ {
+ if (SPI_WaitFifoStateUntilTimeout(hspi, SPI_FLAG_FRLVL, SPI_FRLVL_HALF_FULL, SPI_DEFAULT_TIMEOUT, tickstart) != HAL_OK)
+ {
+ /* Error on the CRC reception */
+ SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC);
+ }
+ /* Read CRC to Flush DR and RXNE flag */
+ tmpreg = READ_REG(hspi->Instance->DR);
+ /* To avoid GCC warning */
+ UNUSED(tmpreg);
+ }
+ }
+#endif /* USE_SPI_CRC */
+
+ /* Check the end of the transaction */
+ if (SPI_EndRxTxTransaction(hspi, SPI_DEFAULT_TIMEOUT, tickstart) != HAL_OK)
+ {
+ SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG);
+ }
+
+ /* Disable Rx/Tx DMA Request */
+ CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN | SPI_CR2_RXDMAEN);
+
+ hspi->TxXferCount = 0U;
+ hspi->RxXferCount = 0U;
+ hspi->State = HAL_SPI_STATE_READY;
+
+#if (USE_SPI_CRC != 0U)
+ /* Check if CRC error occurred */
+ if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_CRCERR))
+ {
+ SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC);
+ __HAL_SPI_CLEAR_CRCERRFLAG(hspi);
+ }
+#endif /* USE_SPI_CRC */
+
+ if (hspi->ErrorCode != HAL_SPI_ERROR_NONE)
+ {
+ /* Call user error callback */
+#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U)
+ hspi->ErrorCallback(hspi);
+#else
+ HAL_SPI_ErrorCallback(hspi);
+#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */
+ return;
+ }
+ }
+ /* Call user TxRx complete callback */
+#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U)
+ hspi->TxRxCpltCallback(hspi);
+#else
+ HAL_SPI_TxRxCpltCallback(hspi);
+#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */
+}
+
+/**
+ * @brief DMA SPI half transmit process complete callback.
+ * @param hdma pointer to a DMA_HandleTypeDef structure that contains
+ * the configuration information for the specified DMA module.
+ * @retval None
+ */
+static void SPI_DMAHalfTransmitCplt(DMA_HandleTypeDef *hdma)
+{
+ SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent); /* Derogation MISRAC2012-Rule-11.5 */
+
+ /* Call user Tx half complete callback */
+#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U)
+ hspi->TxHalfCpltCallback(hspi);
+#else
+ HAL_SPI_TxHalfCpltCallback(hspi);
+#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */
+}
+
+/**
+ * @brief DMA SPI half receive process complete callback
+ * @param hdma pointer to a DMA_HandleTypeDef structure that contains
+ * the configuration information for the specified DMA module.
+ * @retval None
+ */
+static void SPI_DMAHalfReceiveCplt(DMA_HandleTypeDef *hdma)
+{
+ SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent); /* Derogation MISRAC2012-Rule-11.5 */
+
+ /* Call user Rx half complete callback */
+#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U)
+ hspi->RxHalfCpltCallback(hspi);
+#else
+ HAL_SPI_RxHalfCpltCallback(hspi);
+#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */
+}
+
+/**
+ * @brief DMA SPI half transmit receive process complete callback.
+ * @param hdma pointer to a DMA_HandleTypeDef structure that contains
+ * the configuration information for the specified DMA module.
+ * @retval None
+ */
+static void SPI_DMAHalfTransmitReceiveCplt(DMA_HandleTypeDef *hdma)
+{
+ SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent); /* Derogation MISRAC2012-Rule-11.5 */
+
+ /* Call user TxRx half complete callback */
+#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U)
+ hspi->TxRxHalfCpltCallback(hspi);
+#else
+ HAL_SPI_TxRxHalfCpltCallback(hspi);
+#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */
+}
+
+/**
+ * @brief DMA SPI communication error callback.
+ * @param hdma pointer to a DMA_HandleTypeDef structure that contains
+ * the configuration information for the specified DMA module.
+ * @retval None
+ */
+static void SPI_DMAError(DMA_HandleTypeDef *hdma)
+{
+ SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent); /* Derogation MISRAC2012-Rule-11.5 */
+
+ /* Stop the disable DMA transfer on SPI side */
+ CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN | SPI_CR2_RXDMAEN);
+
+ SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_DMA);
+ hspi->State = HAL_SPI_STATE_READY;
+ /* Call user error callback */
+#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U)
+ hspi->ErrorCallback(hspi);
+#else
+ HAL_SPI_ErrorCallback(hspi);
+#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */
+}
+
+/**
+ * @brief DMA SPI communication abort callback, when initiated by HAL services on Error
+ * (To be called at end of DMA Abort procedure following error occurrence).
+ * @param hdma DMA handle.
+ * @retval None
+ */
+static void SPI_DMAAbortOnError(DMA_HandleTypeDef *hdma)
+{
+ SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent); /* Derogation MISRAC2012-Rule-11.5 */
+ hspi->RxXferCount = 0U;
+ hspi->TxXferCount = 0U;
+
+ /* Call user error callback */
+#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U)
+ hspi->ErrorCallback(hspi);
+#else
+ HAL_SPI_ErrorCallback(hspi);
+#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */
+}
+
+/**
+ * @brief DMA SPI Tx communication abort callback, when initiated by user
+ * (To be called at end of DMA Tx Abort procedure following user abort request).
+ * @note When this callback is executed, User Abort complete call back is called only if no
+ * Abort still ongoing for Rx DMA Handle.
+ * @param hdma DMA handle.
+ * @retval None
+ */
+static void SPI_DMATxAbortCallback(DMA_HandleTypeDef *hdma)
+{
+ SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent); /* Derogation MISRAC2012-Rule-11.5 */
+
+ hspi->hdmatx->XferAbortCallback = NULL;
+
+ /* Disable Tx DMA Request */
+ CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN);
+
+ if (SPI_EndRxTxTransaction(hspi, SPI_DEFAULT_TIMEOUT, HAL_GetTick()) != HAL_OK)
+ {
+ hspi->ErrorCode = HAL_SPI_ERROR_ABORT;
+ }
+
+ /* Disable SPI Peripheral */
+ __HAL_SPI_DISABLE(hspi);
+
+ /* Empty the FRLVL fifo */
+ if (SPI_WaitFifoStateUntilTimeout(hspi, SPI_FLAG_FRLVL, SPI_FRLVL_EMPTY, SPI_DEFAULT_TIMEOUT, HAL_GetTick()) != HAL_OK)
+ {
+ hspi->ErrorCode = HAL_SPI_ERROR_ABORT;
+ }
+
+ /* Check if an Abort process is still ongoing */
+ if (hspi->hdmarx != NULL)
+ {
+ if (hspi->hdmarx->XferAbortCallback != NULL)
+ {
+ return;
+ }
+ }
+
+ /* No Abort process still ongoing : All DMA Stream/Channel are aborted, call user Abort Complete callback */
+ hspi->RxXferCount = 0U;
+ hspi->TxXferCount = 0U;
+
+ /* Check no error during Abort procedure */
+ if (hspi->ErrorCode != HAL_SPI_ERROR_ABORT)
+ {
+ /* Reset errorCode */
+ hspi->ErrorCode = HAL_SPI_ERROR_NONE;
+ }
+
+ /* Clear the Error flags in the SR register */
+ __HAL_SPI_CLEAR_OVRFLAG(hspi);
+ __HAL_SPI_CLEAR_FREFLAG(hspi);
+
+ /* Restore hspi->State to Ready */
+ hspi->State = HAL_SPI_STATE_READY;
+
+ /* Call user Abort complete callback */
+#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U)
+ hspi->AbortCpltCallback(hspi);
+#else
+ HAL_SPI_AbortCpltCallback(hspi);
+#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */
+}
+
+/**
+ * @brief DMA SPI Rx communication abort callback, when initiated by user
+ * (To be called at end of DMA Rx Abort procedure following user abort request).
+ * @note When this callback is executed, User Abort complete call back is called only if no
+ * Abort still ongoing for Tx DMA Handle.
+ * @param hdma DMA handle.
+ * @retval None
+ */
+static void SPI_DMARxAbortCallback(DMA_HandleTypeDef *hdma)
+{
+ SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent); /* Derogation MISRAC2012-Rule-11.5 */
+
+ /* Disable SPI Peripheral */
+ __HAL_SPI_DISABLE(hspi);
+
+ hspi->hdmarx->XferAbortCallback = NULL;
+
+ /* Disable Rx DMA Request */
+ CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_RXDMAEN);
+
+ /* Control the BSY flag */
+ if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_BSY, RESET, SPI_DEFAULT_TIMEOUT, HAL_GetTick()) != HAL_OK)
+ {
+ hspi->ErrorCode = HAL_SPI_ERROR_ABORT;
+ }
+
+ /* Empty the FRLVL fifo */
+ if (SPI_WaitFifoStateUntilTimeout(hspi, SPI_FLAG_FRLVL, SPI_FRLVL_EMPTY, SPI_DEFAULT_TIMEOUT, HAL_GetTick()) != HAL_OK)
+ {
+ hspi->ErrorCode = HAL_SPI_ERROR_ABORT;
+ }
+
+ /* Check if an Abort process is still ongoing */
+ if (hspi->hdmatx != NULL)
+ {
+ if (hspi->hdmatx->XferAbortCallback != NULL)
+ {
+ return;
+ }
+ }
+
+ /* No Abort process still ongoing : All DMA Stream/Channel are aborted, call user Abort Complete callback */
+ hspi->RxXferCount = 0U;
+ hspi->TxXferCount = 0U;
+
+ /* Check no error during Abort procedure */
+ if (hspi->ErrorCode != HAL_SPI_ERROR_ABORT)
+ {
+ /* Reset errorCode */
+ hspi->ErrorCode = HAL_SPI_ERROR_NONE;
+ }
+
+ /* Clear the Error flags in the SR register */
+ __HAL_SPI_CLEAR_OVRFLAG(hspi);
+ __HAL_SPI_CLEAR_FREFLAG(hspi);
+
+ /* Restore hspi->State to Ready */
+ hspi->State = HAL_SPI_STATE_READY;
+
+ /* Call user Abort complete callback */
+#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U)
+ hspi->AbortCpltCallback(hspi);
+#else
+ HAL_SPI_AbortCpltCallback(hspi);
+#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */
+}
+
+/**
+ * @brief Rx 8-bit handler for Transmit and Receive in Interrupt mode.
+ * @param hspi pointer to a SPI_HandleTypeDef structure that contains
+ * the configuration information for SPI module.
+ * @retval None
+ */
+static void SPI_2linesRxISR_8BIT(struct __SPI_HandleTypeDef *hspi)
+{
+ /* Receive data in packing mode */
+ if (hspi->RxXferCount > 1U)
+ {
+ *((uint16_t *)hspi->pRxBuffPtr) = (uint16_t)(hspi->Instance->DR);
+ hspi->pRxBuffPtr += sizeof(uint16_t);
+ hspi->RxXferCount -= 2U;
+ if (hspi->RxXferCount == 1U)
+ {
+ /* Set RX Fifo threshold according the reception data length: 8bit */
+ SET_BIT(hspi->Instance->CR2, SPI_RXFIFO_THRESHOLD);
+ }
+ }
+ /* Receive data in 8 Bit mode */
+ else
+ {
+ *hspi->pRxBuffPtr = *((__IO uint8_t *)&hspi->Instance->DR);
+ hspi->pRxBuffPtr++;
+ hspi->RxXferCount--;
+ }
+
+ /* Check end of the reception */
+ if (hspi->RxXferCount == 0U)
+ {
+#if (USE_SPI_CRC != 0U)
+ if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
+ {
+ SET_BIT(hspi->Instance->CR2, SPI_RXFIFO_THRESHOLD);
+ hspi->RxISR = SPI_2linesRxISR_8BITCRC;
+ return;
+ }
+#endif /* USE_SPI_CRC */
+
+ /* Disable RXNE and ERR interrupt */
+ __HAL_SPI_DISABLE_IT(hspi, (SPI_IT_RXNE | SPI_IT_ERR));
+
+ if (hspi->TxXferCount == 0U)
+ {
+ SPI_CloseRxTx_ISR(hspi);
+ }
+ }
+}
+
+#if (USE_SPI_CRC != 0U)
+/**
+ * @brief Rx 8-bit handler for Transmit and Receive in Interrupt mode.
+ * @param hspi pointer to a SPI_HandleTypeDef structure that contains
+ * the configuration information for SPI module.
+ * @retval None
+ */
+static void SPI_2linesRxISR_8BITCRC(struct __SPI_HandleTypeDef *hspi)
+{
+ __IO uint8_t * ptmpreg8;
+ __IO uint8_t tmpreg8 = 0;
+
+ /* Initialize the 8bit temporary pointer */
+ ptmpreg8 = (__IO uint8_t *)&hspi->Instance->DR;
+ /* Read 8bit CRC to flush Data Register */
+ tmpreg8 = *ptmpreg8;
+ /* To avoid GCC warning */
+ UNUSED(tmpreg8);
+
+ hspi->CRCSize--;
+
+ /* Check end of the reception */
+ if (hspi->CRCSize == 0U)
+ {
+ /* Disable RXNE and ERR interrupt */
+ __HAL_SPI_DISABLE_IT(hspi, (SPI_IT_RXNE | SPI_IT_ERR));
+
+ if (hspi->TxXferCount == 0U)
+ {
+ SPI_CloseRxTx_ISR(hspi);
+ }
+ }
+}
+#endif /* USE_SPI_CRC */
+
+/**
+ * @brief Tx 8-bit handler for Transmit and Receive in Interrupt mode.
+ * @param hspi pointer to a SPI_HandleTypeDef structure that contains
+ * the configuration information for SPI module.
+ * @retval None
+ */
+static void SPI_2linesTxISR_8BIT(struct __SPI_HandleTypeDef *hspi)
+{
+ /* Transmit data in packing Bit mode */
+ if (hspi->TxXferCount >= 2U)
+ {
+ hspi->Instance->DR = *((uint16_t *)hspi->pTxBuffPtr);
+ hspi->pTxBuffPtr += sizeof(uint16_t);
+ hspi->TxXferCount -= 2U;
+ }
+ /* Transmit data in 8 Bit mode */
+ else
+ {
+ *(__IO uint8_t *)&hspi->Instance->DR = (*hspi->pTxBuffPtr);
+ hspi->pTxBuffPtr++;
+ hspi->TxXferCount--;
+ }
+
+ /* Check the end of the transmission */
+ if (hspi->TxXferCount == 0U)
+ {
+#if (USE_SPI_CRC != 0U)
+ if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
+ {
+ /* Set CRC Next Bit to send CRC */
+ SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT);
+ /* Disable TXE interrupt */
+ __HAL_SPI_DISABLE_IT(hspi, SPI_IT_TXE);
+ return;
+ }
+#endif /* USE_SPI_CRC */
+
+ /* Disable TXE interrupt */
+ __HAL_SPI_DISABLE_IT(hspi, SPI_IT_TXE);
+
+ if (hspi->RxXferCount == 0U)
+ {
+ SPI_CloseRxTx_ISR(hspi);
+ }
+ }
+}
+
+/**
+ * @brief Rx 16-bit handler for Transmit and Receive in Interrupt mode.
+ * @param hspi pointer to a SPI_HandleTypeDef structure that contains
+ * the configuration information for SPI module.
+ * @retval None
+ */
+static void SPI_2linesRxISR_16BIT(struct __SPI_HandleTypeDef *hspi)
+{
+ /* Receive data in 16 Bit mode */
+ *((uint16_t *)hspi->pRxBuffPtr) = (uint16_t)(hspi->Instance->DR);
+ hspi->pRxBuffPtr += sizeof(uint16_t);
+ hspi->RxXferCount--;
+
+ if (hspi->RxXferCount == 0U)
+ {
+#if (USE_SPI_CRC != 0U)
+ if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
+ {
+ hspi->RxISR = SPI_2linesRxISR_16BITCRC;
+ return;
+ }
+#endif /* USE_SPI_CRC */
+
+ /* Disable RXNE interrupt */
+ __HAL_SPI_DISABLE_IT(hspi, SPI_IT_RXNE);
+
+ if (hspi->TxXferCount == 0U)
+ {
+ SPI_CloseRxTx_ISR(hspi);
+ }
+ }
+}
+
+#if (USE_SPI_CRC != 0U)
+/**
+ * @brief Manage the CRC 16-bit receive for Transmit and Receive in Interrupt mode.
+ * @param hspi pointer to a SPI_HandleTypeDef structure that contains
+ * the configuration information for SPI module.
+ * @retval None
+ */
+static void SPI_2linesRxISR_16BITCRC(struct __SPI_HandleTypeDef *hspi)
+{
+ __IO uint32_t tmpreg = 0U;
+
+ /* Read 16bit CRC to flush Data Register */
+ tmpreg = READ_REG(hspi->Instance->DR);
+ /* To avoid GCC warning */
+ UNUSED(tmpreg);
+
+ /* Disable RXNE interrupt */
+ __HAL_SPI_DISABLE_IT(hspi, SPI_IT_RXNE);
+
+ SPI_CloseRxTx_ISR(hspi);
+}
+#endif /* USE_SPI_CRC */
+
+/**
+ * @brief Tx 16-bit handler for Transmit and Receive in Interrupt mode.
+ * @param hspi pointer to a SPI_HandleTypeDef structure that contains
+ * the configuration information for SPI module.
+ * @retval None
+ */
+static void SPI_2linesTxISR_16BIT(struct __SPI_HandleTypeDef *hspi)
+{
+ /* Transmit data in 16 Bit mode */
+ hspi->Instance->DR = *((uint16_t *)hspi->pTxBuffPtr);
+ hspi->pTxBuffPtr += sizeof(uint16_t);
+ hspi->TxXferCount--;
+
+ /* Enable CRC Transmission */
+ if (hspi->TxXferCount == 0U)
+ {
+#if (USE_SPI_CRC != 0U)
+ if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
+ {
+ /* Set CRC Next Bit to send CRC */
+ SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT);
+ /* Disable TXE interrupt */
+ __HAL_SPI_DISABLE_IT(hspi, SPI_IT_TXE);
+ return;
+ }
+#endif /* USE_SPI_CRC */
+
+ /* Disable TXE interrupt */
+ __HAL_SPI_DISABLE_IT(hspi, SPI_IT_TXE);
+
+ if (hspi->RxXferCount == 0U)
+ {
+ SPI_CloseRxTx_ISR(hspi);
+ }
+ }
+}
+
+#if (USE_SPI_CRC != 0U)
+/**
+ * @brief Manage the CRC 8-bit receive in Interrupt context.
+ * @param hspi pointer to a SPI_HandleTypeDef structure that contains
+ * the configuration information for SPI module.
+ * @retval None
+ */
+static void SPI_RxISR_8BITCRC(struct __SPI_HandleTypeDef *hspi)
+{
+ __IO uint8_t * ptmpreg8;
+ __IO uint8_t tmpreg8 = 0;
+
+ /* Initialize the 8bit temporary pointer */
+ ptmpreg8 = (__IO uint8_t *)&hspi->Instance->DR;
+ /* Read 8bit CRC to flush Data Register */
+ tmpreg8 = *ptmpreg8;
+ /* To avoid GCC warning */
+ UNUSED(tmpreg8);
+
+ hspi->CRCSize--;
+
+ if (hspi->CRCSize == 0U)
+ {
+ SPI_CloseRx_ISR(hspi);
+ }
+}
+#endif /* USE_SPI_CRC */
+
+/**
+ * @brief Manage the receive 8-bit in Interrupt context.
+ * @param hspi pointer to a SPI_HandleTypeDef structure that contains
+ * the configuration information for SPI module.
+ * @retval None
+ */
+static void SPI_RxISR_8BIT(struct __SPI_HandleTypeDef *hspi)
+{
+ *hspi->pRxBuffPtr = (*(__IO uint8_t *)&hspi->Instance->DR);
+ hspi->pRxBuffPtr++;
+ hspi->RxXferCount--;
+
+#if (USE_SPI_CRC != 0U)
+ /* Enable CRC Transmission */
+ if ((hspi->RxXferCount == 1U) && (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE))
+ {
+ SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT);
+ }
+#endif /* USE_SPI_CRC */
+
+ if (hspi->RxXferCount == 0U)
+ {
+#if (USE_SPI_CRC != 0U)
+ if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
+ {
+ hspi->RxISR = SPI_RxISR_8BITCRC;
+ return;
+ }
+#endif /* USE_SPI_CRC */
+ SPI_CloseRx_ISR(hspi);
+ }
+}
+
+#if (USE_SPI_CRC != 0U)
+/**
+ * @brief Manage the CRC 16-bit receive in Interrupt context.
+ * @param hspi pointer to a SPI_HandleTypeDef structure that contains
+ * the configuration information for SPI module.
+ * @retval None
+ */
+static void SPI_RxISR_16BITCRC(struct __SPI_HandleTypeDef *hspi)
+{
+ __IO uint32_t tmpreg = 0U;
+
+ /* Read 16bit CRC to flush Data Register */
+ tmpreg = READ_REG(hspi->Instance->DR);
+ /* To avoid GCC warning */
+ UNUSED(tmpreg);
+
+ /* Disable RXNE and ERR interrupt */
+ __HAL_SPI_DISABLE_IT(hspi, (SPI_IT_RXNE | SPI_IT_ERR));
+
+ SPI_CloseRx_ISR(hspi);
+}
+#endif /* USE_SPI_CRC */
+
+/**
+ * @brief Manage the 16-bit receive in Interrupt context.
+ * @param hspi pointer to a SPI_HandleTypeDef structure that contains
+ * the configuration information for SPI module.
+ * @retval None
+ */
+static void SPI_RxISR_16BIT(struct __SPI_HandleTypeDef *hspi)
+{
+ *((uint16_t *)hspi->pRxBuffPtr) = (uint16_t)(hspi->Instance->DR);
+ hspi->pRxBuffPtr += sizeof(uint16_t);
+ hspi->RxXferCount--;
+
+#if (USE_SPI_CRC != 0U)
+ /* Enable CRC Transmission */
+ if ((hspi->RxXferCount == 1U) && (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE))
+ {
+ SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT);
+ }
+#endif /* USE_SPI_CRC */
+
+ if (hspi->RxXferCount == 0U)
+ {
+#if (USE_SPI_CRC != 0U)
+ if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
+ {
+ hspi->RxISR = SPI_RxISR_16BITCRC;
+ return;
+ }
+#endif /* USE_SPI_CRC */
+ SPI_CloseRx_ISR(hspi);
+ }
+}
+
+/**
+ * @brief Handle the data 8-bit transmit in Interrupt mode.
+ * @param hspi pointer to a SPI_HandleTypeDef structure that contains
+ * the configuration information for SPI module.
+ * @retval None
+ */
+static void SPI_TxISR_8BIT(struct __SPI_HandleTypeDef *hspi)
+{
+ *(__IO uint8_t *)&hspi->Instance->DR = (*hspi->pTxBuffPtr);
+ hspi->pTxBuffPtr++;
+ hspi->TxXferCount--;
+
+ if (hspi->TxXferCount == 0U)
+ {
+#if (USE_SPI_CRC != 0U)
+ if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
+ {
+ /* Enable CRC Transmission */
+ SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT);
+ }
+#endif /* USE_SPI_CRC */
+ SPI_CloseTx_ISR(hspi);
+ }
+}
+
+/**
+ * @brief Handle the data 16-bit transmit in Interrupt mode.
+ * @param hspi pointer to a SPI_HandleTypeDef structure that contains
+ * the configuration information for SPI module.
+ * @retval None
+ */
+static void SPI_TxISR_16BIT(struct __SPI_HandleTypeDef *hspi)
+{
+ /* Transmit data in 16 Bit mode */
+ hspi->Instance->DR = *((uint16_t *)hspi->pTxBuffPtr);
+ hspi->pTxBuffPtr += sizeof(uint16_t);
+ hspi->TxXferCount--;
+
+ if (hspi->TxXferCount == 0U)
+ {
+#if (USE_SPI_CRC != 0U)
+ if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
+ {
+ /* Enable CRC Transmission */
+ SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT);
+ }
+#endif /* USE_SPI_CRC */
+ SPI_CloseTx_ISR(hspi);
+ }
+}
+
+/**
+ * @brief Handle SPI Communication Timeout.
+ * @param hspi pointer to a SPI_HandleTypeDef structure that contains
+ * the configuration information for SPI module.
+ * @param Flag SPI flag to check
+ * @param State flag state to check
+ * @param Timeout Timeout duration
+ * @param Tickstart tick start value
+ * @retval HAL status
+ */
+static HAL_StatusTypeDef SPI_WaitFlagStateUntilTimeout(SPI_HandleTypeDef *hspi, uint32_t Flag, FlagStatus State,
+ uint32_t Timeout, uint32_t Tickstart)
+{
+ __IO uint32_t count;
+ uint32_t tmp_timeout;
+ uint32_t tmp_tickstart;
+
+ /* Adjust Timeout value in case of end of transfer */
+ tmp_timeout = Timeout - (HAL_GetTick() - Tickstart);
+ tmp_tickstart = HAL_GetTick();
+
+ /* Calculate Timeout based on a software loop to avoid blocking issue if Systick is disabled */
+ count = tmp_timeout * ((SystemCoreClock * 32U) >> 20U);
+
+ while ((__HAL_SPI_GET_FLAG(hspi, Flag) ? SET : RESET) != State)
+ {
+ if (Timeout != HAL_MAX_DELAY)
+ {
+ if (((HAL_GetTick() - tmp_tickstart) >= tmp_timeout) || (tmp_timeout == 0U))
+ {
+ /* Disable the SPI and reset the CRC: the CRC value should be cleared
+ on both master and slave sides in order to resynchronize the master
+ and slave for their respective CRC calculation */
+
+ /* Disable TXE, RXNE and ERR interrupts for the interrupt process */
+ __HAL_SPI_DISABLE_IT(hspi, (SPI_IT_TXE | SPI_IT_RXNE | SPI_IT_ERR));
+
+ if ((hspi->Init.Mode == SPI_MODE_MASTER) && ((hspi->Init.Direction == SPI_DIRECTION_1LINE)
+ || (hspi->Init.Direction == SPI_DIRECTION_2LINES_RXONLY)))
+ {
+ /* Disable SPI peripheral */
+ __HAL_SPI_DISABLE(hspi);
+ }
+
+ /* Reset CRC Calculation */
+ if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
+ {
+ SPI_RESET_CRC(hspi);
+ }
+
+ hspi->State = HAL_SPI_STATE_READY;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hspi);
+
+ return HAL_TIMEOUT;
+ }
+ /* If Systick is disabled or not incremented, deactivate timeout to go in disable loop procedure */
+ if(count == 0U)
+ {
+ tmp_timeout = 0U;
+ }
+ count--;
+ }
+ }
+
+ return HAL_OK;
+}
+
+/**
+ * @brief Handle SPI FIFO Communication Timeout.
+ * @param hspi pointer to a SPI_HandleTypeDef structure that contains
+ * the configuration information for SPI module.
+ * @param Fifo Fifo to check
+ * @param State Fifo state to check
+ * @param Timeout Timeout duration
+ * @param Tickstart tick start value
+ * @retval HAL status
+ */
+static HAL_StatusTypeDef SPI_WaitFifoStateUntilTimeout(SPI_HandleTypeDef *hspi, uint32_t Fifo, uint32_t State,
+ uint32_t Timeout, uint32_t Tickstart)
+{
+ __IO uint32_t count;
+ uint32_t tmp_timeout;
+ uint32_t tmp_tickstart;
+ __IO uint8_t * ptmpreg8;
+ __IO uint8_t tmpreg8 = 0;
+
+ /* Adjust Timeout value in case of end of transfer */
+ tmp_timeout = Timeout - (HAL_GetTick() - Tickstart);
+ tmp_tickstart = HAL_GetTick();
+
+ /* Initialize the 8bit temporary pointer */
+ ptmpreg8 = (__IO uint8_t *)&hspi->Instance->DR;
+
+ /* Calculate Timeout based on a software loop to avoid blocking issue if Systick is disabled */
+ count = tmp_timeout * ((SystemCoreClock * 35U) >> 20U);
+
+ while ((hspi->Instance->SR & Fifo) != State)
+ {
+ if ((Fifo == SPI_SR_FRLVL) && (State == SPI_FRLVL_EMPTY))
+ {
+ /* Flush Data Register by a blank read */
+ tmpreg8 = *ptmpreg8;
+ /* To avoid GCC warning */
+ UNUSED(tmpreg8);
+ }
+
+ if (Timeout != HAL_MAX_DELAY)
+ {
+ if (((HAL_GetTick() - tmp_tickstart) >= tmp_timeout) || (tmp_timeout == 0U))
+ {
+ /* Disable the SPI and reset the CRC: the CRC value should be cleared
+ on both master and slave sides in order to resynchronize the master
+ and slave for their respective CRC calculation */
+
+ /* Disable TXE, RXNE and ERR interrupts for the interrupt process */
+ __HAL_SPI_DISABLE_IT(hspi, (SPI_IT_TXE | SPI_IT_RXNE | SPI_IT_ERR));
+
+ if ((hspi->Init.Mode == SPI_MODE_MASTER) && ((hspi->Init.Direction == SPI_DIRECTION_1LINE)
+ || (hspi->Init.Direction == SPI_DIRECTION_2LINES_RXONLY)))
+ {
+ /* Disable SPI peripheral */
+ __HAL_SPI_DISABLE(hspi);
+ }
+
+ /* Reset CRC Calculation */
+ if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
+ {
+ SPI_RESET_CRC(hspi);
+ }
+
+ hspi->State = HAL_SPI_STATE_READY;
+
+ /* Process Unlocked */
+ __HAL_UNLOCK(hspi);
+
+ return HAL_TIMEOUT;
+ }
+ /* If Systick is disabled or not incremented, deactivate timeout to go in disable loop procedure */
+ if(count == 0U)
+ {
+ tmp_timeout = 0U;
+ }
+ count--;
+ }
+ }
+
+ return HAL_OK;
+}
+
+/**
+ * @brief Handle the check of the RX transaction complete.
+ * @param hspi pointer to a SPI_HandleTypeDef structure that contains
+ * the configuration information for SPI module.
+ * @param Timeout Timeout duration
+ * @param Tickstart tick start value
+ * @retval HAL status
+ */
+static HAL_StatusTypeDef SPI_EndRxTransaction(SPI_HandleTypeDef *hspi, uint32_t Timeout, uint32_t Tickstart)
+{
+ if ((hspi->Init.Mode == SPI_MODE_MASTER) && ((hspi->Init.Direction == SPI_DIRECTION_1LINE)
+ || (hspi->Init.Direction == SPI_DIRECTION_2LINES_RXONLY)))
+ {
+ /* Disable SPI peripheral */
+ __HAL_SPI_DISABLE(hspi);
+ }
+
+ /* Control the BSY flag */
+ if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_BSY, RESET, Timeout, Tickstart) != HAL_OK)
+ {
+ SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG);
+ return HAL_TIMEOUT;
+ }
+
+ if ((hspi->Init.Mode == SPI_MODE_MASTER) && ((hspi->Init.Direction == SPI_DIRECTION_1LINE)
+ || (hspi->Init.Direction == SPI_DIRECTION_2LINES_RXONLY)))
+ {
+ /* Empty the FRLVL fifo */
+ if (SPI_WaitFifoStateUntilTimeout(hspi, SPI_FLAG_FRLVL, SPI_FRLVL_EMPTY, Timeout, Tickstart) != HAL_OK)
+ {
+ SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG);
+ return HAL_TIMEOUT;
+ }
+ }
+ return HAL_OK;
+}
+
+/**
+ * @brief Handle the check of the RXTX or TX transaction complete.
+ * @param hspi SPI handle
+ * @param Timeout Timeout duration
+ * @param Tickstart tick start value
+ * @retval HAL status
+ */
+static HAL_StatusTypeDef SPI_EndRxTxTransaction(SPI_HandleTypeDef *hspi, uint32_t Timeout, uint32_t Tickstart)
+{
+ /* Control if the TX fifo is empty */
+ if (SPI_WaitFifoStateUntilTimeout(hspi, SPI_FLAG_FTLVL, SPI_FTLVL_EMPTY, Timeout, Tickstart) != HAL_OK)
+ {
+ SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG);
+ return HAL_TIMEOUT;
+ }
+
+ /* Control the BSY flag */
+ if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_BSY, RESET, Timeout, Tickstart) != HAL_OK)
+ {
+ SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG);
+ return HAL_TIMEOUT;
+ }
+
+ /* Control if the RX fifo is empty */
+ if (SPI_WaitFifoStateUntilTimeout(hspi, SPI_FLAG_FRLVL, SPI_FRLVL_EMPTY, Timeout, Tickstart) != HAL_OK)
+ {
+ SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG);
+ return HAL_TIMEOUT;
+ }
+
+ return HAL_OK;
+}
+
+/**
+ * @brief Handle the end of the RXTX transaction.
+ * @param hspi pointer to a SPI_HandleTypeDef structure that contains
+ * the configuration information for SPI module.
+ * @retval None
+ */
+static void SPI_CloseRxTx_ISR(SPI_HandleTypeDef *hspi)
+{
+ uint32_t tickstart;
+
+ /* Init tickstart for timeout management */
+ tickstart = HAL_GetTick();
+
+ /* Disable ERR interrupt */
+ __HAL_SPI_DISABLE_IT(hspi, SPI_IT_ERR);
+
+ /* Check the end of the transaction */
+ if (SPI_EndRxTxTransaction(hspi, SPI_DEFAULT_TIMEOUT, tickstart) != HAL_OK)
+ {
+ SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG);
+ }
+
+#if (USE_SPI_CRC != 0U)
+ /* Check if CRC error occurred */
+ if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_CRCERR) != RESET)
+ {
+ hspi->State = HAL_SPI_STATE_READY;
+ SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC);
+ __HAL_SPI_CLEAR_CRCERRFLAG(hspi);
+ /* Call user error callback */
+#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U)
+ hspi->ErrorCallback(hspi);
+#else
+ HAL_SPI_ErrorCallback(hspi);
+#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */
+ }
+ else
+ {
+#endif /* USE_SPI_CRC */
+ if (hspi->ErrorCode == HAL_SPI_ERROR_NONE)
+ {
+ if (hspi->State == HAL_SPI_STATE_BUSY_RX)
+ {
+ hspi->State = HAL_SPI_STATE_READY;
+ /* Call user Rx complete callback */
+#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U)
+ hspi->RxCpltCallback(hspi);
+#else
+ HAL_SPI_RxCpltCallback(hspi);
+#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */
+ }
+ else
+ {
+ hspi->State = HAL_SPI_STATE_READY;
+ /* Call user TxRx complete callback */
+#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U)
+ hspi->TxRxCpltCallback(hspi);
+#else
+ HAL_SPI_TxRxCpltCallback(hspi);
+#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */
+ }
+ }
+ else
+ {
+ hspi->State = HAL_SPI_STATE_READY;
+ /* Call user error callback */
+#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U)
+ hspi->ErrorCallback(hspi);
+#else
+ HAL_SPI_ErrorCallback(hspi);
+#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */
+ }
+#if (USE_SPI_CRC != 0U)
+ }
+#endif /* USE_SPI_CRC */
+}
+
+/**
+ * @brief Handle the end of the RX transaction.
+ * @param hspi pointer to a SPI_HandleTypeDef structure that contains
+ * the configuration information for SPI module.
+ * @retval None
+ */
+static void SPI_CloseRx_ISR(SPI_HandleTypeDef *hspi)
+{
+ /* Disable RXNE and ERR interrupt */
+ __HAL_SPI_DISABLE_IT(hspi, (SPI_IT_RXNE | SPI_IT_ERR));
+
+ /* Check the end of the transaction */
+ if (SPI_EndRxTransaction(hspi, SPI_DEFAULT_TIMEOUT, HAL_GetTick()) != HAL_OK)
+ {
+ SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG);
+ }
+ hspi->State = HAL_SPI_STATE_READY;
+
+#if (USE_SPI_CRC != 0U)
+ /* Check if CRC error occurred */
+ if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_CRCERR) != RESET)
+ {
+ SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC);
+ __HAL_SPI_CLEAR_CRCERRFLAG(hspi);
+ /* Call user error callback */
+#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U)
+ hspi->ErrorCallback(hspi);
+#else
+ HAL_SPI_ErrorCallback(hspi);
+#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */
+ }
+ else
+ {
+#endif /* USE_SPI_CRC */
+ if (hspi->ErrorCode == HAL_SPI_ERROR_NONE)
+ {
+ /* Call user Rx complete callback */
+#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U)
+ hspi->RxCpltCallback(hspi);
+#else
+ HAL_SPI_RxCpltCallback(hspi);
+#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */
+ }
+ else
+ {
+ /* Call user error callback */
+#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U)
+ hspi->ErrorCallback(hspi);
+#else
+ HAL_SPI_ErrorCallback(hspi);
+#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */
+ }
+#if (USE_SPI_CRC != 0U)
+ }
+#endif /* USE_SPI_CRC */
+}
+
+/**
+ * @brief Handle the end of the TX transaction.
+ * @param hspi pointer to a SPI_HandleTypeDef structure that contains
+ * the configuration information for SPI module.
+ * @retval None
+ */
+static void SPI_CloseTx_ISR(SPI_HandleTypeDef *hspi)
+{
+ uint32_t tickstart;
+
+ /* Init tickstart for timeout management*/
+ tickstart = HAL_GetTick();
+
+ /* Disable TXE and ERR interrupt */
+ __HAL_SPI_DISABLE_IT(hspi, (SPI_IT_TXE | SPI_IT_ERR));
+
+ /* Check the end of the transaction */
+ if (SPI_EndRxTxTransaction(hspi, SPI_DEFAULT_TIMEOUT, tickstart) != HAL_OK)
+ {
+ SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG);
+ }
+
+ /* Clear overrun flag in 2 Lines communication mode because received is not read */
+ if (hspi->Init.Direction == SPI_DIRECTION_2LINES)
+ {
+ __HAL_SPI_CLEAR_OVRFLAG(hspi);
+ }
+
+ hspi->State = HAL_SPI_STATE_READY;
+ if (hspi->ErrorCode != HAL_SPI_ERROR_NONE)
+ {
+ /* Call user error callback */
+#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U)
+ hspi->ErrorCallback(hspi);
+#else
+ HAL_SPI_ErrorCallback(hspi);
+#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */
+ }
+ else
+ {
+ /* Call user Rx complete callback */
+#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U)
+ hspi->TxCpltCallback(hspi);
+#else
+ HAL_SPI_TxCpltCallback(hspi);
+#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */
+ }
+}
+
+/**
+ * @brief Handle abort a Rx transaction.
+ * @param hspi pointer to a SPI_HandleTypeDef structure that contains
+ * the configuration information for SPI module.
+ * @retval None
+ */
+static void SPI_AbortRx_ISR(SPI_HandleTypeDef *hspi)
+{
+ __IO uint32_t count;
+
+ /* Disable SPI Peripheral */
+ __HAL_SPI_DISABLE(hspi);
+
+ count = SPI_DEFAULT_TIMEOUT * (SystemCoreClock / 24U / 1000U);
+
+ /* Disable RXNEIE interrupt */
+ CLEAR_BIT(hspi->Instance->CR2, (SPI_CR2_RXNEIE));
+
+ /* Check RXNEIE is disabled */
+ do
+ {
+ if (count == 0U)
+ {
+ SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_ABORT);
+ break;
+ }
+ count--;
+ } while (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_RXNEIE));
+
+ /* Control the BSY flag */
+ if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_BSY, RESET, SPI_DEFAULT_TIMEOUT, HAL_GetTick()) != HAL_OK)
+ {
+ hspi->ErrorCode = HAL_SPI_ERROR_ABORT;
+ }
+
+ /* Empty the FRLVL fifo */
+ if (SPI_WaitFifoStateUntilTimeout(hspi, SPI_FLAG_FRLVL, SPI_FRLVL_EMPTY, SPI_DEFAULT_TIMEOUT, HAL_GetTick()) != HAL_OK)
+ {
+ hspi->ErrorCode = HAL_SPI_ERROR_ABORT;
+ }
+
+ hspi->State = HAL_SPI_STATE_ABORT;
+}
+
+/**
+ * @brief Handle abort a Tx or Rx/Tx transaction.
+ * @param hspi pointer to a SPI_HandleTypeDef structure that contains
+ * the configuration information for SPI module.
+ * @retval None
+ */
+static void SPI_AbortTx_ISR(SPI_HandleTypeDef *hspi)
+{
+ __IO uint32_t count;
+
+ count = SPI_DEFAULT_TIMEOUT * (SystemCoreClock / 24U / 1000U);
+
+ /* Disable TXEIE interrupt */
+ CLEAR_BIT(hspi->Instance->CR2, (SPI_CR2_TXEIE));
+
+ /* Check TXEIE is disabled */
+ do
+ {
+ if (count == 0U)
+ {
+ SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_ABORT);
+ break;
+ }
+ count--;
+ } while (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_TXEIE));
+
+ if (SPI_EndRxTxTransaction(hspi, SPI_DEFAULT_TIMEOUT, HAL_GetTick()) != HAL_OK)
+ {
+ hspi->ErrorCode = HAL_SPI_ERROR_ABORT;
+ }
+
+ /* Disable SPI Peripheral */
+ __HAL_SPI_DISABLE(hspi);
+
+ /* Empty the FRLVL fifo */
+ if (SPI_WaitFifoStateUntilTimeout(hspi, SPI_FLAG_FRLVL, SPI_FRLVL_EMPTY, SPI_DEFAULT_TIMEOUT, HAL_GetTick()) != HAL_OK)
+ {
+ hspi->ErrorCode = HAL_SPI_ERROR_ABORT;
+ }
+
+ /* Check case of Full-Duplex Mode and disable directly RXNEIE interrupt */
+ if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_RXNEIE))
+ {
+ /* Disable RXNEIE interrupt */
+ CLEAR_BIT(hspi->Instance->CR2, (SPI_CR2_RXNEIE));
+
+ /* Check RXNEIE is disabled */
+ do
+ {
+ if (count == 0U)
+ {
+ SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_ABORT);
+ break;
+ }
+ count--;
+ } while (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_RXNEIE));
+
+ /* Control the BSY flag */
+ if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_BSY, RESET, SPI_DEFAULT_TIMEOUT, HAL_GetTick()) != HAL_OK)
+ {
+ hspi->ErrorCode = HAL_SPI_ERROR_ABORT;
+ }
+
+ /* Empty the FRLVL fifo */
+ if (SPI_WaitFifoStateUntilTimeout(hspi, SPI_FLAG_FRLVL, SPI_FRLVL_EMPTY, SPI_DEFAULT_TIMEOUT, HAL_GetTick()) != HAL_OK)
+ {
+ hspi->ErrorCode = HAL_SPI_ERROR_ABORT;
+ }
+ }
+ hspi->State = HAL_SPI_STATE_ABORT;
+}
+
+/**
+ * @}
+ */
+
+#endif /* HAL_SPI_MODULE_ENABLED */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_spi_ex.c b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_spi_ex.c
new file mode 100644
index 0000000..fb88495
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_spi_ex.c
@@ -0,0 +1,115 @@
+/**
+ ******************************************************************************
+ * @file stm32f0xx_hal_spi_ex.c
+ * @author MCD Application Team
+ * @brief Extended SPI HAL module driver.
+ * This file provides firmware functions to manage the following
+ * SPI peripheral extended functionalities :
+ * + IO operation functions
+ *
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2016 STMicroelectronics.
+ * All rights reserved.
+ *
+ * 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 "stm32f0xx_hal.h"
+
+/** @addtogroup STM32F0xx_HAL_Driver
+ * @{
+ */
+
+/** @defgroup SPIEx SPIEx
+ * @brief SPI Extended HAL module driver
+ * @{
+ */
+#ifdef HAL_SPI_MODULE_ENABLED
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private defines -----------------------------------------------------------*/
+/** @defgroup SPIEx_Private_Constants SPIEx Private Constants
+ * @{
+ */
+#define SPI_FIFO_SIZE 4UL
+/**
+ * @}
+ */
+
+/* Private macros ------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Exported functions --------------------------------------------------------*/
+
+/** @defgroup SPIEx_Exported_Functions SPIEx Exported Functions
+ * @{
+ */
+
+/** @defgroup SPIEx_Exported_Functions_Group1 IO operation functions
+ * @brief Data transfers functions
+ *
+@verbatim
+ ==============================================================================
+ ##### IO operation functions #####
+ ===============================================================================
+ [..]
+ This subsection provides a set of extended functions to manage the SPI
+ data transfers.
+
+ (#) Rx data flush function:
+ (++) HAL_SPIEx_FlushRxFifo()
+
+@endverbatim
+ * @{
+ */
+
+/**
+ * @brief Flush the RX fifo.
+ * @param hspi pointer to a SPI_HandleTypeDef structure that contains
+ * the configuration information for the specified SPI module.
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_SPIEx_FlushRxFifo(SPI_HandleTypeDef *hspi)
+{
+ __IO uint32_t tmpreg;
+ uint8_t count = 0U;
+ while ((hspi->Instance->SR & SPI_FLAG_FRLVL) != SPI_FRLVL_EMPTY)
+ {
+ count++;
+ tmpreg = hspi->Instance->DR;
+ UNUSED(tmpreg); /* To avoid GCC warning */
+ if (count == SPI_FIFO_SIZE)
+ {
+ return HAL_TIMEOUT;
+ }
+ }
+ return HAL_OK;
+}
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+#endif /* HAL_SPI_MODULE_ENABLED */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_tim.c b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_tim.c
new file mode 100644
index 0000000..e9e8ff3
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_tim.c
@@ -0,0 +1,7635 @@
+/**
+ ******************************************************************************
+ * @file stm32f0xx_hal_tim.c
+ * @author MCD Application Team
+ * @brief TIM HAL module driver.
+ * This file provides firmware functions to manage the following
+ * functionalities of the Timer (TIM) peripheral:
+ * + TIM Time Base Initialization
+ * + TIM Time Base Start
+ * + TIM Time Base Start Interruption
+ * + TIM Time Base Start DMA
+ * + TIM Output Compare/PWM Initialization
+ * + TIM Output Compare/PWM Channel Configuration
+ * + TIM Output Compare/PWM Start
+ * + TIM Output Compare/PWM Start Interruption
+ * + TIM Output Compare/PWM Start DMA
+ * + TIM Input Capture Initialization
+ * + TIM Input Capture Channel Configuration
+ * + TIM Input Capture Start
+ * + TIM Input Capture Start Interruption
+ * + TIM Input Capture Start DMA
+ * + TIM One Pulse Initialization
+ * + TIM One Pulse Channel Configuration
+ * + TIM One Pulse Start
+ * + TIM Encoder Interface Initialization
+ * + TIM Encoder Interface Start
+ * + TIM Encoder Interface Start Interruption
+ * + TIM Encoder Interface Start DMA
+ * + Commutation Event configuration with Interruption and DMA
+ * + TIM OCRef clear configuration
+ * + TIM External Clock configuration
+ @verbatim
+ ==============================================================================
+ ##### TIMER Generic features #####
+ ==============================================================================
+ [..] The Timer features include:
+ (#) 16-bit up, down, up/down auto-reload counter.
+ (#) 16-bit programmable prescaler allowing dividing (also on the fly) the
+ counter clock frequency either by any factor between 1 and 65536.
+ (#) Up to 4 independent channels for:
+ (++) Input Capture
+ (++) Output Compare
+ (++) PWM generation (Edge and Center-aligned Mode)
+ (++) One-pulse mode output
+ (#) Synchronization circuit to control the timer with external signals and to interconnect
+ several timers together.
+ (#) Supports incremental encoder for positioning purposes
+
+ ##### How to use this driver #####
+ ==============================================================================
+ [..]
+ (#) Initialize the TIM low level resources by implementing the following functions
+ depending on the selected feature:
+ (++) Time Base : HAL_TIM_Base_MspInit()
+ (++) Input Capture : HAL_TIM_IC_MspInit()
+ (++) Output Compare : HAL_TIM_OC_MspInit()
+ (++) PWM generation : HAL_TIM_PWM_MspInit()
+ (++) One-pulse mode output : HAL_TIM_OnePulse_MspInit()
+ (++) Encoder mode output : HAL_TIM_Encoder_MspInit()
+
+ (#) Initialize the TIM low level resources :
+ (##) Enable the TIM interface clock using __HAL_RCC_TIMx_CLK_ENABLE();
+ (##) TIM pins configuration
+ (+++) Enable the clock for the TIM GPIOs using the following function:
+ __HAL_RCC_GPIOx_CLK_ENABLE();
+ (+++) Configure these TIM pins in Alternate function mode using HAL_GPIO_Init();
+
+ (#) The external Clock can be configured, if needed (the default clock is the
+ internal clock from the APBx), using the following function:
+ HAL_TIM_ConfigClockSource, the clock configuration should be done before
+ any start function.
+
+ (#) Configure the TIM in the desired functioning mode using one of the
+ Initialization function of this driver:
+ (++) HAL_TIM_Base_Init: to use the Timer to generate a simple time base
+ (++) HAL_TIM_OC_Init and HAL_TIM_OC_ConfigChannel: to use the Timer to generate an
+ Output Compare signal.
+ (++) HAL_TIM_PWM_Init and HAL_TIM_PWM_ConfigChannel: to use the Timer to generate a
+ PWM signal.
+ (++) HAL_TIM_IC_Init and HAL_TIM_IC_ConfigChannel: to use the Timer to measure an
+ external signal.
+ (++) HAL_TIM_OnePulse_Init and HAL_TIM_OnePulse_ConfigChannel: to use the Timer
+ in One Pulse Mode.
+ (++) HAL_TIM_Encoder_Init: to use the Timer Encoder Interface.
+
+ (#) Activate the TIM peripheral using one of the start functions depending from the feature used:
+ (++) Time Base : HAL_TIM_Base_Start(), HAL_TIM_Base_Start_DMA(), HAL_TIM_Base_Start_IT()
+ (++) Input Capture : HAL_TIM_IC_Start(), HAL_TIM_IC_Start_DMA(), HAL_TIM_IC_Start_IT()
+ (++) Output Compare : HAL_TIM_OC_Start(), HAL_TIM_OC_Start_DMA(), HAL_TIM_OC_Start_IT()
+ (++) PWM generation : HAL_TIM_PWM_Start(), HAL_TIM_PWM_Start_DMA(), HAL_TIM_PWM_Start_IT()
+ (++) One-pulse mode output : HAL_TIM_OnePulse_Start(), HAL_TIM_OnePulse_Start_IT()
+ (++) Encoder mode output : HAL_TIM_Encoder_Start(), HAL_TIM_Encoder_Start_DMA(), HAL_TIM_Encoder_Start_IT().
+
+ (#) The DMA Burst is managed with the two following functions:
+ HAL_TIM_DMABurst_WriteStart()
+ HAL_TIM_DMABurst_ReadStart()
+
+ *** Callback registration ***
+ =============================================
+
+ [..]
+ The compilation define USE_HAL_TIM_REGISTER_CALLBACKS when set to 1
+ allows the user to configure dynamically the driver callbacks.
+
+ [..]
+ Use Function HAL_TIM_RegisterCallback() to register a callback.
+ HAL_TIM_RegisterCallback() takes as parameters the HAL peripheral handle,
+ the Callback ID and a pointer to the user callback function.
+
+ [..]
+ Use function HAL_TIM_UnRegisterCallback() to reset a callback to the default
+ weak function.
+ HAL_TIM_UnRegisterCallback takes as parameters the HAL peripheral handle,
+ and the Callback ID.
+
+ [..]
+ These functions allow to register/unregister following callbacks:
+ (+) Base_MspInitCallback : TIM Base Msp Init Callback.
+ (+) Base_MspDeInitCallback : TIM Base Msp DeInit Callback.
+ (+) IC_MspInitCallback : TIM IC Msp Init Callback.
+ (+) IC_MspDeInitCallback : TIM IC Msp DeInit Callback.
+ (+) OC_MspInitCallback : TIM OC Msp Init Callback.
+ (+) OC_MspDeInitCallback : TIM OC Msp DeInit Callback.
+ (+) PWM_MspInitCallback : TIM PWM Msp Init Callback.
+ (+) PWM_MspDeInitCallback : TIM PWM Msp DeInit Callback.
+ (+) OnePulse_MspInitCallback : TIM One Pulse Msp Init Callback.
+ (+) OnePulse_MspDeInitCallback : TIM One Pulse Msp DeInit Callback.
+ (+) Encoder_MspInitCallback : TIM Encoder Msp Init Callback.
+ (+) Encoder_MspDeInitCallback : TIM Encoder Msp DeInit Callback.
+ (+) HallSensor_MspInitCallback : TIM Hall Sensor Msp Init Callback.
+ (+) HallSensor_MspDeInitCallback : TIM Hall Sensor Msp DeInit Callback.
+ (+) PeriodElapsedCallback : TIM Period Elapsed Callback.
+ (+) PeriodElapsedHalfCpltCallback : TIM Period Elapsed half complete Callback.
+ (+) TriggerCallback : TIM Trigger Callback.
+ (+) TriggerHalfCpltCallback : TIM Trigger half complete Callback.
+ (+) IC_CaptureCallback : TIM Input Capture Callback.
+ (+) IC_CaptureHalfCpltCallback : TIM Input Capture half complete Callback.
+ (+) OC_DelayElapsedCallback : TIM Output Compare Delay Elapsed Callback.
+ (+) PWM_PulseFinishedCallback : TIM PWM Pulse Finished Callback.
+ (+) PWM_PulseFinishedHalfCpltCallback : TIM PWM Pulse Finished half complete Callback.
+ (+) ErrorCallback : TIM Error Callback.
+ (+) CommutationCallback : TIM Commutation Callback.
+ (+) CommutationHalfCpltCallback : TIM Commutation half complete Callback.
+ (+) BreakCallback : TIM Break Callback.
+
+ [..]
+By default, after the Init and when the state is HAL_TIM_STATE_RESET
+all interrupt callbacks are set to the corresponding weak functions:
+ examples HAL_TIM_TriggerCallback(), HAL_TIM_ErrorCallback().
+
+ [..]
+ Exception done for MspInit and MspDeInit functions that are reset to the legacy weak
+ functionalities in the Init / DeInit only when these callbacks are null
+ (not registered beforehand). If not, MspInit or MspDeInit are not null, the Init / DeInit
+ keep and use the user MspInit / MspDeInit callbacks(registered beforehand)
+
+ [..]
+ Callbacks can be registered / unregistered in HAL_TIM_STATE_READY state only.
+ Exception done MspInit / MspDeInit that can be registered / unregistered
+ in HAL_TIM_STATE_READY or HAL_TIM_STATE_RESET state,
+ thus registered(user) MspInit / DeInit callbacks can be used during the Init / DeInit.
+ In that case first register the MspInit/MspDeInit user callbacks
+ using HAL_TIM_RegisterCallback() before calling DeInit or Init function.
+
+ [..]
+ When The compilation define USE_HAL_TIM_REGISTER_CALLBACKS is set to 0 or
+ not defined, the callback registration feature is not available and all callbacks
+ are set to the corresponding weak functions.
+
+ @endverbatim
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2016 STMicroelectronics.
+ * All rights reserved.
+ *
+ * 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 "stm32f0xx_hal.h"
+
+/** @addtogroup STM32F0xx_HAL_Driver
+ * @{
+ */
+
+/** @defgroup TIM TIM
+ * @brief TIM HAL module driver
+ * @{
+ */
+
+#ifdef HAL_TIM_MODULE_ENABLED
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macros ------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/** @addtogroup TIM_Private_Functions
+ * @{
+ */
+static void TIM_OC1_SetConfig(TIM_TypeDef *TIMx, TIM_OC_InitTypeDef *OC_Config);
+static void TIM_OC3_SetConfig(TIM_TypeDef *TIMx, TIM_OC_InitTypeDef *OC_Config);
+static void TIM_OC4_SetConfig(TIM_TypeDef *TIMx, TIM_OC_InitTypeDef *OC_Config);
+static void TIM_TI1_ConfigInputStage(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32_t TIM_ICFilter);
+static void TIM_TI2_SetConfig(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32_t TIM_ICSelection,
+ uint32_t TIM_ICFilter);
+static void TIM_TI2_ConfigInputStage(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32_t TIM_ICFilter);
+static void TIM_TI3_SetConfig(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32_t TIM_ICSelection,
+ uint32_t TIM_ICFilter);
+static void TIM_TI4_SetConfig(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32_t TIM_ICSelection,
+ uint32_t TIM_ICFilter);
+static void TIM_ITRx_SetConfig(TIM_TypeDef *TIMx, uint32_t InputTriggerSource);
+static void TIM_DMAPeriodElapsedCplt(DMA_HandleTypeDef *hdma);
+static void TIM_DMAPeriodElapsedHalfCplt(DMA_HandleTypeDef *hdma);
+static void TIM_DMADelayPulseCplt(DMA_HandleTypeDef *hdma);
+static void TIM_DMATriggerCplt(DMA_HandleTypeDef *hdma);
+static void TIM_DMATriggerHalfCplt(DMA_HandleTypeDef *hdma);
+static HAL_StatusTypeDef TIM_SlaveTimer_SetConfig(TIM_HandleTypeDef *htim,
+ TIM_SlaveConfigTypeDef *sSlaveConfig);
+/**
+ * @}
+ */
+/* Exported functions --------------------------------------------------------*/
+
+/** @defgroup TIM_Exported_Functions TIM Exported Functions
+ * @{
+ */
+
+/** @defgroup TIM_Exported_Functions_Group1 TIM Time Base functions
+ * @brief Time Base functions
+ *
+@verbatim
+ ==============================================================================
+ ##### Time Base functions #####
+ ==============================================================================
+ [..]
+ This section provides functions allowing to:
+ (+) Initialize and configure the TIM base.
+ (+) De-initialize the TIM base.
+ (+) Start the Time Base.
+ (+) Stop the Time Base.
+ (+) Start the Time Base and enable interrupt.
+ (+) Stop the Time Base and disable interrupt.
+ (+) Start the Time Base and enable DMA transfer.
+ (+) Stop the Time Base and disable DMA transfer.
+
+@endverbatim
+ * @{
+ */
+/**
+ * @brief Initializes the TIM Time base Unit according to the specified
+ * parameters in the TIM_HandleTypeDef and initialize the associated handle.
+ * @note Switching from Center Aligned counter mode to Edge counter mode (or reverse)
+ * requires a timer reset to avoid unexpected direction
+ * due to DIR bit readonly in center aligned mode.
+ * Ex: call @ref HAL_TIM_Base_DeInit() before HAL_TIM_Base_Init()
+ * @param htim TIM Base handle
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIM_Base_Init(TIM_HandleTypeDef *htim)
+{
+ /* Check the TIM handle allocation */
+ if (htim == NULL)
+ {
+ return HAL_ERROR;
+ }
+
+ /* Check the parameters */
+ assert_param(IS_TIM_INSTANCE(htim->Instance));
+ assert_param(IS_TIM_COUNTER_MODE(htim->Init.CounterMode));
+ assert_param(IS_TIM_CLOCKDIVISION_DIV(htim->Init.ClockDivision));
+ assert_param(IS_TIM_AUTORELOAD_PRELOAD(htim->Init.AutoReloadPreload));
+
+ if (htim->State == HAL_TIM_STATE_RESET)
+ {
+ /* Allocate lock resource and initialize it */
+ htim->Lock = HAL_UNLOCKED;
+
+#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1)
+ /* Reset interrupt callbacks to legacy weak callbacks */
+ TIM_ResetCallback(htim);
+
+ if (htim->Base_MspInitCallback == NULL)
+ {
+ htim->Base_MspInitCallback = HAL_TIM_Base_MspInit;
+ }
+ /* Init the low level hardware : GPIO, CLOCK, NVIC */
+ htim->Base_MspInitCallback(htim);
+#else
+ /* Init the low level hardware : GPIO, CLOCK, NVIC */
+ HAL_TIM_Base_MspInit(htim);
+#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */
+ }
+
+ /* Set the TIM state */
+ htim->State = HAL_TIM_STATE_BUSY;
+
+ /* Set the Time Base configuration */
+ TIM_Base_SetConfig(htim->Instance, &htim->Init);
+
+ /* Initialize the DMA burst operation state */
+ htim->DMABurstState = HAL_DMA_BURST_STATE_READY;
+
+ /* Initialize the TIM channels state */
+ TIM_CHANNEL_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_READY);
+ TIM_CHANNEL_N_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_READY);
+
+ /* Initialize the TIM state*/
+ htim->State = HAL_TIM_STATE_READY;
+
+ return HAL_OK;
+}
+
+/**
+ * @brief DeInitializes the TIM Base peripheral
+ * @param htim TIM Base handle
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIM_Base_DeInit(TIM_HandleTypeDef *htim)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_INSTANCE(htim->Instance));
+
+ htim->State = HAL_TIM_STATE_BUSY;
+
+ /* Disable the TIM Peripheral Clock */
+ __HAL_TIM_DISABLE(htim);
+
+#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1)
+ if (htim->Base_MspDeInitCallback == NULL)
+ {
+ htim->Base_MspDeInitCallback = HAL_TIM_Base_MspDeInit;
+ }
+ /* DeInit the low level hardware */
+ htim->Base_MspDeInitCallback(htim);
+#else
+ /* DeInit the low level hardware: GPIO, CLOCK, NVIC */
+ HAL_TIM_Base_MspDeInit(htim);
+#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */
+
+ /* Change the DMA burst operation state */
+ htim->DMABurstState = HAL_DMA_BURST_STATE_RESET;
+
+ /* Change the TIM channels state */
+ TIM_CHANNEL_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_RESET);
+ TIM_CHANNEL_N_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_RESET);
+
+ /* Change TIM state */
+ htim->State = HAL_TIM_STATE_RESET;
+
+ /* Release Lock */
+ __HAL_UNLOCK(htim);
+
+ return HAL_OK;
+}
+
+/**
+ * @brief Initializes the TIM Base MSP.
+ * @param htim TIM Base handle
+ * @retval None
+ */
+__weak void HAL_TIM_Base_MspInit(TIM_HandleTypeDef *htim)
+{
+ /* Prevent unused argument(s) compilation warning */
+ UNUSED(htim);
+
+ /* NOTE : This function should not be modified, when the callback is needed,
+ the HAL_TIM_Base_MspInit could be implemented in the user file
+ */
+}
+
+/**
+ * @brief DeInitializes TIM Base MSP.
+ * @param htim TIM Base handle
+ * @retval None
+ */
+__weak void HAL_TIM_Base_MspDeInit(TIM_HandleTypeDef *htim)
+{
+ /* Prevent unused argument(s) compilation warning */
+ UNUSED(htim);
+
+ /* NOTE : This function should not be modified, when the callback is needed,
+ the HAL_TIM_Base_MspDeInit could be implemented in the user file
+ */
+}
+
+
+/**
+ * @brief Starts the TIM Base generation.
+ * @param htim TIM Base handle
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIM_Base_Start(TIM_HandleTypeDef *htim)
+{
+ uint32_t tmpsmcr;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_INSTANCE(htim->Instance));
+
+ /* Check the TIM state */
+ if (htim->State != HAL_TIM_STATE_READY)
+ {
+ return HAL_ERROR;
+ }
+
+ /* Set the TIM state */
+ htim->State = HAL_TIM_STATE_BUSY;
+
+ /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */
+ if (IS_TIM_SLAVE_INSTANCE(htim->Instance))
+ {
+ tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS;
+ if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr))
+ {
+ __HAL_TIM_ENABLE(htim);
+ }
+ }
+ else
+ {
+ __HAL_TIM_ENABLE(htim);
+ }
+
+ /* Return function status */
+ return HAL_OK;
+}
+
+/**
+ * @brief Stops the TIM Base generation.
+ * @param htim TIM Base handle
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIM_Base_Stop(TIM_HandleTypeDef *htim)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_INSTANCE(htim->Instance));
+
+ /* Disable the Peripheral */
+ __HAL_TIM_DISABLE(htim);
+
+ /* Set the TIM state */
+ htim->State = HAL_TIM_STATE_READY;
+
+ /* Return function status */
+ return HAL_OK;
+}
+
+/**
+ * @brief Starts the TIM Base generation in interrupt mode.
+ * @param htim TIM Base handle
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIM_Base_Start_IT(TIM_HandleTypeDef *htim)
+{
+ uint32_t tmpsmcr;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_INSTANCE(htim->Instance));
+
+ /* Check the TIM state */
+ if (htim->State != HAL_TIM_STATE_READY)
+ {
+ return HAL_ERROR;
+ }
+
+ /* Set the TIM state */
+ htim->State = HAL_TIM_STATE_BUSY;
+
+ /* Enable the TIM Update interrupt */
+ __HAL_TIM_ENABLE_IT(htim, TIM_IT_UPDATE);
+
+ /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */
+ if (IS_TIM_SLAVE_INSTANCE(htim->Instance))
+ {
+ tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS;
+ if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr))
+ {
+ __HAL_TIM_ENABLE(htim);
+ }
+ }
+ else
+ {
+ __HAL_TIM_ENABLE(htim);
+ }
+
+ /* Return function status */
+ return HAL_OK;
+}
+
+/**
+ * @brief Stops the TIM Base generation in interrupt mode.
+ * @param htim TIM Base handle
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIM_Base_Stop_IT(TIM_HandleTypeDef *htim)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_INSTANCE(htim->Instance));
+
+ /* Disable the TIM Update interrupt */
+ __HAL_TIM_DISABLE_IT(htim, TIM_IT_UPDATE);
+
+ /* Disable the Peripheral */
+ __HAL_TIM_DISABLE(htim);
+
+ /* Set the TIM state */
+ htim->State = HAL_TIM_STATE_READY;
+
+ /* Return function status */
+ return HAL_OK;
+}
+
+/**
+ * @brief Starts the TIM Base generation in DMA mode.
+ * @param htim TIM Base handle
+ * @param pData The source Buffer address.
+ * @param Length The length of data to be transferred from memory to peripheral.
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIM_Base_Start_DMA(TIM_HandleTypeDef *htim, uint32_t *pData, uint16_t Length)
+{
+ uint32_t tmpsmcr;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_DMA_INSTANCE(htim->Instance));
+
+ /* Set the TIM state */
+ if (htim->State == HAL_TIM_STATE_BUSY)
+ {
+ return HAL_BUSY;
+ }
+ else if (htim->State == HAL_TIM_STATE_READY)
+ {
+ if ((pData == NULL) && (Length > 0U))
+ {
+ return HAL_ERROR;
+ }
+ else
+ {
+ htim->State = HAL_TIM_STATE_BUSY;
+ }
+ }
+ else
+ {
+ return HAL_ERROR;
+ }
+
+ /* Set the DMA Period elapsed callbacks */
+ htim->hdma[TIM_DMA_ID_UPDATE]->XferCpltCallback = TIM_DMAPeriodElapsedCplt;
+ htim->hdma[TIM_DMA_ID_UPDATE]->XferHalfCpltCallback = TIM_DMAPeriodElapsedHalfCplt;
+
+ /* Set the DMA error callback */
+ htim->hdma[TIM_DMA_ID_UPDATE]->XferErrorCallback = TIM_DMAError ;
+
+ /* Enable the DMA channel */
+ if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_UPDATE], (uint32_t)pData, (uint32_t)&htim->Instance->ARR,
+ Length) != HAL_OK)
+ {
+ /* Return error status */
+ return HAL_ERROR;
+ }
+
+ /* Enable the TIM Update DMA request */
+ __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_UPDATE);
+
+ /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */
+ if (IS_TIM_SLAVE_INSTANCE(htim->Instance))
+ {
+ tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS;
+ if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr))
+ {
+ __HAL_TIM_ENABLE(htim);
+ }
+ }
+ else
+ {
+ __HAL_TIM_ENABLE(htim);
+ }
+
+ /* Return function status */
+ return HAL_OK;
+}
+
+/**
+ * @brief Stops the TIM Base generation in DMA mode.
+ * @param htim TIM Base handle
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIM_Base_Stop_DMA(TIM_HandleTypeDef *htim)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_DMA_INSTANCE(htim->Instance));
+
+ /* Disable the TIM Update DMA request */
+ __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_UPDATE);
+
+ (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_UPDATE]);
+
+ /* Disable the Peripheral */
+ __HAL_TIM_DISABLE(htim);
+
+ /* Set the TIM state */
+ htim->State = HAL_TIM_STATE_READY;
+
+ /* Return function status */
+ return HAL_OK;
+}
+
+/**
+ * @}
+ */
+
+/** @defgroup TIM_Exported_Functions_Group2 TIM Output Compare functions
+ * @brief TIM Output Compare functions
+ *
+@verbatim
+ ==============================================================================
+ ##### TIM Output Compare functions #####
+ ==============================================================================
+ [..]
+ This section provides functions allowing to:
+ (+) Initialize and configure the TIM Output Compare.
+ (+) De-initialize the TIM Output Compare.
+ (+) Start the TIM Output Compare.
+ (+) Stop the TIM Output Compare.
+ (+) Start the TIM Output Compare and enable interrupt.
+ (+) Stop the TIM Output Compare and disable interrupt.
+ (+) Start the TIM Output Compare and enable DMA transfer.
+ (+) Stop the TIM Output Compare and disable DMA transfer.
+
+@endverbatim
+ * @{
+ */
+/**
+ * @brief Initializes the TIM Output Compare according to the specified
+ * parameters in the TIM_HandleTypeDef and initializes the associated handle.
+ * @note Switching from Center Aligned counter mode to Edge counter mode (or reverse)
+ * requires a timer reset to avoid unexpected direction
+ * due to DIR bit readonly in center aligned mode.
+ * Ex: call @ref HAL_TIM_OC_DeInit() before HAL_TIM_OC_Init()
+ * @param htim TIM Output Compare handle
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIM_OC_Init(TIM_HandleTypeDef *htim)
+{
+ /* Check the TIM handle allocation */
+ if (htim == NULL)
+ {
+ return HAL_ERROR;
+ }
+
+ /* Check the parameters */
+ assert_param(IS_TIM_INSTANCE(htim->Instance));
+ assert_param(IS_TIM_COUNTER_MODE(htim->Init.CounterMode));
+ assert_param(IS_TIM_CLOCKDIVISION_DIV(htim->Init.ClockDivision));
+ assert_param(IS_TIM_AUTORELOAD_PRELOAD(htim->Init.AutoReloadPreload));
+
+ if (htim->State == HAL_TIM_STATE_RESET)
+ {
+ /* Allocate lock resource and initialize it */
+ htim->Lock = HAL_UNLOCKED;
+
+#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1)
+ /* Reset interrupt callbacks to legacy weak callbacks */
+ TIM_ResetCallback(htim);
+
+ if (htim->OC_MspInitCallback == NULL)
+ {
+ htim->OC_MspInitCallback = HAL_TIM_OC_MspInit;
+ }
+ /* Init the low level hardware : GPIO, CLOCK, NVIC */
+ htim->OC_MspInitCallback(htim);
+#else
+ /* Init the low level hardware : GPIO, CLOCK, NVIC and DMA */
+ HAL_TIM_OC_MspInit(htim);
+#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */
+ }
+
+ /* Set the TIM state */
+ htim->State = HAL_TIM_STATE_BUSY;
+
+ /* Init the base time for the Output Compare */
+ TIM_Base_SetConfig(htim->Instance, &htim->Init);
+
+ /* Initialize the DMA burst operation state */
+ htim->DMABurstState = HAL_DMA_BURST_STATE_READY;
+
+ /* Initialize the TIM channels state */
+ TIM_CHANNEL_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_READY);
+ TIM_CHANNEL_N_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_READY);
+
+ /* Initialize the TIM state*/
+ htim->State = HAL_TIM_STATE_READY;
+
+ return HAL_OK;
+}
+
+/**
+ * @brief DeInitializes the TIM peripheral
+ * @param htim TIM Output Compare handle
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIM_OC_DeInit(TIM_HandleTypeDef *htim)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_INSTANCE(htim->Instance));
+
+ htim->State = HAL_TIM_STATE_BUSY;
+
+ /* Disable the TIM Peripheral Clock */
+ __HAL_TIM_DISABLE(htim);
+
+#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1)
+ if (htim->OC_MspDeInitCallback == NULL)
+ {
+ htim->OC_MspDeInitCallback = HAL_TIM_OC_MspDeInit;
+ }
+ /* DeInit the low level hardware */
+ htim->OC_MspDeInitCallback(htim);
+#else
+ /* DeInit the low level hardware: GPIO, CLOCK, NVIC and DMA */
+ HAL_TIM_OC_MspDeInit(htim);
+#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */
+
+ /* Change the DMA burst operation state */
+ htim->DMABurstState = HAL_DMA_BURST_STATE_RESET;
+
+ /* Change the TIM channels state */
+ TIM_CHANNEL_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_RESET);
+ TIM_CHANNEL_N_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_RESET);
+
+ /* Change TIM state */
+ htim->State = HAL_TIM_STATE_RESET;
+
+ /* Release Lock */
+ __HAL_UNLOCK(htim);
+
+ return HAL_OK;
+}
+
+/**
+ * @brief Initializes the TIM Output Compare MSP.
+ * @param htim TIM Output Compare handle
+ * @retval None
+ */
+__weak void HAL_TIM_OC_MspInit(TIM_HandleTypeDef *htim)
+{
+ /* Prevent unused argument(s) compilation warning */
+ UNUSED(htim);
+
+ /* NOTE : This function should not be modified, when the callback is needed,
+ the HAL_TIM_OC_MspInit could be implemented in the user file
+ */
+}
+
+/**
+ * @brief DeInitializes TIM Output Compare MSP.
+ * @param htim TIM Output Compare handle
+ * @retval None
+ */
+__weak void HAL_TIM_OC_MspDeInit(TIM_HandleTypeDef *htim)
+{
+ /* Prevent unused argument(s) compilation warning */
+ UNUSED(htim);
+
+ /* NOTE : This function should not be modified, when the callback is needed,
+ the HAL_TIM_OC_MspDeInit could be implemented in the user file
+ */
+}
+
+/**
+ * @brief Starts the TIM Output Compare signal generation.
+ * @param htim TIM Output Compare handle
+ * @param Channel TIM Channel to be enabled
+ * This parameter can be one of the following values:
+ * @arg TIM_CHANNEL_1: TIM Channel 1 selected
+ * @arg TIM_CHANNEL_2: TIM Channel 2 selected
+ * @arg TIM_CHANNEL_3: TIM Channel 3 selected
+ * @arg TIM_CHANNEL_4: TIM Channel 4 selected
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIM_OC_Start(TIM_HandleTypeDef *htim, uint32_t Channel)
+{
+ uint32_t tmpsmcr;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel));
+
+ /* Check the TIM channel state */
+ if (TIM_CHANNEL_STATE_GET(htim, Channel) != HAL_TIM_CHANNEL_STATE_READY)
+ {
+ return HAL_ERROR;
+ }
+
+ /* Set the TIM channel state */
+ TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY);
+
+ /* Enable the Output compare channel */
+ TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_ENABLE);
+
+ if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET)
+ {
+ /* Enable the main output */
+ __HAL_TIM_MOE_ENABLE(htim);
+ }
+
+ /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */
+ if (IS_TIM_SLAVE_INSTANCE(htim->Instance))
+ {
+ tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS;
+ if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr))
+ {
+ __HAL_TIM_ENABLE(htim);
+ }
+ }
+ else
+ {
+ __HAL_TIM_ENABLE(htim);
+ }
+
+ /* Return function status */
+ return HAL_OK;
+}
+
+/**
+ * @brief Stops the TIM Output Compare signal generation.
+ * @param htim TIM Output Compare handle
+ * @param Channel TIM Channel to be disabled
+ * This parameter can be one of the following values:
+ * @arg TIM_CHANNEL_1: TIM Channel 1 selected
+ * @arg TIM_CHANNEL_2: TIM Channel 2 selected
+ * @arg TIM_CHANNEL_3: TIM Channel 3 selected
+ * @arg TIM_CHANNEL_4: TIM Channel 4 selected
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIM_OC_Stop(TIM_HandleTypeDef *htim, uint32_t Channel)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel));
+
+ /* Disable the Output compare channel */
+ TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_DISABLE);
+
+ if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET)
+ {
+ /* Disable the Main Output */
+ __HAL_TIM_MOE_DISABLE(htim);
+ }
+
+ /* Disable the Peripheral */
+ __HAL_TIM_DISABLE(htim);
+
+ /* Set the TIM channel state */
+ TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY);
+
+ /* Return function status */
+ return HAL_OK;
+}
+
+/**
+ * @brief Starts the TIM Output Compare signal generation in interrupt mode.
+ * @param htim TIM Output Compare handle
+ * @param Channel TIM Channel to be enabled
+ * This parameter can be one of the following values:
+ * @arg TIM_CHANNEL_1: TIM Channel 1 selected
+ * @arg TIM_CHANNEL_2: TIM Channel 2 selected
+ * @arg TIM_CHANNEL_3: TIM Channel 3 selected
+ * @arg TIM_CHANNEL_4: TIM Channel 4 selected
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIM_OC_Start_IT(TIM_HandleTypeDef *htim, uint32_t Channel)
+{
+ HAL_StatusTypeDef status = HAL_OK;
+ uint32_t tmpsmcr;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel));
+
+ /* Check the TIM channel state */
+ if (TIM_CHANNEL_STATE_GET(htim, Channel) != HAL_TIM_CHANNEL_STATE_READY)
+ {
+ return HAL_ERROR;
+ }
+
+ /* Set the TIM channel state */
+ TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY);
+
+ switch (Channel)
+ {
+ case TIM_CHANNEL_1:
+ {
+ /* Enable the TIM Capture/Compare 1 interrupt */
+ __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC1);
+ break;
+ }
+
+ case TIM_CHANNEL_2:
+ {
+ /* Enable the TIM Capture/Compare 2 interrupt */
+ __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC2);
+ break;
+ }
+
+ case TIM_CHANNEL_3:
+ {
+ /* Enable the TIM Capture/Compare 3 interrupt */
+ __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC3);
+ break;
+ }
+
+ case TIM_CHANNEL_4:
+ {
+ /* Enable the TIM Capture/Compare 4 interrupt */
+ __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC4);
+ break;
+ }
+
+ default:
+ status = HAL_ERROR;
+ break;
+ }
+
+ if (status == HAL_OK)
+ {
+ /* Enable the Output compare channel */
+ TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_ENABLE);
+
+ if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET)
+ {
+ /* Enable the main output */
+ __HAL_TIM_MOE_ENABLE(htim);
+ }
+
+ /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */
+ if (IS_TIM_SLAVE_INSTANCE(htim->Instance))
+ {
+ tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS;
+ if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr))
+ {
+ __HAL_TIM_ENABLE(htim);
+ }
+ }
+ else
+ {
+ __HAL_TIM_ENABLE(htim);
+ }
+ }
+
+ /* Return function status */
+ return status;
+}
+
+/**
+ * @brief Stops the TIM Output Compare signal generation in interrupt mode.
+ * @param htim TIM Output Compare handle
+ * @param Channel TIM Channel to be disabled
+ * This parameter can be one of the following values:
+ * @arg TIM_CHANNEL_1: TIM Channel 1 selected
+ * @arg TIM_CHANNEL_2: TIM Channel 2 selected
+ * @arg TIM_CHANNEL_3: TIM Channel 3 selected
+ * @arg TIM_CHANNEL_4: TIM Channel 4 selected
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIM_OC_Stop_IT(TIM_HandleTypeDef *htim, uint32_t Channel)
+{
+ HAL_StatusTypeDef status = HAL_OK;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel));
+
+ switch (Channel)
+ {
+ case TIM_CHANNEL_1:
+ {
+ /* Disable the TIM Capture/Compare 1 interrupt */
+ __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC1);
+ break;
+ }
+
+ case TIM_CHANNEL_2:
+ {
+ /* Disable the TIM Capture/Compare 2 interrupt */
+ __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC2);
+ break;
+ }
+
+ case TIM_CHANNEL_3:
+ {
+ /* Disable the TIM Capture/Compare 3 interrupt */
+ __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC3);
+ break;
+ }
+
+ case TIM_CHANNEL_4:
+ {
+ /* Disable the TIM Capture/Compare 4 interrupt */
+ __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC4);
+ break;
+ }
+
+ default:
+ status = HAL_ERROR;
+ break;
+ }
+
+ if (status == HAL_OK)
+ {
+ /* Disable the Output compare channel */
+ TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_DISABLE);
+
+ if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET)
+ {
+ /* Disable the Main Output */
+ __HAL_TIM_MOE_DISABLE(htim);
+ }
+
+ /* Disable the Peripheral */
+ __HAL_TIM_DISABLE(htim);
+
+ /* Set the TIM channel state */
+ TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY);
+ }
+
+ /* Return function status */
+ return status;
+}
+
+/**
+ * @brief Starts the TIM Output Compare signal generation in DMA mode.
+ * @param htim TIM Output Compare handle
+ * @param Channel TIM Channel to be enabled
+ * This parameter can be one of the following values:
+ * @arg TIM_CHANNEL_1: TIM Channel 1 selected
+ * @arg TIM_CHANNEL_2: TIM Channel 2 selected
+ * @arg TIM_CHANNEL_3: TIM Channel 3 selected
+ * @arg TIM_CHANNEL_4: TIM Channel 4 selected
+ * @param pData The source Buffer address.
+ * @param Length The length of data to be transferred from memory to TIM peripheral
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIM_OC_Start_DMA(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pData, uint16_t Length)
+{
+ HAL_StatusTypeDef status = HAL_OK;
+ uint32_t tmpsmcr;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel));
+
+ /* Set the TIM channel state */
+ if (TIM_CHANNEL_STATE_GET(htim, Channel) == HAL_TIM_CHANNEL_STATE_BUSY)
+ {
+ return HAL_BUSY;
+ }
+ else if (TIM_CHANNEL_STATE_GET(htim, Channel) == HAL_TIM_CHANNEL_STATE_READY)
+ {
+ if ((pData == NULL) && (Length > 0U))
+ {
+ return HAL_ERROR;
+ }
+ else
+ {
+ TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY);
+ }
+ }
+ else
+ {
+ return HAL_ERROR;
+ }
+
+ switch (Channel)
+ {
+ case TIM_CHANNEL_1:
+ {
+ /* Set the DMA compare callbacks */
+ htim->hdma[TIM_DMA_ID_CC1]->XferCpltCallback = TIM_DMADelayPulseCplt;
+ htim->hdma[TIM_DMA_ID_CC1]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt;
+
+ /* Set the DMA error callback */
+ htim->hdma[TIM_DMA_ID_CC1]->XferErrorCallback = TIM_DMAError ;
+
+ /* Enable the DMA channel */
+ if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC1], (uint32_t)pData, (uint32_t)&htim->Instance->CCR1,
+ Length) != HAL_OK)
+ {
+ /* Return error status */
+ return HAL_ERROR;
+ }
+
+ /* Enable the TIM Capture/Compare 1 DMA request */
+ __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC1);
+ break;
+ }
+
+ case TIM_CHANNEL_2:
+ {
+ /* Set the DMA compare callbacks */
+ htim->hdma[TIM_DMA_ID_CC2]->XferCpltCallback = TIM_DMADelayPulseCplt;
+ htim->hdma[TIM_DMA_ID_CC2]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt;
+
+ /* Set the DMA error callback */
+ htim->hdma[TIM_DMA_ID_CC2]->XferErrorCallback = TIM_DMAError ;
+
+ /* Enable the DMA channel */
+ if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC2], (uint32_t)pData, (uint32_t)&htim->Instance->CCR2,
+ Length) != HAL_OK)
+ {
+ /* Return error status */
+ return HAL_ERROR;
+ }
+
+ /* Enable the TIM Capture/Compare 2 DMA request */
+ __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC2);
+ break;
+ }
+
+ case TIM_CHANNEL_3:
+ {
+ /* Set the DMA compare callbacks */
+ htim->hdma[TIM_DMA_ID_CC3]->XferCpltCallback = TIM_DMADelayPulseCplt;
+ htim->hdma[TIM_DMA_ID_CC3]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt;
+
+ /* Set the DMA error callback */
+ htim->hdma[TIM_DMA_ID_CC3]->XferErrorCallback = TIM_DMAError ;
+
+ /* Enable the DMA channel */
+ if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC3], (uint32_t)pData, (uint32_t)&htim->Instance->CCR3,
+ Length) != HAL_OK)
+ {
+ /* Return error status */
+ return HAL_ERROR;
+ }
+ /* Enable the TIM Capture/Compare 3 DMA request */
+ __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC3);
+ break;
+ }
+
+ case TIM_CHANNEL_4:
+ {
+ /* Set the DMA compare callbacks */
+ htim->hdma[TIM_DMA_ID_CC4]->XferCpltCallback = TIM_DMADelayPulseCplt;
+ htim->hdma[TIM_DMA_ID_CC4]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt;
+
+ /* Set the DMA error callback */
+ htim->hdma[TIM_DMA_ID_CC4]->XferErrorCallback = TIM_DMAError ;
+
+ /* Enable the DMA channel */
+ if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC4], (uint32_t)pData, (uint32_t)&htim->Instance->CCR4,
+ Length) != HAL_OK)
+ {
+ /* Return error status */
+ return HAL_ERROR;
+ }
+ /* Enable the TIM Capture/Compare 4 DMA request */
+ __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC4);
+ break;
+ }
+
+ default:
+ status = HAL_ERROR;
+ break;
+ }
+
+ if (status == HAL_OK)
+ {
+ /* Enable the Output compare channel */
+ TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_ENABLE);
+
+ if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET)
+ {
+ /* Enable the main output */
+ __HAL_TIM_MOE_ENABLE(htim);
+ }
+
+ /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */
+ if (IS_TIM_SLAVE_INSTANCE(htim->Instance))
+ {
+ tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS;
+ if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr))
+ {
+ __HAL_TIM_ENABLE(htim);
+ }
+ }
+ else
+ {
+ __HAL_TIM_ENABLE(htim);
+ }
+ }
+
+ /* Return function status */
+ return status;
+}
+
+/**
+ * @brief Stops the TIM Output Compare signal generation in DMA mode.
+ * @param htim TIM Output Compare handle
+ * @param Channel TIM Channel to be disabled
+ * This parameter can be one of the following values:
+ * @arg TIM_CHANNEL_1: TIM Channel 1 selected
+ * @arg TIM_CHANNEL_2: TIM Channel 2 selected
+ * @arg TIM_CHANNEL_3: TIM Channel 3 selected
+ * @arg TIM_CHANNEL_4: TIM Channel 4 selected
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIM_OC_Stop_DMA(TIM_HandleTypeDef *htim, uint32_t Channel)
+{
+ HAL_StatusTypeDef status = HAL_OK;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel));
+
+ switch (Channel)
+ {
+ case TIM_CHANNEL_1:
+ {
+ /* Disable the TIM Capture/Compare 1 DMA request */
+ __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC1);
+ (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC1]);
+ break;
+ }
+
+ case TIM_CHANNEL_2:
+ {
+ /* Disable the TIM Capture/Compare 2 DMA request */
+ __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC2);
+ (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC2]);
+ break;
+ }
+
+ case TIM_CHANNEL_3:
+ {
+ /* Disable the TIM Capture/Compare 3 DMA request */
+ __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC3);
+ (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC3]);
+ break;
+ }
+
+ case TIM_CHANNEL_4:
+ {
+ /* Disable the TIM Capture/Compare 4 interrupt */
+ __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC4);
+ (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC4]);
+ break;
+ }
+
+ default:
+ status = HAL_ERROR;
+ break;
+ }
+
+ if (status == HAL_OK)
+ {
+ /* Disable the Output compare channel */
+ TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_DISABLE);
+
+ if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET)
+ {
+ /* Disable the Main Output */
+ __HAL_TIM_MOE_DISABLE(htim);
+ }
+
+ /* Disable the Peripheral */
+ __HAL_TIM_DISABLE(htim);
+
+ /* Set the TIM channel state */
+ TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY);
+ }
+
+ /* Return function status */
+ return status;
+}
+
+/**
+ * @}
+ */
+
+/** @defgroup TIM_Exported_Functions_Group3 TIM PWM functions
+ * @brief TIM PWM functions
+ *
+@verbatim
+ ==============================================================================
+ ##### TIM PWM functions #####
+ ==============================================================================
+ [..]
+ This section provides functions allowing to:
+ (+) Initialize and configure the TIM PWM.
+ (+) De-initialize the TIM PWM.
+ (+) Start the TIM PWM.
+ (+) Stop the TIM PWM.
+ (+) Start the TIM PWM and enable interrupt.
+ (+) Stop the TIM PWM and disable interrupt.
+ (+) Start the TIM PWM and enable DMA transfer.
+ (+) Stop the TIM PWM and disable DMA transfer.
+
+@endverbatim
+ * @{
+ */
+/**
+ * @brief Initializes the TIM PWM Time Base according to the specified
+ * parameters in the TIM_HandleTypeDef and initializes the associated handle.
+ * @note Switching from Center Aligned counter mode to Edge counter mode (or reverse)
+ * requires a timer reset to avoid unexpected direction
+ * due to DIR bit readonly in center aligned mode.
+ * Ex: call @ref HAL_TIM_PWM_DeInit() before HAL_TIM_PWM_Init()
+ * @param htim TIM PWM handle
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIM_PWM_Init(TIM_HandleTypeDef *htim)
+{
+ /* Check the TIM handle allocation */
+ if (htim == NULL)
+ {
+ return HAL_ERROR;
+ }
+
+ /* Check the parameters */
+ assert_param(IS_TIM_INSTANCE(htim->Instance));
+ assert_param(IS_TIM_COUNTER_MODE(htim->Init.CounterMode));
+ assert_param(IS_TIM_CLOCKDIVISION_DIV(htim->Init.ClockDivision));
+ assert_param(IS_TIM_AUTORELOAD_PRELOAD(htim->Init.AutoReloadPreload));
+
+ if (htim->State == HAL_TIM_STATE_RESET)
+ {
+ /* Allocate lock resource and initialize it */
+ htim->Lock = HAL_UNLOCKED;
+
+#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1)
+ /* Reset interrupt callbacks to legacy weak callbacks */
+ TIM_ResetCallback(htim);
+
+ if (htim->PWM_MspInitCallback == NULL)
+ {
+ htim->PWM_MspInitCallback = HAL_TIM_PWM_MspInit;
+ }
+ /* Init the low level hardware : GPIO, CLOCK, NVIC */
+ htim->PWM_MspInitCallback(htim);
+#else
+ /* Init the low level hardware : GPIO, CLOCK, NVIC and DMA */
+ HAL_TIM_PWM_MspInit(htim);
+#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */
+ }
+
+ /* Set the TIM state */
+ htim->State = HAL_TIM_STATE_BUSY;
+
+ /* Init the base time for the PWM */
+ TIM_Base_SetConfig(htim->Instance, &htim->Init);
+
+ /* Initialize the DMA burst operation state */
+ htim->DMABurstState = HAL_DMA_BURST_STATE_READY;
+
+ /* Initialize the TIM channels state */
+ TIM_CHANNEL_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_READY);
+ TIM_CHANNEL_N_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_READY);
+
+ /* Initialize the TIM state*/
+ htim->State = HAL_TIM_STATE_READY;
+
+ return HAL_OK;
+}
+
+/**
+ * @brief DeInitializes the TIM peripheral
+ * @param htim TIM PWM handle
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIM_PWM_DeInit(TIM_HandleTypeDef *htim)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_INSTANCE(htim->Instance));
+
+ htim->State = HAL_TIM_STATE_BUSY;
+
+ /* Disable the TIM Peripheral Clock */
+ __HAL_TIM_DISABLE(htim);
+
+#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1)
+ if (htim->PWM_MspDeInitCallback == NULL)
+ {
+ htim->PWM_MspDeInitCallback = HAL_TIM_PWM_MspDeInit;
+ }
+ /* DeInit the low level hardware */
+ htim->PWM_MspDeInitCallback(htim);
+#else
+ /* DeInit the low level hardware: GPIO, CLOCK, NVIC and DMA */
+ HAL_TIM_PWM_MspDeInit(htim);
+#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */
+
+ /* Change the DMA burst operation state */
+ htim->DMABurstState = HAL_DMA_BURST_STATE_RESET;
+
+ /* Change the TIM channels state */
+ TIM_CHANNEL_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_RESET);
+ TIM_CHANNEL_N_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_RESET);
+
+ /* Change TIM state */
+ htim->State = HAL_TIM_STATE_RESET;
+
+ /* Release Lock */
+ __HAL_UNLOCK(htim);
+
+ return HAL_OK;
+}
+
+/**
+ * @brief Initializes the TIM PWM MSP.
+ * @param htim TIM PWM handle
+ * @retval None
+ */
+__weak void HAL_TIM_PWM_MspInit(TIM_HandleTypeDef *htim)
+{
+ /* Prevent unused argument(s) compilation warning */
+ UNUSED(htim);
+
+ /* NOTE : This function should not be modified, when the callback is needed,
+ the HAL_TIM_PWM_MspInit could be implemented in the user file
+ */
+}
+
+/**
+ * @brief DeInitializes TIM PWM MSP.
+ * @param htim TIM PWM handle
+ * @retval None
+ */
+__weak void HAL_TIM_PWM_MspDeInit(TIM_HandleTypeDef *htim)
+{
+ /* Prevent unused argument(s) compilation warning */
+ UNUSED(htim);
+
+ /* NOTE : This function should not be modified, when the callback is needed,
+ the HAL_TIM_PWM_MspDeInit could be implemented in the user file
+ */
+}
+
+/**
+ * @brief Starts the PWM signal generation.
+ * @param htim TIM handle
+ * @param Channel TIM Channels to be enabled
+ * This parameter can be one of the following values:
+ * @arg TIM_CHANNEL_1: TIM Channel 1 selected
+ * @arg TIM_CHANNEL_2: TIM Channel 2 selected
+ * @arg TIM_CHANNEL_3: TIM Channel 3 selected
+ * @arg TIM_CHANNEL_4: TIM Channel 4 selected
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIM_PWM_Start(TIM_HandleTypeDef *htim, uint32_t Channel)
+{
+ uint32_t tmpsmcr;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel));
+
+ /* Check the TIM channel state */
+ if (TIM_CHANNEL_STATE_GET(htim, Channel) != HAL_TIM_CHANNEL_STATE_READY)
+ {
+ return HAL_ERROR;
+ }
+
+ /* Set the TIM channel state */
+ TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY);
+
+ /* Enable the Capture compare channel */
+ TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_ENABLE);
+
+ if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET)
+ {
+ /* Enable the main output */
+ __HAL_TIM_MOE_ENABLE(htim);
+ }
+
+ /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */
+ if (IS_TIM_SLAVE_INSTANCE(htim->Instance))
+ {
+ tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS;
+ if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr))
+ {
+ __HAL_TIM_ENABLE(htim);
+ }
+ }
+ else
+ {
+ __HAL_TIM_ENABLE(htim);
+ }
+
+ /* Return function status */
+ return HAL_OK;
+}
+
+/**
+ * @brief Stops the PWM signal generation.
+ * @param htim TIM PWM handle
+ * @param Channel TIM Channels to be disabled
+ * This parameter can be one of the following values:
+ * @arg TIM_CHANNEL_1: TIM Channel 1 selected
+ * @arg TIM_CHANNEL_2: TIM Channel 2 selected
+ * @arg TIM_CHANNEL_3: TIM Channel 3 selected
+ * @arg TIM_CHANNEL_4: TIM Channel 4 selected
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIM_PWM_Stop(TIM_HandleTypeDef *htim, uint32_t Channel)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel));
+
+ /* Disable the Capture compare channel */
+ TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_DISABLE);
+
+ if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET)
+ {
+ /* Disable the Main Output */
+ __HAL_TIM_MOE_DISABLE(htim);
+ }
+
+ /* Disable the Peripheral */
+ __HAL_TIM_DISABLE(htim);
+
+ /* Set the TIM channel state */
+ TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY);
+
+ /* Return function status */
+ return HAL_OK;
+}
+
+/**
+ * @brief Starts the PWM signal generation in interrupt mode.
+ * @param htim TIM PWM handle
+ * @param Channel TIM Channel to be enabled
+ * This parameter can be one of the following values:
+ * @arg TIM_CHANNEL_1: TIM Channel 1 selected
+ * @arg TIM_CHANNEL_2: TIM Channel 2 selected
+ * @arg TIM_CHANNEL_3: TIM Channel 3 selected
+ * @arg TIM_CHANNEL_4: TIM Channel 4 selected
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIM_PWM_Start_IT(TIM_HandleTypeDef *htim, uint32_t Channel)
+{
+ HAL_StatusTypeDef status = HAL_OK;
+ uint32_t tmpsmcr;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel));
+
+ /* Check the TIM channel state */
+ if (TIM_CHANNEL_STATE_GET(htim, Channel) != HAL_TIM_CHANNEL_STATE_READY)
+ {
+ return HAL_ERROR;
+ }
+
+ /* Set the TIM channel state */
+ TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY);
+
+ switch (Channel)
+ {
+ case TIM_CHANNEL_1:
+ {
+ /* Enable the TIM Capture/Compare 1 interrupt */
+ __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC1);
+ break;
+ }
+
+ case TIM_CHANNEL_2:
+ {
+ /* Enable the TIM Capture/Compare 2 interrupt */
+ __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC2);
+ break;
+ }
+
+ case TIM_CHANNEL_3:
+ {
+ /* Enable the TIM Capture/Compare 3 interrupt */
+ __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC3);
+ break;
+ }
+
+ case TIM_CHANNEL_4:
+ {
+ /* Enable the TIM Capture/Compare 4 interrupt */
+ __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC4);
+ break;
+ }
+
+ default:
+ status = HAL_ERROR;
+ break;
+ }
+
+ if (status == HAL_OK)
+ {
+ /* Enable the Capture compare channel */
+ TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_ENABLE);
+
+ if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET)
+ {
+ /* Enable the main output */
+ __HAL_TIM_MOE_ENABLE(htim);
+ }
+
+ /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */
+ if (IS_TIM_SLAVE_INSTANCE(htim->Instance))
+ {
+ tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS;
+ if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr))
+ {
+ __HAL_TIM_ENABLE(htim);
+ }
+ }
+ else
+ {
+ __HAL_TIM_ENABLE(htim);
+ }
+ }
+
+ /* Return function status */
+ return status;
+}
+
+/**
+ * @brief Stops the PWM signal generation in interrupt mode.
+ * @param htim TIM PWM handle
+ * @param Channel TIM Channels to be disabled
+ * This parameter can be one of the following values:
+ * @arg TIM_CHANNEL_1: TIM Channel 1 selected
+ * @arg TIM_CHANNEL_2: TIM Channel 2 selected
+ * @arg TIM_CHANNEL_3: TIM Channel 3 selected
+ * @arg TIM_CHANNEL_4: TIM Channel 4 selected
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIM_PWM_Stop_IT(TIM_HandleTypeDef *htim, uint32_t Channel)
+{
+ HAL_StatusTypeDef status = HAL_OK;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel));
+
+ switch (Channel)
+ {
+ case TIM_CHANNEL_1:
+ {
+ /* Disable the TIM Capture/Compare 1 interrupt */
+ __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC1);
+ break;
+ }
+
+ case TIM_CHANNEL_2:
+ {
+ /* Disable the TIM Capture/Compare 2 interrupt */
+ __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC2);
+ break;
+ }
+
+ case TIM_CHANNEL_3:
+ {
+ /* Disable the TIM Capture/Compare 3 interrupt */
+ __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC3);
+ break;
+ }
+
+ case TIM_CHANNEL_4:
+ {
+ /* Disable the TIM Capture/Compare 4 interrupt */
+ __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC4);
+ break;
+ }
+
+ default:
+ status = HAL_ERROR;
+ break;
+ }
+
+ if (status == HAL_OK)
+ {
+ /* Disable the Capture compare channel */
+ TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_DISABLE);
+
+ if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET)
+ {
+ /* Disable the Main Output */
+ __HAL_TIM_MOE_DISABLE(htim);
+ }
+
+ /* Disable the Peripheral */
+ __HAL_TIM_DISABLE(htim);
+
+ /* Set the TIM channel state */
+ TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY);
+ }
+
+ /* Return function status */
+ return status;
+}
+
+/**
+ * @brief Starts the TIM PWM signal generation in DMA mode.
+ * @param htim TIM PWM handle
+ * @param Channel TIM Channels to be enabled
+ * This parameter can be one of the following values:
+ * @arg TIM_CHANNEL_1: TIM Channel 1 selected
+ * @arg TIM_CHANNEL_2: TIM Channel 2 selected
+ * @arg TIM_CHANNEL_3: TIM Channel 3 selected
+ * @arg TIM_CHANNEL_4: TIM Channel 4 selected
+ * @param pData The source Buffer address.
+ * @param Length The length of data to be transferred from memory to TIM peripheral
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIM_PWM_Start_DMA(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pData, uint16_t Length)
+{
+ HAL_StatusTypeDef status = HAL_OK;
+ uint32_t tmpsmcr;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel));
+
+ /* Set the TIM channel state */
+ if (TIM_CHANNEL_STATE_GET(htim, Channel) == HAL_TIM_CHANNEL_STATE_BUSY)
+ {
+ return HAL_BUSY;
+ }
+ else if (TIM_CHANNEL_STATE_GET(htim, Channel) == HAL_TIM_CHANNEL_STATE_READY)
+ {
+ if ((pData == NULL) && (Length > 0U))
+ {
+ return HAL_ERROR;
+ }
+ else
+ {
+ TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY);
+ }
+ }
+ else
+ {
+ return HAL_ERROR;
+ }
+
+ switch (Channel)
+ {
+ case TIM_CHANNEL_1:
+ {
+ /* Set the DMA compare callbacks */
+ htim->hdma[TIM_DMA_ID_CC1]->XferCpltCallback = TIM_DMADelayPulseCplt;
+ htim->hdma[TIM_DMA_ID_CC1]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt;
+
+ /* Set the DMA error callback */
+ htim->hdma[TIM_DMA_ID_CC1]->XferErrorCallback = TIM_DMAError ;
+
+ /* Enable the DMA channel */
+ if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC1], (uint32_t)pData, (uint32_t)&htim->Instance->CCR1,
+ Length) != HAL_OK)
+ {
+ /* Return error status */
+ return HAL_ERROR;
+ }
+
+ /* Enable the TIM Capture/Compare 1 DMA request */
+ __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC1);
+ break;
+ }
+
+ case TIM_CHANNEL_2:
+ {
+ /* Set the DMA compare callbacks */
+ htim->hdma[TIM_DMA_ID_CC2]->XferCpltCallback = TIM_DMADelayPulseCplt;
+ htim->hdma[TIM_DMA_ID_CC2]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt;
+
+ /* Set the DMA error callback */
+ htim->hdma[TIM_DMA_ID_CC2]->XferErrorCallback = TIM_DMAError ;
+
+ /* Enable the DMA channel */
+ if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC2], (uint32_t)pData, (uint32_t)&htim->Instance->CCR2,
+ Length) != HAL_OK)
+ {
+ /* Return error status */
+ return HAL_ERROR;
+ }
+ /* Enable the TIM Capture/Compare 2 DMA request */
+ __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC2);
+ break;
+ }
+
+ case TIM_CHANNEL_3:
+ {
+ /* Set the DMA compare callbacks */
+ htim->hdma[TIM_DMA_ID_CC3]->XferCpltCallback = TIM_DMADelayPulseCplt;
+ htim->hdma[TIM_DMA_ID_CC3]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt;
+
+ /* Set the DMA error callback */
+ htim->hdma[TIM_DMA_ID_CC3]->XferErrorCallback = TIM_DMAError ;
+
+ /* Enable the DMA channel */
+ if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC3], (uint32_t)pData, (uint32_t)&htim->Instance->CCR3,
+ Length) != HAL_OK)
+ {
+ /* Return error status */
+ return HAL_ERROR;
+ }
+ /* Enable the TIM Output Capture/Compare 3 request */
+ __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC3);
+ break;
+ }
+
+ case TIM_CHANNEL_4:
+ {
+ /* Set the DMA compare callbacks */
+ htim->hdma[TIM_DMA_ID_CC4]->XferCpltCallback = TIM_DMADelayPulseCplt;
+ htim->hdma[TIM_DMA_ID_CC4]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt;
+
+ /* Set the DMA error callback */
+ htim->hdma[TIM_DMA_ID_CC4]->XferErrorCallback = TIM_DMAError ;
+
+ /* Enable the DMA channel */
+ if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC4], (uint32_t)pData, (uint32_t)&htim->Instance->CCR4,
+ Length) != HAL_OK)
+ {
+ /* Return error status */
+ return HAL_ERROR;
+ }
+ /* Enable the TIM Capture/Compare 4 DMA request */
+ __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC4);
+ break;
+ }
+
+ default:
+ status = HAL_ERROR;
+ break;
+ }
+
+ if (status == HAL_OK)
+ {
+ /* Enable the Capture compare channel */
+ TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_ENABLE);
+
+ if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET)
+ {
+ /* Enable the main output */
+ __HAL_TIM_MOE_ENABLE(htim);
+ }
+
+ /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */
+ if (IS_TIM_SLAVE_INSTANCE(htim->Instance))
+ {
+ tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS;
+ if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr))
+ {
+ __HAL_TIM_ENABLE(htim);
+ }
+ }
+ else
+ {
+ __HAL_TIM_ENABLE(htim);
+ }
+ }
+
+ /* Return function status */
+ return status;
+}
+
+/**
+ * @brief Stops the TIM PWM signal generation in DMA mode.
+ * @param htim TIM PWM handle
+ * @param Channel TIM Channels to be disabled
+ * This parameter can be one of the following values:
+ * @arg TIM_CHANNEL_1: TIM Channel 1 selected
+ * @arg TIM_CHANNEL_2: TIM Channel 2 selected
+ * @arg TIM_CHANNEL_3: TIM Channel 3 selected
+ * @arg TIM_CHANNEL_4: TIM Channel 4 selected
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIM_PWM_Stop_DMA(TIM_HandleTypeDef *htim, uint32_t Channel)
+{
+ HAL_StatusTypeDef status = HAL_OK;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel));
+
+ switch (Channel)
+ {
+ case TIM_CHANNEL_1:
+ {
+ /* Disable the TIM Capture/Compare 1 DMA request */
+ __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC1);
+ (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC1]);
+ break;
+ }
+
+ case TIM_CHANNEL_2:
+ {
+ /* Disable the TIM Capture/Compare 2 DMA request */
+ __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC2);
+ (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC2]);
+ break;
+ }
+
+ case TIM_CHANNEL_3:
+ {
+ /* Disable the TIM Capture/Compare 3 DMA request */
+ __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC3);
+ (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC3]);
+ break;
+ }
+
+ case TIM_CHANNEL_4:
+ {
+ /* Disable the TIM Capture/Compare 4 interrupt */
+ __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC4);
+ (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC4]);
+ break;
+ }
+
+ default:
+ status = HAL_ERROR;
+ break;
+ }
+
+ if (status == HAL_OK)
+ {
+ /* Disable the Capture compare channel */
+ TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_DISABLE);
+
+ if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET)
+ {
+ /* Disable the Main Output */
+ __HAL_TIM_MOE_DISABLE(htim);
+ }
+
+ /* Disable the Peripheral */
+ __HAL_TIM_DISABLE(htim);
+
+ /* Set the TIM channel state */
+ TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY);
+ }
+
+ /* Return function status */
+ return status;
+}
+
+/**
+ * @}
+ */
+
+/** @defgroup TIM_Exported_Functions_Group4 TIM Input Capture functions
+ * @brief TIM Input Capture functions
+ *
+@verbatim
+ ==============================================================================
+ ##### TIM Input Capture functions #####
+ ==============================================================================
+ [..]
+ This section provides functions allowing to:
+ (+) Initialize and configure the TIM Input Capture.
+ (+) De-initialize the TIM Input Capture.
+ (+) Start the TIM Input Capture.
+ (+) Stop the TIM Input Capture.
+ (+) Start the TIM Input Capture and enable interrupt.
+ (+) Stop the TIM Input Capture and disable interrupt.
+ (+) Start the TIM Input Capture and enable DMA transfer.
+ (+) Stop the TIM Input Capture and disable DMA transfer.
+
+@endverbatim
+ * @{
+ */
+/**
+ * @brief Initializes the TIM Input Capture Time base according to the specified
+ * parameters in the TIM_HandleTypeDef and initializes the associated handle.
+ * @note Switching from Center Aligned counter mode to Edge counter mode (or reverse)
+ * requires a timer reset to avoid unexpected direction
+ * due to DIR bit readonly in center aligned mode.
+ * Ex: call @ref HAL_TIM_IC_DeInit() before HAL_TIM_IC_Init()
+ * @param htim TIM Input Capture handle
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIM_IC_Init(TIM_HandleTypeDef *htim)
+{
+ /* Check the TIM handle allocation */
+ if (htim == NULL)
+ {
+ return HAL_ERROR;
+ }
+
+ /* Check the parameters */
+ assert_param(IS_TIM_INSTANCE(htim->Instance));
+ assert_param(IS_TIM_COUNTER_MODE(htim->Init.CounterMode));
+ assert_param(IS_TIM_CLOCKDIVISION_DIV(htim->Init.ClockDivision));
+ assert_param(IS_TIM_AUTORELOAD_PRELOAD(htim->Init.AutoReloadPreload));
+
+ if (htim->State == HAL_TIM_STATE_RESET)
+ {
+ /* Allocate lock resource and initialize it */
+ htim->Lock = HAL_UNLOCKED;
+
+#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1)
+ /* Reset interrupt callbacks to legacy weak callbacks */
+ TIM_ResetCallback(htim);
+
+ if (htim->IC_MspInitCallback == NULL)
+ {
+ htim->IC_MspInitCallback = HAL_TIM_IC_MspInit;
+ }
+ /* Init the low level hardware : GPIO, CLOCK, NVIC */
+ htim->IC_MspInitCallback(htim);
+#else
+ /* Init the low level hardware : GPIO, CLOCK, NVIC and DMA */
+ HAL_TIM_IC_MspInit(htim);
+#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */
+ }
+
+ /* Set the TIM state */
+ htim->State = HAL_TIM_STATE_BUSY;
+
+ /* Init the base time for the input capture */
+ TIM_Base_SetConfig(htim->Instance, &htim->Init);
+
+ /* Initialize the DMA burst operation state */
+ htim->DMABurstState = HAL_DMA_BURST_STATE_READY;
+
+ /* Initialize the TIM channels state */
+ TIM_CHANNEL_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_READY);
+ TIM_CHANNEL_N_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_READY);
+
+ /* Initialize the TIM state*/
+ htim->State = HAL_TIM_STATE_READY;
+
+ return HAL_OK;
+}
+
+/**
+ * @brief DeInitializes the TIM peripheral
+ * @param htim TIM Input Capture handle
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIM_IC_DeInit(TIM_HandleTypeDef *htim)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_INSTANCE(htim->Instance));
+
+ htim->State = HAL_TIM_STATE_BUSY;
+
+ /* Disable the TIM Peripheral Clock */
+ __HAL_TIM_DISABLE(htim);
+
+#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1)
+ if (htim->IC_MspDeInitCallback == NULL)
+ {
+ htim->IC_MspDeInitCallback = HAL_TIM_IC_MspDeInit;
+ }
+ /* DeInit the low level hardware */
+ htim->IC_MspDeInitCallback(htim);
+#else
+ /* DeInit the low level hardware: GPIO, CLOCK, NVIC and DMA */
+ HAL_TIM_IC_MspDeInit(htim);
+#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */
+
+ /* Change the DMA burst operation state */
+ htim->DMABurstState = HAL_DMA_BURST_STATE_RESET;
+
+ /* Change the TIM channels state */
+ TIM_CHANNEL_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_RESET);
+ TIM_CHANNEL_N_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_RESET);
+
+ /* Change TIM state */
+ htim->State = HAL_TIM_STATE_RESET;
+
+ /* Release Lock */
+ __HAL_UNLOCK(htim);
+
+ return HAL_OK;
+}
+
+/**
+ * @brief Initializes the TIM Input Capture MSP.
+ * @param htim TIM Input Capture handle
+ * @retval None
+ */
+__weak void HAL_TIM_IC_MspInit(TIM_HandleTypeDef *htim)
+{
+ /* Prevent unused argument(s) compilation warning */
+ UNUSED(htim);
+
+ /* NOTE : This function should not be modified, when the callback is needed,
+ the HAL_TIM_IC_MspInit could be implemented in the user file
+ */
+}
+
+/**
+ * @brief DeInitializes TIM Input Capture MSP.
+ * @param htim TIM handle
+ * @retval None
+ */
+__weak void HAL_TIM_IC_MspDeInit(TIM_HandleTypeDef *htim)
+{
+ /* Prevent unused argument(s) compilation warning */
+ UNUSED(htim);
+
+ /* NOTE : This function should not be modified, when the callback is needed,
+ the HAL_TIM_IC_MspDeInit could be implemented in the user file
+ */
+}
+
+/**
+ * @brief Starts the TIM Input Capture measurement.
+ * @param htim TIM Input Capture handle
+ * @param Channel TIM Channels to be enabled
+ * This parameter can be one of the following values:
+ * @arg TIM_CHANNEL_1: TIM Channel 1 selected
+ * @arg TIM_CHANNEL_2: TIM Channel 2 selected
+ * @arg TIM_CHANNEL_3: TIM Channel 3 selected
+ * @arg TIM_CHANNEL_4: TIM Channel 4 selected
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIM_IC_Start(TIM_HandleTypeDef *htim, uint32_t Channel)
+{
+ uint32_t tmpsmcr;
+ HAL_TIM_ChannelStateTypeDef channel_state = TIM_CHANNEL_STATE_GET(htim, Channel);
+ HAL_TIM_ChannelStateTypeDef complementary_channel_state = TIM_CHANNEL_N_STATE_GET(htim, Channel);
+
+ /* Check the parameters */
+ assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel));
+
+ /* Check the TIM channel state */
+ if ((channel_state != HAL_TIM_CHANNEL_STATE_READY)
+ || (complementary_channel_state != HAL_TIM_CHANNEL_STATE_READY))
+ {
+ return HAL_ERROR;
+ }
+
+ /* Set the TIM channel state */
+ TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY);
+ TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY);
+
+ /* Enable the Input Capture channel */
+ TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_ENABLE);
+
+ /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */
+ if (IS_TIM_SLAVE_INSTANCE(htim->Instance))
+ {
+ tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS;
+ if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr))
+ {
+ __HAL_TIM_ENABLE(htim);
+ }
+ }
+ else
+ {
+ __HAL_TIM_ENABLE(htim);
+ }
+
+ /* Return function status */
+ return HAL_OK;
+}
+
+/**
+ * @brief Stops the TIM Input Capture measurement.
+ * @param htim TIM Input Capture handle
+ * @param Channel TIM Channels to be disabled
+ * This parameter can be one of the following values:
+ * @arg TIM_CHANNEL_1: TIM Channel 1 selected
+ * @arg TIM_CHANNEL_2: TIM Channel 2 selected
+ * @arg TIM_CHANNEL_3: TIM Channel 3 selected
+ * @arg TIM_CHANNEL_4: TIM Channel 4 selected
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIM_IC_Stop(TIM_HandleTypeDef *htim, uint32_t Channel)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel));
+
+ /* Disable the Input Capture channel */
+ TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_DISABLE);
+
+ /* Disable the Peripheral */
+ __HAL_TIM_DISABLE(htim);
+
+ /* Set the TIM channel state */
+ TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY);
+ TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY);
+
+ /* Return function status */
+ return HAL_OK;
+}
+
+/**
+ * @brief Starts the TIM Input Capture measurement in interrupt mode.
+ * @param htim TIM Input Capture handle
+ * @param Channel TIM Channels to be enabled
+ * This parameter can be one of the following values:
+ * @arg TIM_CHANNEL_1: TIM Channel 1 selected
+ * @arg TIM_CHANNEL_2: TIM Channel 2 selected
+ * @arg TIM_CHANNEL_3: TIM Channel 3 selected
+ * @arg TIM_CHANNEL_4: TIM Channel 4 selected
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIM_IC_Start_IT(TIM_HandleTypeDef *htim, uint32_t Channel)
+{
+ HAL_StatusTypeDef status = HAL_OK;
+ uint32_t tmpsmcr;
+
+ HAL_TIM_ChannelStateTypeDef channel_state = TIM_CHANNEL_STATE_GET(htim, Channel);
+ HAL_TIM_ChannelStateTypeDef complementary_channel_state = TIM_CHANNEL_N_STATE_GET(htim, Channel);
+
+ /* Check the parameters */
+ assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel));
+
+ /* Check the TIM channel state */
+ if ((channel_state != HAL_TIM_CHANNEL_STATE_READY)
+ || (complementary_channel_state != HAL_TIM_CHANNEL_STATE_READY))
+ {
+ return HAL_ERROR;
+ }
+
+ /* Set the TIM channel state */
+ TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY);
+ TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY);
+
+ switch (Channel)
+ {
+ case TIM_CHANNEL_1:
+ {
+ /* Enable the TIM Capture/Compare 1 interrupt */
+ __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC1);
+ break;
+ }
+
+ case TIM_CHANNEL_2:
+ {
+ /* Enable the TIM Capture/Compare 2 interrupt */
+ __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC2);
+ break;
+ }
+
+ case TIM_CHANNEL_3:
+ {
+ /* Enable the TIM Capture/Compare 3 interrupt */
+ __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC3);
+ break;
+ }
+
+ case TIM_CHANNEL_4:
+ {
+ /* Enable the TIM Capture/Compare 4 interrupt */
+ __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC4);
+ break;
+ }
+
+ default:
+ status = HAL_ERROR;
+ break;
+ }
+
+ if (status == HAL_OK)
+ {
+ /* Enable the Input Capture channel */
+ TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_ENABLE);
+
+ /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */
+ if (IS_TIM_SLAVE_INSTANCE(htim->Instance))
+ {
+ tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS;
+ if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr))
+ {
+ __HAL_TIM_ENABLE(htim);
+ }
+ }
+ else
+ {
+ __HAL_TIM_ENABLE(htim);
+ }
+ }
+
+ /* Return function status */
+ return status;
+}
+
+/**
+ * @brief Stops the TIM Input Capture measurement in interrupt mode.
+ * @param htim TIM Input Capture handle
+ * @param Channel TIM Channels to be disabled
+ * This parameter can be one of the following values:
+ * @arg TIM_CHANNEL_1: TIM Channel 1 selected
+ * @arg TIM_CHANNEL_2: TIM Channel 2 selected
+ * @arg TIM_CHANNEL_3: TIM Channel 3 selected
+ * @arg TIM_CHANNEL_4: TIM Channel 4 selected
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIM_IC_Stop_IT(TIM_HandleTypeDef *htim, uint32_t Channel)
+{
+ HAL_StatusTypeDef status = HAL_OK;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel));
+
+ switch (Channel)
+ {
+ case TIM_CHANNEL_1:
+ {
+ /* Disable the TIM Capture/Compare 1 interrupt */
+ __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC1);
+ break;
+ }
+
+ case TIM_CHANNEL_2:
+ {
+ /* Disable the TIM Capture/Compare 2 interrupt */
+ __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC2);
+ break;
+ }
+
+ case TIM_CHANNEL_3:
+ {
+ /* Disable the TIM Capture/Compare 3 interrupt */
+ __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC3);
+ break;
+ }
+
+ case TIM_CHANNEL_4:
+ {
+ /* Disable the TIM Capture/Compare 4 interrupt */
+ __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC4);
+ break;
+ }
+
+ default:
+ status = HAL_ERROR;
+ break;
+ }
+
+ if (status == HAL_OK)
+ {
+ /* Disable the Input Capture channel */
+ TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_DISABLE);
+
+ /* Disable the Peripheral */
+ __HAL_TIM_DISABLE(htim);
+
+ /* Set the TIM channel state */
+ TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY);
+ TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY);
+ }
+
+ /* Return function status */
+ return status;
+}
+
+/**
+ * @brief Starts the TIM Input Capture measurement in DMA mode.
+ * @param htim TIM Input Capture handle
+ * @param Channel TIM Channels to be enabled
+ * This parameter can be one of the following values:
+ * @arg TIM_CHANNEL_1: TIM Channel 1 selected
+ * @arg TIM_CHANNEL_2: TIM Channel 2 selected
+ * @arg TIM_CHANNEL_3: TIM Channel 3 selected
+ * @arg TIM_CHANNEL_4: TIM Channel 4 selected
+ * @param pData The destination Buffer address.
+ * @param Length The length of data to be transferred from TIM peripheral to memory.
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIM_IC_Start_DMA(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pData, uint16_t Length)
+{
+ HAL_StatusTypeDef status = HAL_OK;
+ uint32_t tmpsmcr;
+
+ HAL_TIM_ChannelStateTypeDef channel_state = TIM_CHANNEL_STATE_GET(htim, Channel);
+ HAL_TIM_ChannelStateTypeDef complementary_channel_state = TIM_CHANNEL_N_STATE_GET(htim, Channel);
+
+ /* Check the parameters */
+ assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel));
+ assert_param(IS_TIM_DMA_CC_INSTANCE(htim->Instance));
+
+ /* Set the TIM channel state */
+ if ((channel_state == HAL_TIM_CHANNEL_STATE_BUSY)
+ || (complementary_channel_state == HAL_TIM_CHANNEL_STATE_BUSY))
+ {
+ return HAL_BUSY;
+ }
+ else if ((channel_state == HAL_TIM_CHANNEL_STATE_READY)
+ && (complementary_channel_state == HAL_TIM_CHANNEL_STATE_READY))
+ {
+ if ((pData == NULL) && (Length > 0U))
+ {
+ return HAL_ERROR;
+ }
+ else
+ {
+ TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY);
+ TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY);
+ }
+ }
+ else
+ {
+ return HAL_ERROR;
+ }
+
+ /* Enable the Input Capture channel */
+ TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_ENABLE);
+
+ switch (Channel)
+ {
+ case TIM_CHANNEL_1:
+ {
+ /* Set the DMA capture callbacks */
+ htim->hdma[TIM_DMA_ID_CC1]->XferCpltCallback = TIM_DMACaptureCplt;
+ htim->hdma[TIM_DMA_ID_CC1]->XferHalfCpltCallback = TIM_DMACaptureHalfCplt;
+
+ /* Set the DMA error callback */
+ htim->hdma[TIM_DMA_ID_CC1]->XferErrorCallback = TIM_DMAError ;
+
+ /* Enable the DMA channel */
+ if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC1], (uint32_t)&htim->Instance->CCR1, (uint32_t)pData,
+ Length) != HAL_OK)
+ {
+ /* Return error status */
+ return HAL_ERROR;
+ }
+ /* Enable the TIM Capture/Compare 1 DMA request */
+ __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC1);
+ break;
+ }
+
+ case TIM_CHANNEL_2:
+ {
+ /* Set the DMA capture callbacks */
+ htim->hdma[TIM_DMA_ID_CC2]->XferCpltCallback = TIM_DMACaptureCplt;
+ htim->hdma[TIM_DMA_ID_CC2]->XferHalfCpltCallback = TIM_DMACaptureHalfCplt;
+
+ /* Set the DMA error callback */
+ htim->hdma[TIM_DMA_ID_CC2]->XferErrorCallback = TIM_DMAError ;
+
+ /* Enable the DMA channel */
+ if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC2], (uint32_t)&htim->Instance->CCR2, (uint32_t)pData,
+ Length) != HAL_OK)
+ {
+ /* Return error status */
+ return HAL_ERROR;
+ }
+ /* Enable the TIM Capture/Compare 2 DMA request */
+ __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC2);
+ break;
+ }
+
+ case TIM_CHANNEL_3:
+ {
+ /* Set the DMA capture callbacks */
+ htim->hdma[TIM_DMA_ID_CC3]->XferCpltCallback = TIM_DMACaptureCplt;
+ htim->hdma[TIM_DMA_ID_CC3]->XferHalfCpltCallback = TIM_DMACaptureHalfCplt;
+
+ /* Set the DMA error callback */
+ htim->hdma[TIM_DMA_ID_CC3]->XferErrorCallback = TIM_DMAError ;
+
+ /* Enable the DMA channel */
+ if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC3], (uint32_t)&htim->Instance->CCR3, (uint32_t)pData,
+ Length) != HAL_OK)
+ {
+ /* Return error status */
+ return HAL_ERROR;
+ }
+ /* Enable the TIM Capture/Compare 3 DMA request */
+ __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC3);
+ break;
+ }
+
+ case TIM_CHANNEL_4:
+ {
+ /* Set the DMA capture callbacks */
+ htim->hdma[TIM_DMA_ID_CC4]->XferCpltCallback = TIM_DMACaptureCplt;
+ htim->hdma[TIM_DMA_ID_CC4]->XferHalfCpltCallback = TIM_DMACaptureHalfCplt;
+
+ /* Set the DMA error callback */
+ htim->hdma[TIM_DMA_ID_CC4]->XferErrorCallback = TIM_DMAError ;
+
+ /* Enable the DMA channel */
+ if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC4], (uint32_t)&htim->Instance->CCR4, (uint32_t)pData,
+ Length) != HAL_OK)
+ {
+ /* Return error status */
+ return HAL_ERROR;
+ }
+ /* Enable the TIM Capture/Compare 4 DMA request */
+ __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC4);
+ break;
+ }
+
+ default:
+ status = HAL_ERROR;
+ break;
+ }
+
+ /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */
+ if (IS_TIM_SLAVE_INSTANCE(htim->Instance))
+ {
+ tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS;
+ if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr))
+ {
+ __HAL_TIM_ENABLE(htim);
+ }
+ }
+ else
+ {
+ __HAL_TIM_ENABLE(htim);
+ }
+
+ /* Return function status */
+ return status;
+}
+
+/**
+ * @brief Stops the TIM Input Capture measurement in DMA mode.
+ * @param htim TIM Input Capture handle
+ * @param Channel TIM Channels to be disabled
+ * This parameter can be one of the following values:
+ * @arg TIM_CHANNEL_1: TIM Channel 1 selected
+ * @arg TIM_CHANNEL_2: TIM Channel 2 selected
+ * @arg TIM_CHANNEL_3: TIM Channel 3 selected
+ * @arg TIM_CHANNEL_4: TIM Channel 4 selected
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIM_IC_Stop_DMA(TIM_HandleTypeDef *htim, uint32_t Channel)
+{
+ HAL_StatusTypeDef status = HAL_OK;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel));
+ assert_param(IS_TIM_DMA_CC_INSTANCE(htim->Instance));
+
+ /* Disable the Input Capture channel */
+ TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_DISABLE);
+
+ switch (Channel)
+ {
+ case TIM_CHANNEL_1:
+ {
+ /* Disable the TIM Capture/Compare 1 DMA request */
+ __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC1);
+ (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC1]);
+ break;
+ }
+
+ case TIM_CHANNEL_2:
+ {
+ /* Disable the TIM Capture/Compare 2 DMA request */
+ __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC2);
+ (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC2]);
+ break;
+ }
+
+ case TIM_CHANNEL_3:
+ {
+ /* Disable the TIM Capture/Compare 3 DMA request */
+ __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC3);
+ (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC3]);
+ break;
+ }
+
+ case TIM_CHANNEL_4:
+ {
+ /* Disable the TIM Capture/Compare 4 DMA request */
+ __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC4);
+ (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC4]);
+ break;
+ }
+
+ default:
+ status = HAL_ERROR;
+ break;
+ }
+
+ if (status == HAL_OK)
+ {
+ /* Disable the Peripheral */
+ __HAL_TIM_DISABLE(htim);
+
+ /* Set the TIM channel state */
+ TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY);
+ TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY);
+ }
+
+ /* Return function status */
+ return status;
+}
+/**
+ * @}
+ */
+
+/** @defgroup TIM_Exported_Functions_Group5 TIM One Pulse functions
+ * @brief TIM One Pulse functions
+ *
+@verbatim
+ ==============================================================================
+ ##### TIM One Pulse functions #####
+ ==============================================================================
+ [..]
+ This section provides functions allowing to:
+ (+) Initialize and configure the TIM One Pulse.
+ (+) De-initialize the TIM One Pulse.
+ (+) Start the TIM One Pulse.
+ (+) Stop the TIM One Pulse.
+ (+) Start the TIM One Pulse and enable interrupt.
+ (+) Stop the TIM One Pulse and disable interrupt.
+ (+) Start the TIM One Pulse and enable DMA transfer.
+ (+) Stop the TIM One Pulse and disable DMA transfer.
+
+@endverbatim
+ * @{
+ */
+/**
+ * @brief Initializes the TIM One Pulse Time Base according to the specified
+ * parameters in the TIM_HandleTypeDef and initializes the associated handle.
+ * @note Switching from Center Aligned counter mode to Edge counter mode (or reverse)
+ * requires a timer reset to avoid unexpected direction
+ * due to DIR bit readonly in center aligned mode.
+ * Ex: call @ref HAL_TIM_OnePulse_DeInit() before HAL_TIM_OnePulse_Init()
+ * @note When the timer instance is initialized in One Pulse mode, timer
+ * channels 1 and channel 2 are reserved and cannot be used for other
+ * purpose.
+ * @param htim TIM One Pulse handle
+ * @param OnePulseMode Select the One pulse mode.
+ * This parameter can be one of the following values:
+ * @arg TIM_OPMODE_SINGLE: Only one pulse will be generated.
+ * @arg TIM_OPMODE_REPETITIVE: Repetitive pulses will be generated.
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIM_OnePulse_Init(TIM_HandleTypeDef *htim, uint32_t OnePulseMode)
+{
+ /* Check the TIM handle allocation */
+ if (htim == NULL)
+ {
+ return HAL_ERROR;
+ }
+
+ /* Check the parameters */
+ assert_param(IS_TIM_INSTANCE(htim->Instance));
+ assert_param(IS_TIM_COUNTER_MODE(htim->Init.CounterMode));
+ assert_param(IS_TIM_CLOCKDIVISION_DIV(htim->Init.ClockDivision));
+ assert_param(IS_TIM_OPM_MODE(OnePulseMode));
+ assert_param(IS_TIM_AUTORELOAD_PRELOAD(htim->Init.AutoReloadPreload));
+
+ if (htim->State == HAL_TIM_STATE_RESET)
+ {
+ /* Allocate lock resource and initialize it */
+ htim->Lock = HAL_UNLOCKED;
+
+#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1)
+ /* Reset interrupt callbacks to legacy weak callbacks */
+ TIM_ResetCallback(htim);
+
+ if (htim->OnePulse_MspInitCallback == NULL)
+ {
+ htim->OnePulse_MspInitCallback = HAL_TIM_OnePulse_MspInit;
+ }
+ /* Init the low level hardware : GPIO, CLOCK, NVIC */
+ htim->OnePulse_MspInitCallback(htim);
+#else
+ /* Init the low level hardware : GPIO, CLOCK, NVIC and DMA */
+ HAL_TIM_OnePulse_MspInit(htim);
+#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */
+ }
+
+ /* Set the TIM state */
+ htim->State = HAL_TIM_STATE_BUSY;
+
+ /* Configure the Time base in the One Pulse Mode */
+ TIM_Base_SetConfig(htim->Instance, &htim->Init);
+
+ /* Reset the OPM Bit */
+ htim->Instance->CR1 &= ~TIM_CR1_OPM;
+
+ /* Configure the OPM Mode */
+ htim->Instance->CR1 |= OnePulseMode;
+
+ /* Initialize the DMA burst operation state */
+ htim->DMABurstState = HAL_DMA_BURST_STATE_READY;
+
+ /* Initialize the TIM channels state */
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY);
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY);
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY);
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY);
+
+ /* Initialize the TIM state*/
+ htim->State = HAL_TIM_STATE_READY;
+
+ return HAL_OK;
+}
+
+/**
+ * @brief DeInitializes the TIM One Pulse
+ * @param htim TIM One Pulse handle
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIM_OnePulse_DeInit(TIM_HandleTypeDef *htim)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_INSTANCE(htim->Instance));
+
+ htim->State = HAL_TIM_STATE_BUSY;
+
+ /* Disable the TIM Peripheral Clock */
+ __HAL_TIM_DISABLE(htim);
+
+#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1)
+ if (htim->OnePulse_MspDeInitCallback == NULL)
+ {
+ htim->OnePulse_MspDeInitCallback = HAL_TIM_OnePulse_MspDeInit;
+ }
+ /* DeInit the low level hardware */
+ htim->OnePulse_MspDeInitCallback(htim);
+#else
+ /* DeInit the low level hardware: GPIO, CLOCK, NVIC */
+ HAL_TIM_OnePulse_MspDeInit(htim);
+#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */
+
+ /* Change the DMA burst operation state */
+ htim->DMABurstState = HAL_DMA_BURST_STATE_RESET;
+
+ /* Set the TIM channel state */
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_RESET);
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_RESET);
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_RESET);
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_RESET);
+
+ /* Change TIM state */
+ htim->State = HAL_TIM_STATE_RESET;
+
+ /* Release Lock */
+ __HAL_UNLOCK(htim);
+
+ return HAL_OK;
+}
+
+/**
+ * @brief Initializes the TIM One Pulse MSP.
+ * @param htim TIM One Pulse handle
+ * @retval None
+ */
+__weak void HAL_TIM_OnePulse_MspInit(TIM_HandleTypeDef *htim)
+{
+ /* Prevent unused argument(s) compilation warning */
+ UNUSED(htim);
+
+ /* NOTE : This function should not be modified, when the callback is needed,
+ the HAL_TIM_OnePulse_MspInit could be implemented in the user file
+ */
+}
+
+/**
+ * @brief DeInitializes TIM One Pulse MSP.
+ * @param htim TIM One Pulse handle
+ * @retval None
+ */
+__weak void HAL_TIM_OnePulse_MspDeInit(TIM_HandleTypeDef *htim)
+{
+ /* Prevent unused argument(s) compilation warning */
+ UNUSED(htim);
+
+ /* NOTE : This function should not be modified, when the callback is needed,
+ the HAL_TIM_OnePulse_MspDeInit could be implemented in the user file
+ */
+}
+
+/**
+ * @brief Starts the TIM One Pulse signal generation.
+ * @note Though OutputChannel parameter is deprecated and ignored by the function
+ * it has been kept to avoid HAL_TIM API compatibility break.
+ * @note The pulse output channel is determined when calling
+ * @ref HAL_TIM_OnePulse_ConfigChannel().
+ * @param htim TIM One Pulse handle
+ * @param OutputChannel See note above
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIM_OnePulse_Start(TIM_HandleTypeDef *htim, uint32_t OutputChannel)
+{
+ HAL_TIM_ChannelStateTypeDef channel_1_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_1);
+ HAL_TIM_ChannelStateTypeDef channel_2_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_2);
+ HAL_TIM_ChannelStateTypeDef complementary_channel_1_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_1);
+ HAL_TIM_ChannelStateTypeDef complementary_channel_2_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_2);
+
+ /* Prevent unused argument(s) compilation warning */
+ UNUSED(OutputChannel);
+
+ /* Check the TIM channels state */
+ if ((channel_1_state != HAL_TIM_CHANNEL_STATE_READY)
+ || (channel_2_state != HAL_TIM_CHANNEL_STATE_READY)
+ || (complementary_channel_1_state != HAL_TIM_CHANNEL_STATE_READY)
+ || (complementary_channel_2_state != HAL_TIM_CHANNEL_STATE_READY))
+ {
+ return HAL_ERROR;
+ }
+
+ /* Set the TIM channels state */
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY);
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY);
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY);
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY);
+
+ /* Enable the Capture compare and the Input Capture channels
+ (in the OPM Mode the two possible channels that can be used are TIM_CHANNEL_1 and TIM_CHANNEL_2)
+ if TIM_CHANNEL_1 is used as output, the TIM_CHANNEL_2 will be used as input and
+ if TIM_CHANNEL_1 is used as input, the TIM_CHANNEL_2 will be used as output
+ whatever the combination, the TIM_CHANNEL_1 and TIM_CHANNEL_2 should be enabled together
+
+ No need to enable the counter, it's enabled automatically by hardware
+ (the counter starts in response to a stimulus and generate a pulse */
+
+ TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_ENABLE);
+ TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_ENABLE);
+
+ if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET)
+ {
+ /* Enable the main output */
+ __HAL_TIM_MOE_ENABLE(htim);
+ }
+
+ /* Return function status */
+ return HAL_OK;
+}
+
+/**
+ * @brief Stops the TIM One Pulse signal generation.
+ * @note Though OutputChannel parameter is deprecated and ignored by the function
+ * it has been kept to avoid HAL_TIM API compatibility break.
+ * @note The pulse output channel is determined when calling
+ * @ref HAL_TIM_OnePulse_ConfigChannel().
+ * @param htim TIM One Pulse handle
+ * @param OutputChannel See note above
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIM_OnePulse_Stop(TIM_HandleTypeDef *htim, uint32_t OutputChannel)
+{
+ /* Prevent unused argument(s) compilation warning */
+ UNUSED(OutputChannel);
+
+ /* Disable the Capture compare and the Input Capture channels
+ (in the OPM Mode the two possible channels that can be used are TIM_CHANNEL_1 and TIM_CHANNEL_2)
+ if TIM_CHANNEL_1 is used as output, the TIM_CHANNEL_2 will be used as input and
+ if TIM_CHANNEL_1 is used as input, the TIM_CHANNEL_2 will be used as output
+ whatever the combination, the TIM_CHANNEL_1 and TIM_CHANNEL_2 should be disabled together */
+
+ TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_DISABLE);
+ TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_DISABLE);
+
+ if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET)
+ {
+ /* Disable the Main Output */
+ __HAL_TIM_MOE_DISABLE(htim);
+ }
+
+ /* Disable the Peripheral */
+ __HAL_TIM_DISABLE(htim);
+
+ /* Set the TIM channels state */
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY);
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY);
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY);
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY);
+
+ /* Return function status */
+ return HAL_OK;
+}
+
+/**
+ * @brief Starts the TIM One Pulse signal generation in interrupt mode.
+ * @note Though OutputChannel parameter is deprecated and ignored by the function
+ * it has been kept to avoid HAL_TIM API compatibility break.
+ * @note The pulse output channel is determined when calling
+ * @ref HAL_TIM_OnePulse_ConfigChannel().
+ * @param htim TIM One Pulse handle
+ * @param OutputChannel See note above
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIM_OnePulse_Start_IT(TIM_HandleTypeDef *htim, uint32_t OutputChannel)
+{
+ HAL_TIM_ChannelStateTypeDef channel_1_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_1);
+ HAL_TIM_ChannelStateTypeDef channel_2_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_2);
+ HAL_TIM_ChannelStateTypeDef complementary_channel_1_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_1);
+ HAL_TIM_ChannelStateTypeDef complementary_channel_2_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_2);
+
+ /* Prevent unused argument(s) compilation warning */
+ UNUSED(OutputChannel);
+
+ /* Check the TIM channels state */
+ if ((channel_1_state != HAL_TIM_CHANNEL_STATE_READY)
+ || (channel_2_state != HAL_TIM_CHANNEL_STATE_READY)
+ || (complementary_channel_1_state != HAL_TIM_CHANNEL_STATE_READY)
+ || (complementary_channel_2_state != HAL_TIM_CHANNEL_STATE_READY))
+ {
+ return HAL_ERROR;
+ }
+
+ /* Set the TIM channels state */
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY);
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY);
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY);
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY);
+
+ /* Enable the Capture compare and the Input Capture channels
+ (in the OPM Mode the two possible channels that can be used are TIM_CHANNEL_1 and TIM_CHANNEL_2)
+ if TIM_CHANNEL_1 is used as output, the TIM_CHANNEL_2 will be used as input and
+ if TIM_CHANNEL_1 is used as input, the TIM_CHANNEL_2 will be used as output
+ whatever the combination, the TIM_CHANNEL_1 and TIM_CHANNEL_2 should be enabled together
+
+ No need to enable the counter, it's enabled automatically by hardware
+ (the counter starts in response to a stimulus and generate a pulse */
+
+ /* Enable the TIM Capture/Compare 1 interrupt */
+ __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC1);
+
+ /* Enable the TIM Capture/Compare 2 interrupt */
+ __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC2);
+
+ TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_ENABLE);
+ TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_ENABLE);
+
+ if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET)
+ {
+ /* Enable the main output */
+ __HAL_TIM_MOE_ENABLE(htim);
+ }
+
+ /* Return function status */
+ return HAL_OK;
+}
+
+/**
+ * @brief Stops the TIM One Pulse signal generation in interrupt mode.
+ * @note Though OutputChannel parameter is deprecated and ignored by the function
+ * it has been kept to avoid HAL_TIM API compatibility break.
+ * @note The pulse output channel is determined when calling
+ * @ref HAL_TIM_OnePulse_ConfigChannel().
+ * @param htim TIM One Pulse handle
+ * @param OutputChannel See note above
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIM_OnePulse_Stop_IT(TIM_HandleTypeDef *htim, uint32_t OutputChannel)
+{
+ /* Prevent unused argument(s) compilation warning */
+ UNUSED(OutputChannel);
+
+ /* Disable the TIM Capture/Compare 1 interrupt */
+ __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC1);
+
+ /* Disable the TIM Capture/Compare 2 interrupt */
+ __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC2);
+
+ /* Disable the Capture compare and the Input Capture channels
+ (in the OPM Mode the two possible channels that can be used are TIM_CHANNEL_1 and TIM_CHANNEL_2)
+ if TIM_CHANNEL_1 is used as output, the TIM_CHANNEL_2 will be used as input and
+ if TIM_CHANNEL_1 is used as input, the TIM_CHANNEL_2 will be used as output
+ whatever the combination, the TIM_CHANNEL_1 and TIM_CHANNEL_2 should be disabled together */
+ TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_DISABLE);
+ TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_DISABLE);
+
+ if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET)
+ {
+ /* Disable the Main Output */
+ __HAL_TIM_MOE_DISABLE(htim);
+ }
+
+ /* Disable the Peripheral */
+ __HAL_TIM_DISABLE(htim);
+
+ /* Set the TIM channels state */
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY);
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY);
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY);
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY);
+
+ /* Return function status */
+ return HAL_OK;
+}
+
+/**
+ * @}
+ */
+
+/** @defgroup TIM_Exported_Functions_Group6 TIM Encoder functions
+ * @brief TIM Encoder functions
+ *
+@verbatim
+ ==============================================================================
+ ##### TIM Encoder functions #####
+ ==============================================================================
+ [..]
+ This section provides functions allowing to:
+ (+) Initialize and configure the TIM Encoder.
+ (+) De-initialize the TIM Encoder.
+ (+) Start the TIM Encoder.
+ (+) Stop the TIM Encoder.
+ (+) Start the TIM Encoder and enable interrupt.
+ (+) Stop the TIM Encoder and disable interrupt.
+ (+) Start the TIM Encoder and enable DMA transfer.
+ (+) Stop the TIM Encoder and disable DMA transfer.
+
+@endverbatim
+ * @{
+ */
+/**
+ * @brief Initializes the TIM Encoder Interface and initialize the associated handle.
+ * @note Switching from Center Aligned counter mode to Edge counter mode (or reverse)
+ * requires a timer reset to avoid unexpected direction
+ * due to DIR bit readonly in center aligned mode.
+ * Ex: call @ref HAL_TIM_Encoder_DeInit() before HAL_TIM_Encoder_Init()
+ * @note Encoder mode and External clock mode 2 are not compatible and must not be selected together
+ * Ex: A call for @ref HAL_TIM_Encoder_Init will erase the settings of @ref HAL_TIM_ConfigClockSource
+ * using TIM_CLOCKSOURCE_ETRMODE2 and vice versa
+ * @note When the timer instance is initialized in Encoder mode, timer
+ * channels 1 and channel 2 are reserved and cannot be used for other
+ * purpose.
+ * @param htim TIM Encoder Interface handle
+ * @param sConfig TIM Encoder Interface configuration structure
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIM_Encoder_Init(TIM_HandleTypeDef *htim, TIM_Encoder_InitTypeDef *sConfig)
+{
+ uint32_t tmpsmcr;
+ uint32_t tmpccmr1;
+ uint32_t tmpccer;
+
+ /* Check the TIM handle allocation */
+ if (htim == NULL)
+ {
+ return HAL_ERROR;
+ }
+
+ /* Check the parameters */
+ assert_param(IS_TIM_ENCODER_INTERFACE_INSTANCE(htim->Instance));
+ assert_param(IS_TIM_COUNTER_MODE(htim->Init.CounterMode));
+ assert_param(IS_TIM_CLOCKDIVISION_DIV(htim->Init.ClockDivision));
+ assert_param(IS_TIM_AUTORELOAD_PRELOAD(htim->Init.AutoReloadPreload));
+ assert_param(IS_TIM_ENCODER_MODE(sConfig->EncoderMode));
+ assert_param(IS_TIM_IC_SELECTION(sConfig->IC1Selection));
+ assert_param(IS_TIM_IC_SELECTION(sConfig->IC2Selection));
+ assert_param(IS_TIM_ENCODERINPUT_POLARITY(sConfig->IC1Polarity));
+ assert_param(IS_TIM_ENCODERINPUT_POLARITY(sConfig->IC2Polarity));
+ assert_param(IS_TIM_IC_PRESCALER(sConfig->IC1Prescaler));
+ assert_param(IS_TIM_IC_PRESCALER(sConfig->IC2Prescaler));
+ assert_param(IS_TIM_IC_FILTER(sConfig->IC1Filter));
+ assert_param(IS_TIM_IC_FILTER(sConfig->IC2Filter));
+
+ if (htim->State == HAL_TIM_STATE_RESET)
+ {
+ /* Allocate lock resource and initialize it */
+ htim->Lock = HAL_UNLOCKED;
+
+#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1)
+ /* Reset interrupt callbacks to legacy weak callbacks */
+ TIM_ResetCallback(htim);
+
+ if (htim->Encoder_MspInitCallback == NULL)
+ {
+ htim->Encoder_MspInitCallback = HAL_TIM_Encoder_MspInit;
+ }
+ /* Init the low level hardware : GPIO, CLOCK, NVIC */
+ htim->Encoder_MspInitCallback(htim);
+#else
+ /* Init the low level hardware : GPIO, CLOCK, NVIC and DMA */
+ HAL_TIM_Encoder_MspInit(htim);
+#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */
+ }
+
+ /* Set the TIM state */
+ htim->State = HAL_TIM_STATE_BUSY;
+
+ /* Reset the SMS and ECE bits */
+ htim->Instance->SMCR &= ~(TIM_SMCR_SMS | TIM_SMCR_ECE);
+
+ /* Configure the Time base in the Encoder Mode */
+ TIM_Base_SetConfig(htim->Instance, &htim->Init);
+
+ /* Get the TIMx SMCR register value */
+ tmpsmcr = htim->Instance->SMCR;
+
+ /* Get the TIMx CCMR1 register value */
+ tmpccmr1 = htim->Instance->CCMR1;
+
+ /* Get the TIMx CCER register value */
+ tmpccer = htim->Instance->CCER;
+
+ /* Set the encoder Mode */
+ tmpsmcr |= sConfig->EncoderMode;
+
+ /* Select the Capture Compare 1 and the Capture Compare 2 as input */
+ tmpccmr1 &= ~(TIM_CCMR1_CC1S | TIM_CCMR1_CC2S);
+ tmpccmr1 |= (sConfig->IC1Selection | (sConfig->IC2Selection << 8U));
+
+ /* Set the Capture Compare 1 and the Capture Compare 2 prescalers and filters */
+ tmpccmr1 &= ~(TIM_CCMR1_IC1PSC | TIM_CCMR1_IC2PSC);
+ tmpccmr1 &= ~(TIM_CCMR1_IC1F | TIM_CCMR1_IC2F);
+ tmpccmr1 |= sConfig->IC1Prescaler | (sConfig->IC2Prescaler << 8U);
+ tmpccmr1 |= (sConfig->IC1Filter << 4U) | (sConfig->IC2Filter << 12U);
+
+ /* Set the TI1 and the TI2 Polarities */
+ tmpccer &= ~(TIM_CCER_CC1P | TIM_CCER_CC2P);
+ tmpccer &= ~(TIM_CCER_CC1NP | TIM_CCER_CC2NP);
+ tmpccer |= sConfig->IC1Polarity | (sConfig->IC2Polarity << 4U);
+
+ /* Write to TIMx SMCR */
+ htim->Instance->SMCR = tmpsmcr;
+
+ /* Write to TIMx CCMR1 */
+ htim->Instance->CCMR1 = tmpccmr1;
+
+ /* Write to TIMx CCER */
+ htim->Instance->CCER = tmpccer;
+
+ /* Initialize the DMA burst operation state */
+ htim->DMABurstState = HAL_DMA_BURST_STATE_READY;
+
+ /* Set the TIM channels state */
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY);
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY);
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY);
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY);
+
+ /* Initialize the TIM state*/
+ htim->State = HAL_TIM_STATE_READY;
+
+ return HAL_OK;
+}
+
+
+/**
+ * @brief DeInitializes the TIM Encoder interface
+ * @param htim TIM Encoder Interface handle
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIM_Encoder_DeInit(TIM_HandleTypeDef *htim)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_INSTANCE(htim->Instance));
+
+ htim->State = HAL_TIM_STATE_BUSY;
+
+ /* Disable the TIM Peripheral Clock */
+ __HAL_TIM_DISABLE(htim);
+
+#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1)
+ if (htim->Encoder_MspDeInitCallback == NULL)
+ {
+ htim->Encoder_MspDeInitCallback = HAL_TIM_Encoder_MspDeInit;
+ }
+ /* DeInit the low level hardware */
+ htim->Encoder_MspDeInitCallback(htim);
+#else
+ /* DeInit the low level hardware: GPIO, CLOCK, NVIC */
+ HAL_TIM_Encoder_MspDeInit(htim);
+#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */
+
+ /* Change the DMA burst operation state */
+ htim->DMABurstState = HAL_DMA_BURST_STATE_RESET;
+
+ /* Set the TIM channels state */
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_RESET);
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_RESET);
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_RESET);
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_RESET);
+
+ /* Change TIM state */
+ htim->State = HAL_TIM_STATE_RESET;
+
+ /* Release Lock */
+ __HAL_UNLOCK(htim);
+
+ return HAL_OK;
+}
+
+/**
+ * @brief Initializes the TIM Encoder Interface MSP.
+ * @param htim TIM Encoder Interface handle
+ * @retval None
+ */
+__weak void HAL_TIM_Encoder_MspInit(TIM_HandleTypeDef *htim)
+{
+ /* Prevent unused argument(s) compilation warning */
+ UNUSED(htim);
+
+ /* NOTE : This function should not be modified, when the callback is needed,
+ the HAL_TIM_Encoder_MspInit could be implemented in the user file
+ */
+}
+
+/**
+ * @brief DeInitializes TIM Encoder Interface MSP.
+ * @param htim TIM Encoder Interface handle
+ * @retval None
+ */
+__weak void HAL_TIM_Encoder_MspDeInit(TIM_HandleTypeDef *htim)
+{
+ /* Prevent unused argument(s) compilation warning */
+ UNUSED(htim);
+
+ /* NOTE : This function should not be modified, when the callback is needed,
+ the HAL_TIM_Encoder_MspDeInit could be implemented in the user file
+ */
+}
+
+/**
+ * @brief Starts the TIM Encoder Interface.
+ * @param htim TIM Encoder Interface handle
+ * @param Channel TIM Channels to be enabled
+ * This parameter can be one of the following values:
+ * @arg TIM_CHANNEL_1: TIM Channel 1 selected
+ * @arg TIM_CHANNEL_2: TIM Channel 2 selected
+ * @arg TIM_CHANNEL_ALL: TIM Channel 1 and TIM Channel 2 are selected
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIM_Encoder_Start(TIM_HandleTypeDef *htim, uint32_t Channel)
+{
+ HAL_TIM_ChannelStateTypeDef channel_1_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_1);
+ HAL_TIM_ChannelStateTypeDef channel_2_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_2);
+ HAL_TIM_ChannelStateTypeDef complementary_channel_1_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_1);
+ HAL_TIM_ChannelStateTypeDef complementary_channel_2_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_2);
+
+ /* Check the parameters */
+ assert_param(IS_TIM_ENCODER_INTERFACE_INSTANCE(htim->Instance));
+
+ /* Set the TIM channel(s) state */
+ if (Channel == TIM_CHANNEL_1)
+ {
+ if ((channel_1_state != HAL_TIM_CHANNEL_STATE_READY)
+ || (complementary_channel_1_state != HAL_TIM_CHANNEL_STATE_READY))
+ {
+ return HAL_ERROR;
+ }
+ else
+ {
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY);
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY);
+ }
+ }
+ else if (Channel == TIM_CHANNEL_2)
+ {
+ if ((channel_2_state != HAL_TIM_CHANNEL_STATE_READY)
+ || (complementary_channel_2_state != HAL_TIM_CHANNEL_STATE_READY))
+ {
+ return HAL_ERROR;
+ }
+ else
+ {
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY);
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY);
+ }
+ }
+ else
+ {
+ if ((channel_1_state != HAL_TIM_CHANNEL_STATE_READY)
+ || (channel_2_state != HAL_TIM_CHANNEL_STATE_READY)
+ || (complementary_channel_1_state != HAL_TIM_CHANNEL_STATE_READY)
+ || (complementary_channel_2_state != HAL_TIM_CHANNEL_STATE_READY))
+ {
+ return HAL_ERROR;
+ }
+ else
+ {
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY);
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY);
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY);
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY);
+ }
+ }
+
+ /* Enable the encoder interface channels */
+ switch (Channel)
+ {
+ case TIM_CHANNEL_1:
+ {
+ TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_ENABLE);
+ break;
+ }
+
+ case TIM_CHANNEL_2:
+ {
+ TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_ENABLE);
+ break;
+ }
+
+ default :
+ {
+ TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_ENABLE);
+ TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_ENABLE);
+ break;
+ }
+ }
+ /* Enable the Peripheral */
+ __HAL_TIM_ENABLE(htim);
+
+ /* Return function status */
+ return HAL_OK;
+}
+
+/**
+ * @brief Stops the TIM Encoder Interface.
+ * @param htim TIM Encoder Interface handle
+ * @param Channel TIM Channels to be disabled
+ * This parameter can be one of the following values:
+ * @arg TIM_CHANNEL_1: TIM Channel 1 selected
+ * @arg TIM_CHANNEL_2: TIM Channel 2 selected
+ * @arg TIM_CHANNEL_ALL: TIM Channel 1 and TIM Channel 2 are selected
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIM_Encoder_Stop(TIM_HandleTypeDef *htim, uint32_t Channel)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_ENCODER_INTERFACE_INSTANCE(htim->Instance));
+
+ /* Disable the Input Capture channels 1 and 2
+ (in the EncoderInterface the two possible channels that can be used are TIM_CHANNEL_1 and TIM_CHANNEL_2) */
+ switch (Channel)
+ {
+ case TIM_CHANNEL_1:
+ {
+ TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_DISABLE);
+ break;
+ }
+
+ case TIM_CHANNEL_2:
+ {
+ TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_DISABLE);
+ break;
+ }
+
+ default :
+ {
+ TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_DISABLE);
+ TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_DISABLE);
+ break;
+ }
+ }
+
+ /* Disable the Peripheral */
+ __HAL_TIM_DISABLE(htim);
+
+ /* Set the TIM channel(s) state */
+ if ((Channel == TIM_CHANNEL_1) || (Channel == TIM_CHANNEL_2))
+ {
+ TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY);
+ TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY);
+ }
+ else
+ {
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY);
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY);
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY);
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY);
+ }
+
+ /* Return function status */
+ return HAL_OK;
+}
+
+/**
+ * @brief Starts the TIM Encoder Interface in interrupt mode.
+ * @param htim TIM Encoder Interface handle
+ * @param Channel TIM Channels to be enabled
+ * This parameter can be one of the following values:
+ * @arg TIM_CHANNEL_1: TIM Channel 1 selected
+ * @arg TIM_CHANNEL_2: TIM Channel 2 selected
+ * @arg TIM_CHANNEL_ALL: TIM Channel 1 and TIM Channel 2 are selected
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIM_Encoder_Start_IT(TIM_HandleTypeDef *htim, uint32_t Channel)
+{
+ HAL_TIM_ChannelStateTypeDef channel_1_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_1);
+ HAL_TIM_ChannelStateTypeDef channel_2_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_2);
+ HAL_TIM_ChannelStateTypeDef complementary_channel_1_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_1);
+ HAL_TIM_ChannelStateTypeDef complementary_channel_2_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_2);
+
+ /* Check the parameters */
+ assert_param(IS_TIM_ENCODER_INTERFACE_INSTANCE(htim->Instance));
+
+ /* Set the TIM channel(s) state */
+ if (Channel == TIM_CHANNEL_1)
+ {
+ if ((channel_1_state != HAL_TIM_CHANNEL_STATE_READY)
+ || (complementary_channel_1_state != HAL_TIM_CHANNEL_STATE_READY))
+ {
+ return HAL_ERROR;
+ }
+ else
+ {
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY);
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY);
+ }
+ }
+ else if (Channel == TIM_CHANNEL_2)
+ {
+ if ((channel_2_state != HAL_TIM_CHANNEL_STATE_READY)
+ || (complementary_channel_2_state != HAL_TIM_CHANNEL_STATE_READY))
+ {
+ return HAL_ERROR;
+ }
+ else
+ {
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY);
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY);
+ }
+ }
+ else
+ {
+ if ((channel_1_state != HAL_TIM_CHANNEL_STATE_READY)
+ || (channel_2_state != HAL_TIM_CHANNEL_STATE_READY)
+ || (complementary_channel_1_state != HAL_TIM_CHANNEL_STATE_READY)
+ || (complementary_channel_2_state != HAL_TIM_CHANNEL_STATE_READY))
+ {
+ return HAL_ERROR;
+ }
+ else
+ {
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY);
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY);
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY);
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY);
+ }
+ }
+
+ /* Enable the encoder interface channels */
+ /* Enable the capture compare Interrupts 1 and/or 2 */
+ switch (Channel)
+ {
+ case TIM_CHANNEL_1:
+ {
+ TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_ENABLE);
+ __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC1);
+ break;
+ }
+
+ case TIM_CHANNEL_2:
+ {
+ TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_ENABLE);
+ __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC2);
+ break;
+ }
+
+ default :
+ {
+ TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_ENABLE);
+ TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_ENABLE);
+ __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC1);
+ __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC2);
+ break;
+ }
+ }
+
+ /* Enable the Peripheral */
+ __HAL_TIM_ENABLE(htim);
+
+ /* Return function status */
+ return HAL_OK;
+}
+
+/**
+ * @brief Stops the TIM Encoder Interface in interrupt mode.
+ * @param htim TIM Encoder Interface handle
+ * @param Channel TIM Channels to be disabled
+ * This parameter can be one of the following values:
+ * @arg TIM_CHANNEL_1: TIM Channel 1 selected
+ * @arg TIM_CHANNEL_2: TIM Channel 2 selected
+ * @arg TIM_CHANNEL_ALL: TIM Channel 1 and TIM Channel 2 are selected
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIM_Encoder_Stop_IT(TIM_HandleTypeDef *htim, uint32_t Channel)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_ENCODER_INTERFACE_INSTANCE(htim->Instance));
+
+ /* Disable the Input Capture channels 1 and 2
+ (in the EncoderInterface the two possible channels that can be used are TIM_CHANNEL_1 and TIM_CHANNEL_2) */
+ if (Channel == TIM_CHANNEL_1)
+ {
+ TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_DISABLE);
+
+ /* Disable the capture compare Interrupts 1 */
+ __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC1);
+ }
+ else if (Channel == TIM_CHANNEL_2)
+ {
+ TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_DISABLE);
+
+ /* Disable the capture compare Interrupts 2 */
+ __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC2);
+ }
+ else
+ {
+ TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_DISABLE);
+ TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_DISABLE);
+
+ /* Disable the capture compare Interrupts 1 and 2 */
+ __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC1);
+ __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC2);
+ }
+
+ /* Disable the Peripheral */
+ __HAL_TIM_DISABLE(htim);
+
+ /* Set the TIM channel(s) state */
+ if ((Channel == TIM_CHANNEL_1) || (Channel == TIM_CHANNEL_2))
+ {
+ TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY);
+ TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY);
+ }
+ else
+ {
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY);
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY);
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY);
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY);
+ }
+
+ /* Return function status */
+ return HAL_OK;
+}
+
+/**
+ * @brief Starts the TIM Encoder Interface in DMA mode.
+ * @param htim TIM Encoder Interface handle
+ * @param Channel TIM Channels to be enabled
+ * This parameter can be one of the following values:
+ * @arg TIM_CHANNEL_1: TIM Channel 1 selected
+ * @arg TIM_CHANNEL_2: TIM Channel 2 selected
+ * @arg TIM_CHANNEL_ALL: TIM Channel 1 and TIM Channel 2 are selected
+ * @param pData1 The destination Buffer address for IC1.
+ * @param pData2 The destination Buffer address for IC2.
+ * @param Length The length of data to be transferred from TIM peripheral to memory.
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIM_Encoder_Start_DMA(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pData1,
+ uint32_t *pData2, uint16_t Length)
+{
+ HAL_TIM_ChannelStateTypeDef channel_1_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_1);
+ HAL_TIM_ChannelStateTypeDef channel_2_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_2);
+ HAL_TIM_ChannelStateTypeDef complementary_channel_1_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_1);
+ HAL_TIM_ChannelStateTypeDef complementary_channel_2_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_2);
+
+ /* Check the parameters */
+ assert_param(IS_TIM_ENCODER_INTERFACE_INSTANCE(htim->Instance));
+
+ /* Set the TIM channel(s) state */
+ if (Channel == TIM_CHANNEL_1)
+ {
+ if ((channel_1_state == HAL_TIM_CHANNEL_STATE_BUSY)
+ || (complementary_channel_1_state == HAL_TIM_CHANNEL_STATE_BUSY))
+ {
+ return HAL_BUSY;
+ }
+ else if ((channel_1_state == HAL_TIM_CHANNEL_STATE_READY)
+ && (complementary_channel_1_state == HAL_TIM_CHANNEL_STATE_READY))
+ {
+ if ((pData1 == NULL) && (Length > 0U))
+ {
+ return HAL_ERROR;
+ }
+ else
+ {
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY);
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY);
+ }
+ }
+ else
+ {
+ return HAL_ERROR;
+ }
+ }
+ else if (Channel == TIM_CHANNEL_2)
+ {
+ if ((channel_2_state == HAL_TIM_CHANNEL_STATE_BUSY)
+ || (complementary_channel_2_state == HAL_TIM_CHANNEL_STATE_BUSY))
+ {
+ return HAL_BUSY;
+ }
+ else if ((channel_2_state == HAL_TIM_CHANNEL_STATE_READY)
+ && (complementary_channel_2_state == HAL_TIM_CHANNEL_STATE_READY))
+ {
+ if ((pData2 == NULL) && (Length > 0U))
+ {
+ return HAL_ERROR;
+ }
+ else
+ {
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY);
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY);
+ }
+ }
+ else
+ {
+ return HAL_ERROR;
+ }
+ }
+ else
+ {
+ if ((channel_1_state == HAL_TIM_CHANNEL_STATE_BUSY)
+ || (channel_2_state == HAL_TIM_CHANNEL_STATE_BUSY)
+ || (complementary_channel_1_state == HAL_TIM_CHANNEL_STATE_BUSY)
+ || (complementary_channel_2_state == HAL_TIM_CHANNEL_STATE_BUSY))
+ {
+ return HAL_BUSY;
+ }
+ else if ((channel_1_state == HAL_TIM_CHANNEL_STATE_READY)
+ && (channel_2_state == HAL_TIM_CHANNEL_STATE_READY)
+ && (complementary_channel_1_state == HAL_TIM_CHANNEL_STATE_READY)
+ && (complementary_channel_2_state == HAL_TIM_CHANNEL_STATE_READY))
+ {
+ if ((((pData1 == NULL) || (pData2 == NULL))) && (Length > 0U))
+ {
+ return HAL_ERROR;
+ }
+ else
+ {
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY);
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY);
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY);
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY);
+ }
+ }
+ else
+ {
+ return HAL_ERROR;
+ }
+ }
+
+ switch (Channel)
+ {
+ case TIM_CHANNEL_1:
+ {
+ /* Set the DMA capture callbacks */
+ htim->hdma[TIM_DMA_ID_CC1]->XferCpltCallback = TIM_DMACaptureCplt;
+ htim->hdma[TIM_DMA_ID_CC1]->XferHalfCpltCallback = TIM_DMACaptureHalfCplt;
+
+ /* Set the DMA error callback */
+ htim->hdma[TIM_DMA_ID_CC1]->XferErrorCallback = TIM_DMAError ;
+
+ /* Enable the DMA channel */
+ if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC1], (uint32_t)&htim->Instance->CCR1, (uint32_t)pData1,
+ Length) != HAL_OK)
+ {
+ /* Return error status */
+ return HAL_ERROR;
+ }
+ /* Enable the TIM Input Capture DMA request */
+ __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC1);
+
+ /* Enable the Capture compare channel */
+ TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_ENABLE);
+
+ /* Enable the Peripheral */
+ __HAL_TIM_ENABLE(htim);
+
+ break;
+ }
+
+ case TIM_CHANNEL_2:
+ {
+ /* Set the DMA capture callbacks */
+ htim->hdma[TIM_DMA_ID_CC2]->XferCpltCallback = TIM_DMACaptureCplt;
+ htim->hdma[TIM_DMA_ID_CC2]->XferHalfCpltCallback = TIM_DMACaptureHalfCplt;
+
+ /* Set the DMA error callback */
+ htim->hdma[TIM_DMA_ID_CC2]->XferErrorCallback = TIM_DMAError;
+ /* Enable the DMA channel */
+ if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC2], (uint32_t)&htim->Instance->CCR2, (uint32_t)pData2,
+ Length) != HAL_OK)
+ {
+ /* Return error status */
+ return HAL_ERROR;
+ }
+ /* Enable the TIM Input Capture DMA request */
+ __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC2);
+
+ /* Enable the Capture compare channel */
+ TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_ENABLE);
+
+ /* Enable the Peripheral */
+ __HAL_TIM_ENABLE(htim);
+
+ break;
+ }
+
+ default:
+ {
+ /* Set the DMA capture callbacks */
+ htim->hdma[TIM_DMA_ID_CC1]->XferCpltCallback = TIM_DMACaptureCplt;
+ htim->hdma[TIM_DMA_ID_CC1]->XferHalfCpltCallback = TIM_DMACaptureHalfCplt;
+
+ /* Set the DMA error callback */
+ htim->hdma[TIM_DMA_ID_CC1]->XferErrorCallback = TIM_DMAError ;
+
+ /* Enable the DMA channel */
+ if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC1], (uint32_t)&htim->Instance->CCR1, (uint32_t)pData1,
+ Length) != HAL_OK)
+ {
+ /* Return error status */
+ return HAL_ERROR;
+ }
+
+ /* Set the DMA capture callbacks */
+ htim->hdma[TIM_DMA_ID_CC2]->XferCpltCallback = TIM_DMACaptureCplt;
+ htim->hdma[TIM_DMA_ID_CC2]->XferHalfCpltCallback = TIM_DMACaptureHalfCplt;
+
+ /* Set the DMA error callback */
+ htim->hdma[TIM_DMA_ID_CC2]->XferErrorCallback = TIM_DMAError ;
+
+ /* Enable the DMA channel */
+ if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC2], (uint32_t)&htim->Instance->CCR2, (uint32_t)pData2,
+ Length) != HAL_OK)
+ {
+ /* Return error status */
+ return HAL_ERROR;
+ }
+
+ /* Enable the TIM Input Capture DMA request */
+ __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC1);
+ /* Enable the TIM Input Capture DMA request */
+ __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC2);
+
+ /* Enable the Capture compare channel */
+ TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_ENABLE);
+ TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_ENABLE);
+
+ /* Enable the Peripheral */
+ __HAL_TIM_ENABLE(htim);
+
+ break;
+ }
+ }
+
+ /* Return function status */
+ return HAL_OK;
+}
+
+/**
+ * @brief Stops the TIM Encoder Interface in DMA mode.
+ * @param htim TIM Encoder Interface handle
+ * @param Channel TIM Channels to be enabled
+ * This parameter can be one of the following values:
+ * @arg TIM_CHANNEL_1: TIM Channel 1 selected
+ * @arg TIM_CHANNEL_2: TIM Channel 2 selected
+ * @arg TIM_CHANNEL_ALL: TIM Channel 1 and TIM Channel 2 are selected
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIM_Encoder_Stop_DMA(TIM_HandleTypeDef *htim, uint32_t Channel)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_ENCODER_INTERFACE_INSTANCE(htim->Instance));
+
+ /* Disable the Input Capture channels 1 and 2
+ (in the EncoderInterface the two possible channels that can be used are TIM_CHANNEL_1 and TIM_CHANNEL_2) */
+ if (Channel == TIM_CHANNEL_1)
+ {
+ TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_DISABLE);
+
+ /* Disable the capture compare DMA Request 1 */
+ __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC1);
+ (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC1]);
+ }
+ else if (Channel == TIM_CHANNEL_2)
+ {
+ TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_DISABLE);
+
+ /* Disable the capture compare DMA Request 2 */
+ __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC2);
+ (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC2]);
+ }
+ else
+ {
+ TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_DISABLE);
+ TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_DISABLE);
+
+ /* Disable the capture compare DMA Request 1 and 2 */
+ __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC1);
+ __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC2);
+ (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC1]);
+ (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC2]);
+ }
+
+ /* Disable the Peripheral */
+ __HAL_TIM_DISABLE(htim);
+
+ /* Set the TIM channel(s) state */
+ if ((Channel == TIM_CHANNEL_1) || (Channel == TIM_CHANNEL_2))
+ {
+ TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY);
+ TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY);
+ }
+ else
+ {
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY);
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY);
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY);
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY);
+ }
+
+ /* Return function status */
+ return HAL_OK;
+}
+
+/**
+ * @}
+ */
+/** @defgroup TIM_Exported_Functions_Group7 TIM IRQ handler management
+ * @brief TIM IRQ handler management
+ *
+@verbatim
+ ==============================================================================
+ ##### IRQ handler management #####
+ ==============================================================================
+ [..]
+ This section provides Timer IRQ handler function.
+
+@endverbatim
+ * @{
+ */
+/**
+ * @brief This function handles TIM interrupts requests.
+ * @param htim TIM handle
+ * @retval None
+ */
+void HAL_TIM_IRQHandler(TIM_HandleTypeDef *htim)
+{
+ /* Capture compare 1 event */
+ if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_CC1) != RESET)
+ {
+ if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_CC1) != RESET)
+ {
+ {
+ __HAL_TIM_CLEAR_IT(htim, TIM_IT_CC1);
+ htim->Channel = HAL_TIM_ACTIVE_CHANNEL_1;
+
+ /* Input capture event */
+ if ((htim->Instance->CCMR1 & TIM_CCMR1_CC1S) != 0x00U)
+ {
+#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1)
+ htim->IC_CaptureCallback(htim);
+#else
+ HAL_TIM_IC_CaptureCallback(htim);
+#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */
+ }
+ /* Output compare event */
+ else
+ {
+#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1)
+ htim->OC_DelayElapsedCallback(htim);
+ htim->PWM_PulseFinishedCallback(htim);
+#else
+ HAL_TIM_OC_DelayElapsedCallback(htim);
+ HAL_TIM_PWM_PulseFinishedCallback(htim);
+#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */
+ }
+ htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED;
+ }
+ }
+ }
+ /* Capture compare 2 event */
+ if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_CC2) != RESET)
+ {
+ if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_CC2) != RESET)
+ {
+ __HAL_TIM_CLEAR_IT(htim, TIM_IT_CC2);
+ htim->Channel = HAL_TIM_ACTIVE_CHANNEL_2;
+ /* Input capture event */
+ if ((htim->Instance->CCMR1 & TIM_CCMR1_CC2S) != 0x00U)
+ {
+#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1)
+ htim->IC_CaptureCallback(htim);
+#else
+ HAL_TIM_IC_CaptureCallback(htim);
+#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */
+ }
+ /* Output compare event */
+ else
+ {
+#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1)
+ htim->OC_DelayElapsedCallback(htim);
+ htim->PWM_PulseFinishedCallback(htim);
+#else
+ HAL_TIM_OC_DelayElapsedCallback(htim);
+ HAL_TIM_PWM_PulseFinishedCallback(htim);
+#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */
+ }
+ htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED;
+ }
+ }
+ /* Capture compare 3 event */
+ if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_CC3) != RESET)
+ {
+ if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_CC3) != RESET)
+ {
+ __HAL_TIM_CLEAR_IT(htim, TIM_IT_CC3);
+ htim->Channel = HAL_TIM_ACTIVE_CHANNEL_3;
+ /* Input capture event */
+ if ((htim->Instance->CCMR2 & TIM_CCMR2_CC3S) != 0x00U)
+ {
+#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1)
+ htim->IC_CaptureCallback(htim);
+#else
+ HAL_TIM_IC_CaptureCallback(htim);
+#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */
+ }
+ /* Output compare event */
+ else
+ {
+#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1)
+ htim->OC_DelayElapsedCallback(htim);
+ htim->PWM_PulseFinishedCallback(htim);
+#else
+ HAL_TIM_OC_DelayElapsedCallback(htim);
+ HAL_TIM_PWM_PulseFinishedCallback(htim);
+#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */
+ }
+ htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED;
+ }
+ }
+ /* Capture compare 4 event */
+ if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_CC4) != RESET)
+ {
+ if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_CC4) != RESET)
+ {
+ __HAL_TIM_CLEAR_IT(htim, TIM_IT_CC4);
+ htim->Channel = HAL_TIM_ACTIVE_CHANNEL_4;
+ /* Input capture event */
+ if ((htim->Instance->CCMR2 & TIM_CCMR2_CC4S) != 0x00U)
+ {
+#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1)
+ htim->IC_CaptureCallback(htim);
+#else
+ HAL_TIM_IC_CaptureCallback(htim);
+#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */
+ }
+ /* Output compare event */
+ else
+ {
+#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1)
+ htim->OC_DelayElapsedCallback(htim);
+ htim->PWM_PulseFinishedCallback(htim);
+#else
+ HAL_TIM_OC_DelayElapsedCallback(htim);
+ HAL_TIM_PWM_PulseFinishedCallback(htim);
+#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */
+ }
+ htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED;
+ }
+ }
+ /* TIM Update event */
+ if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_UPDATE) != RESET)
+ {
+ if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_UPDATE) != RESET)
+ {
+ __HAL_TIM_CLEAR_IT(htim, TIM_IT_UPDATE);
+#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1)
+ htim->PeriodElapsedCallback(htim);
+#else
+ HAL_TIM_PeriodElapsedCallback(htim);
+#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */
+ }
+ }
+ /* TIM Break input event */
+ if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_BREAK) != RESET)
+ {
+ if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_BREAK) != RESET)
+ {
+ __HAL_TIM_CLEAR_IT(htim, TIM_IT_BREAK);
+#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1)
+ htim->BreakCallback(htim);
+#else
+ HAL_TIMEx_BreakCallback(htim);
+#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */
+ }
+ }
+ /* TIM Trigger detection event */
+ if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_TRIGGER) != RESET)
+ {
+ if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_TRIGGER) != RESET)
+ {
+ __HAL_TIM_CLEAR_IT(htim, TIM_IT_TRIGGER);
+#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1)
+ htim->TriggerCallback(htim);
+#else
+ HAL_TIM_TriggerCallback(htim);
+#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */
+ }
+ }
+ /* TIM commutation event */
+ if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_COM) != RESET)
+ {
+ if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_COM) != RESET)
+ {
+ __HAL_TIM_CLEAR_IT(htim, TIM_FLAG_COM);
+#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1)
+ htim->CommutationCallback(htim);
+#else
+ HAL_TIMEx_CommutCallback(htim);
+#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */
+ }
+ }
+}
+
+/**
+ * @}
+ */
+
+/** @defgroup TIM_Exported_Functions_Group8 TIM Peripheral Control functions
+ * @brief TIM Peripheral Control functions
+ *
+@verbatim
+ ==============================================================================
+ ##### Peripheral Control functions #####
+ ==============================================================================
+ [..]
+ This section provides functions allowing to:
+ (+) Configure The Input Output channels for OC, PWM, IC or One Pulse mode.
+ (+) Configure External Clock source.
+ (+) Configure Complementary channels, break features and dead time.
+ (+) Configure Master and the Slave synchronization.
+ (+) Configure the DMA Burst Mode.
+
+@endverbatim
+ * @{
+ */
+
+/**
+ * @brief Initializes the TIM Output Compare Channels according to the specified
+ * parameters in the TIM_OC_InitTypeDef.
+ * @param htim TIM Output Compare handle
+ * @param sConfig TIM Output Compare configuration structure
+ * @param Channel TIM Channels to configure
+ * This parameter can be one of the following values:
+ * @arg TIM_CHANNEL_1: TIM Channel 1 selected
+ * @arg TIM_CHANNEL_2: TIM Channel 2 selected
+ * @arg TIM_CHANNEL_3: TIM Channel 3 selected
+ * @arg TIM_CHANNEL_4: TIM Channel 4 selected
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIM_OC_ConfigChannel(TIM_HandleTypeDef *htim,
+ TIM_OC_InitTypeDef *sConfig,
+ uint32_t Channel)
+{
+ HAL_StatusTypeDef status = HAL_OK;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_CHANNELS(Channel));
+ assert_param(IS_TIM_OC_MODE(sConfig->OCMode));
+ assert_param(IS_TIM_OC_POLARITY(sConfig->OCPolarity));
+
+ /* Process Locked */
+ __HAL_LOCK(htim);
+
+ switch (Channel)
+ {
+ case TIM_CHANNEL_1:
+ {
+ /* Check the parameters */
+ assert_param(IS_TIM_CC1_INSTANCE(htim->Instance));
+
+ /* Configure the TIM Channel 1 in Output Compare */
+ TIM_OC1_SetConfig(htim->Instance, sConfig);
+ break;
+ }
+
+ case TIM_CHANNEL_2:
+ {
+ /* Check the parameters */
+ assert_param(IS_TIM_CC2_INSTANCE(htim->Instance));
+
+ /* Configure the TIM Channel 2 in Output Compare */
+ TIM_OC2_SetConfig(htim->Instance, sConfig);
+ break;
+ }
+
+ case TIM_CHANNEL_3:
+ {
+ /* Check the parameters */
+ assert_param(IS_TIM_CC3_INSTANCE(htim->Instance));
+
+ /* Configure the TIM Channel 3 in Output Compare */
+ TIM_OC3_SetConfig(htim->Instance, sConfig);
+ break;
+ }
+
+ case TIM_CHANNEL_4:
+ {
+ /* Check the parameters */
+ assert_param(IS_TIM_CC4_INSTANCE(htim->Instance));
+
+ /* Configure the TIM Channel 4 in Output Compare */
+ TIM_OC4_SetConfig(htim->Instance, sConfig);
+ break;
+ }
+
+ default:
+ status = HAL_ERROR;
+ break;
+ }
+
+ __HAL_UNLOCK(htim);
+
+ return status;
+}
+
+/**
+ * @brief Initializes the TIM Input Capture Channels according to the specified
+ * parameters in the TIM_IC_InitTypeDef.
+ * @param htim TIM IC handle
+ * @param sConfig TIM Input Capture configuration structure
+ * @param Channel TIM Channel to configure
+ * This parameter can be one of the following values:
+ * @arg TIM_CHANNEL_1: TIM Channel 1 selected
+ * @arg TIM_CHANNEL_2: TIM Channel 2 selected
+ * @arg TIM_CHANNEL_3: TIM Channel 3 selected
+ * @arg TIM_CHANNEL_4: TIM Channel 4 selected
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIM_IC_ConfigChannel(TIM_HandleTypeDef *htim, TIM_IC_InitTypeDef *sConfig, uint32_t Channel)
+{
+ HAL_StatusTypeDef status = HAL_OK;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_CC1_INSTANCE(htim->Instance));
+ assert_param(IS_TIM_IC_POLARITY(sConfig->ICPolarity));
+ assert_param(IS_TIM_IC_SELECTION(sConfig->ICSelection));
+ assert_param(IS_TIM_IC_PRESCALER(sConfig->ICPrescaler));
+ assert_param(IS_TIM_IC_FILTER(sConfig->ICFilter));
+
+ /* Process Locked */
+ __HAL_LOCK(htim);
+
+ if (Channel == TIM_CHANNEL_1)
+ {
+ /* TI1 Configuration */
+ TIM_TI1_SetConfig(htim->Instance,
+ sConfig->ICPolarity,
+ sConfig->ICSelection,
+ sConfig->ICFilter);
+
+ /* Reset the IC1PSC Bits */
+ htim->Instance->CCMR1 &= ~TIM_CCMR1_IC1PSC;
+
+ /* Set the IC1PSC value */
+ htim->Instance->CCMR1 |= sConfig->ICPrescaler;
+ }
+ else if (Channel == TIM_CHANNEL_2)
+ {
+ /* TI2 Configuration */
+ assert_param(IS_TIM_CC2_INSTANCE(htim->Instance));
+
+ TIM_TI2_SetConfig(htim->Instance,
+ sConfig->ICPolarity,
+ sConfig->ICSelection,
+ sConfig->ICFilter);
+
+ /* Reset the IC2PSC Bits */
+ htim->Instance->CCMR1 &= ~TIM_CCMR1_IC2PSC;
+
+ /* Set the IC2PSC value */
+ htim->Instance->CCMR1 |= (sConfig->ICPrescaler << 8U);
+ }
+ else if (Channel == TIM_CHANNEL_3)
+ {
+ /* TI3 Configuration */
+ assert_param(IS_TIM_CC3_INSTANCE(htim->Instance));
+
+ TIM_TI3_SetConfig(htim->Instance,
+ sConfig->ICPolarity,
+ sConfig->ICSelection,
+ sConfig->ICFilter);
+
+ /* Reset the IC3PSC Bits */
+ htim->Instance->CCMR2 &= ~TIM_CCMR2_IC3PSC;
+
+ /* Set the IC3PSC value */
+ htim->Instance->CCMR2 |= sConfig->ICPrescaler;
+ }
+ else if (Channel == TIM_CHANNEL_4)
+ {
+ /* TI4 Configuration */
+ assert_param(IS_TIM_CC4_INSTANCE(htim->Instance));
+
+ TIM_TI4_SetConfig(htim->Instance,
+ sConfig->ICPolarity,
+ sConfig->ICSelection,
+ sConfig->ICFilter);
+
+ /* Reset the IC4PSC Bits */
+ htim->Instance->CCMR2 &= ~TIM_CCMR2_IC4PSC;
+
+ /* Set the IC4PSC value */
+ htim->Instance->CCMR2 |= (sConfig->ICPrescaler << 8U);
+ }
+ else
+ {
+ status = HAL_ERROR;
+ }
+
+ __HAL_UNLOCK(htim);
+
+ return status;
+}
+
+/**
+ * @brief Initializes the TIM PWM channels according to the specified
+ * parameters in the TIM_OC_InitTypeDef.
+ * @param htim TIM PWM handle
+ * @param sConfig TIM PWM configuration structure
+ * @param Channel TIM Channels to be configured
+ * This parameter can be one of the following values:
+ * @arg TIM_CHANNEL_1: TIM Channel 1 selected
+ * @arg TIM_CHANNEL_2: TIM Channel 2 selected
+ * @arg TIM_CHANNEL_3: TIM Channel 3 selected
+ * @arg TIM_CHANNEL_4: TIM Channel 4 selected
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIM_PWM_ConfigChannel(TIM_HandleTypeDef *htim,
+ TIM_OC_InitTypeDef *sConfig,
+ uint32_t Channel)
+{
+ HAL_StatusTypeDef status = HAL_OK;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_CHANNELS(Channel));
+ assert_param(IS_TIM_PWM_MODE(sConfig->OCMode));
+ assert_param(IS_TIM_OC_POLARITY(sConfig->OCPolarity));
+ assert_param(IS_TIM_FAST_STATE(sConfig->OCFastMode));
+
+ /* Process Locked */
+ __HAL_LOCK(htim);
+
+ switch (Channel)
+ {
+ case TIM_CHANNEL_1:
+ {
+ /* Check the parameters */
+ assert_param(IS_TIM_CC1_INSTANCE(htim->Instance));
+
+ /* Configure the Channel 1 in PWM mode */
+ TIM_OC1_SetConfig(htim->Instance, sConfig);
+
+ /* Set the Preload enable bit for channel1 */
+ htim->Instance->CCMR1 |= TIM_CCMR1_OC1PE;
+
+ /* Configure the Output Fast mode */
+ htim->Instance->CCMR1 &= ~TIM_CCMR1_OC1FE;
+ htim->Instance->CCMR1 |= sConfig->OCFastMode;
+ break;
+ }
+
+ case TIM_CHANNEL_2:
+ {
+ /* Check the parameters */
+ assert_param(IS_TIM_CC2_INSTANCE(htim->Instance));
+
+ /* Configure the Channel 2 in PWM mode */
+ TIM_OC2_SetConfig(htim->Instance, sConfig);
+
+ /* Set the Preload enable bit for channel2 */
+ htim->Instance->CCMR1 |= TIM_CCMR1_OC2PE;
+
+ /* Configure the Output Fast mode */
+ htim->Instance->CCMR1 &= ~TIM_CCMR1_OC2FE;
+ htim->Instance->CCMR1 |= sConfig->OCFastMode << 8U;
+ break;
+ }
+
+ case TIM_CHANNEL_3:
+ {
+ /* Check the parameters */
+ assert_param(IS_TIM_CC3_INSTANCE(htim->Instance));
+
+ /* Configure the Channel 3 in PWM mode */
+ TIM_OC3_SetConfig(htim->Instance, sConfig);
+
+ /* Set the Preload enable bit for channel3 */
+ htim->Instance->CCMR2 |= TIM_CCMR2_OC3PE;
+
+ /* Configure the Output Fast mode */
+ htim->Instance->CCMR2 &= ~TIM_CCMR2_OC3FE;
+ htim->Instance->CCMR2 |= sConfig->OCFastMode;
+ break;
+ }
+
+ case TIM_CHANNEL_4:
+ {
+ /* Check the parameters */
+ assert_param(IS_TIM_CC4_INSTANCE(htim->Instance));
+
+ /* Configure the Channel 4 in PWM mode */
+ TIM_OC4_SetConfig(htim->Instance, sConfig);
+
+ /* Set the Preload enable bit for channel4 */
+ htim->Instance->CCMR2 |= TIM_CCMR2_OC4PE;
+
+ /* Configure the Output Fast mode */
+ htim->Instance->CCMR2 &= ~TIM_CCMR2_OC4FE;
+ htim->Instance->CCMR2 |= sConfig->OCFastMode << 8U;
+ break;
+ }
+
+ default:
+ status = HAL_ERROR;
+ break;
+ }
+
+ __HAL_UNLOCK(htim);
+
+ return status;
+}
+
+/**
+ * @brief Initializes the TIM One Pulse Channels according to the specified
+ * parameters in the TIM_OnePulse_InitTypeDef.
+ * @param htim TIM One Pulse handle
+ * @param sConfig TIM One Pulse configuration structure
+ * @param OutputChannel TIM output channel to configure
+ * This parameter can be one of the following values:
+ * @arg TIM_CHANNEL_1: TIM Channel 1 selected
+ * @arg TIM_CHANNEL_2: TIM Channel 2 selected
+ * @param InputChannel TIM input Channel to configure
+ * This parameter can be one of the following values:
+ * @arg TIM_CHANNEL_1: TIM Channel 1 selected
+ * @arg TIM_CHANNEL_2: TIM Channel 2 selected
+ * @note To output a waveform with a minimum delay user can enable the fast
+ * mode by calling the @ref __HAL_TIM_ENABLE_OCxFAST macro. Then CCx
+ * output is forced in response to the edge detection on TIx input,
+ * without taking in account the comparison.
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIM_OnePulse_ConfigChannel(TIM_HandleTypeDef *htim, TIM_OnePulse_InitTypeDef *sConfig,
+ uint32_t OutputChannel, uint32_t InputChannel)
+{
+ HAL_StatusTypeDef status = HAL_OK;
+ TIM_OC_InitTypeDef temp1;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_OPM_CHANNELS(OutputChannel));
+ assert_param(IS_TIM_OPM_CHANNELS(InputChannel));
+
+ if (OutputChannel != InputChannel)
+ {
+ /* Process Locked */
+ __HAL_LOCK(htim);
+
+ htim->State = HAL_TIM_STATE_BUSY;
+
+ /* Extract the Output compare configuration from sConfig structure */
+ temp1.OCMode = sConfig->OCMode;
+ temp1.Pulse = sConfig->Pulse;
+ temp1.OCPolarity = sConfig->OCPolarity;
+ temp1.OCNPolarity = sConfig->OCNPolarity;
+ temp1.OCIdleState = sConfig->OCIdleState;
+ temp1.OCNIdleState = sConfig->OCNIdleState;
+
+ switch (OutputChannel)
+ {
+ case TIM_CHANNEL_1:
+ {
+ assert_param(IS_TIM_CC1_INSTANCE(htim->Instance));
+
+ TIM_OC1_SetConfig(htim->Instance, &temp1);
+ break;
+ }
+
+ case TIM_CHANNEL_2:
+ {
+ assert_param(IS_TIM_CC2_INSTANCE(htim->Instance));
+
+ TIM_OC2_SetConfig(htim->Instance, &temp1);
+ break;
+ }
+
+ default:
+ status = HAL_ERROR;
+ break;
+ }
+
+ if (status == HAL_OK)
+ {
+ switch (InputChannel)
+ {
+ case TIM_CHANNEL_1:
+ {
+ assert_param(IS_TIM_CC1_INSTANCE(htim->Instance));
+
+ TIM_TI1_SetConfig(htim->Instance, sConfig->ICPolarity,
+ sConfig->ICSelection, sConfig->ICFilter);
+
+ /* Reset the IC1PSC Bits */
+ htim->Instance->CCMR1 &= ~TIM_CCMR1_IC1PSC;
+
+ /* Select the Trigger source */
+ htim->Instance->SMCR &= ~TIM_SMCR_TS;
+ htim->Instance->SMCR |= TIM_TS_TI1FP1;
+
+ /* Select the Slave Mode */
+ htim->Instance->SMCR &= ~TIM_SMCR_SMS;
+ htim->Instance->SMCR |= TIM_SLAVEMODE_TRIGGER;
+ break;
+ }
+
+ case TIM_CHANNEL_2:
+ {
+ assert_param(IS_TIM_CC2_INSTANCE(htim->Instance));
+
+ TIM_TI2_SetConfig(htim->Instance, sConfig->ICPolarity,
+ sConfig->ICSelection, sConfig->ICFilter);
+
+ /* Reset the IC2PSC Bits */
+ htim->Instance->CCMR1 &= ~TIM_CCMR1_IC2PSC;
+
+ /* Select the Trigger source */
+ htim->Instance->SMCR &= ~TIM_SMCR_TS;
+ htim->Instance->SMCR |= TIM_TS_TI2FP2;
+
+ /* Select the Slave Mode */
+ htim->Instance->SMCR &= ~TIM_SMCR_SMS;
+ htim->Instance->SMCR |= TIM_SLAVEMODE_TRIGGER;
+ break;
+ }
+
+ default:
+ status = HAL_ERROR;
+ break;
+ }
+ }
+
+ htim->State = HAL_TIM_STATE_READY;
+
+ __HAL_UNLOCK(htim);
+
+ return status;
+ }
+ else
+ {
+ return HAL_ERROR;
+ }
+}
+
+/**
+ * @brief Configure the DMA Burst to transfer Data from the memory to the TIM peripheral
+ * @param htim TIM handle
+ * @param BurstBaseAddress TIM Base address from where the DMA will start the Data write
+ * This parameter can be one of the following values:
+ * @arg TIM_DMABASE_CR1
+ * @arg TIM_DMABASE_CR2
+ * @arg TIM_DMABASE_SMCR
+ * @arg TIM_DMABASE_DIER
+ * @arg TIM_DMABASE_SR
+ * @arg TIM_DMABASE_EGR
+ * @arg TIM_DMABASE_CCMR1
+ * @arg TIM_DMABASE_CCMR2
+ * @arg TIM_DMABASE_CCER
+ * @arg TIM_DMABASE_CNT
+ * @arg TIM_DMABASE_PSC
+ * @arg TIM_DMABASE_ARR
+ * @arg TIM_DMABASE_RCR
+ * @arg TIM_DMABASE_CCR1
+ * @arg TIM_DMABASE_CCR2
+ * @arg TIM_DMABASE_CCR3
+ * @arg TIM_DMABASE_CCR4
+ * @arg TIM_DMABASE_BDTR
+ * @param BurstRequestSrc TIM DMA Request sources
+ * This parameter can be one of the following values:
+ * @arg TIM_DMA_UPDATE: TIM update Interrupt source
+ * @arg TIM_DMA_CC1: TIM Capture Compare 1 DMA source
+ * @arg TIM_DMA_CC2: TIM Capture Compare 2 DMA source
+ * @arg TIM_DMA_CC3: TIM Capture Compare 3 DMA source
+ * @arg TIM_DMA_CC4: TIM Capture Compare 4 DMA source
+ * @arg TIM_DMA_COM: TIM Commutation DMA source
+ * @arg TIM_DMA_TRIGGER: TIM Trigger DMA source
+ * @param BurstBuffer The Buffer address.
+ * @param BurstLength DMA Burst length. This parameter can be one value
+ * between: TIM_DMABURSTLENGTH_1TRANSFER and TIM_DMABURSTLENGTH_18TRANSFERS.
+ * @note This function should be used only when BurstLength is equal to DMA data transfer length.
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIM_DMABurst_WriteStart(TIM_HandleTypeDef *htim, uint32_t BurstBaseAddress,
+ uint32_t BurstRequestSrc, uint32_t *BurstBuffer, uint32_t BurstLength)
+{
+ HAL_StatusTypeDef status = HAL_OK;
+
+ if (status == HAL_OK)
+ {
+ status = HAL_TIM_DMABurst_MultiWriteStart(htim, BurstBaseAddress, BurstRequestSrc, BurstBuffer, BurstLength,
+ ((BurstLength) >> 8U) + 1U);
+ }
+
+
+ return status;
+}
+
+/**
+ * @brief Configure the DMA Burst to transfer multiple Data from the memory to the TIM peripheral
+ * @param htim TIM handle
+ * @param BurstBaseAddress TIM Base address from where the DMA will start the Data write
+ * This parameter can be one of the following values:
+ * @arg TIM_DMABASE_CR1
+ * @arg TIM_DMABASE_CR2
+ * @arg TIM_DMABASE_SMCR
+ * @arg TIM_DMABASE_DIER
+ * @arg TIM_DMABASE_SR
+ * @arg TIM_DMABASE_EGR
+ * @arg TIM_DMABASE_CCMR1
+ * @arg TIM_DMABASE_CCMR2
+ * @arg TIM_DMABASE_CCER
+ * @arg TIM_DMABASE_CNT
+ * @arg TIM_DMABASE_PSC
+ * @arg TIM_DMABASE_ARR
+ * @arg TIM_DMABASE_RCR
+ * @arg TIM_DMABASE_CCR1
+ * @arg TIM_DMABASE_CCR2
+ * @arg TIM_DMABASE_CCR3
+ * @arg TIM_DMABASE_CCR4
+ * @arg TIM_DMABASE_BDTR
+ * @param BurstRequestSrc TIM DMA Request sources
+ * This parameter can be one of the following values:
+ * @arg TIM_DMA_UPDATE: TIM update Interrupt source
+ * @arg TIM_DMA_CC1: TIM Capture Compare 1 DMA source
+ * @arg TIM_DMA_CC2: TIM Capture Compare 2 DMA source
+ * @arg TIM_DMA_CC3: TIM Capture Compare 3 DMA source
+ * @arg TIM_DMA_CC4: TIM Capture Compare 4 DMA source
+ * @arg TIM_DMA_COM: TIM Commutation DMA source
+ * @arg TIM_DMA_TRIGGER: TIM Trigger DMA source
+ * @param BurstBuffer The Buffer address.
+ * @param BurstLength DMA Burst length. This parameter can be one value
+ * between: TIM_DMABURSTLENGTH_1TRANSFER and TIM_DMABURSTLENGTH_18TRANSFERS.
+ * @param DataLength Data length. This parameter can be one value
+ * between 1 and 0xFFFF.
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIM_DMABurst_MultiWriteStart(TIM_HandleTypeDef *htim, uint32_t BurstBaseAddress,
+ uint32_t BurstRequestSrc, uint32_t *BurstBuffer,
+ uint32_t BurstLength, uint32_t DataLength)
+{
+ HAL_StatusTypeDef status = HAL_OK;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_DMABURST_INSTANCE(htim->Instance));
+ assert_param(IS_TIM_DMA_BASE(BurstBaseAddress));
+ assert_param(IS_TIM_DMA_SOURCE(BurstRequestSrc));
+ assert_param(IS_TIM_DMA_LENGTH(BurstLength));
+ assert_param(IS_TIM_DMA_DATA_LENGTH(DataLength));
+
+ if (htim->DMABurstState == HAL_DMA_BURST_STATE_BUSY)
+ {
+ return HAL_BUSY;
+ }
+ else if (htim->DMABurstState == HAL_DMA_BURST_STATE_READY)
+ {
+ if ((BurstBuffer == NULL) && (BurstLength > 0U))
+ {
+ return HAL_ERROR;
+ }
+ else
+ {
+ htim->DMABurstState = HAL_DMA_BURST_STATE_BUSY;
+ }
+ }
+ else
+ {
+ /* nothing to do */
+ }
+
+ switch (BurstRequestSrc)
+ {
+ case TIM_DMA_UPDATE:
+ {
+ /* Set the DMA Period elapsed callbacks */
+ htim->hdma[TIM_DMA_ID_UPDATE]->XferCpltCallback = TIM_DMAPeriodElapsedCplt;
+ htim->hdma[TIM_DMA_ID_UPDATE]->XferHalfCpltCallback = TIM_DMAPeriodElapsedHalfCplt;
+
+ /* Set the DMA error callback */
+ htim->hdma[TIM_DMA_ID_UPDATE]->XferErrorCallback = TIM_DMAError ;
+
+ /* Enable the DMA channel */
+ if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_UPDATE], (uint32_t)BurstBuffer,
+ (uint32_t)&htim->Instance->DMAR, DataLength) != HAL_OK)
+ {
+ /* Return error status */
+ return HAL_ERROR;
+ }
+ break;
+ }
+ case TIM_DMA_CC1:
+ {
+ /* Set the DMA compare callbacks */
+ htim->hdma[TIM_DMA_ID_CC1]->XferCpltCallback = TIM_DMADelayPulseCplt;
+ htim->hdma[TIM_DMA_ID_CC1]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt;
+
+ /* Set the DMA error callback */
+ htim->hdma[TIM_DMA_ID_CC1]->XferErrorCallback = TIM_DMAError ;
+
+ /* Enable the DMA channel */
+ if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC1], (uint32_t)BurstBuffer,
+ (uint32_t)&htim->Instance->DMAR, DataLength) != HAL_OK)
+ {
+ /* Return error status */
+ return HAL_ERROR;
+ }
+ break;
+ }
+ case TIM_DMA_CC2:
+ {
+ /* Set the DMA compare callbacks */
+ htim->hdma[TIM_DMA_ID_CC2]->XferCpltCallback = TIM_DMADelayPulseCplt;
+ htim->hdma[TIM_DMA_ID_CC2]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt;
+
+ /* Set the DMA error callback */
+ htim->hdma[TIM_DMA_ID_CC2]->XferErrorCallback = TIM_DMAError ;
+
+ /* Enable the DMA channel */
+ if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC2], (uint32_t)BurstBuffer,
+ (uint32_t)&htim->Instance->DMAR, DataLength) != HAL_OK)
+ {
+ /* Return error status */
+ return HAL_ERROR;
+ }
+ break;
+ }
+ case TIM_DMA_CC3:
+ {
+ /* Set the DMA compare callbacks */
+ htim->hdma[TIM_DMA_ID_CC3]->XferCpltCallback = TIM_DMADelayPulseCplt;
+ htim->hdma[TIM_DMA_ID_CC3]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt;
+
+ /* Set the DMA error callback */
+ htim->hdma[TIM_DMA_ID_CC3]->XferErrorCallback = TIM_DMAError ;
+
+ /* Enable the DMA channel */
+ if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC3], (uint32_t)BurstBuffer,
+ (uint32_t)&htim->Instance->DMAR, DataLength) != HAL_OK)
+ {
+ /* Return error status */
+ return HAL_ERROR;
+ }
+ break;
+ }
+ case TIM_DMA_CC4:
+ {
+ /* Set the DMA compare callbacks */
+ htim->hdma[TIM_DMA_ID_CC4]->XferCpltCallback = TIM_DMADelayPulseCplt;
+ htim->hdma[TIM_DMA_ID_CC4]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt;
+
+ /* Set the DMA error callback */
+ htim->hdma[TIM_DMA_ID_CC4]->XferErrorCallback = TIM_DMAError ;
+
+ /* Enable the DMA channel */
+ if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC4], (uint32_t)BurstBuffer,
+ (uint32_t)&htim->Instance->DMAR, DataLength) != HAL_OK)
+ {
+ /* Return error status */
+ return HAL_ERROR;
+ }
+ break;
+ }
+ case TIM_DMA_COM:
+ {
+ /* Set the DMA commutation callbacks */
+ htim->hdma[TIM_DMA_ID_COMMUTATION]->XferCpltCallback = TIMEx_DMACommutationCplt;
+ htim->hdma[TIM_DMA_ID_COMMUTATION]->XferHalfCpltCallback = TIMEx_DMACommutationHalfCplt;
+
+ /* Set the DMA error callback */
+ htim->hdma[TIM_DMA_ID_COMMUTATION]->XferErrorCallback = TIM_DMAError ;
+
+ /* Enable the DMA channel */
+ if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_COMMUTATION], (uint32_t)BurstBuffer,
+ (uint32_t)&htim->Instance->DMAR, DataLength) != HAL_OK)
+ {
+ /* Return error status */
+ return HAL_ERROR;
+ }
+ break;
+ }
+ case TIM_DMA_TRIGGER:
+ {
+ /* Set the DMA trigger callbacks */
+ htim->hdma[TIM_DMA_ID_TRIGGER]->XferCpltCallback = TIM_DMATriggerCplt;
+ htim->hdma[TIM_DMA_ID_TRIGGER]->XferHalfCpltCallback = TIM_DMATriggerHalfCplt;
+
+ /* Set the DMA error callback */
+ htim->hdma[TIM_DMA_ID_TRIGGER]->XferErrorCallback = TIM_DMAError ;
+
+ /* Enable the DMA channel */
+ if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_TRIGGER], (uint32_t)BurstBuffer,
+ (uint32_t)&htim->Instance->DMAR, DataLength) != HAL_OK)
+ {
+ /* Return error status */
+ return HAL_ERROR;
+ }
+ break;
+ }
+ default:
+ status = HAL_ERROR;
+ break;
+ }
+
+ if (status == HAL_OK)
+ {
+ /* Configure the DMA Burst Mode */
+ htim->Instance->DCR = (BurstBaseAddress | BurstLength);
+ /* Enable the TIM DMA Request */
+ __HAL_TIM_ENABLE_DMA(htim, BurstRequestSrc);
+ }
+
+ /* Return function status */
+ return status;
+}
+
+/**
+ * @brief Stops the TIM DMA Burst mode
+ * @param htim TIM handle
+ * @param BurstRequestSrc TIM DMA Request sources to disable
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIM_DMABurst_WriteStop(TIM_HandleTypeDef *htim, uint32_t BurstRequestSrc)
+{
+ HAL_StatusTypeDef status = HAL_OK;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_DMA_SOURCE(BurstRequestSrc));
+
+ /* Abort the DMA transfer (at least disable the DMA channel) */
+ switch (BurstRequestSrc)
+ {
+ case TIM_DMA_UPDATE:
+ {
+ (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_UPDATE]);
+ break;
+ }
+ case TIM_DMA_CC1:
+ {
+ (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC1]);
+ break;
+ }
+ case TIM_DMA_CC2:
+ {
+ (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC2]);
+ break;
+ }
+ case TIM_DMA_CC3:
+ {
+ (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC3]);
+ break;
+ }
+ case TIM_DMA_CC4:
+ {
+ (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC4]);
+ break;
+ }
+ case TIM_DMA_COM:
+ {
+ (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_COMMUTATION]);
+ break;
+ }
+ case TIM_DMA_TRIGGER:
+ {
+ (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_TRIGGER]);
+ break;
+ }
+ default:
+ status = HAL_ERROR;
+ break;
+ }
+
+ if (status == HAL_OK)
+ {
+ /* Disable the TIM Update DMA request */
+ __HAL_TIM_DISABLE_DMA(htim, BurstRequestSrc);
+
+ /* Change the DMA burst operation state */
+ htim->DMABurstState = HAL_DMA_BURST_STATE_READY;
+ }
+
+ /* Return function status */
+ return status;
+}
+
+/**
+ * @brief Configure the DMA Burst to transfer Data from the TIM peripheral to the memory
+ * @param htim TIM handle
+ * @param BurstBaseAddress TIM Base address from where the DMA will start the Data read
+ * This parameter can be one of the following values:
+ * @arg TIM_DMABASE_CR1
+ * @arg TIM_DMABASE_CR2
+ * @arg TIM_DMABASE_SMCR
+ * @arg TIM_DMABASE_DIER
+ * @arg TIM_DMABASE_SR
+ * @arg TIM_DMABASE_EGR
+ * @arg TIM_DMABASE_CCMR1
+ * @arg TIM_DMABASE_CCMR2
+ * @arg TIM_DMABASE_CCER
+ * @arg TIM_DMABASE_CNT
+ * @arg TIM_DMABASE_PSC
+ * @arg TIM_DMABASE_ARR
+ * @arg TIM_DMABASE_RCR
+ * @arg TIM_DMABASE_CCR1
+ * @arg TIM_DMABASE_CCR2
+ * @arg TIM_DMABASE_CCR3
+ * @arg TIM_DMABASE_CCR4
+ * @arg TIM_DMABASE_BDTR
+ * @param BurstRequestSrc TIM DMA Request sources
+ * This parameter can be one of the following values:
+ * @arg TIM_DMA_UPDATE: TIM update Interrupt source
+ * @arg TIM_DMA_CC1: TIM Capture Compare 1 DMA source
+ * @arg TIM_DMA_CC2: TIM Capture Compare 2 DMA source
+ * @arg TIM_DMA_CC3: TIM Capture Compare 3 DMA source
+ * @arg TIM_DMA_CC4: TIM Capture Compare 4 DMA source
+ * @arg TIM_DMA_COM: TIM Commutation DMA source
+ * @arg TIM_DMA_TRIGGER: TIM Trigger DMA source
+ * @param BurstBuffer The Buffer address.
+ * @param BurstLength DMA Burst length. This parameter can be one value
+ * between: TIM_DMABURSTLENGTH_1TRANSFER and TIM_DMABURSTLENGTH_18TRANSFERS.
+ * @note This function should be used only when BurstLength is equal to DMA data transfer length.
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIM_DMABurst_ReadStart(TIM_HandleTypeDef *htim, uint32_t BurstBaseAddress,
+ uint32_t BurstRequestSrc, uint32_t *BurstBuffer, uint32_t BurstLength)
+{
+ HAL_StatusTypeDef status = HAL_OK;
+
+ if (status == HAL_OK)
+ {
+ status = HAL_TIM_DMABurst_MultiReadStart(htim, BurstBaseAddress, BurstRequestSrc, BurstBuffer, BurstLength,
+ ((BurstLength) >> 8U) + 1U);
+ }
+
+ return status;
+}
+
+/**
+ * @brief Configure the DMA Burst to transfer Data from the TIM peripheral to the memory
+ * @param htim TIM handle
+ * @param BurstBaseAddress TIM Base address from where the DMA will start the Data read
+ * This parameter can be one of the following values:
+ * @arg TIM_DMABASE_CR1
+ * @arg TIM_DMABASE_CR2
+ * @arg TIM_DMABASE_SMCR
+ * @arg TIM_DMABASE_DIER
+ * @arg TIM_DMABASE_SR
+ * @arg TIM_DMABASE_EGR
+ * @arg TIM_DMABASE_CCMR1
+ * @arg TIM_DMABASE_CCMR2
+ * @arg TIM_DMABASE_CCER
+ * @arg TIM_DMABASE_CNT
+ * @arg TIM_DMABASE_PSC
+ * @arg TIM_DMABASE_ARR
+ * @arg TIM_DMABASE_RCR
+ * @arg TIM_DMABASE_CCR1
+ * @arg TIM_DMABASE_CCR2
+ * @arg TIM_DMABASE_CCR3
+ * @arg TIM_DMABASE_CCR4
+ * @arg TIM_DMABASE_BDTR
+ * @param BurstRequestSrc TIM DMA Request sources
+ * This parameter can be one of the following values:
+ * @arg TIM_DMA_UPDATE: TIM update Interrupt source
+ * @arg TIM_DMA_CC1: TIM Capture Compare 1 DMA source
+ * @arg TIM_DMA_CC2: TIM Capture Compare 2 DMA source
+ * @arg TIM_DMA_CC3: TIM Capture Compare 3 DMA source
+ * @arg TIM_DMA_CC4: TIM Capture Compare 4 DMA source
+ * @arg TIM_DMA_COM: TIM Commutation DMA source
+ * @arg TIM_DMA_TRIGGER: TIM Trigger DMA source
+ * @param BurstBuffer The Buffer address.
+ * @param BurstLength DMA Burst length. This parameter can be one value
+ * between: TIM_DMABURSTLENGTH_1TRANSFER and TIM_DMABURSTLENGTH_18TRANSFERS.
+ * @param DataLength Data length. This parameter can be one value
+ * between 1 and 0xFFFF.
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIM_DMABurst_MultiReadStart(TIM_HandleTypeDef *htim, uint32_t BurstBaseAddress,
+ uint32_t BurstRequestSrc, uint32_t *BurstBuffer,
+ uint32_t BurstLength, uint32_t DataLength)
+{
+ HAL_StatusTypeDef status = HAL_OK;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_DMABURST_INSTANCE(htim->Instance));
+ assert_param(IS_TIM_DMA_BASE(BurstBaseAddress));
+ assert_param(IS_TIM_DMA_SOURCE(BurstRequestSrc));
+ assert_param(IS_TIM_DMA_LENGTH(BurstLength));
+ assert_param(IS_TIM_DMA_DATA_LENGTH(DataLength));
+
+ if (htim->DMABurstState == HAL_DMA_BURST_STATE_BUSY)
+ {
+ return HAL_BUSY;
+ }
+ else if (htim->DMABurstState == HAL_DMA_BURST_STATE_READY)
+ {
+ if ((BurstBuffer == NULL) && (BurstLength > 0U))
+ {
+ return HAL_ERROR;
+ }
+ else
+ {
+ htim->DMABurstState = HAL_DMA_BURST_STATE_BUSY;
+ }
+ }
+ else
+ {
+ /* nothing to do */
+ }
+ switch (BurstRequestSrc)
+ {
+ case TIM_DMA_UPDATE:
+ {
+ /* Set the DMA Period elapsed callbacks */
+ htim->hdma[TIM_DMA_ID_UPDATE]->XferCpltCallback = TIM_DMAPeriodElapsedCplt;
+ htim->hdma[TIM_DMA_ID_UPDATE]->XferHalfCpltCallback = TIM_DMAPeriodElapsedHalfCplt;
+
+ /* Set the DMA error callback */
+ htim->hdma[TIM_DMA_ID_UPDATE]->XferErrorCallback = TIM_DMAError ;
+
+ /* Enable the DMA channel */
+ if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_UPDATE], (uint32_t)&htim->Instance->DMAR, (uint32_t)BurstBuffer,
+ DataLength) != HAL_OK)
+ {
+ /* Return error status */
+ return HAL_ERROR;
+ }
+ break;
+ }
+ case TIM_DMA_CC1:
+ {
+ /* Set the DMA capture callbacks */
+ htim->hdma[TIM_DMA_ID_CC1]->XferCpltCallback = TIM_DMACaptureCplt;
+ htim->hdma[TIM_DMA_ID_CC1]->XferHalfCpltCallback = TIM_DMACaptureHalfCplt;
+
+ /* Set the DMA error callback */
+ htim->hdma[TIM_DMA_ID_CC1]->XferErrorCallback = TIM_DMAError ;
+
+ /* Enable the DMA channel */
+ if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC1], (uint32_t)&htim->Instance->DMAR, (uint32_t)BurstBuffer,
+ DataLength) != HAL_OK)
+ {
+ /* Return error status */
+ return HAL_ERROR;
+ }
+ break;
+ }
+ case TIM_DMA_CC2:
+ {
+ /* Set the DMA capture callbacks */
+ htim->hdma[TIM_DMA_ID_CC2]->XferCpltCallback = TIM_DMACaptureCplt;
+ htim->hdma[TIM_DMA_ID_CC2]->XferHalfCpltCallback = TIM_DMACaptureHalfCplt;
+
+ /* Set the DMA error callback */
+ htim->hdma[TIM_DMA_ID_CC2]->XferErrorCallback = TIM_DMAError ;
+
+ /* Enable the DMA channel */
+ if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC2], (uint32_t)&htim->Instance->DMAR, (uint32_t)BurstBuffer,
+ DataLength) != HAL_OK)
+ {
+ /* Return error status */
+ return HAL_ERROR;
+ }
+ break;
+ }
+ case TIM_DMA_CC3:
+ {
+ /* Set the DMA capture callbacks */
+ htim->hdma[TIM_DMA_ID_CC3]->XferCpltCallback = TIM_DMACaptureCplt;
+ htim->hdma[TIM_DMA_ID_CC3]->XferHalfCpltCallback = TIM_DMACaptureHalfCplt;
+
+ /* Set the DMA error callback */
+ htim->hdma[TIM_DMA_ID_CC3]->XferErrorCallback = TIM_DMAError ;
+
+ /* Enable the DMA channel */
+ if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC3], (uint32_t)&htim->Instance->DMAR, (uint32_t)BurstBuffer,
+ DataLength) != HAL_OK)
+ {
+ /* Return error status */
+ return HAL_ERROR;
+ }
+ break;
+ }
+ case TIM_DMA_CC4:
+ {
+ /* Set the DMA capture callbacks */
+ htim->hdma[TIM_DMA_ID_CC4]->XferCpltCallback = TIM_DMACaptureCplt;
+ htim->hdma[TIM_DMA_ID_CC4]->XferHalfCpltCallback = TIM_DMACaptureHalfCplt;
+
+ /* Set the DMA error callback */
+ htim->hdma[TIM_DMA_ID_CC4]->XferErrorCallback = TIM_DMAError ;
+
+ /* Enable the DMA channel */
+ if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC4], (uint32_t)&htim->Instance->DMAR, (uint32_t)BurstBuffer,
+ DataLength) != HAL_OK)
+ {
+ /* Return error status */
+ return HAL_ERROR;
+ }
+ break;
+ }
+ case TIM_DMA_COM:
+ {
+ /* Set the DMA commutation callbacks */
+ htim->hdma[TIM_DMA_ID_COMMUTATION]->XferCpltCallback = TIMEx_DMACommutationCplt;
+ htim->hdma[TIM_DMA_ID_COMMUTATION]->XferHalfCpltCallback = TIMEx_DMACommutationHalfCplt;
+
+ /* Set the DMA error callback */
+ htim->hdma[TIM_DMA_ID_COMMUTATION]->XferErrorCallback = TIM_DMAError ;
+
+ /* Enable the DMA channel */
+ if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_COMMUTATION], (uint32_t)&htim->Instance->DMAR, (uint32_t)BurstBuffer,
+ DataLength) != HAL_OK)
+ {
+ /* Return error status */
+ return HAL_ERROR;
+ }
+ break;
+ }
+ case TIM_DMA_TRIGGER:
+ {
+ /* Set the DMA trigger callbacks */
+ htim->hdma[TIM_DMA_ID_TRIGGER]->XferCpltCallback = TIM_DMATriggerCplt;
+ htim->hdma[TIM_DMA_ID_TRIGGER]->XferHalfCpltCallback = TIM_DMATriggerHalfCplt;
+
+ /* Set the DMA error callback */
+ htim->hdma[TIM_DMA_ID_TRIGGER]->XferErrorCallback = TIM_DMAError ;
+
+ /* Enable the DMA channel */
+ if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_TRIGGER], (uint32_t)&htim->Instance->DMAR, (uint32_t)BurstBuffer,
+ DataLength) != HAL_OK)
+ {
+ /* Return error status */
+ return HAL_ERROR;
+ }
+ break;
+ }
+ default:
+ status = HAL_ERROR;
+ break;
+ }
+
+ if (status == HAL_OK)
+ {
+ /* Configure the DMA Burst Mode */
+ htim->Instance->DCR = (BurstBaseAddress | BurstLength);
+
+ /* Enable the TIM DMA Request */
+ __HAL_TIM_ENABLE_DMA(htim, BurstRequestSrc);
+ }
+
+ /* Return function status */
+ return status;
+}
+
+/**
+ * @brief Stop the DMA burst reading
+ * @param htim TIM handle
+ * @param BurstRequestSrc TIM DMA Request sources to disable.
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIM_DMABurst_ReadStop(TIM_HandleTypeDef *htim, uint32_t BurstRequestSrc)
+{
+ HAL_StatusTypeDef status = HAL_OK;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_DMA_SOURCE(BurstRequestSrc));
+
+ /* Abort the DMA transfer (at least disable the DMA channel) */
+ switch (BurstRequestSrc)
+ {
+ case TIM_DMA_UPDATE:
+ {
+ (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_UPDATE]);
+ break;
+ }
+ case TIM_DMA_CC1:
+ {
+ (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC1]);
+ break;
+ }
+ case TIM_DMA_CC2:
+ {
+ (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC2]);
+ break;
+ }
+ case TIM_DMA_CC3:
+ {
+ (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC3]);
+ break;
+ }
+ case TIM_DMA_CC4:
+ {
+ (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC4]);
+ break;
+ }
+ case TIM_DMA_COM:
+ {
+ (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_COMMUTATION]);
+ break;
+ }
+ case TIM_DMA_TRIGGER:
+ {
+ (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_TRIGGER]);
+ break;
+ }
+ default:
+ status = HAL_ERROR;
+ break;
+ }
+
+ if (status == HAL_OK)
+ {
+ /* Disable the TIM Update DMA request */
+ __HAL_TIM_DISABLE_DMA(htim, BurstRequestSrc);
+
+ /* Change the DMA burst operation state */
+ htim->DMABurstState = HAL_DMA_BURST_STATE_READY;
+ }
+
+ /* Return function status */
+ return status;
+}
+
+/**
+ * @brief Generate a software event
+ * @param htim TIM handle
+ * @param EventSource specifies the event source.
+ * This parameter can be one of the following values:
+ * @arg TIM_EVENTSOURCE_UPDATE: Timer update Event source
+ * @arg TIM_EVENTSOURCE_CC1: Timer Capture Compare 1 Event source
+ * @arg TIM_EVENTSOURCE_CC2: Timer Capture Compare 2 Event source
+ * @arg TIM_EVENTSOURCE_CC3: Timer Capture Compare 3 Event source
+ * @arg TIM_EVENTSOURCE_CC4: Timer Capture Compare 4 Event source
+ * @arg TIM_EVENTSOURCE_COM: Timer COM event source
+ * @arg TIM_EVENTSOURCE_TRIGGER: Timer Trigger Event source
+ * @arg TIM_EVENTSOURCE_BREAK: Timer Break event source
+ * @note Basic timers can only generate an update event.
+ * @note TIM_EVENTSOURCE_COM is relevant only with advanced timer instances.
+ * @note TIM_EVENTSOURCE_BREAK are relevant only for timer instances
+ * supporting a break input.
+ * @retval HAL status
+ */
+
+HAL_StatusTypeDef HAL_TIM_GenerateEvent(TIM_HandleTypeDef *htim, uint32_t EventSource)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_INSTANCE(htim->Instance));
+ assert_param(IS_TIM_EVENT_SOURCE(EventSource));
+
+ /* Process Locked */
+ __HAL_LOCK(htim);
+
+ /* Change the TIM state */
+ htim->State = HAL_TIM_STATE_BUSY;
+
+ /* Set the event sources */
+ htim->Instance->EGR = EventSource;
+
+ /* Change the TIM state */
+ htim->State = HAL_TIM_STATE_READY;
+
+ __HAL_UNLOCK(htim);
+
+ /* Return function status */
+ return HAL_OK;
+}
+
+/**
+ * @brief Configures the OCRef clear feature
+ * @param htim TIM handle
+ * @param sClearInputConfig pointer to a TIM_ClearInputConfigTypeDef structure that
+ * contains the OCREF clear feature and parameters for the TIM peripheral.
+ * @param Channel specifies the TIM Channel
+ * This parameter can be one of the following values:
+ * @arg TIM_CHANNEL_1: TIM Channel 1
+ * @arg TIM_CHANNEL_2: TIM Channel 2
+ * @arg TIM_CHANNEL_3: TIM Channel 3
+ * @arg TIM_CHANNEL_4: TIM Channel 4
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIM_ConfigOCrefClear(TIM_HandleTypeDef *htim,
+ TIM_ClearInputConfigTypeDef *sClearInputConfig,
+ uint32_t Channel)
+{
+ HAL_StatusTypeDef status = HAL_OK;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_OCXREF_CLEAR_INSTANCE(htim->Instance));
+ assert_param(IS_TIM_CLEARINPUT_SOURCE(sClearInputConfig->ClearInputSource));
+
+ /* Process Locked */
+ __HAL_LOCK(htim);
+
+ htim->State = HAL_TIM_STATE_BUSY;
+
+ switch (sClearInputConfig->ClearInputSource)
+ {
+ case TIM_CLEARINPUTSOURCE_NONE:
+ {
+ /* Clear the OCREF clear selection bit and the the ETR Bits */
+ CLEAR_BIT(htim->Instance->SMCR, (TIM_SMCR_OCCS | TIM_SMCR_ETF | TIM_SMCR_ETPS | TIM_SMCR_ECE | TIM_SMCR_ETP));
+ break;
+ }
+ case TIM_CLEARINPUTSOURCE_OCREFCLR:
+ {
+ /* Clear the OCREF clear selection bit */
+ CLEAR_BIT(htim->Instance->SMCR, TIM_SMCR_OCCS);
+ }
+ break;
+
+ case TIM_CLEARINPUTSOURCE_ETR:
+ {
+ /* Check the parameters */
+ assert_param(IS_TIM_CLEARINPUT_POLARITY(sClearInputConfig->ClearInputPolarity));
+ assert_param(IS_TIM_CLEARINPUT_PRESCALER(sClearInputConfig->ClearInputPrescaler));
+ assert_param(IS_TIM_CLEARINPUT_FILTER(sClearInputConfig->ClearInputFilter));
+
+ /* When OCRef clear feature is used with ETR source, ETR prescaler must be off */
+ if (sClearInputConfig->ClearInputPrescaler != TIM_CLEARINPUTPRESCALER_DIV1)
+ {
+ htim->State = HAL_TIM_STATE_READY;
+ __HAL_UNLOCK(htim);
+ return HAL_ERROR;
+ }
+
+ TIM_ETR_SetConfig(htim->Instance,
+ sClearInputConfig->ClearInputPrescaler,
+ sClearInputConfig->ClearInputPolarity,
+ sClearInputConfig->ClearInputFilter);
+
+ /* Set the OCREF clear selection bit */
+ SET_BIT(htim->Instance->SMCR, TIM_SMCR_OCCS);
+ break;
+ }
+
+ default:
+ status = HAL_ERROR;
+ break;
+ }
+
+ if (status == HAL_OK)
+ {
+ switch (Channel)
+ {
+ case TIM_CHANNEL_1:
+ {
+ if (sClearInputConfig->ClearInputState != (uint32_t)DISABLE)
+ {
+ /* Enable the OCREF clear feature for Channel 1 */
+ SET_BIT(htim->Instance->CCMR1, TIM_CCMR1_OC1CE);
+ }
+ else
+ {
+ /* Disable the OCREF clear feature for Channel 1 */
+ CLEAR_BIT(htim->Instance->CCMR1, TIM_CCMR1_OC1CE);
+ }
+ break;
+ }
+ case TIM_CHANNEL_2:
+ {
+ if (sClearInputConfig->ClearInputState != (uint32_t)DISABLE)
+ {
+ /* Enable the OCREF clear feature for Channel 2 */
+ SET_BIT(htim->Instance->CCMR1, TIM_CCMR1_OC2CE);
+ }
+ else
+ {
+ /* Disable the OCREF clear feature for Channel 2 */
+ CLEAR_BIT(htim->Instance->CCMR1, TIM_CCMR1_OC2CE);
+ }
+ break;
+ }
+ case TIM_CHANNEL_3:
+ {
+ if (sClearInputConfig->ClearInputState != (uint32_t)DISABLE)
+ {
+ /* Enable the OCREF clear feature for Channel 3 */
+ SET_BIT(htim->Instance->CCMR2, TIM_CCMR2_OC3CE);
+ }
+ else
+ {
+ /* Disable the OCREF clear feature for Channel 3 */
+ CLEAR_BIT(htim->Instance->CCMR2, TIM_CCMR2_OC3CE);
+ }
+ break;
+ }
+ case TIM_CHANNEL_4:
+ {
+ if (sClearInputConfig->ClearInputState != (uint32_t)DISABLE)
+ {
+ /* Enable the OCREF clear feature for Channel 4 */
+ SET_BIT(htim->Instance->CCMR2, TIM_CCMR2_OC4CE);
+ }
+ else
+ {
+ /* Disable the OCREF clear feature for Channel 4 */
+ CLEAR_BIT(htim->Instance->CCMR2, TIM_CCMR2_OC4CE);
+ }
+ break;
+ }
+ default:
+ break;
+ }
+ }
+
+ htim->State = HAL_TIM_STATE_READY;
+
+ __HAL_UNLOCK(htim);
+
+ return status;
+}
+
+/**
+ * @brief Configures the clock source to be used
+ * @param htim TIM handle
+ * @param sClockSourceConfig pointer to a TIM_ClockConfigTypeDef structure that
+ * contains the clock source information for the TIM peripheral.
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIM_ConfigClockSource(TIM_HandleTypeDef *htim, TIM_ClockConfigTypeDef *sClockSourceConfig)
+{
+ HAL_StatusTypeDef status = HAL_OK;
+ uint32_t tmpsmcr;
+
+ /* Process Locked */
+ __HAL_LOCK(htim);
+
+ htim->State = HAL_TIM_STATE_BUSY;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_CLOCKSOURCE(sClockSourceConfig->ClockSource));
+
+ /* Reset the SMS, TS, ECE, ETPS and ETRF bits */
+ tmpsmcr = htim->Instance->SMCR;
+ tmpsmcr &= ~(TIM_SMCR_SMS | TIM_SMCR_TS);
+ tmpsmcr &= ~(TIM_SMCR_ETF | TIM_SMCR_ETPS | TIM_SMCR_ECE | TIM_SMCR_ETP);
+ htim->Instance->SMCR = tmpsmcr;
+
+ switch (sClockSourceConfig->ClockSource)
+ {
+ case TIM_CLOCKSOURCE_INTERNAL:
+ {
+ assert_param(IS_TIM_INSTANCE(htim->Instance));
+ break;
+ }
+
+ case TIM_CLOCKSOURCE_ETRMODE1:
+ {
+ /* Check whether or not the timer instance supports external trigger input mode 1 (ETRF)*/
+ assert_param(IS_TIM_CLOCKSOURCE_ETRMODE1_INSTANCE(htim->Instance));
+
+ /* Check ETR input conditioning related parameters */
+ assert_param(IS_TIM_CLOCKPRESCALER(sClockSourceConfig->ClockPrescaler));
+ assert_param(IS_TIM_CLOCKPOLARITY(sClockSourceConfig->ClockPolarity));
+ assert_param(IS_TIM_CLOCKFILTER(sClockSourceConfig->ClockFilter));
+
+ /* Configure the ETR Clock source */
+ TIM_ETR_SetConfig(htim->Instance,
+ sClockSourceConfig->ClockPrescaler,
+ sClockSourceConfig->ClockPolarity,
+ sClockSourceConfig->ClockFilter);
+
+ /* Select the External clock mode1 and the ETRF trigger */
+ tmpsmcr = htim->Instance->SMCR;
+ tmpsmcr |= (TIM_SLAVEMODE_EXTERNAL1 | TIM_CLOCKSOURCE_ETRMODE1);
+ /* Write to TIMx SMCR */
+ htim->Instance->SMCR = tmpsmcr;
+ break;
+ }
+
+ case TIM_CLOCKSOURCE_ETRMODE2:
+ {
+ /* Check whether or not the timer instance supports external trigger input mode 2 (ETRF)*/
+ assert_param(IS_TIM_CLOCKSOURCE_ETRMODE2_INSTANCE(htim->Instance));
+
+ /* Check ETR input conditioning related parameters */
+ assert_param(IS_TIM_CLOCKPRESCALER(sClockSourceConfig->ClockPrescaler));
+ assert_param(IS_TIM_CLOCKPOLARITY(sClockSourceConfig->ClockPolarity));
+ assert_param(IS_TIM_CLOCKFILTER(sClockSourceConfig->ClockFilter));
+
+ /* Configure the ETR Clock source */
+ TIM_ETR_SetConfig(htim->Instance,
+ sClockSourceConfig->ClockPrescaler,
+ sClockSourceConfig->ClockPolarity,
+ sClockSourceConfig->ClockFilter);
+ /* Enable the External clock mode2 */
+ htim->Instance->SMCR |= TIM_SMCR_ECE;
+ break;
+ }
+
+ case TIM_CLOCKSOURCE_TI1:
+ {
+ /* Check whether or not the timer instance supports external clock mode 1 */
+ assert_param(IS_TIM_CLOCKSOURCE_TIX_INSTANCE(htim->Instance));
+
+ /* Check TI1 input conditioning related parameters */
+ assert_param(IS_TIM_CLOCKPOLARITY(sClockSourceConfig->ClockPolarity));
+ assert_param(IS_TIM_CLOCKFILTER(sClockSourceConfig->ClockFilter));
+
+ TIM_TI1_ConfigInputStage(htim->Instance,
+ sClockSourceConfig->ClockPolarity,
+ sClockSourceConfig->ClockFilter);
+ TIM_ITRx_SetConfig(htim->Instance, TIM_CLOCKSOURCE_TI1);
+ break;
+ }
+
+ case TIM_CLOCKSOURCE_TI2:
+ {
+ /* Check whether or not the timer instance supports external clock mode 1 (ETRF)*/
+ assert_param(IS_TIM_CLOCKSOURCE_TIX_INSTANCE(htim->Instance));
+
+ /* Check TI2 input conditioning related parameters */
+ assert_param(IS_TIM_CLOCKPOLARITY(sClockSourceConfig->ClockPolarity));
+ assert_param(IS_TIM_CLOCKFILTER(sClockSourceConfig->ClockFilter));
+
+ TIM_TI2_ConfigInputStage(htim->Instance,
+ sClockSourceConfig->ClockPolarity,
+ sClockSourceConfig->ClockFilter);
+ TIM_ITRx_SetConfig(htim->Instance, TIM_CLOCKSOURCE_TI2);
+ break;
+ }
+
+ case TIM_CLOCKSOURCE_TI1ED:
+ {
+ /* Check whether or not the timer instance supports external clock mode 1 */
+ assert_param(IS_TIM_CLOCKSOURCE_TIX_INSTANCE(htim->Instance));
+
+ /* Check TI1 input conditioning related parameters */
+ assert_param(IS_TIM_CLOCKPOLARITY(sClockSourceConfig->ClockPolarity));
+ assert_param(IS_TIM_CLOCKFILTER(sClockSourceConfig->ClockFilter));
+
+ TIM_TI1_ConfigInputStage(htim->Instance,
+ sClockSourceConfig->ClockPolarity,
+ sClockSourceConfig->ClockFilter);
+ TIM_ITRx_SetConfig(htim->Instance, TIM_CLOCKSOURCE_TI1ED);
+ break;
+ }
+
+ case TIM_CLOCKSOURCE_ITR0:
+ case TIM_CLOCKSOURCE_ITR1:
+ case TIM_CLOCKSOURCE_ITR2:
+ case TIM_CLOCKSOURCE_ITR3:
+ {
+ /* Check whether or not the timer instance supports internal trigger input */
+ assert_param(IS_TIM_CLOCKSOURCE_ITRX_INSTANCE(htim->Instance));
+
+ TIM_ITRx_SetConfig(htim->Instance, sClockSourceConfig->ClockSource);
+ break;
+ }
+
+ default:
+ status = HAL_ERROR;
+ break;
+ }
+ htim->State = HAL_TIM_STATE_READY;
+
+ __HAL_UNLOCK(htim);
+
+ return status;
+}
+
+/**
+ * @brief Selects the signal connected to the TI1 input: direct from CH1_input
+ * or a XOR combination between CH1_input, CH2_input & CH3_input
+ * @param htim TIM handle.
+ * @param TI1_Selection Indicate whether or not channel 1 is connected to the
+ * output of a XOR gate.
+ * This parameter can be one of the following values:
+ * @arg TIM_TI1SELECTION_CH1: The TIMx_CH1 pin is connected to TI1 input
+ * @arg TIM_TI1SELECTION_XORCOMBINATION: The TIMx_CH1, CH2 and CH3
+ * pins are connected to the TI1 input (XOR combination)
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIM_ConfigTI1Input(TIM_HandleTypeDef *htim, uint32_t TI1_Selection)
+{
+ uint32_t tmpcr2;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_XOR_INSTANCE(htim->Instance));
+ assert_param(IS_TIM_TI1SELECTION(TI1_Selection));
+
+ /* Get the TIMx CR2 register value */
+ tmpcr2 = htim->Instance->CR2;
+
+ /* Reset the TI1 selection */
+ tmpcr2 &= ~TIM_CR2_TI1S;
+
+ /* Set the TI1 selection */
+ tmpcr2 |= TI1_Selection;
+
+ /* Write to TIMxCR2 */
+ htim->Instance->CR2 = tmpcr2;
+
+ return HAL_OK;
+}
+
+/**
+ * @brief Configures the TIM in Slave mode
+ * @param htim TIM handle.
+ * @param sSlaveConfig pointer to a TIM_SlaveConfigTypeDef structure that
+ * contains the selected trigger (internal trigger input, filtered
+ * timer input or external trigger input) and the Slave mode
+ * (Disable, Reset, Gated, Trigger, External clock mode 1).
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIM_SlaveConfigSynchro(TIM_HandleTypeDef *htim, TIM_SlaveConfigTypeDef *sSlaveConfig)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_SLAVE_INSTANCE(htim->Instance));
+ assert_param(IS_TIM_SLAVE_MODE(sSlaveConfig->SlaveMode));
+ assert_param(IS_TIM_TRIGGER_SELECTION(sSlaveConfig->InputTrigger));
+
+ __HAL_LOCK(htim);
+
+ htim->State = HAL_TIM_STATE_BUSY;
+
+ if (TIM_SlaveTimer_SetConfig(htim, sSlaveConfig) != HAL_OK)
+ {
+ htim->State = HAL_TIM_STATE_READY;
+ __HAL_UNLOCK(htim);
+ return HAL_ERROR;
+ }
+
+ /* Disable Trigger Interrupt */
+ __HAL_TIM_DISABLE_IT(htim, TIM_IT_TRIGGER);
+
+ /* Disable Trigger DMA request */
+ __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_TRIGGER);
+
+ htim->State = HAL_TIM_STATE_READY;
+
+ __HAL_UNLOCK(htim);
+
+ return HAL_OK;
+}
+
+/**
+ * @brief Configures the TIM in Slave mode in interrupt mode
+ * @param htim TIM handle.
+ * @param sSlaveConfig pointer to a TIM_SlaveConfigTypeDef structure that
+ * contains the selected trigger (internal trigger input, filtered
+ * timer input or external trigger input) and the Slave mode
+ * (Disable, Reset, Gated, Trigger, External clock mode 1).
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIM_SlaveConfigSynchro_IT(TIM_HandleTypeDef *htim,
+ TIM_SlaveConfigTypeDef *sSlaveConfig)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_SLAVE_INSTANCE(htim->Instance));
+ assert_param(IS_TIM_SLAVE_MODE(sSlaveConfig->SlaveMode));
+ assert_param(IS_TIM_TRIGGER_SELECTION(sSlaveConfig->InputTrigger));
+
+ __HAL_LOCK(htim);
+
+ htim->State = HAL_TIM_STATE_BUSY;
+
+ if (TIM_SlaveTimer_SetConfig(htim, sSlaveConfig) != HAL_OK)
+ {
+ htim->State = HAL_TIM_STATE_READY;
+ __HAL_UNLOCK(htim);
+ return HAL_ERROR;
+ }
+
+ /* Enable Trigger Interrupt */
+ __HAL_TIM_ENABLE_IT(htim, TIM_IT_TRIGGER);
+
+ /* Disable Trigger DMA request */
+ __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_TRIGGER);
+
+ htim->State = HAL_TIM_STATE_READY;
+
+ __HAL_UNLOCK(htim);
+
+ return HAL_OK;
+}
+
+/**
+ * @brief Read the captured value from Capture Compare unit
+ * @param htim TIM handle.
+ * @param Channel TIM Channels to be enabled
+ * This parameter can be one of the following values:
+ * @arg TIM_CHANNEL_1: TIM Channel 1 selected
+ * @arg TIM_CHANNEL_2: TIM Channel 2 selected
+ * @arg TIM_CHANNEL_3: TIM Channel 3 selected
+ * @arg TIM_CHANNEL_4: TIM Channel 4 selected
+ * @retval Captured value
+ */
+uint32_t HAL_TIM_ReadCapturedValue(TIM_HandleTypeDef *htim, uint32_t Channel)
+{
+ uint32_t tmpreg = 0U;
+
+ switch (Channel)
+ {
+ case TIM_CHANNEL_1:
+ {
+ /* Check the parameters */
+ assert_param(IS_TIM_CC1_INSTANCE(htim->Instance));
+
+ /* Return the capture 1 value */
+ tmpreg = htim->Instance->CCR1;
+
+ break;
+ }
+ case TIM_CHANNEL_2:
+ {
+ /* Check the parameters */
+ assert_param(IS_TIM_CC2_INSTANCE(htim->Instance));
+
+ /* Return the capture 2 value */
+ tmpreg = htim->Instance->CCR2;
+
+ break;
+ }
+
+ case TIM_CHANNEL_3:
+ {
+ /* Check the parameters */
+ assert_param(IS_TIM_CC3_INSTANCE(htim->Instance));
+
+ /* Return the capture 3 value */
+ tmpreg = htim->Instance->CCR3;
+
+ break;
+ }
+
+ case TIM_CHANNEL_4:
+ {
+ /* Check the parameters */
+ assert_param(IS_TIM_CC4_INSTANCE(htim->Instance));
+
+ /* Return the capture 4 value */
+ tmpreg = htim->Instance->CCR4;
+
+ break;
+ }
+
+ default:
+ break;
+ }
+
+ return tmpreg;
+}
+
+/**
+ * @}
+ */
+
+/** @defgroup TIM_Exported_Functions_Group9 TIM Callbacks functions
+ * @brief TIM Callbacks functions
+ *
+@verbatim
+ ==============================================================================
+ ##### TIM Callbacks functions #####
+ ==============================================================================
+ [..]
+ This section provides TIM callback functions:
+ (+) TIM Period elapsed callback
+ (+) TIM Output Compare callback
+ (+) TIM Input capture callback
+ (+) TIM Trigger callback
+ (+) TIM Error callback
+
+@endverbatim
+ * @{
+ */
+
+/**
+ * @brief Period elapsed callback in non-blocking mode
+ * @param htim TIM handle
+ * @retval None
+ */
+__weak void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim)
+{
+ /* Prevent unused argument(s) compilation warning */
+ UNUSED(htim);
+
+ /* NOTE : This function should not be modified, when the callback is needed,
+ the HAL_TIM_PeriodElapsedCallback could be implemented in the user file
+ */
+}
+
+/**
+ * @brief Period elapsed half complete callback in non-blocking mode
+ * @param htim TIM handle
+ * @retval None
+ */
+__weak void HAL_TIM_PeriodElapsedHalfCpltCallback(TIM_HandleTypeDef *htim)
+{
+ /* Prevent unused argument(s) compilation warning */
+ UNUSED(htim);
+
+ /* NOTE : This function should not be modified, when the callback is needed,
+ the HAL_TIM_PeriodElapsedHalfCpltCallback could be implemented in the user file
+ */
+}
+
+/**
+ * @brief Output Compare callback in non-blocking mode
+ * @param htim TIM OC handle
+ * @retval None
+ */
+__weak void HAL_TIM_OC_DelayElapsedCallback(TIM_HandleTypeDef *htim)
+{
+ /* Prevent unused argument(s) compilation warning */
+ UNUSED(htim);
+
+ /* NOTE : This function should not be modified, when the callback is needed,
+ the HAL_TIM_OC_DelayElapsedCallback could be implemented in the user file
+ */
+}
+
+/**
+ * @brief Input Capture callback in non-blocking mode
+ * @param htim TIM IC handle
+ * @retval None
+ */
+__weak void HAL_TIM_IC_CaptureCallback(TIM_HandleTypeDef *htim)
+{
+ /* Prevent unused argument(s) compilation warning */
+ UNUSED(htim);
+
+ /* NOTE : This function should not be modified, when the callback is needed,
+ the HAL_TIM_IC_CaptureCallback could be implemented in the user file
+ */
+}
+
+/**
+ * @brief Input Capture half complete callback in non-blocking mode
+ * @param htim TIM IC handle
+ * @retval None
+ */
+__weak void HAL_TIM_IC_CaptureHalfCpltCallback(TIM_HandleTypeDef *htim)
+{
+ /* Prevent unused argument(s) compilation warning */
+ UNUSED(htim);
+
+ /* NOTE : This function should not be modified, when the callback is needed,
+ the HAL_TIM_IC_CaptureHalfCpltCallback could be implemented in the user file
+ */
+}
+
+/**
+ * @brief PWM Pulse finished callback in non-blocking mode
+ * @param htim TIM handle
+ * @retval None
+ */
+__weak void HAL_TIM_PWM_PulseFinishedCallback(TIM_HandleTypeDef *htim)
+{
+ /* Prevent unused argument(s) compilation warning */
+ UNUSED(htim);
+
+ /* NOTE : This function should not be modified, when the callback is needed,
+ the HAL_TIM_PWM_PulseFinishedCallback could be implemented in the user file
+ */
+}
+
+/**
+ * @brief PWM Pulse finished half complete callback in non-blocking mode
+ * @param htim TIM handle
+ * @retval None
+ */
+__weak void HAL_TIM_PWM_PulseFinishedHalfCpltCallback(TIM_HandleTypeDef *htim)
+{
+ /* Prevent unused argument(s) compilation warning */
+ UNUSED(htim);
+
+ /* NOTE : This function should not be modified, when the callback is needed,
+ the HAL_TIM_PWM_PulseFinishedHalfCpltCallback could be implemented in the user file
+ */
+}
+
+/**
+ * @brief Hall Trigger detection callback in non-blocking mode
+ * @param htim TIM handle
+ * @retval None
+ */
+__weak void HAL_TIM_TriggerCallback(TIM_HandleTypeDef *htim)
+{
+ /* Prevent unused argument(s) compilation warning */
+ UNUSED(htim);
+
+ /* NOTE : This function should not be modified, when the callback is needed,
+ the HAL_TIM_TriggerCallback could be implemented in the user file
+ */
+}
+
+/**
+ * @brief Hall Trigger detection half complete callback in non-blocking mode
+ * @param htim TIM handle
+ * @retval None
+ */
+__weak void HAL_TIM_TriggerHalfCpltCallback(TIM_HandleTypeDef *htim)
+{
+ /* Prevent unused argument(s) compilation warning */
+ UNUSED(htim);
+
+ /* NOTE : This function should not be modified, when the callback is needed,
+ the HAL_TIM_TriggerHalfCpltCallback could be implemented in the user file
+ */
+}
+
+/**
+ * @brief Timer error callback in non-blocking mode
+ * @param htim TIM handle
+ * @retval None
+ */
+__weak void HAL_TIM_ErrorCallback(TIM_HandleTypeDef *htim)
+{
+ /* Prevent unused argument(s) compilation warning */
+ UNUSED(htim);
+
+ /* NOTE : This function should not be modified, when the callback is needed,
+ the HAL_TIM_ErrorCallback could be implemented in the user file
+ */
+}
+
+#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1)
+/**
+ * @brief Register a User TIM callback to be used instead of the weak predefined callback
+ * @param htim tim handle
+ * @param CallbackID ID of the callback to be registered
+ * This parameter can be one of the following values:
+ * @arg @ref HAL_TIM_BASE_MSPINIT_CB_ID Base MspInit Callback ID
+ * @arg @ref HAL_TIM_BASE_MSPDEINIT_CB_ID Base MspDeInit Callback ID
+ * @arg @ref HAL_TIM_IC_MSPINIT_CB_ID IC MspInit Callback ID
+ * @arg @ref HAL_TIM_IC_MSPDEINIT_CB_ID IC MspDeInit Callback ID
+ * @arg @ref HAL_TIM_OC_MSPINIT_CB_ID OC MspInit Callback ID
+ * @arg @ref HAL_TIM_OC_MSPDEINIT_CB_ID OC MspDeInit Callback ID
+ * @arg @ref HAL_TIM_PWM_MSPINIT_CB_ID PWM MspInit Callback ID
+ * @arg @ref HAL_TIM_PWM_MSPDEINIT_CB_ID PWM MspDeInit Callback ID
+ * @arg @ref HAL_TIM_ONE_PULSE_MSPINIT_CB_ID One Pulse MspInit Callback ID
+ * @arg @ref HAL_TIM_ONE_PULSE_MSPDEINIT_CB_ID One Pulse MspDeInit Callback ID
+ * @arg @ref HAL_TIM_ENCODER_MSPINIT_CB_ID Encoder MspInit Callback ID
+ * @arg @ref HAL_TIM_ENCODER_MSPDEINIT_CB_ID Encoder MspDeInit Callback ID
+ * @arg @ref HAL_TIM_HALL_SENSOR_MSPINIT_CB_ID Hall Sensor MspInit Callback ID
+ * @arg @ref HAL_TIM_HALL_SENSOR_MSPDEINIT_CB_ID Hall Sensor MspDeInit Callback ID
+ * @arg @ref HAL_TIM_PERIOD_ELAPSED_CB_ID Period Elapsed Callback ID
+ * @arg @ref HAL_TIM_PERIOD_ELAPSED_HALF_CB_ID Period Elapsed half complete Callback ID
+ * @arg @ref HAL_TIM_TRIGGER_CB_ID Trigger Callback ID
+ * @arg @ref HAL_TIM_TRIGGER_HALF_CB_ID Trigger half complete Callback ID
+ * @arg @ref HAL_TIM_IC_CAPTURE_CB_ID Input Capture Callback ID
+ * @arg @ref HAL_TIM_IC_CAPTURE_HALF_CB_ID Input Capture half complete Callback ID
+ * @arg @ref HAL_TIM_OC_DELAY_ELAPSED_CB_ID Output Compare Delay Elapsed Callback ID
+ * @arg @ref HAL_TIM_PWM_PULSE_FINISHED_CB_ID PWM Pulse Finished Callback ID
+ * @arg @ref HAL_TIM_PWM_PULSE_FINISHED_HALF_CB_ID PWM Pulse Finished half complete Callback ID
+ * @arg @ref HAL_TIM_ERROR_CB_ID Error Callback ID
+ * @arg @ref HAL_TIM_COMMUTATION_CB_ID Commutation Callback ID
+ * @arg @ref HAL_TIM_COMMUTATION_HALF_CB_ID Commutation half complete Callback ID
+ * @arg @ref HAL_TIM_BREAK_CB_ID Break Callback ID
+ * @param pCallback pointer to the callback function
+ * @retval status
+ */
+HAL_StatusTypeDef HAL_TIM_RegisterCallback(TIM_HandleTypeDef *htim, HAL_TIM_CallbackIDTypeDef CallbackID,
+ pTIM_CallbackTypeDef pCallback)
+{
+ HAL_StatusTypeDef status = HAL_OK;
+
+ if (pCallback == NULL)
+ {
+ return HAL_ERROR;
+ }
+ /* Process locked */
+ __HAL_LOCK(htim);
+
+ if (htim->State == HAL_TIM_STATE_READY)
+ {
+ switch (CallbackID)
+ {
+ case HAL_TIM_BASE_MSPINIT_CB_ID :
+ htim->Base_MspInitCallback = pCallback;
+ break;
+
+ case HAL_TIM_BASE_MSPDEINIT_CB_ID :
+ htim->Base_MspDeInitCallback = pCallback;
+ break;
+
+ case HAL_TIM_IC_MSPINIT_CB_ID :
+ htim->IC_MspInitCallback = pCallback;
+ break;
+
+ case HAL_TIM_IC_MSPDEINIT_CB_ID :
+ htim->IC_MspDeInitCallback = pCallback;
+ break;
+
+ case HAL_TIM_OC_MSPINIT_CB_ID :
+ htim->OC_MspInitCallback = pCallback;
+ break;
+
+ case HAL_TIM_OC_MSPDEINIT_CB_ID :
+ htim->OC_MspDeInitCallback = pCallback;
+ break;
+
+ case HAL_TIM_PWM_MSPINIT_CB_ID :
+ htim->PWM_MspInitCallback = pCallback;
+ break;
+
+ case HAL_TIM_PWM_MSPDEINIT_CB_ID :
+ htim->PWM_MspDeInitCallback = pCallback;
+ break;
+
+ case HAL_TIM_ONE_PULSE_MSPINIT_CB_ID :
+ htim->OnePulse_MspInitCallback = pCallback;
+ break;
+
+ case HAL_TIM_ONE_PULSE_MSPDEINIT_CB_ID :
+ htim->OnePulse_MspDeInitCallback = pCallback;
+ break;
+
+ case HAL_TIM_ENCODER_MSPINIT_CB_ID :
+ htim->Encoder_MspInitCallback = pCallback;
+ break;
+
+ case HAL_TIM_ENCODER_MSPDEINIT_CB_ID :
+ htim->Encoder_MspDeInitCallback = pCallback;
+ break;
+
+ case HAL_TIM_HALL_SENSOR_MSPINIT_CB_ID :
+ htim->HallSensor_MspInitCallback = pCallback;
+ break;
+
+ case HAL_TIM_HALL_SENSOR_MSPDEINIT_CB_ID :
+ htim->HallSensor_MspDeInitCallback = pCallback;
+ break;
+
+ case HAL_TIM_PERIOD_ELAPSED_CB_ID :
+ htim->PeriodElapsedCallback = pCallback;
+ break;
+
+ case HAL_TIM_PERIOD_ELAPSED_HALF_CB_ID :
+ htim->PeriodElapsedHalfCpltCallback = pCallback;
+ break;
+
+ case HAL_TIM_TRIGGER_CB_ID :
+ htim->TriggerCallback = pCallback;
+ break;
+
+ case HAL_TIM_TRIGGER_HALF_CB_ID :
+ htim->TriggerHalfCpltCallback = pCallback;
+ break;
+
+ case HAL_TIM_IC_CAPTURE_CB_ID :
+ htim->IC_CaptureCallback = pCallback;
+ break;
+
+ case HAL_TIM_IC_CAPTURE_HALF_CB_ID :
+ htim->IC_CaptureHalfCpltCallback = pCallback;
+ break;
+
+ case HAL_TIM_OC_DELAY_ELAPSED_CB_ID :
+ htim->OC_DelayElapsedCallback = pCallback;
+ break;
+
+ case HAL_TIM_PWM_PULSE_FINISHED_CB_ID :
+ htim->PWM_PulseFinishedCallback = pCallback;
+ break;
+
+ case HAL_TIM_PWM_PULSE_FINISHED_HALF_CB_ID :
+ htim->PWM_PulseFinishedHalfCpltCallback = pCallback;
+ break;
+
+ case HAL_TIM_ERROR_CB_ID :
+ htim->ErrorCallback = pCallback;
+ break;
+
+ case HAL_TIM_COMMUTATION_CB_ID :
+ htim->CommutationCallback = pCallback;
+ break;
+
+ case HAL_TIM_COMMUTATION_HALF_CB_ID :
+ htim->CommutationHalfCpltCallback = pCallback;
+ break;
+
+ case HAL_TIM_BREAK_CB_ID :
+ htim->BreakCallback = pCallback;
+ break;
+
+ default :
+ /* Return error status */
+ status = HAL_ERROR;
+ break;
+ }
+ }
+ else if (htim->State == HAL_TIM_STATE_RESET)
+ {
+ switch (CallbackID)
+ {
+ case HAL_TIM_BASE_MSPINIT_CB_ID :
+ htim->Base_MspInitCallback = pCallback;
+ break;
+
+ case HAL_TIM_BASE_MSPDEINIT_CB_ID :
+ htim->Base_MspDeInitCallback = pCallback;
+ break;
+
+ case HAL_TIM_IC_MSPINIT_CB_ID :
+ htim->IC_MspInitCallback = pCallback;
+ break;
+
+ case HAL_TIM_IC_MSPDEINIT_CB_ID :
+ htim->IC_MspDeInitCallback = pCallback;
+ break;
+
+ case HAL_TIM_OC_MSPINIT_CB_ID :
+ htim->OC_MspInitCallback = pCallback;
+ break;
+
+ case HAL_TIM_OC_MSPDEINIT_CB_ID :
+ htim->OC_MspDeInitCallback = pCallback;
+ break;
+
+ case HAL_TIM_PWM_MSPINIT_CB_ID :
+ htim->PWM_MspInitCallback = pCallback;
+ break;
+
+ case HAL_TIM_PWM_MSPDEINIT_CB_ID :
+ htim->PWM_MspDeInitCallback = pCallback;
+ break;
+
+ case HAL_TIM_ONE_PULSE_MSPINIT_CB_ID :
+ htim->OnePulse_MspInitCallback = pCallback;
+ break;
+
+ case HAL_TIM_ONE_PULSE_MSPDEINIT_CB_ID :
+ htim->OnePulse_MspDeInitCallback = pCallback;
+ break;
+
+ case HAL_TIM_ENCODER_MSPINIT_CB_ID :
+ htim->Encoder_MspInitCallback = pCallback;
+ break;
+
+ case HAL_TIM_ENCODER_MSPDEINIT_CB_ID :
+ htim->Encoder_MspDeInitCallback = pCallback;
+ break;
+
+ case HAL_TIM_HALL_SENSOR_MSPINIT_CB_ID :
+ htim->HallSensor_MspInitCallback = pCallback;
+ break;
+
+ case HAL_TIM_HALL_SENSOR_MSPDEINIT_CB_ID :
+ htim->HallSensor_MspDeInitCallback = pCallback;
+ break;
+
+ default :
+ /* Return error status */
+ status = HAL_ERROR;
+ break;
+ }
+ }
+ else
+ {
+ /* Return error status */
+ status = HAL_ERROR;
+ }
+
+ /* Release Lock */
+ __HAL_UNLOCK(htim);
+
+ return status;
+}
+
+/**
+ * @brief Unregister a TIM callback
+ * TIM callback is redirected to the weak predefined callback
+ * @param htim tim handle
+ * @param CallbackID ID of the callback to be unregistered
+ * This parameter can be one of the following values:
+ * @arg @ref HAL_TIM_BASE_MSPINIT_CB_ID Base MspInit Callback ID
+ * @arg @ref HAL_TIM_BASE_MSPDEINIT_CB_ID Base MspDeInit Callback ID
+ * @arg @ref HAL_TIM_IC_MSPINIT_CB_ID IC MspInit Callback ID
+ * @arg @ref HAL_TIM_IC_MSPDEINIT_CB_ID IC MspDeInit Callback ID
+ * @arg @ref HAL_TIM_OC_MSPINIT_CB_ID OC MspInit Callback ID
+ * @arg @ref HAL_TIM_OC_MSPDEINIT_CB_ID OC MspDeInit Callback ID
+ * @arg @ref HAL_TIM_PWM_MSPINIT_CB_ID PWM MspInit Callback ID
+ * @arg @ref HAL_TIM_PWM_MSPDEINIT_CB_ID PWM MspDeInit Callback ID
+ * @arg @ref HAL_TIM_ONE_PULSE_MSPINIT_CB_ID One Pulse MspInit Callback ID
+ * @arg @ref HAL_TIM_ONE_PULSE_MSPDEINIT_CB_ID One Pulse MspDeInit Callback ID
+ * @arg @ref HAL_TIM_ENCODER_MSPINIT_CB_ID Encoder MspInit Callback ID
+ * @arg @ref HAL_TIM_ENCODER_MSPDEINIT_CB_ID Encoder MspDeInit Callback ID
+ * @arg @ref HAL_TIM_HALL_SENSOR_MSPINIT_CB_ID Hall Sensor MspInit Callback ID
+ * @arg @ref HAL_TIM_HALL_SENSOR_MSPDEINIT_CB_ID Hall Sensor MspDeInit Callback ID
+ * @arg @ref HAL_TIM_PERIOD_ELAPSED_CB_ID Period Elapsed Callback ID
+ * @arg @ref HAL_TIM_PERIOD_ELAPSED_HALF_CB_ID Period Elapsed half complete Callback ID
+ * @arg @ref HAL_TIM_TRIGGER_CB_ID Trigger Callback ID
+ * @arg @ref HAL_TIM_TRIGGER_HALF_CB_ID Trigger half complete Callback ID
+ * @arg @ref HAL_TIM_IC_CAPTURE_CB_ID Input Capture Callback ID
+ * @arg @ref HAL_TIM_IC_CAPTURE_HALF_CB_ID Input Capture half complete Callback ID
+ * @arg @ref HAL_TIM_OC_DELAY_ELAPSED_CB_ID Output Compare Delay Elapsed Callback ID
+ * @arg @ref HAL_TIM_PWM_PULSE_FINISHED_CB_ID PWM Pulse Finished Callback ID
+ * @arg @ref HAL_TIM_PWM_PULSE_FINISHED_HALF_CB_ID PWM Pulse Finished half complete Callback ID
+ * @arg @ref HAL_TIM_ERROR_CB_ID Error Callback ID
+ * @arg @ref HAL_TIM_COMMUTATION_CB_ID Commutation Callback ID
+ * @arg @ref HAL_TIM_COMMUTATION_HALF_CB_ID Commutation half complete Callback ID
+ * @arg @ref HAL_TIM_BREAK_CB_ID Break Callback ID
+ * @retval status
+ */
+HAL_StatusTypeDef HAL_TIM_UnRegisterCallback(TIM_HandleTypeDef *htim, HAL_TIM_CallbackIDTypeDef CallbackID)
+{
+ HAL_StatusTypeDef status = HAL_OK;
+
+ /* Process locked */
+ __HAL_LOCK(htim);
+
+ if (htim->State == HAL_TIM_STATE_READY)
+ {
+ switch (CallbackID)
+ {
+ case HAL_TIM_BASE_MSPINIT_CB_ID :
+ /* Legacy weak Base MspInit Callback */
+ htim->Base_MspInitCallback = HAL_TIM_Base_MspInit;
+ break;
+
+ case HAL_TIM_BASE_MSPDEINIT_CB_ID :
+ /* Legacy weak Base Msp DeInit Callback */
+ htim->Base_MspDeInitCallback = HAL_TIM_Base_MspDeInit;
+ break;
+
+ case HAL_TIM_IC_MSPINIT_CB_ID :
+ /* Legacy weak IC Msp Init Callback */
+ htim->IC_MspInitCallback = HAL_TIM_IC_MspInit;
+ break;
+
+ case HAL_TIM_IC_MSPDEINIT_CB_ID :
+ /* Legacy weak IC Msp DeInit Callback */
+ htim->IC_MspDeInitCallback = HAL_TIM_IC_MspDeInit;
+ break;
+
+ case HAL_TIM_OC_MSPINIT_CB_ID :
+ /* Legacy weak OC Msp Init Callback */
+ htim->OC_MspInitCallback = HAL_TIM_OC_MspInit;
+ break;
+
+ case HAL_TIM_OC_MSPDEINIT_CB_ID :
+ /* Legacy weak OC Msp DeInit Callback */
+ htim->OC_MspDeInitCallback = HAL_TIM_OC_MspDeInit;
+ break;
+
+ case HAL_TIM_PWM_MSPINIT_CB_ID :
+ /* Legacy weak PWM Msp Init Callback */
+ htim->PWM_MspInitCallback = HAL_TIM_PWM_MspInit;
+ break;
+
+ case HAL_TIM_PWM_MSPDEINIT_CB_ID :
+ /* Legacy weak PWM Msp DeInit Callback */
+ htim->PWM_MspDeInitCallback = HAL_TIM_PWM_MspDeInit;
+ break;
+
+ case HAL_TIM_ONE_PULSE_MSPINIT_CB_ID :
+ /* Legacy weak One Pulse Msp Init Callback */
+ htim->OnePulse_MspInitCallback = HAL_TIM_OnePulse_MspInit;
+ break;
+
+ case HAL_TIM_ONE_PULSE_MSPDEINIT_CB_ID :
+ /* Legacy weak One Pulse Msp DeInit Callback */
+ htim->OnePulse_MspDeInitCallback = HAL_TIM_OnePulse_MspDeInit;
+ break;
+
+ case HAL_TIM_ENCODER_MSPINIT_CB_ID :
+ /* Legacy weak Encoder Msp Init Callback */
+ htim->Encoder_MspInitCallback = HAL_TIM_Encoder_MspInit;
+ break;
+
+ case HAL_TIM_ENCODER_MSPDEINIT_CB_ID :
+ /* Legacy weak Encoder Msp DeInit Callback */
+ htim->Encoder_MspDeInitCallback = HAL_TIM_Encoder_MspDeInit;
+ break;
+
+ case HAL_TIM_HALL_SENSOR_MSPINIT_CB_ID :
+ /* Legacy weak Hall Sensor Msp Init Callback */
+ htim->HallSensor_MspInitCallback = HAL_TIMEx_HallSensor_MspInit;
+ break;
+
+ case HAL_TIM_HALL_SENSOR_MSPDEINIT_CB_ID :
+ /* Legacy weak Hall Sensor Msp DeInit Callback */
+ htim->HallSensor_MspDeInitCallback = HAL_TIMEx_HallSensor_MspDeInit;
+ break;
+
+ case HAL_TIM_PERIOD_ELAPSED_CB_ID :
+ /* Legacy weak Period Elapsed Callback */
+ htim->PeriodElapsedCallback = HAL_TIM_PeriodElapsedCallback;
+ break;
+
+ case HAL_TIM_PERIOD_ELAPSED_HALF_CB_ID :
+ /* Legacy weak Period Elapsed half complete Callback */
+ htim->PeriodElapsedHalfCpltCallback = HAL_TIM_PeriodElapsedHalfCpltCallback;
+ break;
+
+ case HAL_TIM_TRIGGER_CB_ID :
+ /* Legacy weak Trigger Callback */
+ htim->TriggerCallback = HAL_TIM_TriggerCallback;
+ break;
+
+ case HAL_TIM_TRIGGER_HALF_CB_ID :
+ /* Legacy weak Trigger half complete Callback */
+ htim->TriggerHalfCpltCallback = HAL_TIM_TriggerHalfCpltCallback;
+ break;
+
+ case HAL_TIM_IC_CAPTURE_CB_ID :
+ /* Legacy weak IC Capture Callback */
+ htim->IC_CaptureCallback = HAL_TIM_IC_CaptureCallback;
+ break;
+
+ case HAL_TIM_IC_CAPTURE_HALF_CB_ID :
+ /* Legacy weak IC Capture half complete Callback */
+ htim->IC_CaptureHalfCpltCallback = HAL_TIM_IC_CaptureHalfCpltCallback;
+ break;
+
+ case HAL_TIM_OC_DELAY_ELAPSED_CB_ID :
+ /* Legacy weak OC Delay Elapsed Callback */
+ htim->OC_DelayElapsedCallback = HAL_TIM_OC_DelayElapsedCallback;
+ break;
+
+ case HAL_TIM_PWM_PULSE_FINISHED_CB_ID :
+ /* Legacy weak PWM Pulse Finished Callback */
+ htim->PWM_PulseFinishedCallback = HAL_TIM_PWM_PulseFinishedCallback;
+ break;
+
+ case HAL_TIM_PWM_PULSE_FINISHED_HALF_CB_ID :
+ /* Legacy weak PWM Pulse Finished half complete Callback */
+ htim->PWM_PulseFinishedHalfCpltCallback = HAL_TIM_PWM_PulseFinishedHalfCpltCallback;
+ break;
+
+ case HAL_TIM_ERROR_CB_ID :
+ /* Legacy weak Error Callback */
+ htim->ErrorCallback = HAL_TIM_ErrorCallback;
+ break;
+
+ case HAL_TIM_COMMUTATION_CB_ID :
+ /* Legacy weak Commutation Callback */
+ htim->CommutationCallback = HAL_TIMEx_CommutCallback;
+ break;
+
+ case HAL_TIM_COMMUTATION_HALF_CB_ID :
+ /* Legacy weak Commutation half complete Callback */
+ htim->CommutationHalfCpltCallback = HAL_TIMEx_CommutHalfCpltCallback;
+ break;
+
+ case HAL_TIM_BREAK_CB_ID :
+ /* Legacy weak Break Callback */
+ htim->BreakCallback = HAL_TIMEx_BreakCallback;
+ break;
+
+ default :
+ /* Return error status */
+ status = HAL_ERROR;
+ break;
+ }
+ }
+ else if (htim->State == HAL_TIM_STATE_RESET)
+ {
+ switch (CallbackID)
+ {
+ case HAL_TIM_BASE_MSPINIT_CB_ID :
+ /* Legacy weak Base MspInit Callback */
+ htim->Base_MspInitCallback = HAL_TIM_Base_MspInit;
+ break;
+
+ case HAL_TIM_BASE_MSPDEINIT_CB_ID :
+ /* Legacy weak Base Msp DeInit Callback */
+ htim->Base_MspDeInitCallback = HAL_TIM_Base_MspDeInit;
+ break;
+
+ case HAL_TIM_IC_MSPINIT_CB_ID :
+ /* Legacy weak IC Msp Init Callback */
+ htim->IC_MspInitCallback = HAL_TIM_IC_MspInit;
+ break;
+
+ case HAL_TIM_IC_MSPDEINIT_CB_ID :
+ /* Legacy weak IC Msp DeInit Callback */
+ htim->IC_MspDeInitCallback = HAL_TIM_IC_MspDeInit;
+ break;
+
+ case HAL_TIM_OC_MSPINIT_CB_ID :
+ /* Legacy weak OC Msp Init Callback */
+ htim->OC_MspInitCallback = HAL_TIM_OC_MspInit;
+ break;
+
+ case HAL_TIM_OC_MSPDEINIT_CB_ID :
+ /* Legacy weak OC Msp DeInit Callback */
+ htim->OC_MspDeInitCallback = HAL_TIM_OC_MspDeInit;
+ break;
+
+ case HAL_TIM_PWM_MSPINIT_CB_ID :
+ /* Legacy weak PWM Msp Init Callback */
+ htim->PWM_MspInitCallback = HAL_TIM_PWM_MspInit;
+ break;
+
+ case HAL_TIM_PWM_MSPDEINIT_CB_ID :
+ /* Legacy weak PWM Msp DeInit Callback */
+ htim->PWM_MspDeInitCallback = HAL_TIM_PWM_MspDeInit;
+ break;
+
+ case HAL_TIM_ONE_PULSE_MSPINIT_CB_ID :
+ /* Legacy weak One Pulse Msp Init Callback */
+ htim->OnePulse_MspInitCallback = HAL_TIM_OnePulse_MspInit;
+ break;
+
+ case HAL_TIM_ONE_PULSE_MSPDEINIT_CB_ID :
+ /* Legacy weak One Pulse Msp DeInit Callback */
+ htim->OnePulse_MspDeInitCallback = HAL_TIM_OnePulse_MspDeInit;
+ break;
+
+ case HAL_TIM_ENCODER_MSPINIT_CB_ID :
+ /* Legacy weak Encoder Msp Init Callback */
+ htim->Encoder_MspInitCallback = HAL_TIM_Encoder_MspInit;
+ break;
+
+ case HAL_TIM_ENCODER_MSPDEINIT_CB_ID :
+ /* Legacy weak Encoder Msp DeInit Callback */
+ htim->Encoder_MspDeInitCallback = HAL_TIM_Encoder_MspDeInit;
+ break;
+
+ case HAL_TIM_HALL_SENSOR_MSPINIT_CB_ID :
+ /* Legacy weak Hall Sensor Msp Init Callback */
+ htim->HallSensor_MspInitCallback = HAL_TIMEx_HallSensor_MspInit;
+ break;
+
+ case HAL_TIM_HALL_SENSOR_MSPDEINIT_CB_ID :
+ /* Legacy weak Hall Sensor Msp DeInit Callback */
+ htim->HallSensor_MspDeInitCallback = HAL_TIMEx_HallSensor_MspDeInit;
+ break;
+
+ default :
+ /* Return error status */
+ status = HAL_ERROR;
+ break;
+ }
+ }
+ else
+ {
+ /* Return error status */
+ status = HAL_ERROR;
+ }
+
+ /* Release Lock */
+ __HAL_UNLOCK(htim);
+
+ return status;
+}
+#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */
+
+/**
+ * @}
+ */
+
+/** @defgroup TIM_Exported_Functions_Group10 TIM Peripheral State functions
+ * @brief TIM Peripheral State functions
+ *
+@verbatim
+ ==============================================================================
+ ##### Peripheral State functions #####
+ ==============================================================================
+ [..]
+ This subsection permits to get in run-time the status of the peripheral
+ and the data flow.
+
+@endverbatim
+ * @{
+ */
+
+/**
+ * @brief Return the TIM Base handle state.
+ * @param htim TIM Base handle
+ * @retval HAL state
+ */
+HAL_TIM_StateTypeDef HAL_TIM_Base_GetState(TIM_HandleTypeDef *htim)
+{
+ return htim->State;
+}
+
+/**
+ * @brief Return the TIM OC handle state.
+ * @param htim TIM Output Compare handle
+ * @retval HAL state
+ */
+HAL_TIM_StateTypeDef HAL_TIM_OC_GetState(TIM_HandleTypeDef *htim)
+{
+ return htim->State;
+}
+
+/**
+ * @brief Return the TIM PWM handle state.
+ * @param htim TIM handle
+ * @retval HAL state
+ */
+HAL_TIM_StateTypeDef HAL_TIM_PWM_GetState(TIM_HandleTypeDef *htim)
+{
+ return htim->State;
+}
+
+/**
+ * @brief Return the TIM Input Capture handle state.
+ * @param htim TIM IC handle
+ * @retval HAL state
+ */
+HAL_TIM_StateTypeDef HAL_TIM_IC_GetState(TIM_HandleTypeDef *htim)
+{
+ return htim->State;
+}
+
+/**
+ * @brief Return the TIM One Pulse Mode handle state.
+ * @param htim TIM OPM handle
+ * @retval HAL state
+ */
+HAL_TIM_StateTypeDef HAL_TIM_OnePulse_GetState(TIM_HandleTypeDef *htim)
+{
+ return htim->State;
+}
+
+/**
+ * @brief Return the TIM Encoder Mode handle state.
+ * @param htim TIM Encoder Interface handle
+ * @retval HAL state
+ */
+HAL_TIM_StateTypeDef HAL_TIM_Encoder_GetState(TIM_HandleTypeDef *htim)
+{
+ return htim->State;
+}
+
+/**
+ * @brief Return the TIM Encoder Mode handle state.
+ * @param htim TIM handle
+ * @retval Active channel
+ */
+HAL_TIM_ActiveChannel HAL_TIM_GetActiveChannel(TIM_HandleTypeDef *htim)
+{
+ return htim->Channel;
+}
+
+/**
+ * @brief Return actual state of the TIM channel.
+ * @param htim TIM handle
+ * @param Channel TIM Channel
+ * This parameter can be one of the following values:
+ * @arg TIM_CHANNEL_1: TIM Channel 1
+ * @arg TIM_CHANNEL_2: TIM Channel 2
+ * @arg TIM_CHANNEL_3: TIM Channel 3
+ * @arg TIM_CHANNEL_4: TIM Channel 4
+ * @arg TIM_CHANNEL_5: TIM Channel 5
+ * @arg TIM_CHANNEL_6: TIM Channel 6
+ * @retval TIM Channel state
+ */
+HAL_TIM_ChannelStateTypeDef HAL_TIM_GetChannelState(TIM_HandleTypeDef *htim, uint32_t Channel)
+{
+ HAL_TIM_ChannelStateTypeDef channel_state;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel));
+
+ channel_state = TIM_CHANNEL_STATE_GET(htim, Channel);
+
+ return channel_state;
+}
+
+/**
+ * @brief Return actual state of a DMA burst operation.
+ * @param htim TIM handle
+ * @retval DMA burst state
+ */
+HAL_TIM_DMABurstStateTypeDef HAL_TIM_DMABurstState(TIM_HandleTypeDef *htim)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_DMABURST_INSTANCE(htim->Instance));
+
+ return htim->DMABurstState;
+}
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/** @defgroup TIM_Private_Functions TIM Private Functions
+ * @{
+ */
+
+/**
+ * @brief TIM DMA error callback
+ * @param hdma pointer to DMA handle.
+ * @retval None
+ */
+void TIM_DMAError(DMA_HandleTypeDef *hdma)
+{
+ TIM_HandleTypeDef *htim = (TIM_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent;
+
+ if (hdma == htim->hdma[TIM_DMA_ID_CC1])
+ {
+ htim->Channel = HAL_TIM_ACTIVE_CHANNEL_1;
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY);
+ }
+ else if (hdma == htim->hdma[TIM_DMA_ID_CC2])
+ {
+ htim->Channel = HAL_TIM_ACTIVE_CHANNEL_2;
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY);
+ }
+ else if (hdma == htim->hdma[TIM_DMA_ID_CC3])
+ {
+ htim->Channel = HAL_TIM_ACTIVE_CHANNEL_3;
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_3, HAL_TIM_CHANNEL_STATE_READY);
+ }
+ else if (hdma == htim->hdma[TIM_DMA_ID_CC4])
+ {
+ htim->Channel = HAL_TIM_ACTIVE_CHANNEL_4;
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_4, HAL_TIM_CHANNEL_STATE_READY);
+ }
+ else
+ {
+ htim->State = HAL_TIM_STATE_READY;
+ }
+
+#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1)
+ htim->ErrorCallback(htim);
+#else
+ HAL_TIM_ErrorCallback(htim);
+#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */
+
+ htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED;
+}
+
+/**
+ * @brief TIM DMA Delay Pulse complete callback.
+ * @param hdma pointer to DMA handle.
+ * @retval None
+ */
+static void TIM_DMADelayPulseCplt(DMA_HandleTypeDef *hdma)
+{
+ TIM_HandleTypeDef *htim = (TIM_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent;
+
+ if (hdma == htim->hdma[TIM_DMA_ID_CC1])
+ {
+ htim->Channel = HAL_TIM_ACTIVE_CHANNEL_1;
+
+ if (hdma->Init.Mode == DMA_NORMAL)
+ {
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY);
+ }
+ }
+ else if (hdma == htim->hdma[TIM_DMA_ID_CC2])
+ {
+ htim->Channel = HAL_TIM_ACTIVE_CHANNEL_2;
+
+ if (hdma->Init.Mode == DMA_NORMAL)
+ {
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY);
+ }
+ }
+ else if (hdma == htim->hdma[TIM_DMA_ID_CC3])
+ {
+ htim->Channel = HAL_TIM_ACTIVE_CHANNEL_3;
+
+ if (hdma->Init.Mode == DMA_NORMAL)
+ {
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_3, HAL_TIM_CHANNEL_STATE_READY);
+ }
+ }
+ else if (hdma == htim->hdma[TIM_DMA_ID_CC4])
+ {
+ htim->Channel = HAL_TIM_ACTIVE_CHANNEL_4;
+
+ if (hdma->Init.Mode == DMA_NORMAL)
+ {
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_4, HAL_TIM_CHANNEL_STATE_READY);
+ }
+ }
+ else
+ {
+ /* nothing to do */
+ }
+
+#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1)
+ htim->PWM_PulseFinishedCallback(htim);
+#else
+ HAL_TIM_PWM_PulseFinishedCallback(htim);
+#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */
+
+ htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED;
+}
+
+/**
+ * @brief TIM DMA Delay Pulse half complete callback.
+ * @param hdma pointer to DMA handle.
+ * @retval None
+ */
+void TIM_DMADelayPulseHalfCplt(DMA_HandleTypeDef *hdma)
+{
+ TIM_HandleTypeDef *htim = (TIM_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent;
+
+ if (hdma == htim->hdma[TIM_DMA_ID_CC1])
+ {
+ htim->Channel = HAL_TIM_ACTIVE_CHANNEL_1;
+ }
+ else if (hdma == htim->hdma[TIM_DMA_ID_CC2])
+ {
+ htim->Channel = HAL_TIM_ACTIVE_CHANNEL_2;
+ }
+ else if (hdma == htim->hdma[TIM_DMA_ID_CC3])
+ {
+ htim->Channel = HAL_TIM_ACTIVE_CHANNEL_3;
+ }
+ else if (hdma == htim->hdma[TIM_DMA_ID_CC4])
+ {
+ htim->Channel = HAL_TIM_ACTIVE_CHANNEL_4;
+ }
+ else
+ {
+ /* nothing to do */
+ }
+
+#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1)
+ htim->PWM_PulseFinishedHalfCpltCallback(htim);
+#else
+ HAL_TIM_PWM_PulseFinishedHalfCpltCallback(htim);
+#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */
+
+ htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED;
+}
+
+/**
+ * @brief TIM DMA Capture complete callback.
+ * @param hdma pointer to DMA handle.
+ * @retval None
+ */
+void TIM_DMACaptureCplt(DMA_HandleTypeDef *hdma)
+{
+ TIM_HandleTypeDef *htim = (TIM_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent;
+
+ if (hdma == htim->hdma[TIM_DMA_ID_CC1])
+ {
+ htim->Channel = HAL_TIM_ACTIVE_CHANNEL_1;
+
+ if (hdma->Init.Mode == DMA_NORMAL)
+ {
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY);
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY);
+ }
+ }
+ else if (hdma == htim->hdma[TIM_DMA_ID_CC2])
+ {
+ htim->Channel = HAL_TIM_ACTIVE_CHANNEL_2;
+
+ if (hdma->Init.Mode == DMA_NORMAL)
+ {
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY);
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY);
+ }
+ }
+ else if (hdma == htim->hdma[TIM_DMA_ID_CC3])
+ {
+ htim->Channel = HAL_TIM_ACTIVE_CHANNEL_3;
+
+ if (hdma->Init.Mode == DMA_NORMAL)
+ {
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_3, HAL_TIM_CHANNEL_STATE_READY);
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_3, HAL_TIM_CHANNEL_STATE_READY);
+ }
+ }
+ else if (hdma == htim->hdma[TIM_DMA_ID_CC4])
+ {
+ htim->Channel = HAL_TIM_ACTIVE_CHANNEL_4;
+
+ if (hdma->Init.Mode == DMA_NORMAL)
+ {
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_4, HAL_TIM_CHANNEL_STATE_READY);
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_4, HAL_TIM_CHANNEL_STATE_READY);
+ }
+ }
+ else
+ {
+ /* nothing to do */
+ }
+
+#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1)
+ htim->IC_CaptureCallback(htim);
+#else
+ HAL_TIM_IC_CaptureCallback(htim);
+#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */
+
+ htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED;
+}
+
+/**
+ * @brief TIM DMA Capture half complete callback.
+ * @param hdma pointer to DMA handle.
+ * @retval None
+ */
+void TIM_DMACaptureHalfCplt(DMA_HandleTypeDef *hdma)
+{
+ TIM_HandleTypeDef *htim = (TIM_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent;
+
+ if (hdma == htim->hdma[TIM_DMA_ID_CC1])
+ {
+ htim->Channel = HAL_TIM_ACTIVE_CHANNEL_1;
+ }
+ else if (hdma == htim->hdma[TIM_DMA_ID_CC2])
+ {
+ htim->Channel = HAL_TIM_ACTIVE_CHANNEL_2;
+ }
+ else if (hdma == htim->hdma[TIM_DMA_ID_CC3])
+ {
+ htim->Channel = HAL_TIM_ACTIVE_CHANNEL_3;
+ }
+ else if (hdma == htim->hdma[TIM_DMA_ID_CC4])
+ {
+ htim->Channel = HAL_TIM_ACTIVE_CHANNEL_4;
+ }
+ else
+ {
+ /* nothing to do */
+ }
+
+#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1)
+ htim->IC_CaptureHalfCpltCallback(htim);
+#else
+ HAL_TIM_IC_CaptureHalfCpltCallback(htim);
+#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */
+
+ htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED;
+}
+
+/**
+ * @brief TIM DMA Period Elapse complete callback.
+ * @param hdma pointer to DMA handle.
+ * @retval None
+ */
+static void TIM_DMAPeriodElapsedCplt(DMA_HandleTypeDef *hdma)
+{
+ TIM_HandleTypeDef *htim = (TIM_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent;
+
+ if (htim->hdma[TIM_DMA_ID_UPDATE]->Init.Mode == DMA_NORMAL)
+ {
+ htim->State = HAL_TIM_STATE_READY;
+ }
+
+#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1)
+ htim->PeriodElapsedCallback(htim);
+#else
+ HAL_TIM_PeriodElapsedCallback(htim);
+#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */
+}
+
+/**
+ * @brief TIM DMA Period Elapse half complete callback.
+ * @param hdma pointer to DMA handle.
+ * @retval None
+ */
+static void TIM_DMAPeriodElapsedHalfCplt(DMA_HandleTypeDef *hdma)
+{
+ TIM_HandleTypeDef *htim = (TIM_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent;
+
+#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1)
+ htim->PeriodElapsedHalfCpltCallback(htim);
+#else
+ HAL_TIM_PeriodElapsedHalfCpltCallback(htim);
+#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */
+}
+
+/**
+ * @brief TIM DMA Trigger callback.
+ * @param hdma pointer to DMA handle.
+ * @retval None
+ */
+static void TIM_DMATriggerCplt(DMA_HandleTypeDef *hdma)
+{
+ TIM_HandleTypeDef *htim = (TIM_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent;
+
+ if (htim->hdma[TIM_DMA_ID_TRIGGER]->Init.Mode == DMA_NORMAL)
+ {
+ htim->State = HAL_TIM_STATE_READY;
+ }
+
+#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1)
+ htim->TriggerCallback(htim);
+#else
+ HAL_TIM_TriggerCallback(htim);
+#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */
+}
+
+/**
+ * @brief TIM DMA Trigger half complete callback.
+ * @param hdma pointer to DMA handle.
+ * @retval None
+ */
+static void TIM_DMATriggerHalfCplt(DMA_HandleTypeDef *hdma)
+{
+ TIM_HandleTypeDef *htim = (TIM_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent;
+
+#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1)
+ htim->TriggerHalfCpltCallback(htim);
+#else
+ HAL_TIM_TriggerHalfCpltCallback(htim);
+#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */
+}
+
+/**
+ * @brief Time Base configuration
+ * @param TIMx TIM peripheral
+ * @param Structure TIM Base configuration structure
+ * @retval None
+ */
+void TIM_Base_SetConfig(TIM_TypeDef *TIMx, TIM_Base_InitTypeDef *Structure)
+{
+ uint32_t tmpcr1;
+ tmpcr1 = TIMx->CR1;
+
+ /* Set TIM Time Base Unit parameters ---------------------------------------*/
+ if (IS_TIM_COUNTER_MODE_SELECT_INSTANCE(TIMx))
+ {
+ /* Select the Counter Mode */
+ tmpcr1 &= ~(TIM_CR1_DIR | TIM_CR1_CMS);
+ tmpcr1 |= Structure->CounterMode;
+ }
+
+ if (IS_TIM_CLOCK_DIVISION_INSTANCE(TIMx))
+ {
+ /* Set the clock division */
+ tmpcr1 &= ~TIM_CR1_CKD;
+ tmpcr1 |= (uint32_t)Structure->ClockDivision;
+ }
+
+ /* Set the auto-reload preload */
+ MODIFY_REG(tmpcr1, TIM_CR1_ARPE, Structure->AutoReloadPreload);
+
+ TIMx->CR1 = tmpcr1;
+
+ /* Set the Autoreload value */
+ TIMx->ARR = (uint32_t)Structure->Period ;
+
+ /* Set the Prescaler value */
+ TIMx->PSC = Structure->Prescaler;
+
+ if (IS_TIM_REPETITION_COUNTER_INSTANCE(TIMx))
+ {
+ /* Set the Repetition Counter value */
+ TIMx->RCR = Structure->RepetitionCounter;
+ }
+
+ /* Generate an update event to reload the Prescaler
+ and the repetition counter (only for advanced timer) value immediately */
+ TIMx->EGR = TIM_EGR_UG;
+}
+
+/**
+ * @brief Timer Output Compare 1 configuration
+ * @param TIMx to select the TIM peripheral
+ * @param OC_Config The output configuration structure
+ * @retval None
+ */
+static void TIM_OC1_SetConfig(TIM_TypeDef *TIMx, TIM_OC_InitTypeDef *OC_Config)
+{
+ uint32_t tmpccmrx;
+ uint32_t tmpccer;
+ uint32_t tmpcr2;
+
+ /* Disable the Channel 1: Reset the CC1E Bit */
+ TIMx->CCER &= ~TIM_CCER_CC1E;
+
+ /* Get the TIMx CCER register value */
+ tmpccer = TIMx->CCER;
+ /* Get the TIMx CR2 register value */
+ tmpcr2 = TIMx->CR2;
+
+ /* Get the TIMx CCMR1 register value */
+ tmpccmrx = TIMx->CCMR1;
+
+ /* Reset the Output Compare Mode Bits */
+ tmpccmrx &= ~TIM_CCMR1_OC1M;
+ tmpccmrx &= ~TIM_CCMR1_CC1S;
+ /* Select the Output Compare Mode */
+ tmpccmrx |= OC_Config->OCMode;
+
+ /* Reset the Output Polarity level */
+ tmpccer &= ~TIM_CCER_CC1P;
+ /* Set the Output Compare Polarity */
+ tmpccer |= OC_Config->OCPolarity;
+
+ if (IS_TIM_CCXN_INSTANCE(TIMx, TIM_CHANNEL_1))
+ {
+ /* Check parameters */
+ assert_param(IS_TIM_OCN_POLARITY(OC_Config->OCNPolarity));
+
+ /* Reset the Output N Polarity level */
+ tmpccer &= ~TIM_CCER_CC1NP;
+ /* Set the Output N Polarity */
+ tmpccer |= OC_Config->OCNPolarity;
+ /* Reset the Output N State */
+ tmpccer &= ~TIM_CCER_CC1NE;
+ }
+
+ if (IS_TIM_BREAK_INSTANCE(TIMx))
+ {
+ /* Check parameters */
+ assert_param(IS_TIM_OCNIDLE_STATE(OC_Config->OCNIdleState));
+ assert_param(IS_TIM_OCIDLE_STATE(OC_Config->OCIdleState));
+
+ /* Reset the Output Compare and Output Compare N IDLE State */
+ tmpcr2 &= ~TIM_CR2_OIS1;
+ tmpcr2 &= ~TIM_CR2_OIS1N;
+ /* Set the Output Idle state */
+ tmpcr2 |= OC_Config->OCIdleState;
+ /* Set the Output N Idle state */
+ tmpcr2 |= OC_Config->OCNIdleState;
+ }
+
+ /* Write to TIMx CR2 */
+ TIMx->CR2 = tmpcr2;
+
+ /* Write to TIMx CCMR1 */
+ TIMx->CCMR1 = tmpccmrx;
+
+ /* Set the Capture Compare Register value */
+ TIMx->CCR1 = OC_Config->Pulse;
+
+ /* Write to TIMx CCER */
+ TIMx->CCER = tmpccer;
+}
+
+/**
+ * @brief Timer Output Compare 2 configuration
+ * @param TIMx to select the TIM peripheral
+ * @param OC_Config The output configuration structure
+ * @retval None
+ */
+void TIM_OC2_SetConfig(TIM_TypeDef *TIMx, TIM_OC_InitTypeDef *OC_Config)
+{
+ uint32_t tmpccmrx;
+ uint32_t tmpccer;
+ uint32_t tmpcr2;
+
+ /* Disable the Channel 2: Reset the CC2E Bit */
+ TIMx->CCER &= ~TIM_CCER_CC2E;
+
+ /* Get the TIMx CCER register value */
+ tmpccer = TIMx->CCER;
+ /* Get the TIMx CR2 register value */
+ tmpcr2 = TIMx->CR2;
+
+ /* Get the TIMx CCMR1 register value */
+ tmpccmrx = TIMx->CCMR1;
+
+ /* Reset the Output Compare mode and Capture/Compare selection Bits */
+ tmpccmrx &= ~TIM_CCMR1_OC2M;
+ tmpccmrx &= ~TIM_CCMR1_CC2S;
+
+ /* Select the Output Compare Mode */
+ tmpccmrx |= (OC_Config->OCMode << 8U);
+
+ /* Reset the Output Polarity level */
+ tmpccer &= ~TIM_CCER_CC2P;
+ /* Set the Output Compare Polarity */
+ tmpccer |= (OC_Config->OCPolarity << 4U);
+
+ if (IS_TIM_CCXN_INSTANCE(TIMx, TIM_CHANNEL_2))
+ {
+ assert_param(IS_TIM_OCN_POLARITY(OC_Config->OCNPolarity));
+
+ /* Reset the Output N Polarity level */
+ tmpccer &= ~TIM_CCER_CC2NP;
+ /* Set the Output N Polarity */
+ tmpccer |= (OC_Config->OCNPolarity << 4U);
+ /* Reset the Output N State */
+ tmpccer &= ~TIM_CCER_CC2NE;
+
+ }
+
+ if (IS_TIM_BREAK_INSTANCE(TIMx))
+ {
+ /* Check parameters */
+ assert_param(IS_TIM_OCNIDLE_STATE(OC_Config->OCNIdleState));
+ assert_param(IS_TIM_OCIDLE_STATE(OC_Config->OCIdleState));
+
+ /* Reset the Output Compare and Output Compare N IDLE State */
+ tmpcr2 &= ~TIM_CR2_OIS2;
+ tmpcr2 &= ~TIM_CR2_OIS2N;
+ /* Set the Output Idle state */
+ tmpcr2 |= (OC_Config->OCIdleState << 2U);
+ /* Set the Output N Idle state */
+ tmpcr2 |= (OC_Config->OCNIdleState << 2U);
+ }
+
+ /* Write to TIMx CR2 */
+ TIMx->CR2 = tmpcr2;
+
+ /* Write to TIMx CCMR1 */
+ TIMx->CCMR1 = tmpccmrx;
+
+ /* Set the Capture Compare Register value */
+ TIMx->CCR2 = OC_Config->Pulse;
+
+ /* Write to TIMx CCER */
+ TIMx->CCER = tmpccer;
+}
+
+/**
+ * @brief Timer Output Compare 3 configuration
+ * @param TIMx to select the TIM peripheral
+ * @param OC_Config The output configuration structure
+ * @retval None
+ */
+static void TIM_OC3_SetConfig(TIM_TypeDef *TIMx, TIM_OC_InitTypeDef *OC_Config)
+{
+ uint32_t tmpccmrx;
+ uint32_t tmpccer;
+ uint32_t tmpcr2;
+
+ /* Disable the Channel 3: Reset the CC2E Bit */
+ TIMx->CCER &= ~TIM_CCER_CC3E;
+
+ /* Get the TIMx CCER register value */
+ tmpccer = TIMx->CCER;
+ /* Get the TIMx CR2 register value */
+ tmpcr2 = TIMx->CR2;
+
+ /* Get the TIMx CCMR2 register value */
+ tmpccmrx = TIMx->CCMR2;
+
+ /* Reset the Output Compare mode and Capture/Compare selection Bits */
+ tmpccmrx &= ~TIM_CCMR2_OC3M;
+ tmpccmrx &= ~TIM_CCMR2_CC3S;
+ /* Select the Output Compare Mode */
+ tmpccmrx |= OC_Config->OCMode;
+
+ /* Reset the Output Polarity level */
+ tmpccer &= ~TIM_CCER_CC3P;
+ /* Set the Output Compare Polarity */
+ tmpccer |= (OC_Config->OCPolarity << 8U);
+
+ if (IS_TIM_CCXN_INSTANCE(TIMx, TIM_CHANNEL_3))
+ {
+ assert_param(IS_TIM_OCN_POLARITY(OC_Config->OCNPolarity));
+
+ /* Reset the Output N Polarity level */
+ tmpccer &= ~TIM_CCER_CC3NP;
+ /* Set the Output N Polarity */
+ tmpccer |= (OC_Config->OCNPolarity << 8U);
+ /* Reset the Output N State */
+ tmpccer &= ~TIM_CCER_CC3NE;
+ }
+
+ if (IS_TIM_BREAK_INSTANCE(TIMx))
+ {
+ /* Check parameters */
+ assert_param(IS_TIM_OCNIDLE_STATE(OC_Config->OCNIdleState));
+ assert_param(IS_TIM_OCIDLE_STATE(OC_Config->OCIdleState));
+
+ /* Reset the Output Compare and Output Compare N IDLE State */
+ tmpcr2 &= ~TIM_CR2_OIS3;
+ tmpcr2 &= ~TIM_CR2_OIS3N;
+ /* Set the Output Idle state */
+ tmpcr2 |= (OC_Config->OCIdleState << 4U);
+ /* Set the Output N Idle state */
+ tmpcr2 |= (OC_Config->OCNIdleState << 4U);
+ }
+
+ /* Write to TIMx CR2 */
+ TIMx->CR2 = tmpcr2;
+
+ /* Write to TIMx CCMR2 */
+ TIMx->CCMR2 = tmpccmrx;
+
+ /* Set the Capture Compare Register value */
+ TIMx->CCR3 = OC_Config->Pulse;
+
+ /* Write to TIMx CCER */
+ TIMx->CCER = tmpccer;
+}
+
+/**
+ * @brief Timer Output Compare 4 configuration
+ * @param TIMx to select the TIM peripheral
+ * @param OC_Config The output configuration structure
+ * @retval None
+ */
+static void TIM_OC4_SetConfig(TIM_TypeDef *TIMx, TIM_OC_InitTypeDef *OC_Config)
+{
+ uint32_t tmpccmrx;
+ uint32_t tmpccer;
+ uint32_t tmpcr2;
+
+ /* Disable the Channel 4: Reset the CC4E Bit */
+ TIMx->CCER &= ~TIM_CCER_CC4E;
+
+ /* Get the TIMx CCER register value */
+ tmpccer = TIMx->CCER;
+ /* Get the TIMx CR2 register value */
+ tmpcr2 = TIMx->CR2;
+
+ /* Get the TIMx CCMR2 register value */
+ tmpccmrx = TIMx->CCMR2;
+
+ /* Reset the Output Compare mode and Capture/Compare selection Bits */
+ tmpccmrx &= ~TIM_CCMR2_OC4M;
+ tmpccmrx &= ~TIM_CCMR2_CC4S;
+
+ /* Select the Output Compare Mode */
+ tmpccmrx |= (OC_Config->OCMode << 8U);
+
+ /* Reset the Output Polarity level */
+ tmpccer &= ~TIM_CCER_CC4P;
+ /* Set the Output Compare Polarity */
+ tmpccer |= (OC_Config->OCPolarity << 12U);
+
+ if (IS_TIM_BREAK_INSTANCE(TIMx))
+ {
+ /* Check parameters */
+ assert_param(IS_TIM_OCIDLE_STATE(OC_Config->OCIdleState));
+
+ /* Reset the Output Compare IDLE State */
+ tmpcr2 &= ~TIM_CR2_OIS4;
+
+ /* Set the Output Idle state */
+ tmpcr2 |= (OC_Config->OCIdleState << 6U);
+ }
+
+ /* Write to TIMx CR2 */
+ TIMx->CR2 = tmpcr2;
+
+ /* Write to TIMx CCMR2 */
+ TIMx->CCMR2 = tmpccmrx;
+
+ /* Set the Capture Compare Register value */
+ TIMx->CCR4 = OC_Config->Pulse;
+
+ /* Write to TIMx CCER */
+ TIMx->CCER = tmpccer;
+}
+
+/**
+ * @brief Slave Timer configuration function
+ * @param htim TIM handle
+ * @param sSlaveConfig Slave timer configuration
+ * @retval None
+ */
+static HAL_StatusTypeDef TIM_SlaveTimer_SetConfig(TIM_HandleTypeDef *htim,
+ TIM_SlaveConfigTypeDef *sSlaveConfig)
+{
+ HAL_StatusTypeDef status = HAL_OK;
+ uint32_t tmpsmcr;
+ uint32_t tmpccmr1;
+ uint32_t tmpccer;
+
+ /* Get the TIMx SMCR register value */
+ tmpsmcr = htim->Instance->SMCR;
+
+ /* Reset the Trigger Selection Bits */
+ tmpsmcr &= ~TIM_SMCR_TS;
+ /* Set the Input Trigger source */
+ tmpsmcr |= sSlaveConfig->InputTrigger;
+
+ /* Reset the slave mode Bits */
+ tmpsmcr &= ~TIM_SMCR_SMS;
+ /* Set the slave mode */
+ tmpsmcr |= sSlaveConfig->SlaveMode;
+
+ /* Write to TIMx SMCR */
+ htim->Instance->SMCR = tmpsmcr;
+
+ /* Configure the trigger prescaler, filter, and polarity */
+ switch (sSlaveConfig->InputTrigger)
+ {
+ case TIM_TS_ETRF:
+ {
+ /* Check the parameters */
+ assert_param(IS_TIM_CLOCKSOURCE_ETRMODE1_INSTANCE(htim->Instance));
+ assert_param(IS_TIM_TRIGGERPRESCALER(sSlaveConfig->TriggerPrescaler));
+ assert_param(IS_TIM_TRIGGERPOLARITY(sSlaveConfig->TriggerPolarity));
+ assert_param(IS_TIM_TRIGGERFILTER(sSlaveConfig->TriggerFilter));
+ /* Configure the ETR Trigger source */
+ TIM_ETR_SetConfig(htim->Instance,
+ sSlaveConfig->TriggerPrescaler,
+ sSlaveConfig->TriggerPolarity,
+ sSlaveConfig->TriggerFilter);
+ break;
+ }
+
+ case TIM_TS_TI1F_ED:
+ {
+ /* Check the parameters */
+ assert_param(IS_TIM_CC1_INSTANCE(htim->Instance));
+ assert_param(IS_TIM_TRIGGERFILTER(sSlaveConfig->TriggerFilter));
+
+ if (sSlaveConfig->SlaveMode == TIM_SLAVEMODE_GATED)
+ {
+ return HAL_ERROR;
+ }
+
+ /* Disable the Channel 1: Reset the CC1E Bit */
+ tmpccer = htim->Instance->CCER;
+ htim->Instance->CCER &= ~TIM_CCER_CC1E;
+ tmpccmr1 = htim->Instance->CCMR1;
+
+ /* Set the filter */
+ tmpccmr1 &= ~TIM_CCMR1_IC1F;
+ tmpccmr1 |= ((sSlaveConfig->TriggerFilter) << 4U);
+
+ /* Write to TIMx CCMR1 and CCER registers */
+ htim->Instance->CCMR1 = tmpccmr1;
+ htim->Instance->CCER = tmpccer;
+ break;
+ }
+
+ case TIM_TS_TI1FP1:
+ {
+ /* Check the parameters */
+ assert_param(IS_TIM_CC1_INSTANCE(htim->Instance));
+ assert_param(IS_TIM_TRIGGERPOLARITY(sSlaveConfig->TriggerPolarity));
+ assert_param(IS_TIM_TRIGGERFILTER(sSlaveConfig->TriggerFilter));
+
+ /* Configure TI1 Filter and Polarity */
+ TIM_TI1_ConfigInputStage(htim->Instance,
+ sSlaveConfig->TriggerPolarity,
+ sSlaveConfig->TriggerFilter);
+ break;
+ }
+
+ case TIM_TS_TI2FP2:
+ {
+ /* Check the parameters */
+ assert_param(IS_TIM_CC2_INSTANCE(htim->Instance));
+ assert_param(IS_TIM_TRIGGERPOLARITY(sSlaveConfig->TriggerPolarity));
+ assert_param(IS_TIM_TRIGGERFILTER(sSlaveConfig->TriggerFilter));
+
+ /* Configure TI2 Filter and Polarity */
+ TIM_TI2_ConfigInputStage(htim->Instance,
+ sSlaveConfig->TriggerPolarity,
+ sSlaveConfig->TriggerFilter);
+ break;
+ }
+
+ case TIM_TS_ITR0:
+ case TIM_TS_ITR1:
+ case TIM_TS_ITR2:
+ case TIM_TS_ITR3:
+ {
+ /* Check the parameter */
+ assert_param(IS_TIM_CC2_INSTANCE(htim->Instance));
+ break;
+ }
+
+ default:
+ status = HAL_ERROR;
+ break;
+ }
+
+ return status;
+}
+
+/**
+ * @brief Configure the TI1 as Input.
+ * @param TIMx to select the TIM peripheral.
+ * @param TIM_ICPolarity The Input Polarity.
+ * This parameter can be one of the following values:
+ * @arg TIM_ICPOLARITY_RISING
+ * @arg TIM_ICPOLARITY_FALLING
+ * @arg TIM_ICPOLARITY_BOTHEDGE
+ * @param TIM_ICSelection specifies the input to be used.
+ * This parameter can be one of the following values:
+ * @arg TIM_ICSELECTION_DIRECTTI: TIM Input 1 is selected to be connected to IC1.
+ * @arg TIM_ICSELECTION_INDIRECTTI: TIM Input 1 is selected to be connected to IC2.
+ * @arg TIM_ICSELECTION_TRC: TIM Input 1 is selected to be connected to TRC.
+ * @param TIM_ICFilter Specifies the Input Capture Filter.
+ * This parameter must be a value between 0x00 and 0x0F.
+ * @retval None
+ * @note TIM_ICFilter and TIM_ICPolarity are not used in INDIRECT mode as TI2FP1
+ * (on channel2 path) is used as the input signal. Therefore CCMR1 must be
+ * protected against un-initialized filter and polarity values.
+ */
+void TIM_TI1_SetConfig(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32_t TIM_ICSelection,
+ uint32_t TIM_ICFilter)
+{
+ uint32_t tmpccmr1;
+ uint32_t tmpccer;
+
+ /* Disable the Channel 1: Reset the CC1E Bit */
+ TIMx->CCER &= ~TIM_CCER_CC1E;
+ tmpccmr1 = TIMx->CCMR1;
+ tmpccer = TIMx->CCER;
+
+ /* Select the Input */
+ if (IS_TIM_CC2_INSTANCE(TIMx) != RESET)
+ {
+ tmpccmr1 &= ~TIM_CCMR1_CC1S;
+ tmpccmr1 |= TIM_ICSelection;
+ }
+ else
+ {
+ tmpccmr1 |= TIM_CCMR1_CC1S_0;
+ }
+
+ /* Set the filter */
+ tmpccmr1 &= ~TIM_CCMR1_IC1F;
+ tmpccmr1 |= ((TIM_ICFilter << 4U) & TIM_CCMR1_IC1F);
+
+ /* Select the Polarity and set the CC1E Bit */
+ tmpccer &= ~(TIM_CCER_CC1P | TIM_CCER_CC1NP);
+ tmpccer |= (TIM_ICPolarity & (TIM_CCER_CC1P | TIM_CCER_CC1NP));
+
+ /* Write to TIMx CCMR1 and CCER registers */
+ TIMx->CCMR1 = tmpccmr1;
+ TIMx->CCER = tmpccer;
+}
+
+/**
+ * @brief Configure the Polarity and Filter for TI1.
+ * @param TIMx to select the TIM peripheral.
+ * @param TIM_ICPolarity The Input Polarity.
+ * This parameter can be one of the following values:
+ * @arg TIM_ICPOLARITY_RISING
+ * @arg TIM_ICPOLARITY_FALLING
+ * @arg TIM_ICPOLARITY_BOTHEDGE
+ * @param TIM_ICFilter Specifies the Input Capture Filter.
+ * This parameter must be a value between 0x00 and 0x0F.
+ * @retval None
+ */
+static void TIM_TI1_ConfigInputStage(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32_t TIM_ICFilter)
+{
+ uint32_t tmpccmr1;
+ uint32_t tmpccer;
+
+ /* Disable the Channel 1: Reset the CC1E Bit */
+ tmpccer = TIMx->CCER;
+ TIMx->CCER &= ~TIM_CCER_CC1E;
+ tmpccmr1 = TIMx->CCMR1;
+
+ /* Set the filter */
+ tmpccmr1 &= ~TIM_CCMR1_IC1F;
+ tmpccmr1 |= (TIM_ICFilter << 4U);
+
+ /* Select the Polarity and set the CC1E Bit */
+ tmpccer &= ~(TIM_CCER_CC1P | TIM_CCER_CC1NP);
+ tmpccer |= TIM_ICPolarity;
+
+ /* Write to TIMx CCMR1 and CCER registers */
+ TIMx->CCMR1 = tmpccmr1;
+ TIMx->CCER = tmpccer;
+}
+
+/**
+ * @brief Configure the TI2 as Input.
+ * @param TIMx to select the TIM peripheral
+ * @param TIM_ICPolarity The Input Polarity.
+ * This parameter can be one of the following values:
+ * @arg TIM_ICPOLARITY_RISING
+ * @arg TIM_ICPOLARITY_FALLING
+ * @arg TIM_ICPOLARITY_BOTHEDGE
+ * @param TIM_ICSelection specifies the input to be used.
+ * This parameter can be one of the following values:
+ * @arg TIM_ICSELECTION_DIRECTTI: TIM Input 2 is selected to be connected to IC2.
+ * @arg TIM_ICSELECTION_INDIRECTTI: TIM Input 2 is selected to be connected to IC1.
+ * @arg TIM_ICSELECTION_TRC: TIM Input 2 is selected to be connected to TRC.
+ * @param TIM_ICFilter Specifies the Input Capture Filter.
+ * This parameter must be a value between 0x00 and 0x0F.
+ * @retval None
+ * @note TIM_ICFilter and TIM_ICPolarity are not used in INDIRECT mode as TI1FP2
+ * (on channel1 path) is used as the input signal. Therefore CCMR1 must be
+ * protected against un-initialized filter and polarity values.
+ */
+static void TIM_TI2_SetConfig(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32_t TIM_ICSelection,
+ uint32_t TIM_ICFilter)
+{
+ uint32_t tmpccmr1;
+ uint32_t tmpccer;
+
+ /* Disable the Channel 2: Reset the CC2E Bit */
+ TIMx->CCER &= ~TIM_CCER_CC2E;
+ tmpccmr1 = TIMx->CCMR1;
+ tmpccer = TIMx->CCER;
+
+ /* Select the Input */
+ tmpccmr1 &= ~TIM_CCMR1_CC2S;
+ tmpccmr1 |= (TIM_ICSelection << 8U);
+
+ /* Set the filter */
+ tmpccmr1 &= ~TIM_CCMR1_IC2F;
+ tmpccmr1 |= ((TIM_ICFilter << 12U) & TIM_CCMR1_IC2F);
+
+ /* Select the Polarity and set the CC2E Bit */
+ tmpccer &= ~(TIM_CCER_CC2P | TIM_CCER_CC2NP);
+ tmpccer |= ((TIM_ICPolarity << 4U) & (TIM_CCER_CC2P | TIM_CCER_CC2NP));
+
+ /* Write to TIMx CCMR1 and CCER registers */
+ TIMx->CCMR1 = tmpccmr1 ;
+ TIMx->CCER = tmpccer;
+}
+
+/**
+ * @brief Configure the Polarity and Filter for TI2.
+ * @param TIMx to select the TIM peripheral.
+ * @param TIM_ICPolarity The Input Polarity.
+ * This parameter can be one of the following values:
+ * @arg TIM_ICPOLARITY_RISING
+ * @arg TIM_ICPOLARITY_FALLING
+ * @arg TIM_ICPOLARITY_BOTHEDGE
+ * @param TIM_ICFilter Specifies the Input Capture Filter.
+ * This parameter must be a value between 0x00 and 0x0F.
+ * @retval None
+ */
+static void TIM_TI2_ConfigInputStage(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32_t TIM_ICFilter)
+{
+ uint32_t tmpccmr1;
+ uint32_t tmpccer;
+
+ /* Disable the Channel 2: Reset the CC2E Bit */
+ TIMx->CCER &= ~TIM_CCER_CC2E;
+ tmpccmr1 = TIMx->CCMR1;
+ tmpccer = TIMx->CCER;
+
+ /* Set the filter */
+ tmpccmr1 &= ~TIM_CCMR1_IC2F;
+ tmpccmr1 |= (TIM_ICFilter << 12U);
+
+ /* Select the Polarity and set the CC2E Bit */
+ tmpccer &= ~(TIM_CCER_CC2P | TIM_CCER_CC2NP);
+ tmpccer |= (TIM_ICPolarity << 4U);
+
+ /* Write to TIMx CCMR1 and CCER registers */
+ TIMx->CCMR1 = tmpccmr1 ;
+ TIMx->CCER = tmpccer;
+}
+
+/**
+ * @brief Configure the TI3 as Input.
+ * @param TIMx to select the TIM peripheral
+ * @param TIM_ICPolarity The Input Polarity.
+ * This parameter can be one of the following values:
+ * @arg TIM_ICPOLARITY_RISING
+ * @arg TIM_ICPOLARITY_FALLING
+ * @arg TIM_ICPOLARITY_BOTHEDGE
+ * @param TIM_ICSelection specifies the input to be used.
+ * This parameter can be one of the following values:
+ * @arg TIM_ICSELECTION_DIRECTTI: TIM Input 3 is selected to be connected to IC3.
+ * @arg TIM_ICSELECTION_INDIRECTTI: TIM Input 3 is selected to be connected to IC4.
+ * @arg TIM_ICSELECTION_TRC: TIM Input 3 is selected to be connected to TRC.
+ * @param TIM_ICFilter Specifies the Input Capture Filter.
+ * This parameter must be a value between 0x00 and 0x0F.
+ * @retval None
+ * @note TIM_ICFilter and TIM_ICPolarity are not used in INDIRECT mode as TI3FP4
+ * (on channel1 path) is used as the input signal. Therefore CCMR2 must be
+ * protected against un-initialized filter and polarity values.
+ */
+static void TIM_TI3_SetConfig(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32_t TIM_ICSelection,
+ uint32_t TIM_ICFilter)
+{
+ uint32_t tmpccmr2;
+ uint32_t tmpccer;
+
+ /* Disable the Channel 3: Reset the CC3E Bit */
+ TIMx->CCER &= ~TIM_CCER_CC3E;
+ tmpccmr2 = TIMx->CCMR2;
+ tmpccer = TIMx->CCER;
+
+ /* Select the Input */
+ tmpccmr2 &= ~TIM_CCMR2_CC3S;
+ tmpccmr2 |= TIM_ICSelection;
+
+ /* Set the filter */
+ tmpccmr2 &= ~TIM_CCMR2_IC3F;
+ tmpccmr2 |= ((TIM_ICFilter << 4U) & TIM_CCMR2_IC3F);
+
+ /* Select the Polarity and set the CC3E Bit */
+ tmpccer &= ~(TIM_CCER_CC3P | TIM_CCER_CC3NP);
+ tmpccer |= ((TIM_ICPolarity << 8U) & (TIM_CCER_CC3P | TIM_CCER_CC3NP));
+
+ /* Write to TIMx CCMR2 and CCER registers */
+ TIMx->CCMR2 = tmpccmr2;
+ TIMx->CCER = tmpccer;
+}
+
+/**
+ * @brief Configure the TI4 as Input.
+ * @param TIMx to select the TIM peripheral
+ * @param TIM_ICPolarity The Input Polarity.
+ * This parameter can be one of the following values:
+ * @arg TIM_ICPOLARITY_RISING
+ * @arg TIM_ICPOLARITY_FALLING
+ * @arg TIM_ICPOLARITY_BOTHEDGE
+ * @param TIM_ICSelection specifies the input to be used.
+ * This parameter can be one of the following values:
+ * @arg TIM_ICSELECTION_DIRECTTI: TIM Input 4 is selected to be connected to IC4.
+ * @arg TIM_ICSELECTION_INDIRECTTI: TIM Input 4 is selected to be connected to IC3.
+ * @arg TIM_ICSELECTION_TRC: TIM Input 4 is selected to be connected to TRC.
+ * @param TIM_ICFilter Specifies the Input Capture Filter.
+ * This parameter must be a value between 0x00 and 0x0F.
+ * @note TIM_ICFilter and TIM_ICPolarity are not used in INDIRECT mode as TI4FP3
+ * (on channel1 path) is used as the input signal. Therefore CCMR2 must be
+ * protected against un-initialized filter and polarity values.
+ * @retval None
+ */
+static void TIM_TI4_SetConfig(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32_t TIM_ICSelection,
+ uint32_t TIM_ICFilter)
+{
+ uint32_t tmpccmr2;
+ uint32_t tmpccer;
+
+ /* Disable the Channel 4: Reset the CC4E Bit */
+ TIMx->CCER &= ~TIM_CCER_CC4E;
+ tmpccmr2 = TIMx->CCMR2;
+ tmpccer = TIMx->CCER;
+
+ /* Select the Input */
+ tmpccmr2 &= ~TIM_CCMR2_CC4S;
+ tmpccmr2 |= (TIM_ICSelection << 8U);
+
+ /* Set the filter */
+ tmpccmr2 &= ~TIM_CCMR2_IC4F;
+ tmpccmr2 |= ((TIM_ICFilter << 12U) & TIM_CCMR2_IC4F);
+
+ /* Select the Polarity and set the CC4E Bit */
+ tmpccer &= ~(TIM_CCER_CC4P | TIM_CCER_CC4NP);
+ tmpccer |= ((TIM_ICPolarity << 12U) & (TIM_CCER_CC4P | TIM_CCER_CC4NP));
+
+ /* Write to TIMx CCMR2 and CCER registers */
+ TIMx->CCMR2 = tmpccmr2;
+ TIMx->CCER = tmpccer ;
+}
+
+/**
+ * @brief Selects the Input Trigger source
+ * @param TIMx to select the TIM peripheral
+ * @param InputTriggerSource The Input Trigger source.
+ * This parameter can be one of the following values:
+ * @arg TIM_TS_ITR0: Internal Trigger 0
+ * @arg TIM_TS_ITR1: Internal Trigger 1
+ * @arg TIM_TS_ITR2: Internal Trigger 2
+ * @arg TIM_TS_ITR3: Internal Trigger 3
+ * @arg TIM_TS_TI1F_ED: TI1 Edge Detector
+ * @arg TIM_TS_TI1FP1: Filtered Timer Input 1
+ * @arg TIM_TS_TI2FP2: Filtered Timer Input 2
+ * @arg TIM_TS_ETRF: External Trigger input
+ * @retval None
+ */
+static void TIM_ITRx_SetConfig(TIM_TypeDef *TIMx, uint32_t InputTriggerSource)
+{
+ uint32_t tmpsmcr;
+
+ /* Get the TIMx SMCR register value */
+ tmpsmcr = TIMx->SMCR;
+ /* Reset the TS Bits */
+ tmpsmcr &= ~TIM_SMCR_TS;
+ /* Set the Input Trigger source and the slave mode*/
+ tmpsmcr |= (InputTriggerSource | TIM_SLAVEMODE_EXTERNAL1);
+ /* Write to TIMx SMCR */
+ TIMx->SMCR = tmpsmcr;
+}
+/**
+ * @brief Configures the TIMx External Trigger (ETR).
+ * @param TIMx to select the TIM peripheral
+ * @param TIM_ExtTRGPrescaler The external Trigger Prescaler.
+ * This parameter can be one of the following values:
+ * @arg TIM_ETRPRESCALER_DIV1: ETRP Prescaler OFF.
+ * @arg TIM_ETRPRESCALER_DIV2: ETRP frequency divided by 2.
+ * @arg TIM_ETRPRESCALER_DIV4: ETRP frequency divided by 4.
+ * @arg TIM_ETRPRESCALER_DIV8: ETRP frequency divided by 8.
+ * @param TIM_ExtTRGPolarity The external Trigger Polarity.
+ * This parameter can be one of the following values:
+ * @arg TIM_ETRPOLARITY_INVERTED: active low or falling edge active.
+ * @arg TIM_ETRPOLARITY_NONINVERTED: active high or rising edge active.
+ * @param ExtTRGFilter External Trigger Filter.
+ * This parameter must be a value between 0x00 and 0x0F
+ * @retval None
+ */
+void TIM_ETR_SetConfig(TIM_TypeDef *TIMx, uint32_t TIM_ExtTRGPrescaler,
+ uint32_t TIM_ExtTRGPolarity, uint32_t ExtTRGFilter)
+{
+ uint32_t tmpsmcr;
+
+ tmpsmcr = TIMx->SMCR;
+
+ /* Reset the ETR Bits */
+ tmpsmcr &= ~(TIM_SMCR_ETF | TIM_SMCR_ETPS | TIM_SMCR_ECE | TIM_SMCR_ETP);
+
+ /* Set the Prescaler, the Filter value and the Polarity */
+ tmpsmcr |= (uint32_t)(TIM_ExtTRGPrescaler | (TIM_ExtTRGPolarity | (ExtTRGFilter << 8U)));
+
+ /* Write to TIMx SMCR */
+ TIMx->SMCR = tmpsmcr;
+}
+
+/**
+ * @brief Enables or disables the TIM Capture Compare Channel x.
+ * @param TIMx to select the TIM peripheral
+ * @param Channel specifies the TIM Channel
+ * This parameter can be one of the following values:
+ * @arg TIM_CHANNEL_1: TIM Channel 1
+ * @arg TIM_CHANNEL_2: TIM Channel 2
+ * @arg TIM_CHANNEL_3: TIM Channel 3
+ * @arg TIM_CHANNEL_4: TIM Channel 4
+ * @param ChannelState specifies the TIM Channel CCxE bit new state.
+ * This parameter can be: TIM_CCx_ENABLE or TIM_CCx_DISABLE.
+ * @retval None
+ */
+void TIM_CCxChannelCmd(TIM_TypeDef *TIMx, uint32_t Channel, uint32_t ChannelState)
+{
+ uint32_t tmp;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_CC1_INSTANCE(TIMx));
+ assert_param(IS_TIM_CHANNELS(Channel));
+
+ tmp = TIM_CCER_CC1E << (Channel & 0x1FU); /* 0x1FU = 31 bits max shift */
+
+ /* Reset the CCxE Bit */
+ TIMx->CCER &= ~tmp;
+
+ /* Set or reset the CCxE Bit */
+ TIMx->CCER |= (uint32_t)(ChannelState << (Channel & 0x1FU)); /* 0x1FU = 31 bits max shift */
+}
+
+#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1)
+/**
+ * @brief Reset interrupt callbacks to the legacy weak callbacks.
+ * @param htim pointer to a TIM_HandleTypeDef structure that contains
+ * the configuration information for TIM module.
+ * @retval None
+ */
+void TIM_ResetCallback(TIM_HandleTypeDef *htim)
+{
+ /* Reset the TIM callback to the legacy weak callbacks */
+ htim->PeriodElapsedCallback = HAL_TIM_PeriodElapsedCallback;
+ htim->PeriodElapsedHalfCpltCallback = HAL_TIM_PeriodElapsedHalfCpltCallback;
+ htim->TriggerCallback = HAL_TIM_TriggerCallback;
+ htim->TriggerHalfCpltCallback = HAL_TIM_TriggerHalfCpltCallback;
+ htim->IC_CaptureCallback = HAL_TIM_IC_CaptureCallback;
+ htim->IC_CaptureHalfCpltCallback = HAL_TIM_IC_CaptureHalfCpltCallback;
+ htim->OC_DelayElapsedCallback = HAL_TIM_OC_DelayElapsedCallback;
+ htim->PWM_PulseFinishedCallback = HAL_TIM_PWM_PulseFinishedCallback;
+ htim->PWM_PulseFinishedHalfCpltCallback = HAL_TIM_PWM_PulseFinishedHalfCpltCallback;
+ htim->ErrorCallback = HAL_TIM_ErrorCallback;
+ htim->CommutationCallback = HAL_TIMEx_CommutCallback;
+ htim->CommutationHalfCpltCallback = HAL_TIMEx_CommutHalfCpltCallback;
+ htim->BreakCallback = HAL_TIMEx_BreakCallback;
+}
+#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */
+
+/**
+ * @}
+ */
+
+#endif /* HAL_TIM_MODULE_ENABLED */
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_tim_ex.c b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_tim_ex.c
new file mode 100644
index 0000000..b521940
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_tim_ex.c
@@ -0,0 +1,2390 @@
+/**
+ ******************************************************************************
+ * @file stm32f0xx_hal_tim_ex.c
+ * @author MCD Application Team
+ * @brief TIM HAL module driver.
+ * This file provides firmware functions to manage the following
+ * functionalities of the Timer Extended peripheral:
+ * + Time Hall Sensor Interface Initialization
+ * + Time Hall Sensor Interface Start
+ * + Time Complementary signal break and dead time configuration
+ * + Time Master and Slave synchronization configuration
+ * + Time OCRef clear configuration
+ * + Timer remapping capabilities configuration
+ @verbatim
+ ==============================================================================
+ ##### TIMER Extended features #####
+ ==============================================================================
+ [..]
+ The Timer Extended features include:
+ (#) Complementary outputs with programmable dead-time for :
+ (++) Output Compare
+ (++) PWM generation (Edge and Center-aligned Mode)
+ (++) One-pulse mode output
+ (#) Synchronization circuit to control the timer with external signals and to
+ interconnect several timers together.
+ (#) Break input to put the timer output signals in reset state or in a known state.
+ (#) Supports incremental (quadrature) encoder and hall-sensor circuitry for
+ positioning purposes
+
+ ##### How to use this driver #####
+ ==============================================================================
+ [..]
+ (#) Initialize the TIM low level resources by implementing the following functions
+ depending on the selected feature:
+ (++) Hall Sensor output : HAL_TIMEx_HallSensor_MspInit()
+
+ (#) Initialize the TIM low level resources :
+ (##) Enable the TIM interface clock using __HAL_RCC_TIMx_CLK_ENABLE();
+ (##) TIM pins configuration
+ (+++) Enable the clock for the TIM GPIOs using the following function:
+ __HAL_RCC_GPIOx_CLK_ENABLE();
+ (+++) Configure these TIM pins in Alternate function mode using HAL_GPIO_Init();
+
+ (#) The external Clock can be configured, if needed (the default clock is the
+ internal clock from the APBx), using the following function:
+ HAL_TIM_ConfigClockSource, the clock configuration should be done before
+ any start function.
+
+ (#) Configure the TIM in the desired functioning mode using one of the
+ initialization function of this driver:
+ (++) HAL_TIMEx_HallSensor_Init() and HAL_TIMEx_ConfigCommutEvent(): to use the
+ Timer Hall Sensor Interface and the commutation event with the corresponding
+ Interrupt and DMA request if needed (Note that One Timer is used to interface
+ with the Hall sensor Interface and another Timer should be used to use
+ the commutation event).
+
+ (#) Activate the TIM peripheral using one of the start functions:
+ (++) Complementary Output Compare : HAL_TIMEx_OCN_Start(), HAL_TIMEx_OCN_Start_DMA(),
+ HAL_TIMEx_OCN_Start_IT()
+ (++) Complementary PWM generation : HAL_TIMEx_PWMN_Start(), HAL_TIMEx_PWMN_Start_DMA(),
+ HAL_TIMEx_PWMN_Start_IT()
+ (++) Complementary One-pulse mode output : HAL_TIMEx_OnePulseN_Start(), HAL_TIMEx_OnePulseN_Start_IT()
+ (++) Hall Sensor output : HAL_TIMEx_HallSensor_Start(), HAL_TIMEx_HallSensor_Start_DMA(),
+ HAL_TIMEx_HallSensor_Start_IT().
+
+ @endverbatim
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2016 STMicroelectronics.
+ * All rights reserved.
+ *
+ * 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 "stm32f0xx_hal.h"
+
+/** @addtogroup STM32F0xx_HAL_Driver
+ * @{
+ */
+
+/** @defgroup TIMEx TIMEx
+ * @brief TIM Extended HAL module driver
+ * @{
+ */
+
+#ifdef HAL_TIM_MODULE_ENABLED
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macros ------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+static void TIM_DMADelayPulseNCplt(DMA_HandleTypeDef *hdma);
+static void TIM_DMAErrorCCxN(DMA_HandleTypeDef *hdma);
+static void TIM_CCxNChannelCmd(TIM_TypeDef *TIMx, uint32_t Channel, uint32_t ChannelNState);
+
+/* Exported functions --------------------------------------------------------*/
+/** @defgroup TIMEx_Exported_Functions TIM Extended Exported Functions
+ * @{
+ */
+
+/** @defgroup TIMEx_Exported_Functions_Group1 Extended Timer Hall Sensor functions
+ * @brief Timer Hall Sensor functions
+ *
+@verbatim
+ ==============================================================================
+ ##### Timer Hall Sensor functions #####
+ ==============================================================================
+ [..]
+ This section provides functions allowing to:
+ (+) Initialize and configure TIM HAL Sensor.
+ (+) De-initialize TIM HAL Sensor.
+ (+) Start the Hall Sensor Interface.
+ (+) Stop the Hall Sensor Interface.
+ (+) Start the Hall Sensor Interface and enable interrupts.
+ (+) Stop the Hall Sensor Interface and disable interrupts.
+ (+) Start the Hall Sensor Interface and enable DMA transfers.
+ (+) Stop the Hall Sensor Interface and disable DMA transfers.
+
+@endverbatim
+ * @{
+ */
+/**
+ * @brief Initializes the TIM Hall Sensor Interface and initialize the associated handle.
+ * @note When the timer instance is initialized in Hall Sensor Interface mode,
+ * timer channels 1 and channel 2 are reserved and cannot be used for
+ * other purpose.
+ * @param htim TIM Hall Sensor Interface handle
+ * @param sConfig TIM Hall Sensor configuration structure
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIMEx_HallSensor_Init(TIM_HandleTypeDef *htim, TIM_HallSensor_InitTypeDef *sConfig)
+{
+ TIM_OC_InitTypeDef OC_Config;
+
+ /* Check the TIM handle allocation */
+ if (htim == NULL)
+ {
+ return HAL_ERROR;
+ }
+
+ /* Check the parameters */
+ assert_param(IS_TIM_HALL_SENSOR_INTERFACE_INSTANCE(htim->Instance));
+ assert_param(IS_TIM_COUNTER_MODE(htim->Init.CounterMode));
+ assert_param(IS_TIM_CLOCKDIVISION_DIV(htim->Init.ClockDivision));
+ assert_param(IS_TIM_AUTORELOAD_PRELOAD(htim->Init.AutoReloadPreload));
+ assert_param(IS_TIM_IC_POLARITY(sConfig->IC1Polarity));
+ assert_param(IS_TIM_IC_PRESCALER(sConfig->IC1Prescaler));
+ assert_param(IS_TIM_IC_FILTER(sConfig->IC1Filter));
+
+ if (htim->State == HAL_TIM_STATE_RESET)
+ {
+ /* Allocate lock resource and initialize it */
+ htim->Lock = HAL_UNLOCKED;
+
+#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1)
+ /* Reset interrupt callbacks to legacy week callbacks */
+ TIM_ResetCallback(htim);
+
+ if (htim->HallSensor_MspInitCallback == NULL)
+ {
+ htim->HallSensor_MspInitCallback = HAL_TIMEx_HallSensor_MspInit;
+ }
+ /* Init the low level hardware : GPIO, CLOCK, NVIC */
+ htim->HallSensor_MspInitCallback(htim);
+#else
+ /* Init the low level hardware : GPIO, CLOCK, NVIC and DMA */
+ HAL_TIMEx_HallSensor_MspInit(htim);
+#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */
+ }
+
+ /* Set the TIM state */
+ htim->State = HAL_TIM_STATE_BUSY;
+
+ /* Configure the Time base in the Encoder Mode */
+ TIM_Base_SetConfig(htim->Instance, &htim->Init);
+
+ /* Configure the Channel 1 as Input Channel to interface with the three Outputs of the Hall sensor */
+ TIM_TI1_SetConfig(htim->Instance, sConfig->IC1Polarity, TIM_ICSELECTION_TRC, sConfig->IC1Filter);
+
+ /* Reset the IC1PSC Bits */
+ htim->Instance->CCMR1 &= ~TIM_CCMR1_IC1PSC;
+ /* Set the IC1PSC value */
+ htim->Instance->CCMR1 |= sConfig->IC1Prescaler;
+
+ /* Enable the Hall sensor interface (XOR function of the three inputs) */
+ htim->Instance->CR2 |= TIM_CR2_TI1S;
+
+ /* Select the TIM_TS_TI1F_ED signal as Input trigger for the TIM */
+ htim->Instance->SMCR &= ~TIM_SMCR_TS;
+ htim->Instance->SMCR |= TIM_TS_TI1F_ED;
+
+ /* Use the TIM_TS_TI1F_ED signal to reset the TIM counter each edge detection */
+ htim->Instance->SMCR &= ~TIM_SMCR_SMS;
+ htim->Instance->SMCR |= TIM_SLAVEMODE_RESET;
+
+ /* Program channel 2 in PWM 2 mode with the desired Commutation_Delay*/
+ OC_Config.OCFastMode = TIM_OCFAST_DISABLE;
+ OC_Config.OCIdleState = TIM_OCIDLESTATE_RESET;
+ OC_Config.OCMode = TIM_OCMODE_PWM2;
+ OC_Config.OCNIdleState = TIM_OCNIDLESTATE_RESET;
+ OC_Config.OCNPolarity = TIM_OCNPOLARITY_HIGH;
+ OC_Config.OCPolarity = TIM_OCPOLARITY_HIGH;
+ OC_Config.Pulse = sConfig->Commutation_Delay;
+
+ TIM_OC2_SetConfig(htim->Instance, &OC_Config);
+
+ /* Select OC2REF as trigger output on TRGO: write the MMS bits in the TIMx_CR2
+ register to 101 */
+ htim->Instance->CR2 &= ~TIM_CR2_MMS;
+ htim->Instance->CR2 |= TIM_TRGO_OC2REF;
+
+ /* Initialize the DMA burst operation state */
+ htim->DMABurstState = HAL_DMA_BURST_STATE_READY;
+
+ /* Initialize the TIM channels state */
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY);
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY);
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY);
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY);
+
+ /* Initialize the TIM state*/
+ htim->State = HAL_TIM_STATE_READY;
+
+ return HAL_OK;
+}
+
+/**
+ * @brief DeInitializes the TIM Hall Sensor interface
+ * @param htim TIM Hall Sensor Interface handle
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIMEx_HallSensor_DeInit(TIM_HandleTypeDef *htim)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_INSTANCE(htim->Instance));
+
+ htim->State = HAL_TIM_STATE_BUSY;
+
+ /* Disable the TIM Peripheral Clock */
+ __HAL_TIM_DISABLE(htim);
+
+#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1)
+ if (htim->HallSensor_MspDeInitCallback == NULL)
+ {
+ htim->HallSensor_MspDeInitCallback = HAL_TIMEx_HallSensor_MspDeInit;
+ }
+ /* DeInit the low level hardware */
+ htim->HallSensor_MspDeInitCallback(htim);
+#else
+ /* DeInit the low level hardware: GPIO, CLOCK, NVIC */
+ HAL_TIMEx_HallSensor_MspDeInit(htim);
+#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */
+
+ /* Change the DMA burst operation state */
+ htim->DMABurstState = HAL_DMA_BURST_STATE_RESET;
+
+ /* Change the TIM channels state */
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_RESET);
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_RESET);
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_RESET);
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_RESET);
+
+ /* Change TIM state */
+ htim->State = HAL_TIM_STATE_RESET;
+
+ /* Release Lock */
+ __HAL_UNLOCK(htim);
+
+ return HAL_OK;
+}
+
+/**
+ * @brief Initializes the TIM Hall Sensor MSP.
+ * @param htim TIM Hall Sensor Interface handle
+ * @retval None
+ */
+__weak void HAL_TIMEx_HallSensor_MspInit(TIM_HandleTypeDef *htim)
+{
+ /* Prevent unused argument(s) compilation warning */
+ UNUSED(htim);
+
+ /* NOTE : This function should not be modified, when the callback is needed,
+ the HAL_TIMEx_HallSensor_MspInit could be implemented in the user file
+ */
+}
+
+/**
+ * @brief DeInitializes TIM Hall Sensor MSP.
+ * @param htim TIM Hall Sensor Interface handle
+ * @retval None
+ */
+__weak void HAL_TIMEx_HallSensor_MspDeInit(TIM_HandleTypeDef *htim)
+{
+ /* Prevent unused argument(s) compilation warning */
+ UNUSED(htim);
+
+ /* NOTE : This function should not be modified, when the callback is needed,
+ the HAL_TIMEx_HallSensor_MspDeInit could be implemented in the user file
+ */
+}
+
+/**
+ * @brief Starts the TIM Hall Sensor Interface.
+ * @param htim TIM Hall Sensor Interface handle
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIMEx_HallSensor_Start(TIM_HandleTypeDef *htim)
+{
+ uint32_t tmpsmcr;
+ HAL_TIM_ChannelStateTypeDef channel_1_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_1);
+ HAL_TIM_ChannelStateTypeDef channel_2_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_2);
+ HAL_TIM_ChannelStateTypeDef complementary_channel_1_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_1);
+ HAL_TIM_ChannelStateTypeDef complementary_channel_2_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_2);
+
+ /* Check the parameters */
+ assert_param(IS_TIM_HALL_SENSOR_INTERFACE_INSTANCE(htim->Instance));
+
+ /* Check the TIM channels state */
+ if ((channel_1_state != HAL_TIM_CHANNEL_STATE_READY)
+ || (channel_2_state != HAL_TIM_CHANNEL_STATE_READY)
+ || (complementary_channel_1_state != HAL_TIM_CHANNEL_STATE_READY)
+ || (complementary_channel_2_state != HAL_TIM_CHANNEL_STATE_READY))
+ {
+ return HAL_ERROR;
+ }
+
+ /* Set the TIM channels state */
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY);
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY);
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY);
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY);
+
+ /* Enable the Input Capture channel 1
+ (in the Hall Sensor Interface the three possible channels that can be used are TIM_CHANNEL_1,
+ TIM_CHANNEL_2 and TIM_CHANNEL_3) */
+ TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_ENABLE);
+
+ /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */
+ if (IS_TIM_SLAVE_INSTANCE(htim->Instance))
+ {
+ tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS;
+ if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr))
+ {
+ __HAL_TIM_ENABLE(htim);
+ }
+ }
+ else
+ {
+ __HAL_TIM_ENABLE(htim);
+ }
+
+ /* Return function status */
+ return HAL_OK;
+}
+
+/**
+ * @brief Stops the TIM Hall sensor Interface.
+ * @param htim TIM Hall Sensor Interface handle
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIMEx_HallSensor_Stop(TIM_HandleTypeDef *htim)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_HALL_SENSOR_INTERFACE_INSTANCE(htim->Instance));
+
+ /* Disable the Input Capture channels 1, 2 and 3
+ (in the Hall Sensor Interface the three possible channels that can be used are TIM_CHANNEL_1,
+ TIM_CHANNEL_2 and TIM_CHANNEL_3) */
+ TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_DISABLE);
+
+ /* Disable the Peripheral */
+ __HAL_TIM_DISABLE(htim);
+
+ /* Set the TIM channels state */
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY);
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY);
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY);
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY);
+
+ /* Return function status */
+ return HAL_OK;
+}
+
+/**
+ * @brief Starts the TIM Hall Sensor Interface in interrupt mode.
+ * @param htim TIM Hall Sensor Interface handle
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIMEx_HallSensor_Start_IT(TIM_HandleTypeDef *htim)
+{
+ uint32_t tmpsmcr;
+ HAL_TIM_ChannelStateTypeDef channel_1_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_1);
+ HAL_TIM_ChannelStateTypeDef channel_2_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_2);
+ HAL_TIM_ChannelStateTypeDef complementary_channel_1_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_1);
+ HAL_TIM_ChannelStateTypeDef complementary_channel_2_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_2);
+
+ /* Check the parameters */
+ assert_param(IS_TIM_HALL_SENSOR_INTERFACE_INSTANCE(htim->Instance));
+
+ /* Check the TIM channels state */
+ if ((channel_1_state != HAL_TIM_CHANNEL_STATE_READY)
+ || (channel_2_state != HAL_TIM_CHANNEL_STATE_READY)
+ || (complementary_channel_1_state != HAL_TIM_CHANNEL_STATE_READY)
+ || (complementary_channel_2_state != HAL_TIM_CHANNEL_STATE_READY))
+ {
+ return HAL_ERROR;
+ }
+
+ /* Set the TIM channels state */
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY);
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY);
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY);
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY);
+
+ /* Enable the capture compare Interrupts 1 event */
+ __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC1);
+
+ /* Enable the Input Capture channel 1
+ (in the Hall Sensor Interface the three possible channels that can be used are TIM_CHANNEL_1,
+ TIM_CHANNEL_2 and TIM_CHANNEL_3) */
+ TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_ENABLE);
+
+ /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */
+ if (IS_TIM_SLAVE_INSTANCE(htim->Instance))
+ {
+ tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS;
+ if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr))
+ {
+ __HAL_TIM_ENABLE(htim);
+ }
+ }
+ else
+ {
+ __HAL_TIM_ENABLE(htim);
+ }
+
+ /* Return function status */
+ return HAL_OK;
+}
+
+/**
+ * @brief Stops the TIM Hall Sensor Interface in interrupt mode.
+ * @param htim TIM Hall Sensor Interface handle
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIMEx_HallSensor_Stop_IT(TIM_HandleTypeDef *htim)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_HALL_SENSOR_INTERFACE_INSTANCE(htim->Instance));
+
+ /* Disable the Input Capture channel 1
+ (in the Hall Sensor Interface the three possible channels that can be used are TIM_CHANNEL_1,
+ TIM_CHANNEL_2 and TIM_CHANNEL_3) */
+ TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_DISABLE);
+
+ /* Disable the capture compare Interrupts event */
+ __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC1);
+
+ /* Disable the Peripheral */
+ __HAL_TIM_DISABLE(htim);
+
+ /* Set the TIM channels state */
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY);
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY);
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY);
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY);
+
+ /* Return function status */
+ return HAL_OK;
+}
+
+/**
+ * @brief Starts the TIM Hall Sensor Interface in DMA mode.
+ * @param htim TIM Hall Sensor Interface handle
+ * @param pData The destination Buffer address.
+ * @param Length The length of data to be transferred from TIM peripheral to memory.
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIMEx_HallSensor_Start_DMA(TIM_HandleTypeDef *htim, uint32_t *pData, uint16_t Length)
+{
+ uint32_t tmpsmcr;
+ HAL_TIM_ChannelStateTypeDef channel_1_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_1);
+ HAL_TIM_ChannelStateTypeDef complementary_channel_1_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_1);
+
+ /* Check the parameters */
+ assert_param(IS_TIM_HALL_SENSOR_INTERFACE_INSTANCE(htim->Instance));
+
+ /* Set the TIM channel state */
+ if ((channel_1_state == HAL_TIM_CHANNEL_STATE_BUSY)
+ || (complementary_channel_1_state == HAL_TIM_CHANNEL_STATE_BUSY))
+ {
+ return HAL_BUSY;
+ }
+ else if ((channel_1_state == HAL_TIM_CHANNEL_STATE_READY)
+ && (complementary_channel_1_state == HAL_TIM_CHANNEL_STATE_READY))
+ {
+ if ((pData == NULL) && (Length > 0U))
+ {
+ return HAL_ERROR;
+ }
+ else
+ {
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY);
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY);
+ }
+ }
+ else
+ {
+ return HAL_ERROR;
+ }
+
+ /* Enable the Input Capture channel 1
+ (in the Hall Sensor Interface the three possible channels that can be used are TIM_CHANNEL_1,
+ TIM_CHANNEL_2 and TIM_CHANNEL_3) */
+ TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_ENABLE);
+
+ /* Set the DMA Input Capture 1 Callbacks */
+ htim->hdma[TIM_DMA_ID_CC1]->XferCpltCallback = TIM_DMACaptureCplt;
+ htim->hdma[TIM_DMA_ID_CC1]->XferHalfCpltCallback = TIM_DMACaptureHalfCplt;
+ /* Set the DMA error callback */
+ htim->hdma[TIM_DMA_ID_CC1]->XferErrorCallback = TIM_DMAError ;
+
+ /* Enable the DMA channel for Capture 1*/
+ if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC1], (uint32_t)&htim->Instance->CCR1, (uint32_t)pData, Length) != HAL_OK)
+ {
+ /* Return error status */
+ return HAL_ERROR;
+ }
+ /* Enable the capture compare 1 Interrupt */
+ __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC1);
+
+ /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */
+ if (IS_TIM_SLAVE_INSTANCE(htim->Instance))
+ {
+ tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS;
+ if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr))
+ {
+ __HAL_TIM_ENABLE(htim);
+ }
+ }
+ else
+ {
+ __HAL_TIM_ENABLE(htim);
+ }
+
+ /* Return function status */
+ return HAL_OK;
+}
+
+/**
+ * @brief Stops the TIM Hall Sensor Interface in DMA mode.
+ * @param htim TIM Hall Sensor Interface handle
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIMEx_HallSensor_Stop_DMA(TIM_HandleTypeDef *htim)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_HALL_SENSOR_INTERFACE_INSTANCE(htim->Instance));
+
+ /* Disable the Input Capture channel 1
+ (in the Hall Sensor Interface the three possible channels that can be used are TIM_CHANNEL_1,
+ TIM_CHANNEL_2 and TIM_CHANNEL_3) */
+ TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_DISABLE);
+
+
+ /* Disable the capture compare Interrupts 1 event */
+ __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC1);
+
+ (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC1]);
+
+ /* Disable the Peripheral */
+ __HAL_TIM_DISABLE(htim);
+
+ /* Set the TIM channel state */
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY);
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY);
+
+ /* Return function status */
+ return HAL_OK;
+}
+
+/**
+ * @}
+ */
+
+/** @defgroup TIMEx_Exported_Functions_Group2 Extended Timer Complementary Output Compare functions
+ * @brief Timer Complementary Output Compare functions
+ *
+@verbatim
+ ==============================================================================
+ ##### Timer Complementary Output Compare functions #####
+ ==============================================================================
+ [..]
+ This section provides functions allowing to:
+ (+) Start the Complementary Output Compare/PWM.
+ (+) Stop the Complementary Output Compare/PWM.
+ (+) Start the Complementary Output Compare/PWM and enable interrupts.
+ (+) Stop the Complementary Output Compare/PWM and disable interrupts.
+ (+) Start the Complementary Output Compare/PWM and enable DMA transfers.
+ (+) Stop the Complementary Output Compare/PWM and disable DMA transfers.
+
+@endverbatim
+ * @{
+ */
+
+/**
+ * @brief Starts the TIM Output Compare signal generation on the complementary
+ * output.
+ * @param htim TIM Output Compare handle
+ * @param Channel TIM Channel to be enabled
+ * This parameter can be one of the following values:
+ * @arg TIM_CHANNEL_1: TIM Channel 1 selected
+ * @arg TIM_CHANNEL_2: TIM Channel 2 selected
+ * @arg TIM_CHANNEL_3: TIM Channel 3 selected
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIMEx_OCN_Start(TIM_HandleTypeDef *htim, uint32_t Channel)
+{
+ uint32_t tmpsmcr;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, Channel));
+
+ /* Check the TIM complementary channel state */
+ if (TIM_CHANNEL_N_STATE_GET(htim, Channel) != HAL_TIM_CHANNEL_STATE_READY)
+ {
+ return HAL_ERROR;
+ }
+
+ /* Set the TIM complementary channel state */
+ TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY);
+
+ /* Enable the Capture compare channel N */
+ TIM_CCxNChannelCmd(htim->Instance, Channel, TIM_CCxN_ENABLE);
+
+ /* Enable the Main Output */
+ __HAL_TIM_MOE_ENABLE(htim);
+
+ /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */
+ if (IS_TIM_SLAVE_INSTANCE(htim->Instance))
+ {
+ tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS;
+ if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr))
+ {
+ __HAL_TIM_ENABLE(htim);
+ }
+ }
+ else
+ {
+ __HAL_TIM_ENABLE(htim);
+ }
+
+ /* Return function status */
+ return HAL_OK;
+}
+
+/**
+ * @brief Stops the TIM Output Compare signal generation on the complementary
+ * output.
+ * @param htim TIM handle
+ * @param Channel TIM Channel to be disabled
+ * This parameter can be one of the following values:
+ * @arg TIM_CHANNEL_1: TIM Channel 1 selected
+ * @arg TIM_CHANNEL_2: TIM Channel 2 selected
+ * @arg TIM_CHANNEL_3: TIM Channel 3 selected
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIMEx_OCN_Stop(TIM_HandleTypeDef *htim, uint32_t Channel)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, Channel));
+
+ /* Disable the Capture compare channel N */
+ TIM_CCxNChannelCmd(htim->Instance, Channel, TIM_CCxN_DISABLE);
+
+ /* Disable the Main Output */
+ __HAL_TIM_MOE_DISABLE(htim);
+
+ /* Disable the Peripheral */
+ __HAL_TIM_DISABLE(htim);
+
+ /* Set the TIM complementary channel state */
+ TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY);
+
+ /* Return function status */
+ return HAL_OK;
+}
+
+/**
+ * @brief Starts the TIM Output Compare signal generation in interrupt mode
+ * on the complementary output.
+ * @param htim TIM OC handle
+ * @param Channel TIM Channel to be enabled
+ * This parameter can be one of the following values:
+ * @arg TIM_CHANNEL_1: TIM Channel 1 selected
+ * @arg TIM_CHANNEL_2: TIM Channel 2 selected
+ * @arg TIM_CHANNEL_3: TIM Channel 3 selected
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIMEx_OCN_Start_IT(TIM_HandleTypeDef *htim, uint32_t Channel)
+{
+ HAL_StatusTypeDef status = HAL_OK;
+ uint32_t tmpsmcr;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, Channel));
+
+ /* Check the TIM complementary channel state */
+ if (TIM_CHANNEL_N_STATE_GET(htim, Channel) != HAL_TIM_CHANNEL_STATE_READY)
+ {
+ return HAL_ERROR;
+ }
+
+ /* Set the TIM complementary channel state */
+ TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY);
+
+ switch (Channel)
+ {
+ case TIM_CHANNEL_1:
+ {
+ /* Enable the TIM Output Compare interrupt */
+ __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC1);
+ break;
+ }
+
+ case TIM_CHANNEL_2:
+ {
+ /* Enable the TIM Output Compare interrupt */
+ __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC2);
+ break;
+ }
+
+ case TIM_CHANNEL_3:
+ {
+ /* Enable the TIM Output Compare interrupt */
+ __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC3);
+ break;
+ }
+
+
+ default:
+ status = HAL_ERROR;
+ break;
+ }
+
+ if (status == HAL_OK)
+ {
+ /* Enable the TIM Break interrupt */
+ __HAL_TIM_ENABLE_IT(htim, TIM_IT_BREAK);
+
+ /* Enable the Capture compare channel N */
+ TIM_CCxNChannelCmd(htim->Instance, Channel, TIM_CCxN_ENABLE);
+
+ /* Enable the Main Output */
+ __HAL_TIM_MOE_ENABLE(htim);
+
+ /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */
+ if (IS_TIM_SLAVE_INSTANCE(htim->Instance))
+ {
+ tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS;
+ if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr))
+ {
+ __HAL_TIM_ENABLE(htim);
+ }
+ }
+ else
+ {
+ __HAL_TIM_ENABLE(htim);
+ }
+ }
+
+ /* Return function status */
+ return status;
+}
+
+/**
+ * @brief Stops the TIM Output Compare signal generation in interrupt mode
+ * on the complementary output.
+ * @param htim TIM Output Compare handle
+ * @param Channel TIM Channel to be disabled
+ * This parameter can be one of the following values:
+ * @arg TIM_CHANNEL_1: TIM Channel 1 selected
+ * @arg TIM_CHANNEL_2: TIM Channel 2 selected
+ * @arg TIM_CHANNEL_3: TIM Channel 3 selected
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIMEx_OCN_Stop_IT(TIM_HandleTypeDef *htim, uint32_t Channel)
+{
+ HAL_StatusTypeDef status = HAL_OK;
+ uint32_t tmpccer;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, Channel));
+
+ switch (Channel)
+ {
+ case TIM_CHANNEL_1:
+ {
+ /* Disable the TIM Output Compare interrupt */
+ __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC1);
+ break;
+ }
+
+ case TIM_CHANNEL_2:
+ {
+ /* Disable the TIM Output Compare interrupt */
+ __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC2);
+ break;
+ }
+
+ case TIM_CHANNEL_3:
+ {
+ /* Disable the TIM Output Compare interrupt */
+ __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC3);
+ break;
+ }
+
+ default:
+ status = HAL_ERROR;
+ break;
+ }
+
+ if (status == HAL_OK)
+ {
+ /* Disable the Capture compare channel N */
+ TIM_CCxNChannelCmd(htim->Instance, Channel, TIM_CCxN_DISABLE);
+
+ /* Disable the TIM Break interrupt (only if no more channel is active) */
+ tmpccer = htim->Instance->CCER;
+ if ((tmpccer & (TIM_CCER_CC1NE | TIM_CCER_CC2NE | TIM_CCER_CC3NE)) == (uint32_t)RESET)
+ {
+ __HAL_TIM_DISABLE_IT(htim, TIM_IT_BREAK);
+ }
+
+ /* Disable the Main Output */
+ __HAL_TIM_MOE_DISABLE(htim);
+
+ /* Disable the Peripheral */
+ __HAL_TIM_DISABLE(htim);
+
+ /* Set the TIM complementary channel state */
+ TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY);
+ }
+
+ /* Return function status */
+ return status;
+}
+
+/**
+ * @brief Starts the TIM Output Compare signal generation in DMA mode
+ * on the complementary output.
+ * @param htim TIM Output Compare handle
+ * @param Channel TIM Channel to be enabled
+ * This parameter can be one of the following values:
+ * @arg TIM_CHANNEL_1: TIM Channel 1 selected
+ * @arg TIM_CHANNEL_2: TIM Channel 2 selected
+ * @arg TIM_CHANNEL_3: TIM Channel 3 selected
+ * @param pData The source Buffer address.
+ * @param Length The length of data to be transferred from memory to TIM peripheral
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIMEx_OCN_Start_DMA(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pData, uint16_t Length)
+{
+ HAL_StatusTypeDef status = HAL_OK;
+ uint32_t tmpsmcr;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, Channel));
+
+ /* Set the TIM complementary channel state */
+ if (TIM_CHANNEL_N_STATE_GET(htim, Channel) == HAL_TIM_CHANNEL_STATE_BUSY)
+ {
+ return HAL_BUSY;
+ }
+ else if (TIM_CHANNEL_N_STATE_GET(htim, Channel) == HAL_TIM_CHANNEL_STATE_READY)
+ {
+ if ((pData == NULL) && (Length > 0U))
+ {
+ return HAL_ERROR;
+ }
+ else
+ {
+ TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY);
+ }
+ }
+ else
+ {
+ return HAL_ERROR;
+ }
+
+ switch (Channel)
+ {
+ case TIM_CHANNEL_1:
+ {
+ /* Set the DMA compare callbacks */
+ htim->hdma[TIM_DMA_ID_CC1]->XferCpltCallback = TIM_DMADelayPulseNCplt;
+ htim->hdma[TIM_DMA_ID_CC1]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt;
+
+ /* Set the DMA error callback */
+ htim->hdma[TIM_DMA_ID_CC1]->XferErrorCallback = TIM_DMAErrorCCxN ;
+
+ /* Enable the DMA channel */
+ if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC1], (uint32_t)pData, (uint32_t)&htim->Instance->CCR1,
+ Length) != HAL_OK)
+ {
+ /* Return error status */
+ return HAL_ERROR;
+ }
+ /* Enable the TIM Output Compare DMA request */
+ __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC1);
+ break;
+ }
+
+ case TIM_CHANNEL_2:
+ {
+ /* Set the DMA compare callbacks */
+ htim->hdma[TIM_DMA_ID_CC2]->XferCpltCallback = TIM_DMADelayPulseNCplt;
+ htim->hdma[TIM_DMA_ID_CC2]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt;
+
+ /* Set the DMA error callback */
+ htim->hdma[TIM_DMA_ID_CC2]->XferErrorCallback = TIM_DMAErrorCCxN ;
+
+ /* Enable the DMA channel */
+ if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC2], (uint32_t)pData, (uint32_t)&htim->Instance->CCR2,
+ Length) != HAL_OK)
+ {
+ /* Return error status */
+ return HAL_ERROR;
+ }
+ /* Enable the TIM Output Compare DMA request */
+ __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC2);
+ break;
+ }
+
+ case TIM_CHANNEL_3:
+ {
+ /* Set the DMA compare callbacks */
+ htim->hdma[TIM_DMA_ID_CC3]->XferCpltCallback = TIM_DMADelayPulseNCplt;
+ htim->hdma[TIM_DMA_ID_CC3]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt;
+
+ /* Set the DMA error callback */
+ htim->hdma[TIM_DMA_ID_CC3]->XferErrorCallback = TIM_DMAErrorCCxN ;
+
+ /* Enable the DMA channel */
+ if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC3], (uint32_t)pData, (uint32_t)&htim->Instance->CCR3,
+ Length) != HAL_OK)
+ {
+ /* Return error status */
+ return HAL_ERROR;
+ }
+ /* Enable the TIM Output Compare DMA request */
+ __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC3);
+ break;
+ }
+
+ default:
+ status = HAL_ERROR;
+ break;
+ }
+
+ if (status == HAL_OK)
+ {
+ /* Enable the Capture compare channel N */
+ TIM_CCxNChannelCmd(htim->Instance, Channel, TIM_CCxN_ENABLE);
+
+ /* Enable the Main Output */
+ __HAL_TIM_MOE_ENABLE(htim);
+
+ /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */
+ if (IS_TIM_SLAVE_INSTANCE(htim->Instance))
+ {
+ tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS;
+ if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr))
+ {
+ __HAL_TIM_ENABLE(htim);
+ }
+ }
+ else
+ {
+ __HAL_TIM_ENABLE(htim);
+ }
+ }
+
+ /* Return function status */
+ return status;
+}
+
+/**
+ * @brief Stops the TIM Output Compare signal generation in DMA mode
+ * on the complementary output.
+ * @param htim TIM Output Compare handle
+ * @param Channel TIM Channel to be disabled
+ * This parameter can be one of the following values:
+ * @arg TIM_CHANNEL_1: TIM Channel 1 selected
+ * @arg TIM_CHANNEL_2: TIM Channel 2 selected
+ * @arg TIM_CHANNEL_3: TIM Channel 3 selected
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIMEx_OCN_Stop_DMA(TIM_HandleTypeDef *htim, uint32_t Channel)
+{
+ HAL_StatusTypeDef status = HAL_OK;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, Channel));
+
+ switch (Channel)
+ {
+ case TIM_CHANNEL_1:
+ {
+ /* Disable the TIM Output Compare DMA request */
+ __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC1);
+ (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC1]);
+ break;
+ }
+
+ case TIM_CHANNEL_2:
+ {
+ /* Disable the TIM Output Compare DMA request */
+ __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC2);
+ (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC2]);
+ break;
+ }
+
+ case TIM_CHANNEL_3:
+ {
+ /* Disable the TIM Output Compare DMA request */
+ __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC3);
+ (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC3]);
+ break;
+ }
+
+ default:
+ status = HAL_ERROR;
+ break;
+ }
+
+ if (status == HAL_OK)
+ {
+ /* Disable the Capture compare channel N */
+ TIM_CCxNChannelCmd(htim->Instance, Channel, TIM_CCxN_DISABLE);
+
+ /* Disable the Main Output */
+ __HAL_TIM_MOE_DISABLE(htim);
+
+ /* Disable the Peripheral */
+ __HAL_TIM_DISABLE(htim);
+
+ /* Set the TIM complementary channel state */
+ TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY);
+ }
+
+ /* Return function status */
+ return status;
+}
+
+/**
+ * @}
+ */
+
+/** @defgroup TIMEx_Exported_Functions_Group3 Extended Timer Complementary PWM functions
+ * @brief Timer Complementary PWM functions
+ *
+@verbatim
+ ==============================================================================
+ ##### Timer Complementary PWM functions #####
+ ==============================================================================
+ [..]
+ This section provides functions allowing to:
+ (+) Start the Complementary PWM.
+ (+) Stop the Complementary PWM.
+ (+) Start the Complementary PWM and enable interrupts.
+ (+) Stop the Complementary PWM and disable interrupts.
+ (+) Start the Complementary PWM and enable DMA transfers.
+ (+) Stop the Complementary PWM and disable DMA transfers.
+ (+) Start the Complementary Input Capture measurement.
+ (+) Stop the Complementary Input Capture.
+ (+) Start the Complementary Input Capture and enable interrupts.
+ (+) Stop the Complementary Input Capture and disable interrupts.
+ (+) Start the Complementary Input Capture and enable DMA transfers.
+ (+) Stop the Complementary Input Capture and disable DMA transfers.
+ (+) Start the Complementary One Pulse generation.
+ (+) Stop the Complementary One Pulse.
+ (+) Start the Complementary One Pulse and enable interrupts.
+ (+) Stop the Complementary One Pulse and disable interrupts.
+
+@endverbatim
+ * @{
+ */
+
+/**
+ * @brief Starts the PWM signal generation on the complementary output.
+ * @param htim TIM handle
+ * @param Channel TIM Channel to be enabled
+ * This parameter can be one of the following values:
+ * @arg TIM_CHANNEL_1: TIM Channel 1 selected
+ * @arg TIM_CHANNEL_2: TIM Channel 2 selected
+ * @arg TIM_CHANNEL_3: TIM Channel 3 selected
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIMEx_PWMN_Start(TIM_HandleTypeDef *htim, uint32_t Channel)
+{
+ uint32_t tmpsmcr;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, Channel));
+
+ /* Check the TIM complementary channel state */
+ if (TIM_CHANNEL_N_STATE_GET(htim, Channel) != HAL_TIM_CHANNEL_STATE_READY)
+ {
+ return HAL_ERROR;
+ }
+
+ /* Set the TIM complementary channel state */
+ TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY);
+
+ /* Enable the complementary PWM output */
+ TIM_CCxNChannelCmd(htim->Instance, Channel, TIM_CCxN_ENABLE);
+
+ /* Enable the Main Output */
+ __HAL_TIM_MOE_ENABLE(htim);
+
+ /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */
+ if (IS_TIM_SLAVE_INSTANCE(htim->Instance))
+ {
+ tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS;
+ if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr))
+ {
+ __HAL_TIM_ENABLE(htim);
+ }
+ }
+ else
+ {
+ __HAL_TIM_ENABLE(htim);
+ }
+
+ /* Return function status */
+ return HAL_OK;
+}
+
+/**
+ * @brief Stops the PWM signal generation on the complementary output.
+ * @param htim TIM handle
+ * @param Channel TIM Channel to be disabled
+ * This parameter can be one of the following values:
+ * @arg TIM_CHANNEL_1: TIM Channel 1 selected
+ * @arg TIM_CHANNEL_2: TIM Channel 2 selected
+ * @arg TIM_CHANNEL_3: TIM Channel 3 selected
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIMEx_PWMN_Stop(TIM_HandleTypeDef *htim, uint32_t Channel)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, Channel));
+
+ /* Disable the complementary PWM output */
+ TIM_CCxNChannelCmd(htim->Instance, Channel, TIM_CCxN_DISABLE);
+
+ /* Disable the Main Output */
+ __HAL_TIM_MOE_DISABLE(htim);
+
+ /* Disable the Peripheral */
+ __HAL_TIM_DISABLE(htim);
+
+ /* Set the TIM complementary channel state */
+ TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY);
+
+ /* Return function status */
+ return HAL_OK;
+}
+
+/**
+ * @brief Starts the PWM signal generation in interrupt mode on the
+ * complementary output.
+ * @param htim TIM handle
+ * @param Channel TIM Channel to be disabled
+ * This parameter can be one of the following values:
+ * @arg TIM_CHANNEL_1: TIM Channel 1 selected
+ * @arg TIM_CHANNEL_2: TIM Channel 2 selected
+ * @arg TIM_CHANNEL_3: TIM Channel 3 selected
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIMEx_PWMN_Start_IT(TIM_HandleTypeDef *htim, uint32_t Channel)
+{
+ HAL_StatusTypeDef status = HAL_OK;
+ uint32_t tmpsmcr;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, Channel));
+
+ /* Check the TIM complementary channel state */
+ if (TIM_CHANNEL_N_STATE_GET(htim, Channel) != HAL_TIM_CHANNEL_STATE_READY)
+ {
+ return HAL_ERROR;
+ }
+
+ /* Set the TIM complementary channel state */
+ TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY);
+
+ switch (Channel)
+ {
+ case TIM_CHANNEL_1:
+ {
+ /* Enable the TIM Capture/Compare 1 interrupt */
+ __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC1);
+ break;
+ }
+
+ case TIM_CHANNEL_2:
+ {
+ /* Enable the TIM Capture/Compare 2 interrupt */
+ __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC2);
+ break;
+ }
+
+ case TIM_CHANNEL_3:
+ {
+ /* Enable the TIM Capture/Compare 3 interrupt */
+ __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC3);
+ break;
+ }
+
+ default:
+ status = HAL_ERROR;
+ break;
+ }
+
+ if (status == HAL_OK)
+ {
+ /* Enable the TIM Break interrupt */
+ __HAL_TIM_ENABLE_IT(htim, TIM_IT_BREAK);
+
+ /* Enable the complementary PWM output */
+ TIM_CCxNChannelCmd(htim->Instance, Channel, TIM_CCxN_ENABLE);
+
+ /* Enable the Main Output */
+ __HAL_TIM_MOE_ENABLE(htim);
+
+ /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */
+ if (IS_TIM_SLAVE_INSTANCE(htim->Instance))
+ {
+ tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS;
+ if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr))
+ {
+ __HAL_TIM_ENABLE(htim);
+ }
+ }
+ else
+ {
+ __HAL_TIM_ENABLE(htim);
+ }
+ }
+
+ /* Return function status */
+ return status;
+}
+
+/**
+ * @brief Stops the PWM signal generation in interrupt mode on the
+ * complementary output.
+ * @param htim TIM handle
+ * @param Channel TIM Channel to be disabled
+ * This parameter can be one of the following values:
+ * @arg TIM_CHANNEL_1: TIM Channel 1 selected
+ * @arg TIM_CHANNEL_2: TIM Channel 2 selected
+ * @arg TIM_CHANNEL_3: TIM Channel 3 selected
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIMEx_PWMN_Stop_IT(TIM_HandleTypeDef *htim, uint32_t Channel)
+{
+ HAL_StatusTypeDef status = HAL_OK;
+ uint32_t tmpccer;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, Channel));
+
+ switch (Channel)
+ {
+ case TIM_CHANNEL_1:
+ {
+ /* Disable the TIM Capture/Compare 1 interrupt */
+ __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC1);
+ break;
+ }
+
+ case TIM_CHANNEL_2:
+ {
+ /* Disable the TIM Capture/Compare 2 interrupt */
+ __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC2);
+ break;
+ }
+
+ case TIM_CHANNEL_3:
+ {
+ /* Disable the TIM Capture/Compare 3 interrupt */
+ __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC3);
+ break;
+ }
+
+ default:
+ status = HAL_ERROR;
+ break;
+ }
+
+ if (status == HAL_OK)
+ {
+ /* Disable the complementary PWM output */
+ TIM_CCxNChannelCmd(htim->Instance, Channel, TIM_CCxN_DISABLE);
+
+ /* Disable the TIM Break interrupt (only if no more channel is active) */
+ tmpccer = htim->Instance->CCER;
+ if ((tmpccer & (TIM_CCER_CC1NE | TIM_CCER_CC2NE | TIM_CCER_CC3NE)) == (uint32_t)RESET)
+ {
+ __HAL_TIM_DISABLE_IT(htim, TIM_IT_BREAK);
+ }
+
+ /* Disable the Main Output */
+ __HAL_TIM_MOE_DISABLE(htim);
+
+ /* Disable the Peripheral */
+ __HAL_TIM_DISABLE(htim);
+
+ /* Set the TIM complementary channel state */
+ TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY);
+ }
+
+ /* Return function status */
+ return status;
+}
+
+/**
+ * @brief Starts the TIM PWM signal generation in DMA mode on the
+ * complementary output
+ * @param htim TIM handle
+ * @param Channel TIM Channel to be enabled
+ * This parameter can be one of the following values:
+ * @arg TIM_CHANNEL_1: TIM Channel 1 selected
+ * @arg TIM_CHANNEL_2: TIM Channel 2 selected
+ * @arg TIM_CHANNEL_3: TIM Channel 3 selected
+ * @param pData The source Buffer address.
+ * @param Length The length of data to be transferred from memory to TIM peripheral
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIMEx_PWMN_Start_DMA(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pData, uint16_t Length)
+{
+ HAL_StatusTypeDef status = HAL_OK;
+ uint32_t tmpsmcr;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, Channel));
+
+ /* Set the TIM complementary channel state */
+ if (TIM_CHANNEL_N_STATE_GET(htim, Channel) == HAL_TIM_CHANNEL_STATE_BUSY)
+ {
+ return HAL_BUSY;
+ }
+ else if (TIM_CHANNEL_N_STATE_GET(htim, Channel) == HAL_TIM_CHANNEL_STATE_READY)
+ {
+ if ((pData == NULL) && (Length > 0U))
+ {
+ return HAL_ERROR;
+ }
+ else
+ {
+ TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY);
+ }
+ }
+ else
+ {
+ return HAL_ERROR;
+ }
+
+ switch (Channel)
+ {
+ case TIM_CHANNEL_1:
+ {
+ /* Set the DMA compare callbacks */
+ htim->hdma[TIM_DMA_ID_CC1]->XferCpltCallback = TIM_DMADelayPulseNCplt;
+ htim->hdma[TIM_DMA_ID_CC1]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt;
+
+ /* Set the DMA error callback */
+ htim->hdma[TIM_DMA_ID_CC1]->XferErrorCallback = TIM_DMAErrorCCxN ;
+
+ /* Enable the DMA channel */
+ if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC1], (uint32_t)pData, (uint32_t)&htim->Instance->CCR1,
+ Length) != HAL_OK)
+ {
+ /* Return error status */
+ return HAL_ERROR;
+ }
+ /* Enable the TIM Capture/Compare 1 DMA request */
+ __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC1);
+ break;
+ }
+
+ case TIM_CHANNEL_2:
+ {
+ /* Set the DMA compare callbacks */
+ htim->hdma[TIM_DMA_ID_CC2]->XferCpltCallback = TIM_DMADelayPulseNCplt;
+ htim->hdma[TIM_DMA_ID_CC2]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt;
+
+ /* Set the DMA error callback */
+ htim->hdma[TIM_DMA_ID_CC2]->XferErrorCallback = TIM_DMAErrorCCxN ;
+
+ /* Enable the DMA channel */
+ if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC2], (uint32_t)pData, (uint32_t)&htim->Instance->CCR2,
+ Length) != HAL_OK)
+ {
+ /* Return error status */
+ return HAL_ERROR;
+ }
+ /* Enable the TIM Capture/Compare 2 DMA request */
+ __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC2);
+ break;
+ }
+
+ case TIM_CHANNEL_3:
+ {
+ /* Set the DMA compare callbacks */
+ htim->hdma[TIM_DMA_ID_CC3]->XferCpltCallback = TIM_DMADelayPulseNCplt;
+ htim->hdma[TIM_DMA_ID_CC3]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt;
+
+ /* Set the DMA error callback */
+ htim->hdma[TIM_DMA_ID_CC3]->XferErrorCallback = TIM_DMAErrorCCxN ;
+
+ /* Enable the DMA channel */
+ if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC3], (uint32_t)pData, (uint32_t)&htim->Instance->CCR3,
+ Length) != HAL_OK)
+ {
+ /* Return error status */
+ return HAL_ERROR;
+ }
+ /* Enable the TIM Capture/Compare 3 DMA request */
+ __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC3);
+ break;
+ }
+
+ default:
+ status = HAL_ERROR;
+ break;
+ }
+
+ if (status == HAL_OK)
+ {
+ /* Enable the complementary PWM output */
+ TIM_CCxNChannelCmd(htim->Instance, Channel, TIM_CCxN_ENABLE);
+
+ /* Enable the Main Output */
+ __HAL_TIM_MOE_ENABLE(htim);
+
+ /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */
+ if (IS_TIM_SLAVE_INSTANCE(htim->Instance))
+ {
+ tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS;
+ if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr))
+ {
+ __HAL_TIM_ENABLE(htim);
+ }
+ }
+ else
+ {
+ __HAL_TIM_ENABLE(htim);
+ }
+ }
+
+ /* Return function status */
+ return status;
+}
+
+/**
+ * @brief Stops the TIM PWM signal generation in DMA mode on the complementary
+ * output
+ * @param htim TIM handle
+ * @param Channel TIM Channel to be disabled
+ * This parameter can be one of the following values:
+ * @arg TIM_CHANNEL_1: TIM Channel 1 selected
+ * @arg TIM_CHANNEL_2: TIM Channel 2 selected
+ * @arg TIM_CHANNEL_3: TIM Channel 3 selected
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIMEx_PWMN_Stop_DMA(TIM_HandleTypeDef *htim, uint32_t Channel)
+{
+ HAL_StatusTypeDef status = HAL_OK;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, Channel));
+
+ switch (Channel)
+ {
+ case TIM_CHANNEL_1:
+ {
+ /* Disable the TIM Capture/Compare 1 DMA request */
+ __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC1);
+ (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC1]);
+ break;
+ }
+
+ case TIM_CHANNEL_2:
+ {
+ /* Disable the TIM Capture/Compare 2 DMA request */
+ __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC2);
+ (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC2]);
+ break;
+ }
+
+ case TIM_CHANNEL_3:
+ {
+ /* Disable the TIM Capture/Compare 3 DMA request */
+ __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC3);
+ (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC3]);
+ break;
+ }
+
+ default:
+ status = HAL_ERROR;
+ break;
+ }
+
+ if (status == HAL_OK)
+ {
+ /* Disable the complementary PWM output */
+ TIM_CCxNChannelCmd(htim->Instance, Channel, TIM_CCxN_DISABLE);
+
+ /* Disable the Main Output */
+ __HAL_TIM_MOE_DISABLE(htim);
+
+ /* Disable the Peripheral */
+ __HAL_TIM_DISABLE(htim);
+
+ /* Set the TIM complementary channel state */
+ TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY);
+ }
+
+ /* Return function status */
+ return status;
+}
+
+/**
+ * @}
+ */
+
+/** @defgroup TIMEx_Exported_Functions_Group4 Extended Timer Complementary One Pulse functions
+ * @brief Timer Complementary One Pulse functions
+ *
+@verbatim
+ ==============================================================================
+ ##### Timer Complementary One Pulse functions #####
+ ==============================================================================
+ [..]
+ This section provides functions allowing to:
+ (+) Start the Complementary One Pulse generation.
+ (+) Stop the Complementary One Pulse.
+ (+) Start the Complementary One Pulse and enable interrupts.
+ (+) Stop the Complementary One Pulse and disable interrupts.
+
+@endverbatim
+ * @{
+ */
+
+/**
+ * @brief Starts the TIM One Pulse signal generation on the complementary
+ * output.
+ * @note OutputChannel must match the pulse output channel chosen when calling
+ * @ref HAL_TIM_OnePulse_ConfigChannel().
+ * @param htim TIM One Pulse handle
+ * @param OutputChannel pulse output channel to enable
+ * This parameter can be one of the following values:
+ * @arg TIM_CHANNEL_1: TIM Channel 1 selected
+ * @arg TIM_CHANNEL_2: TIM Channel 2 selected
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIMEx_OnePulseN_Start(TIM_HandleTypeDef *htim, uint32_t OutputChannel)
+{
+ uint32_t input_channel = (OutputChannel == TIM_CHANNEL_1) ? TIM_CHANNEL_2 : TIM_CHANNEL_1;
+ HAL_TIM_ChannelStateTypeDef channel_1_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_1);
+ HAL_TIM_ChannelStateTypeDef channel_2_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_2);
+ HAL_TIM_ChannelStateTypeDef complementary_channel_1_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_1);
+ HAL_TIM_ChannelStateTypeDef complementary_channel_2_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_2);
+
+ /* Check the parameters */
+ assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, OutputChannel));
+
+ /* Check the TIM channels state */
+ if ((channel_1_state != HAL_TIM_CHANNEL_STATE_READY)
+ || (channel_2_state != HAL_TIM_CHANNEL_STATE_READY)
+ || (complementary_channel_1_state != HAL_TIM_CHANNEL_STATE_READY)
+ || (complementary_channel_2_state != HAL_TIM_CHANNEL_STATE_READY))
+ {
+ return HAL_ERROR;
+ }
+
+ /* Set the TIM channels state */
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY);
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY);
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY);
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY);
+
+ /* Enable the complementary One Pulse output channel and the Input Capture channel */
+ TIM_CCxNChannelCmd(htim->Instance, OutputChannel, TIM_CCxN_ENABLE);
+ TIM_CCxChannelCmd(htim->Instance, input_channel, TIM_CCx_ENABLE);
+
+ /* Enable the Main Output */
+ __HAL_TIM_MOE_ENABLE(htim);
+
+ /* Return function status */
+ return HAL_OK;
+}
+
+/**
+ * @brief Stops the TIM One Pulse signal generation on the complementary
+ * output.
+ * @note OutputChannel must match the pulse output channel chosen when calling
+ * @ref HAL_TIM_OnePulse_ConfigChannel().
+ * @param htim TIM One Pulse handle
+ * @param OutputChannel pulse output channel to disable
+ * This parameter can be one of the following values:
+ * @arg TIM_CHANNEL_1: TIM Channel 1 selected
+ * @arg TIM_CHANNEL_2: TIM Channel 2 selected
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIMEx_OnePulseN_Stop(TIM_HandleTypeDef *htim, uint32_t OutputChannel)
+{
+ uint32_t input_channel = (OutputChannel == TIM_CHANNEL_1) ? TIM_CHANNEL_2 : TIM_CHANNEL_1;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, OutputChannel));
+
+ /* Disable the complementary One Pulse output channel and the Input Capture channel */
+ TIM_CCxNChannelCmd(htim->Instance, OutputChannel, TIM_CCxN_DISABLE);
+ TIM_CCxChannelCmd(htim->Instance, input_channel, TIM_CCx_DISABLE);
+
+ /* Disable the Main Output */
+ __HAL_TIM_MOE_DISABLE(htim);
+
+ /* Disable the Peripheral */
+ __HAL_TIM_DISABLE(htim);
+
+ /* Set the TIM channels state */
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY);
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY);
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY);
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY);
+
+ /* Return function status */
+ return HAL_OK;
+}
+
+/**
+ * @brief Starts the TIM One Pulse signal generation in interrupt mode on the
+ * complementary channel.
+ * @note OutputChannel must match the pulse output channel chosen when calling
+ * @ref HAL_TIM_OnePulse_ConfigChannel().
+ * @param htim TIM One Pulse handle
+ * @param OutputChannel pulse output channel to enable
+ * This parameter can be one of the following values:
+ * @arg TIM_CHANNEL_1: TIM Channel 1 selected
+ * @arg TIM_CHANNEL_2: TIM Channel 2 selected
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIMEx_OnePulseN_Start_IT(TIM_HandleTypeDef *htim, uint32_t OutputChannel)
+{
+ uint32_t input_channel = (OutputChannel == TIM_CHANNEL_1) ? TIM_CHANNEL_2 : TIM_CHANNEL_1;
+ HAL_TIM_ChannelStateTypeDef channel_1_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_1);
+ HAL_TIM_ChannelStateTypeDef channel_2_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_2);
+ HAL_TIM_ChannelStateTypeDef complementary_channel_1_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_1);
+ HAL_TIM_ChannelStateTypeDef complementary_channel_2_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_2);
+
+ /* Check the parameters */
+ assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, OutputChannel));
+
+ /* Check the TIM channels state */
+ if ((channel_1_state != HAL_TIM_CHANNEL_STATE_READY)
+ || (channel_2_state != HAL_TIM_CHANNEL_STATE_READY)
+ || (complementary_channel_1_state != HAL_TIM_CHANNEL_STATE_READY)
+ || (complementary_channel_2_state != HAL_TIM_CHANNEL_STATE_READY))
+ {
+ return HAL_ERROR;
+ }
+
+ /* Set the TIM channels state */
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY);
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY);
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY);
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY);
+
+ /* Enable the TIM Capture/Compare 1 interrupt */
+ __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC1);
+
+ /* Enable the TIM Capture/Compare 2 interrupt */
+ __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC2);
+
+ /* Enable the complementary One Pulse output channel and the Input Capture channel */
+ TIM_CCxNChannelCmd(htim->Instance, OutputChannel, TIM_CCxN_ENABLE);
+ TIM_CCxChannelCmd(htim->Instance, input_channel, TIM_CCx_ENABLE);
+
+ /* Enable the Main Output */
+ __HAL_TIM_MOE_ENABLE(htim);
+
+ /* Return function status */
+ return HAL_OK;
+}
+
+/**
+ * @brief Stops the TIM One Pulse signal generation in interrupt mode on the
+ * complementary channel.
+ * @note OutputChannel must match the pulse output channel chosen when calling
+ * @ref HAL_TIM_OnePulse_ConfigChannel().
+ * @param htim TIM One Pulse handle
+ * @param OutputChannel pulse output channel to disable
+ * This parameter can be one of the following values:
+ * @arg TIM_CHANNEL_1: TIM Channel 1 selected
+ * @arg TIM_CHANNEL_2: TIM Channel 2 selected
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIMEx_OnePulseN_Stop_IT(TIM_HandleTypeDef *htim, uint32_t OutputChannel)
+{
+ uint32_t input_channel = (OutputChannel == TIM_CHANNEL_1) ? TIM_CHANNEL_2 : TIM_CHANNEL_1;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, OutputChannel));
+
+ /* Disable the TIM Capture/Compare 1 interrupt */
+ __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC1);
+
+ /* Disable the TIM Capture/Compare 2 interrupt */
+ __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC2);
+
+ /* Disable the complementary One Pulse output channel and the Input Capture channel */
+ TIM_CCxNChannelCmd(htim->Instance, OutputChannel, TIM_CCxN_DISABLE);
+ TIM_CCxChannelCmd(htim->Instance, input_channel, TIM_CCx_DISABLE);
+
+ /* Disable the Main Output */
+ __HAL_TIM_MOE_DISABLE(htim);
+
+ /* Disable the Peripheral */
+ __HAL_TIM_DISABLE(htim);
+
+ /* Set the TIM channels state */
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY);
+ TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY);
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY);
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY);
+
+ /* Return function status */
+ return HAL_OK;
+}
+
+/**
+ * @}
+ */
+
+/** @defgroup TIMEx_Exported_Functions_Group5 Extended Peripheral Control functions
+ * @brief Peripheral Control functions
+ *
+@verbatim
+ ==============================================================================
+ ##### Peripheral Control functions #####
+ ==============================================================================
+ [..]
+ This section provides functions allowing to:
+ (+) Configure the commutation event in case of use of the Hall sensor interface.
+ (+) Configure Output channels for OC and PWM mode.
+
+ (+) Configure Complementary channels, break features and dead time.
+ (+) Configure Master synchronization.
+ (+) Configure timer remapping capabilities.
+
+@endverbatim
+ * @{
+ */
+
+/**
+ * @brief Configure the TIM commutation event sequence.
+ * @note This function is mandatory to use the commutation event in order to
+ * update the configuration at each commutation detection on the TRGI input of the Timer,
+ * the typical use of this feature is with the use of another Timer(interface Timer)
+ * configured in Hall sensor interface, this interface Timer will generate the
+ * commutation at its TRGO output (connected to Timer used in this function) each time
+ * the TI1 of the Interface Timer detect a commutation at its input TI1.
+ * @param htim TIM handle
+ * @param InputTrigger the Internal trigger corresponding to the Timer Interfacing with the Hall sensor
+ * This parameter can be one of the following values:
+ * @arg TIM_TS_ITR0: Internal trigger 0 selected
+ * @arg TIM_TS_ITR1: Internal trigger 1 selected
+ * @arg TIM_TS_ITR2: Internal trigger 2 selected
+ * @arg TIM_TS_ITR3: Internal trigger 3 selected
+ * @arg TIM_TS_NONE: No trigger is needed
+ * @param CommutationSource the Commutation Event source
+ * This parameter can be one of the following values:
+ * @arg TIM_COMMUTATION_TRGI: Commutation source is the TRGI of the Interface Timer
+ * @arg TIM_COMMUTATION_SOFTWARE: Commutation source is set by software using the COMG bit
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIMEx_ConfigCommutEvent(TIM_HandleTypeDef *htim, uint32_t InputTrigger,
+ uint32_t CommutationSource)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_COMMUTATION_EVENT_INSTANCE(htim->Instance));
+ assert_param(IS_TIM_INTERNAL_TRIGGEREVENT_SELECTION(InputTrigger));
+
+ __HAL_LOCK(htim);
+
+ if ((InputTrigger == TIM_TS_ITR0) || (InputTrigger == TIM_TS_ITR1) ||
+ (InputTrigger == TIM_TS_ITR2) || (InputTrigger == TIM_TS_ITR3))
+ {
+ /* Select the Input trigger */
+ htim->Instance->SMCR &= ~TIM_SMCR_TS;
+ htim->Instance->SMCR |= InputTrigger;
+ }
+
+ /* Select the Capture Compare preload feature */
+ htim->Instance->CR2 |= TIM_CR2_CCPC;
+ /* Select the Commutation event source */
+ htim->Instance->CR2 &= ~TIM_CR2_CCUS;
+ htim->Instance->CR2 |= CommutationSource;
+
+ /* Disable Commutation Interrupt */
+ __HAL_TIM_DISABLE_IT(htim, TIM_IT_COM);
+
+ /* Disable Commutation DMA request */
+ __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_COM);
+
+ __HAL_UNLOCK(htim);
+
+ return HAL_OK;
+}
+
+/**
+ * @brief Configure the TIM commutation event sequence with interrupt.
+ * @note This function is mandatory to use the commutation event in order to
+ * update the configuration at each commutation detection on the TRGI input of the Timer,
+ * the typical use of this feature is with the use of another Timer(interface Timer)
+ * configured in Hall sensor interface, this interface Timer will generate the
+ * commutation at its TRGO output (connected to Timer used in this function) each time
+ * the TI1 of the Interface Timer detect a commutation at its input TI1.
+ * @param htim TIM handle
+ * @param InputTrigger the Internal trigger corresponding to the Timer Interfacing with the Hall sensor
+ * This parameter can be one of the following values:
+ * @arg TIM_TS_ITR0: Internal trigger 0 selected
+ * @arg TIM_TS_ITR1: Internal trigger 1 selected
+ * @arg TIM_TS_ITR2: Internal trigger 2 selected
+ * @arg TIM_TS_ITR3: Internal trigger 3 selected
+ * @arg TIM_TS_NONE: No trigger is needed
+ * @param CommutationSource the Commutation Event source
+ * This parameter can be one of the following values:
+ * @arg TIM_COMMUTATION_TRGI: Commutation source is the TRGI of the Interface Timer
+ * @arg TIM_COMMUTATION_SOFTWARE: Commutation source is set by software using the COMG bit
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIMEx_ConfigCommutEvent_IT(TIM_HandleTypeDef *htim, uint32_t InputTrigger,
+ uint32_t CommutationSource)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_COMMUTATION_EVENT_INSTANCE(htim->Instance));
+ assert_param(IS_TIM_INTERNAL_TRIGGEREVENT_SELECTION(InputTrigger));
+
+ __HAL_LOCK(htim);
+
+ if ((InputTrigger == TIM_TS_ITR0) || (InputTrigger == TIM_TS_ITR1) ||
+ (InputTrigger == TIM_TS_ITR2) || (InputTrigger == TIM_TS_ITR3))
+ {
+ /* Select the Input trigger */
+ htim->Instance->SMCR &= ~TIM_SMCR_TS;
+ htim->Instance->SMCR |= InputTrigger;
+ }
+
+ /* Select the Capture Compare preload feature */
+ htim->Instance->CR2 |= TIM_CR2_CCPC;
+ /* Select the Commutation event source */
+ htim->Instance->CR2 &= ~TIM_CR2_CCUS;
+ htim->Instance->CR2 |= CommutationSource;
+
+ /* Disable Commutation DMA request */
+ __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_COM);
+
+ /* Enable the Commutation Interrupt */
+ __HAL_TIM_ENABLE_IT(htim, TIM_IT_COM);
+
+ __HAL_UNLOCK(htim);
+
+ return HAL_OK;
+}
+
+/**
+ * @brief Configure the TIM commutation event sequence with DMA.
+ * @note This function is mandatory to use the commutation event in order to
+ * update the configuration at each commutation detection on the TRGI input of the Timer,
+ * the typical use of this feature is with the use of another Timer(interface Timer)
+ * configured in Hall sensor interface, this interface Timer will generate the
+ * commutation at its TRGO output (connected to Timer used in this function) each time
+ * the TI1 of the Interface Timer detect a commutation at its input TI1.
+ * @note The user should configure the DMA in his own software, in This function only the COMDE bit is set
+ * @param htim TIM handle
+ * @param InputTrigger the Internal trigger corresponding to the Timer Interfacing with the Hall sensor
+ * This parameter can be one of the following values:
+ * @arg TIM_TS_ITR0: Internal trigger 0 selected
+ * @arg TIM_TS_ITR1: Internal trigger 1 selected
+ * @arg TIM_TS_ITR2: Internal trigger 2 selected
+ * @arg TIM_TS_ITR3: Internal trigger 3 selected
+ * @arg TIM_TS_NONE: No trigger is needed
+ * @param CommutationSource the Commutation Event source
+ * This parameter can be one of the following values:
+ * @arg TIM_COMMUTATION_TRGI: Commutation source is the TRGI of the Interface Timer
+ * @arg TIM_COMMUTATION_SOFTWARE: Commutation source is set by software using the COMG bit
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIMEx_ConfigCommutEvent_DMA(TIM_HandleTypeDef *htim, uint32_t InputTrigger,
+ uint32_t CommutationSource)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_COMMUTATION_EVENT_INSTANCE(htim->Instance));
+ assert_param(IS_TIM_INTERNAL_TRIGGEREVENT_SELECTION(InputTrigger));
+
+ __HAL_LOCK(htim);
+
+ if ((InputTrigger == TIM_TS_ITR0) || (InputTrigger == TIM_TS_ITR1) ||
+ (InputTrigger == TIM_TS_ITR2) || (InputTrigger == TIM_TS_ITR3))
+ {
+ /* Select the Input trigger */
+ htim->Instance->SMCR &= ~TIM_SMCR_TS;
+ htim->Instance->SMCR |= InputTrigger;
+ }
+
+ /* Select the Capture Compare preload feature */
+ htim->Instance->CR2 |= TIM_CR2_CCPC;
+ /* Select the Commutation event source */
+ htim->Instance->CR2 &= ~TIM_CR2_CCUS;
+ htim->Instance->CR2 |= CommutationSource;
+
+ /* Enable the Commutation DMA Request */
+ /* Set the DMA Commutation Callback */
+ htim->hdma[TIM_DMA_ID_COMMUTATION]->XferCpltCallback = TIMEx_DMACommutationCplt;
+ htim->hdma[TIM_DMA_ID_COMMUTATION]->XferHalfCpltCallback = TIMEx_DMACommutationHalfCplt;
+ /* Set the DMA error callback */
+ htim->hdma[TIM_DMA_ID_COMMUTATION]->XferErrorCallback = TIM_DMAError;
+
+ /* Disable Commutation Interrupt */
+ __HAL_TIM_DISABLE_IT(htim, TIM_IT_COM);
+
+ /* Enable the Commutation DMA Request */
+ __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_COM);
+
+ __HAL_UNLOCK(htim);
+
+ return HAL_OK;
+}
+
+/**
+ * @brief Configures the TIM in master mode.
+ * @param htim TIM handle.
+ * @param sMasterConfig pointer to a TIM_MasterConfigTypeDef structure that
+ * contains the selected trigger output (TRGO) and the Master/Slave
+ * mode.
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIMEx_MasterConfigSynchronization(TIM_HandleTypeDef *htim,
+ TIM_MasterConfigTypeDef *sMasterConfig)
+{
+ uint32_t tmpcr2;
+ uint32_t tmpsmcr;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_MASTER_INSTANCE(htim->Instance));
+ assert_param(IS_TIM_TRGO_SOURCE(sMasterConfig->MasterOutputTrigger));
+ assert_param(IS_TIM_MSM_STATE(sMasterConfig->MasterSlaveMode));
+
+ /* Check input state */
+ __HAL_LOCK(htim);
+
+ /* Change the handler state */
+ htim->State = HAL_TIM_STATE_BUSY;
+
+ /* Get the TIMx CR2 register value */
+ tmpcr2 = htim->Instance->CR2;
+
+ /* Get the TIMx SMCR register value */
+ tmpsmcr = htim->Instance->SMCR;
+
+ /* Reset the MMS Bits */
+ tmpcr2 &= ~TIM_CR2_MMS;
+ /* Select the TRGO source */
+ tmpcr2 |= sMasterConfig->MasterOutputTrigger;
+
+ /* Update TIMx CR2 */
+ htim->Instance->CR2 = tmpcr2;
+
+ if (IS_TIM_SLAVE_INSTANCE(htim->Instance))
+ {
+ /* Reset the MSM Bit */
+ tmpsmcr &= ~TIM_SMCR_MSM;
+ /* Set master mode */
+ tmpsmcr |= sMasterConfig->MasterSlaveMode;
+
+ /* Update TIMx SMCR */
+ htim->Instance->SMCR = tmpsmcr;
+ }
+
+ /* Change the htim state */
+ htim->State = HAL_TIM_STATE_READY;
+
+ __HAL_UNLOCK(htim);
+
+ return HAL_OK;
+}
+
+/**
+ * @brief Configures the Break feature, dead time, Lock level, OSSI/OSSR State
+ * and the AOE(automatic output enable).
+ * @param htim TIM handle
+ * @param sBreakDeadTimeConfig pointer to a TIM_ConfigBreakDeadConfigTypeDef structure that
+ * contains the BDTR Register configuration information for the TIM peripheral.
+ * @note Interrupts can be generated when an active level is detected on the
+ * break input, the break 2 input or the system break input. Break
+ * interrupt can be enabled by calling the @ref __HAL_TIM_ENABLE_IT macro.
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIMEx_ConfigBreakDeadTime(TIM_HandleTypeDef *htim,
+ TIM_BreakDeadTimeConfigTypeDef *sBreakDeadTimeConfig)
+{
+ /* Keep this variable initialized to 0 as it is used to configure BDTR register */
+ uint32_t tmpbdtr = 0U;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_BREAK_INSTANCE(htim->Instance));
+ assert_param(IS_TIM_OSSR_STATE(sBreakDeadTimeConfig->OffStateRunMode));
+ assert_param(IS_TIM_OSSI_STATE(sBreakDeadTimeConfig->OffStateIDLEMode));
+ assert_param(IS_TIM_LOCK_LEVEL(sBreakDeadTimeConfig->LockLevel));
+ assert_param(IS_TIM_DEADTIME(sBreakDeadTimeConfig->DeadTime));
+ assert_param(IS_TIM_BREAK_STATE(sBreakDeadTimeConfig->BreakState));
+ assert_param(IS_TIM_BREAK_POLARITY(sBreakDeadTimeConfig->BreakPolarity));
+ assert_param(IS_TIM_AUTOMATIC_OUTPUT_STATE(sBreakDeadTimeConfig->AutomaticOutput));
+
+ /* Check input state */
+ __HAL_LOCK(htim);
+
+ /* Set the Lock level, the Break enable Bit and the Polarity, the OSSR State,
+ the OSSI State, the dead time value and the Automatic Output Enable Bit */
+
+ /* Set the BDTR bits */
+ MODIFY_REG(tmpbdtr, TIM_BDTR_DTG, sBreakDeadTimeConfig->DeadTime);
+ MODIFY_REG(tmpbdtr, TIM_BDTR_LOCK, sBreakDeadTimeConfig->LockLevel);
+ MODIFY_REG(tmpbdtr, TIM_BDTR_OSSI, sBreakDeadTimeConfig->OffStateIDLEMode);
+ MODIFY_REG(tmpbdtr, TIM_BDTR_OSSR, sBreakDeadTimeConfig->OffStateRunMode);
+ MODIFY_REG(tmpbdtr, TIM_BDTR_BKE, sBreakDeadTimeConfig->BreakState);
+ MODIFY_REG(tmpbdtr, TIM_BDTR_BKP, sBreakDeadTimeConfig->BreakPolarity);
+ MODIFY_REG(tmpbdtr, TIM_BDTR_AOE, sBreakDeadTimeConfig->AutomaticOutput);
+
+
+ /* Set TIMx_BDTR */
+ htim->Instance->BDTR = tmpbdtr;
+
+ __HAL_UNLOCK(htim);
+
+ return HAL_OK;
+}
+
+/**
+ * @brief Configures the TIMx Remapping input capabilities.
+ * @param htim TIM handle.
+ * @param Remap specifies the TIM remapping source.
+ * For TIM14, the parameter can have the following values:
+ * @arg TIM_TIM14_GPIO: TIM14 TI1 is connected to GPIO
+ * @arg TIM_TIM14_RTC: TIM14 TI1 is connected to RTC_clock
+ * @arg TIM_TIM14_HSE: TIM14 TI1 is connected to HSE/32
+ * @arg TIM_TIM14_MCO: TIM14 TI1 is connected to MCO
+ *
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_TIMEx_RemapConfig(TIM_HandleTypeDef *htim, uint32_t Remap)
+{
+ __HAL_LOCK(htim);
+
+ /* Check parameters */
+ assert_param(IS_TIM_REMAP(htim->Instance, Remap));
+
+ /* Set the Timer remapping configuration */
+ WRITE_REG(htim->Instance->OR, Remap);
+
+ __HAL_UNLOCK(htim);
+
+ return HAL_OK;
+}
+
+/**
+ * @}
+ */
+
+/** @defgroup TIMEx_Exported_Functions_Group6 Extended Callbacks functions
+ * @brief Extended Callbacks functions
+ *
+@verbatim
+ ==============================================================================
+ ##### Extended Callbacks functions #####
+ ==============================================================================
+ [..]
+ This section provides Extended TIM callback functions:
+ (+) Timer Commutation callback
+ (+) Timer Break callback
+
+@endverbatim
+ * @{
+ */
+
+/**
+ * @brief Hall commutation changed callback in non-blocking mode
+ * @param htim TIM handle
+ * @retval None
+ */
+__weak void HAL_TIMEx_CommutCallback(TIM_HandleTypeDef *htim)
+{
+ /* Prevent unused argument(s) compilation warning */
+ UNUSED(htim);
+
+ /* NOTE : This function should not be modified, when the callback is needed,
+ the HAL_TIMEx_CommutCallback could be implemented in the user file
+ */
+}
+/**
+ * @brief Hall commutation changed half complete callback in non-blocking mode
+ * @param htim TIM handle
+ * @retval None
+ */
+__weak void HAL_TIMEx_CommutHalfCpltCallback(TIM_HandleTypeDef *htim)
+{
+ /* Prevent unused argument(s) compilation warning */
+ UNUSED(htim);
+
+ /* NOTE : This function should not be modified, when the callback is needed,
+ the HAL_TIMEx_CommutHalfCpltCallback could be implemented in the user file
+ */
+}
+
+/**
+ * @brief Hall Break detection callback in non-blocking mode
+ * @param htim TIM handle
+ * @retval None
+ */
+__weak void HAL_TIMEx_BreakCallback(TIM_HandleTypeDef *htim)
+{
+ /* Prevent unused argument(s) compilation warning */
+ UNUSED(htim);
+
+ /* NOTE : This function should not be modified, when the callback is needed,
+ the HAL_TIMEx_BreakCallback could be implemented in the user file
+ */
+}
+/**
+ * @}
+ */
+
+/** @defgroup TIMEx_Exported_Functions_Group7 Extended Peripheral State functions
+ * @brief Extended Peripheral State functions
+ *
+@verbatim
+ ==============================================================================
+ ##### Extended Peripheral State functions #####
+ ==============================================================================
+ [..]
+ This subsection permits to get in run-time the status of the peripheral
+ and the data flow.
+
+@endverbatim
+ * @{
+ */
+
+/**
+ * @brief Return the TIM Hall Sensor interface handle state.
+ * @param htim TIM Hall Sensor handle
+ * @retval HAL state
+ */
+HAL_TIM_StateTypeDef HAL_TIMEx_HallSensor_GetState(TIM_HandleTypeDef *htim)
+{
+ return htim->State;
+}
+
+/**
+ * @brief Return actual state of the TIM complementary channel.
+ * @param htim TIM handle
+ * @param ChannelN TIM Complementary channel
+ * This parameter can be one of the following values:
+ * @arg TIM_CHANNEL_1: TIM Channel 1
+ * @arg TIM_CHANNEL_2: TIM Channel 2
+ * @arg TIM_CHANNEL_3: TIM Channel 3
+ * @retval TIM Complementary channel state
+ */
+HAL_TIM_ChannelStateTypeDef HAL_TIMEx_GetChannelNState(TIM_HandleTypeDef *htim, uint32_t ChannelN)
+{
+ HAL_TIM_ChannelStateTypeDef channel_state;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, ChannelN));
+
+ channel_state = TIM_CHANNEL_N_STATE_GET(htim, ChannelN);
+
+ return channel_state;
+}
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/* Private functions ---------------------------------------------------------*/
+/** @defgroup TIMEx_Private_Functions TIMEx Private Functions
+ * @{
+ */
+
+/**
+ * @brief TIM DMA Commutation callback.
+ * @param hdma pointer to DMA handle.
+ * @retval None
+ */
+void TIMEx_DMACommutationCplt(DMA_HandleTypeDef *hdma)
+{
+ TIM_HandleTypeDef *htim = (TIM_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent;
+
+ /* Change the htim state */
+ htim->State = HAL_TIM_STATE_READY;
+
+#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1)
+ htim->CommutationCallback(htim);
+#else
+ HAL_TIMEx_CommutCallback(htim);
+#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */
+}
+
+/**
+ * @brief TIM DMA Commutation half complete callback.
+ * @param hdma pointer to DMA handle.
+ * @retval None
+ */
+void TIMEx_DMACommutationHalfCplt(DMA_HandleTypeDef *hdma)
+{
+ TIM_HandleTypeDef *htim = (TIM_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent;
+
+ /* Change the htim state */
+ htim->State = HAL_TIM_STATE_READY;
+
+#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1)
+ htim->CommutationHalfCpltCallback(htim);
+#else
+ HAL_TIMEx_CommutHalfCpltCallback(htim);
+#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */
+}
+
+
+/**
+ * @brief TIM DMA Delay Pulse complete callback (complementary channel).
+ * @param hdma pointer to DMA handle.
+ * @retval None
+ */
+static void TIM_DMADelayPulseNCplt(DMA_HandleTypeDef *hdma)
+{
+ TIM_HandleTypeDef *htim = (TIM_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent;
+
+ if (hdma == htim->hdma[TIM_DMA_ID_CC1])
+ {
+ htim->Channel = HAL_TIM_ACTIVE_CHANNEL_1;
+
+ if (hdma->Init.Mode == DMA_NORMAL)
+ {
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY);
+ }
+ }
+ else if (hdma == htim->hdma[TIM_DMA_ID_CC2])
+ {
+ htim->Channel = HAL_TIM_ACTIVE_CHANNEL_2;
+
+ if (hdma->Init.Mode == DMA_NORMAL)
+ {
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY);
+ }
+ }
+ else if (hdma == htim->hdma[TIM_DMA_ID_CC3])
+ {
+ htim->Channel = HAL_TIM_ACTIVE_CHANNEL_3;
+
+ if (hdma->Init.Mode == DMA_NORMAL)
+ {
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_3, HAL_TIM_CHANNEL_STATE_READY);
+ }
+ }
+ else if (hdma == htim->hdma[TIM_DMA_ID_CC4])
+ {
+ htim->Channel = HAL_TIM_ACTIVE_CHANNEL_4;
+
+ if (hdma->Init.Mode == DMA_NORMAL)
+ {
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_4, HAL_TIM_CHANNEL_STATE_READY);
+ }
+ }
+ else
+ {
+ /* nothing to do */
+ }
+
+#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1)
+ htim->PWM_PulseFinishedCallback(htim);
+#else
+ HAL_TIM_PWM_PulseFinishedCallback(htim);
+#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */
+
+ htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED;
+}
+
+/**
+ * @brief TIM DMA error callback (complementary channel)
+ * @param hdma pointer to DMA handle.
+ * @retval None
+ */
+static void TIM_DMAErrorCCxN(DMA_HandleTypeDef *hdma)
+{
+ TIM_HandleTypeDef *htim = (TIM_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent;
+
+ if (hdma == htim->hdma[TIM_DMA_ID_CC1])
+ {
+ htim->Channel = HAL_TIM_ACTIVE_CHANNEL_1;
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY);
+ }
+ else if (hdma == htim->hdma[TIM_DMA_ID_CC2])
+ {
+ htim->Channel = HAL_TIM_ACTIVE_CHANNEL_2;
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY);
+ }
+ else if (hdma == htim->hdma[TIM_DMA_ID_CC3])
+ {
+ htim->Channel = HAL_TIM_ACTIVE_CHANNEL_3;
+ TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_3, HAL_TIM_CHANNEL_STATE_READY);
+ }
+ else
+ {
+ /* nothing to do */
+ }
+
+#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1)
+ htim->ErrorCallback(htim);
+#else
+ HAL_TIM_ErrorCallback(htim);
+#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */
+
+ htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED;
+}
+
+/**
+ * @brief Enables or disables the TIM Capture Compare Channel xN.
+ * @param TIMx to select the TIM peripheral
+ * @param Channel specifies the TIM Channel
+ * This parameter can be one of the following values:
+ * @arg TIM_CHANNEL_1: TIM Channel 1
+ * @arg TIM_CHANNEL_2: TIM Channel 2
+ * @arg TIM_CHANNEL_3: TIM Channel 3
+ * @param ChannelNState specifies the TIM Channel CCxNE bit new state.
+ * This parameter can be: TIM_CCxN_ENABLE or TIM_CCxN_Disable.
+ * @retval None
+ */
+static void TIM_CCxNChannelCmd(TIM_TypeDef *TIMx, uint32_t Channel, uint32_t ChannelNState)
+{
+ uint32_t tmp;
+
+ tmp = TIM_CCER_CC1NE << (Channel & 0x1FU); /* 0x1FU = 31 bits max shift */
+
+ /* Reset the CCxNE Bit */
+ TIMx->CCER &= ~tmp;
+
+ /* Set or reset the CCxNE Bit */
+ TIMx->CCER |= (uint32_t)(ChannelNState << (Channel & 0x1FU)); /* 0x1FU = 31 bits max shift */
+}
+/**
+ * @}
+ */
+
+#endif /* HAL_TIM_MODULE_ENABLED */
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_dma.c b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_dma.c
new file mode 100644
index 0000000..4da47bd
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_dma.c
@@ -0,0 +1,397 @@
+/**
+ ******************************************************************************
+ * @file stm32f0xx_ll_dma.c
+ * @author MCD Application Team
+ * @brief DMA LL module driver.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2016 STMicroelectronics.
+ * All rights reserved.
+ *
+ * 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
+ *
+ ******************************************************************************
+ */
+
+#if defined(USE_FULL_LL_DRIVER)
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f0xx_ll_dma.h"
+#include "stm32f0xx_ll_bus.h"
+#ifdef USE_FULL_ASSERT
+#include "stm32_assert.h"
+#else
+#define assert_param(expr) ((void)0U)
+#endif
+
+/** @addtogroup STM32F0xx_LL_Driver
+ * @{
+ */
+
+#if defined (DMA1) || defined (DMA2)
+
+/** @defgroup DMA_LL DMA
+ * @{
+ */
+
+/* Private types -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private constants ---------------------------------------------------------*/
+/* Private macros ------------------------------------------------------------*/
+/** @addtogroup DMA_LL_Private_Macros
+ * @{
+ */
+#define IS_LL_DMA_DIRECTION(__VALUE__) (((__VALUE__) == LL_DMA_DIRECTION_PERIPH_TO_MEMORY) || \
+ ((__VALUE__) == LL_DMA_DIRECTION_MEMORY_TO_PERIPH) || \
+ ((__VALUE__) == LL_DMA_DIRECTION_MEMORY_TO_MEMORY))
+
+#define IS_LL_DMA_MODE(__VALUE__) (((__VALUE__) == LL_DMA_MODE_NORMAL) || \
+ ((__VALUE__) == LL_DMA_MODE_CIRCULAR))
+
+#define IS_LL_DMA_PERIPHINCMODE(__VALUE__) (((__VALUE__) == LL_DMA_PERIPH_INCREMENT) || \
+ ((__VALUE__) == LL_DMA_PERIPH_NOINCREMENT))
+
+#define IS_LL_DMA_MEMORYINCMODE(__VALUE__) (((__VALUE__) == LL_DMA_MEMORY_INCREMENT) || \
+ ((__VALUE__) == LL_DMA_MEMORY_NOINCREMENT))
+
+#define IS_LL_DMA_PERIPHDATASIZE(__VALUE__) (((__VALUE__) == LL_DMA_PDATAALIGN_BYTE) || \
+ ((__VALUE__) == LL_DMA_PDATAALIGN_HALFWORD) || \
+ ((__VALUE__) == LL_DMA_PDATAALIGN_WORD))
+
+#define IS_LL_DMA_MEMORYDATASIZE(__VALUE__) (((__VALUE__) == LL_DMA_MDATAALIGN_BYTE) || \
+ ((__VALUE__) == LL_DMA_MDATAALIGN_HALFWORD) || \
+ ((__VALUE__) == LL_DMA_MDATAALIGN_WORD))
+
+#define IS_LL_DMA_NBDATA(__VALUE__) ((__VALUE__) <= 0x0000FFFFU)
+
+#if (defined(DMA1_CSELR_DEFAULT)||defined(DMA2_CSELR_DEFAULT))
+#define IS_LL_DMA_PERIPHREQUEST(__VALUE__) (((__VALUE__) == LL_DMA_REQUEST_0) || \
+ ((__VALUE__) == LL_DMA_REQUEST_1) || \
+ ((__VALUE__) == LL_DMA_REQUEST_2) || \
+ ((__VALUE__) == LL_DMA_REQUEST_3) || \
+ ((__VALUE__) == LL_DMA_REQUEST_4) || \
+ ((__VALUE__) == LL_DMA_REQUEST_5) || \
+ ((__VALUE__) == LL_DMA_REQUEST_6) || \
+ ((__VALUE__) == LL_DMA_REQUEST_7) || \
+ ((__VALUE__) == LL_DMA_REQUEST_8) || \
+ ((__VALUE__) == LL_DMA_REQUEST_9) || \
+ ((__VALUE__) == LL_DMA_REQUEST_10) || \
+ ((__VALUE__) == LL_DMA_REQUEST_11) || \
+ ((__VALUE__) == LL_DMA_REQUEST_12) || \
+ ((__VALUE__) == LL_DMA_REQUEST_13) || \
+ ((__VALUE__) == LL_DMA_REQUEST_14) || \
+ ((__VALUE__) == LL_DMA_REQUEST_15))
+#endif
+
+#define IS_LL_DMA_PRIORITY(__VALUE__) (((__VALUE__) == LL_DMA_PRIORITY_LOW) || \
+ ((__VALUE__) == LL_DMA_PRIORITY_MEDIUM) || \
+ ((__VALUE__) == LL_DMA_PRIORITY_HIGH) || \
+ ((__VALUE__) == LL_DMA_PRIORITY_VERYHIGH))
+
+#if defined (DMA2)
+#if defined (DMA2_Channel6) && defined (DMA2_Channel7)
+#define IS_LL_DMA_ALL_CHANNEL_INSTANCE(INSTANCE, CHANNEL) ((((INSTANCE) == DMA1) && \
+ (((CHANNEL) == LL_DMA_CHANNEL_1) || \
+ ((CHANNEL) == LL_DMA_CHANNEL_2) || \
+ ((CHANNEL) == LL_DMA_CHANNEL_3) || \
+ ((CHANNEL) == LL_DMA_CHANNEL_4) || \
+ ((CHANNEL) == LL_DMA_CHANNEL_5) || \
+ ((CHANNEL) == LL_DMA_CHANNEL_6) || \
+ ((CHANNEL) == LL_DMA_CHANNEL_7))) || \
+ (((INSTANCE) == DMA2) && \
+ (((CHANNEL) == LL_DMA_CHANNEL_1) || \
+ ((CHANNEL) == LL_DMA_CHANNEL_2) || \
+ ((CHANNEL) == LL_DMA_CHANNEL_3) || \
+ ((CHANNEL) == LL_DMA_CHANNEL_4) || \
+ ((CHANNEL) == LL_DMA_CHANNEL_5) || \
+ ((CHANNEL) == LL_DMA_CHANNEL_6) || \
+ ((CHANNEL) == LL_DMA_CHANNEL_7))))
+#else
+#define IS_LL_DMA_ALL_CHANNEL_INSTANCE(INSTANCE, CHANNEL) ((((INSTANCE) == DMA1) && \
+ (((CHANNEL) == LL_DMA_CHANNEL_1) || \
+ ((CHANNEL) == LL_DMA_CHANNEL_2) || \
+ ((CHANNEL) == LL_DMA_CHANNEL_3) || \
+ ((CHANNEL) == LL_DMA_CHANNEL_4) || \
+ ((CHANNEL) == LL_DMA_CHANNEL_5) || \
+ ((CHANNEL) == LL_DMA_CHANNEL_6) || \
+ ((CHANNEL) == LL_DMA_CHANNEL_7))) || \
+ (((INSTANCE) == DMA2) && \
+ (((CHANNEL) == LL_DMA_CHANNEL_1) || \
+ ((CHANNEL) == LL_DMA_CHANNEL_2) || \
+ ((CHANNEL) == LL_DMA_CHANNEL_3) || \
+ ((CHANNEL) == LL_DMA_CHANNEL_4) || \
+ ((CHANNEL) == LL_DMA_CHANNEL_5))))
+#endif
+#else
+#if defined(DMA1_Channel6) && defined(DMA1_Channel7)
+#define IS_LL_DMA_ALL_CHANNEL_INSTANCE(INSTANCE, CHANNEL) ((((INSTANCE) == DMA1) && \
+ (((CHANNEL) == LL_DMA_CHANNEL_1)|| \
+ ((CHANNEL) == LL_DMA_CHANNEL_2) || \
+ ((CHANNEL) == LL_DMA_CHANNEL_3) || \
+ ((CHANNEL) == LL_DMA_CHANNEL_4) || \
+ ((CHANNEL) == LL_DMA_CHANNEL_5) || \
+ ((CHANNEL) == LL_DMA_CHANNEL_6) || \
+ ((CHANNEL) == LL_DMA_CHANNEL_7))))
+#elif defined (DMA1_Channel6)
+#define IS_LL_DMA_ALL_CHANNEL_INSTANCE(INSTANCE, CHANNEL) ((((INSTANCE) == DMA1) && \
+ (((CHANNEL) == LL_DMA_CHANNEL_1)|| \
+ ((CHANNEL) == LL_DMA_CHANNEL_2) || \
+ ((CHANNEL) == LL_DMA_CHANNEL_3) || \
+ ((CHANNEL) == LL_DMA_CHANNEL_4) || \
+ ((CHANNEL) == LL_DMA_CHANNEL_5) || \
+ ((CHANNEL) == LL_DMA_CHANNEL_6))))
+#else
+#define IS_LL_DMA_ALL_CHANNEL_INSTANCE(INSTANCE, CHANNEL) ((((INSTANCE) == DMA1) && \
+ (((CHANNEL) == LL_DMA_CHANNEL_1)|| \
+ ((CHANNEL) == LL_DMA_CHANNEL_2) || \
+ ((CHANNEL) == LL_DMA_CHANNEL_3) || \
+ ((CHANNEL) == LL_DMA_CHANNEL_4) || \
+ ((CHANNEL) == LL_DMA_CHANNEL_5))))
+#endif /* DMA1_Channel6 && DMA1_Channel7 */
+#endif
+/**
+ * @}
+ */
+
+/* Private function prototypes -----------------------------------------------*/
+
+/* Exported functions --------------------------------------------------------*/
+/** @addtogroup DMA_LL_Exported_Functions
+ * @{
+ */
+
+/** @addtogroup DMA_LL_EF_Init
+ * @{
+ */
+
+/**
+ * @brief De-initialize the DMA registers to their default reset values.
+ * @param DMAx DMAx Instance
+ * @param Channel This parameter can be one of the following values:
+ * @arg @ref LL_DMA_CHANNEL_1
+ * @arg @ref LL_DMA_CHANNEL_2
+ * @arg @ref LL_DMA_CHANNEL_3
+ * @arg @ref LL_DMA_CHANNEL_4
+ * @arg @ref LL_DMA_CHANNEL_5
+ * @arg @ref LL_DMA_CHANNEL_6 (*)
+ * @arg @ref LL_DMA_CHANNEL_7 (*)
+ *
+ * (*) value not defined in all devices
+ * @retval An ErrorStatus enumeration value:
+ * - SUCCESS: DMA registers are de-initialized
+ * - ERROR: DMA registers are not de-initialized
+ */
+uint32_t LL_DMA_DeInit(DMA_TypeDef *DMAx, uint32_t Channel)
+{
+ DMA_Channel_TypeDef *tmp = (DMA_Channel_TypeDef *)DMA1_Channel1;
+ ErrorStatus status = SUCCESS;
+
+ /* Check the DMA Instance DMAx and Channel parameters*/
+ assert_param(IS_LL_DMA_ALL_CHANNEL_INSTANCE(DMAx, Channel));
+
+ tmp = (DMA_Channel_TypeDef *)(__LL_DMA_GET_CHANNEL_INSTANCE(DMAx, Channel));
+
+ /* Disable the selected DMAx_Channely */
+ CLEAR_BIT(tmp->CCR, DMA_CCR_EN);
+
+ /* Reset DMAx_Channely control register */
+ LL_DMA_WriteReg(tmp, CCR, 0U);
+
+ /* Reset DMAx_Channely remaining bytes register */
+ LL_DMA_WriteReg(tmp, CNDTR, 0U);
+
+ /* Reset DMAx_Channely peripheral address register */
+ LL_DMA_WriteReg(tmp, CPAR, 0U);
+
+ /* Reset DMAx_Channely memory address register */
+ LL_DMA_WriteReg(tmp, CMAR, 0U);
+
+#if (defined(DMA1_CSELR_DEFAULT)||defined(DMA2_CSELR_DEFAULT))
+ /* Reset Request register field for DMAx Channel */
+ LL_DMA_SetPeriphRequest(DMAx, Channel, LL_DMA_REQUEST_0);
+#endif
+
+ if (Channel == LL_DMA_CHANNEL_1)
+ {
+ /* Reset interrupt pending bits for DMAx Channel1 */
+ LL_DMA_ClearFlag_GI1(DMAx);
+ }
+ else if (Channel == LL_DMA_CHANNEL_2)
+ {
+ /* Reset interrupt pending bits for DMAx Channel2 */
+ LL_DMA_ClearFlag_GI2(DMAx);
+ }
+ else if (Channel == LL_DMA_CHANNEL_3)
+ {
+ /* Reset interrupt pending bits for DMAx Channel3 */
+ LL_DMA_ClearFlag_GI3(DMAx);
+ }
+ else if (Channel == LL_DMA_CHANNEL_4)
+ {
+ /* Reset interrupt pending bits for DMAx Channel4 */
+ LL_DMA_ClearFlag_GI4(DMAx);
+ }
+ else if (Channel == LL_DMA_CHANNEL_5)
+ {
+ /* Reset interrupt pending bits for DMAx Channel5 */
+ LL_DMA_ClearFlag_GI5(DMAx);
+ }
+
+#if defined(DMA1_Channel6)
+ else if (Channel == LL_DMA_CHANNEL_6)
+ {
+ /* Reset interrupt pending bits for DMAx Channel6 */
+ LL_DMA_ClearFlag_GI6(DMAx);
+ }
+#endif
+#if defined(DMA1_Channel7)
+ else if (Channel == LL_DMA_CHANNEL_7)
+ {
+ /* Reset interrupt pending bits for DMAx Channel7 */
+ LL_DMA_ClearFlag_GI7(DMAx);
+ }
+#endif
+ else
+ {
+ status = ERROR;
+ }
+
+ return status;
+}
+
+/**
+ * @brief Initialize the DMA registers according to the specified parameters in DMA_InitStruct.
+ * @note To convert DMAx_Channely Instance to DMAx Instance and Channely, use helper macros :
+ * @arg @ref __LL_DMA_GET_INSTANCE
+ * @arg @ref __LL_DMA_GET_CHANNEL
+ * @param DMAx DMAx Instance
+ * @param Channel This parameter can be one of the following values:
+ * @arg @ref LL_DMA_CHANNEL_1
+ * @arg @ref LL_DMA_CHANNEL_2
+ * @arg @ref LL_DMA_CHANNEL_3
+ * @arg @ref LL_DMA_CHANNEL_4
+ * @arg @ref LL_DMA_CHANNEL_5
+ * @arg @ref LL_DMA_CHANNEL_6 (*)
+ * @arg @ref LL_DMA_CHANNEL_7 (*)
+ *
+ * (*) value not defined in all devices
+ * @param DMA_InitStruct pointer to a @ref LL_DMA_InitTypeDef structure.
+ * @retval An ErrorStatus enumeration value:
+ * - SUCCESS: DMA registers are initialized
+ * - ERROR: Not applicable
+ */
+uint32_t LL_DMA_Init(DMA_TypeDef *DMAx, uint32_t Channel, LL_DMA_InitTypeDef *DMA_InitStruct)
+{
+ /* Check the DMA Instance DMAx and Channel parameters*/
+ assert_param(IS_LL_DMA_ALL_CHANNEL_INSTANCE(DMAx, Channel));
+
+ /* Check the DMA parameters from DMA_InitStruct */
+ assert_param(IS_LL_DMA_DIRECTION(DMA_InitStruct->Direction));
+ assert_param(IS_LL_DMA_MODE(DMA_InitStruct->Mode));
+ assert_param(IS_LL_DMA_PERIPHINCMODE(DMA_InitStruct->PeriphOrM2MSrcIncMode));
+ assert_param(IS_LL_DMA_MEMORYINCMODE(DMA_InitStruct->MemoryOrM2MDstIncMode));
+ assert_param(IS_LL_DMA_PERIPHDATASIZE(DMA_InitStruct->PeriphOrM2MSrcDataSize));
+ assert_param(IS_LL_DMA_MEMORYDATASIZE(DMA_InitStruct->MemoryOrM2MDstDataSize));
+ assert_param(IS_LL_DMA_NBDATA(DMA_InitStruct->NbData));
+#if (defined(DMA1_CSELR_DEFAULT)||defined(DMA2_CSELR_DEFAULT))
+ assert_param(IS_LL_DMA_PERIPHREQUEST(DMA_InitStruct->PeriphRequest));
+#endif
+ assert_param(IS_LL_DMA_PRIORITY(DMA_InitStruct->Priority));
+
+ /*---------------------------- DMAx CCR Configuration ------------------------
+ * Configure DMAx_Channely: data transfer direction, data transfer mode,
+ * peripheral and memory increment mode,
+ * data size alignment and priority level with parameters :
+ * - Direction: DMA_CCR_DIR and DMA_CCR_MEM2MEM bits
+ * - Mode: DMA_CCR_CIRC bit
+ * - PeriphOrM2MSrcIncMode: DMA_CCR_PINC bit
+ * - MemoryOrM2MDstIncMode: DMA_CCR_MINC bit
+ * - PeriphOrM2MSrcDataSize: DMA_CCR_PSIZE[1:0] bits
+ * - MemoryOrM2MDstDataSize: DMA_CCR_MSIZE[1:0] bits
+ * - Priority: DMA_CCR_PL[1:0] bits
+ */
+ LL_DMA_ConfigTransfer(DMAx, Channel, DMA_InitStruct->Direction | \
+ DMA_InitStruct->Mode | \
+ DMA_InitStruct->PeriphOrM2MSrcIncMode | \
+ DMA_InitStruct->MemoryOrM2MDstIncMode | \
+ DMA_InitStruct->PeriphOrM2MSrcDataSize | \
+ DMA_InitStruct->MemoryOrM2MDstDataSize | \
+ DMA_InitStruct->Priority);
+
+ /*-------------------------- DMAx CMAR Configuration -------------------------
+ * Configure the memory or destination base address with parameter :
+ * - MemoryOrM2MDstAddress: DMA_CMAR_MA[31:0] bits
+ */
+ LL_DMA_SetMemoryAddress(DMAx, Channel, DMA_InitStruct->MemoryOrM2MDstAddress);
+
+ /*-------------------------- DMAx CPAR Configuration -------------------------
+ * Configure the peripheral or source base address with parameter :
+ * - PeriphOrM2MSrcAddress: DMA_CPAR_PA[31:0] bits
+ */
+ LL_DMA_SetPeriphAddress(DMAx, Channel, DMA_InitStruct->PeriphOrM2MSrcAddress);
+
+ /*--------------------------- DMAx CNDTR Configuration -----------------------
+ * Configure the peripheral base address with parameter :
+ * - NbData: DMA_CNDTR_NDT[15:0] bits
+ */
+ LL_DMA_SetDataLength(DMAx, Channel, DMA_InitStruct->NbData);
+
+#if (defined(DMA1_CSELR_DEFAULT)||defined(DMA2_CSELR_DEFAULT))
+ /*--------------------------- DMAx CSELR Configuration -----------------------
+ * Configure the DMA request for DMA instance on Channel x with parameter :
+ * - PeriphRequest: DMA_CSELR[31:0] bits
+ */
+ LL_DMA_SetPeriphRequest(DMAx, Channel, DMA_InitStruct->PeriphRequest);
+#endif
+
+ return SUCCESS;
+}
+
+/**
+ * @brief Set each @ref LL_DMA_InitTypeDef field to default value.
+ * @param DMA_InitStruct Pointer to a @ref LL_DMA_InitTypeDef structure.
+ * @retval None
+ */
+void LL_DMA_StructInit(LL_DMA_InitTypeDef *DMA_InitStruct)
+{
+ /* Set DMA_InitStruct fields to default values */
+ DMA_InitStruct->PeriphOrM2MSrcAddress = 0x00000000U;
+ DMA_InitStruct->MemoryOrM2MDstAddress = 0x00000000U;
+ DMA_InitStruct->Direction = LL_DMA_DIRECTION_PERIPH_TO_MEMORY;
+ DMA_InitStruct->Mode = LL_DMA_MODE_NORMAL;
+ DMA_InitStruct->PeriphOrM2MSrcIncMode = LL_DMA_PERIPH_NOINCREMENT;
+ DMA_InitStruct->MemoryOrM2MDstIncMode = LL_DMA_MEMORY_NOINCREMENT;
+ DMA_InitStruct->PeriphOrM2MSrcDataSize = LL_DMA_PDATAALIGN_BYTE;
+ DMA_InitStruct->MemoryOrM2MDstDataSize = LL_DMA_MDATAALIGN_BYTE;
+ DMA_InitStruct->NbData = 0x00000000U;
+#if (defined(DMA1_CSELR_DEFAULT)||defined(DMA2_CSELR_DEFAULT))
+ DMA_InitStruct->PeriphRequest = LL_DMA_REQUEST_0;
+#endif
+ DMA_InitStruct->Priority = LL_DMA_PRIORITY_LOW;
+}
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+#endif /* DMA1 || DMA2 */
+
+/**
+ * @}
+ */
+
+#endif /* USE_FULL_LL_DRIVER */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_exti.c b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_exti.c
new file mode 100644
index 0000000..ef4d16d
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_exti.c
@@ -0,0 +1,223 @@
+/**
+ ******************************************************************************
+ * @file stm32f0xx_ll_exti.c
+ * @author MCD Application Team
+ * @brief EXTI LL module driver.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2016 STMicroelectronics.
+ * All rights reserved.
+ *
+ * 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
+ *
+ ******************************************************************************
+ */
+
+#if defined(USE_FULL_LL_DRIVER)
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f0xx_ll_exti.h"
+#ifdef USE_FULL_ASSERT
+#include "stm32_assert.h"
+#else
+#define assert_param(expr) ((void)0U)
+#endif
+
+/** @addtogroup STM32F0xx_LL_Driver
+ * @{
+ */
+
+#if defined (EXTI)
+
+/** @defgroup EXTI_LL EXTI
+ * @{
+ */
+
+/* Private types -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private constants ---------------------------------------------------------*/
+/* Private macros ------------------------------------------------------------*/
+/** @addtogroup EXTI_LL_Private_Macros
+ * @{
+ */
+
+#define IS_LL_EXTI_LINE_0_31(__VALUE__) (((__VALUE__) & ~LL_EXTI_LINE_ALL_0_31) == 0x00000000U)
+
+#define IS_LL_EXTI_MODE(__VALUE__) (((__VALUE__) == LL_EXTI_MODE_IT) \
+ || ((__VALUE__) == LL_EXTI_MODE_EVENT) \
+ || ((__VALUE__) == LL_EXTI_MODE_IT_EVENT))
+
+
+#define IS_LL_EXTI_TRIGGER(__VALUE__) (((__VALUE__) == LL_EXTI_TRIGGER_NONE) \
+ || ((__VALUE__) == LL_EXTI_TRIGGER_RISING) \
+ || ((__VALUE__) == LL_EXTI_TRIGGER_FALLING) \
+ || ((__VALUE__) == LL_EXTI_TRIGGER_RISING_FALLING))
+
+/**
+ * @}
+ */
+
+/* Private function prototypes -----------------------------------------------*/
+
+/* Exported functions --------------------------------------------------------*/
+/** @addtogroup EXTI_LL_Exported_Functions
+ * @{
+ */
+
+/** @addtogroup EXTI_LL_EF_Init
+ * @{
+ */
+
+/**
+ * @brief De-initialize the EXTI registers to their default reset values.
+ * @retval An ErrorStatus enumeration value:
+ * - SUCCESS: EXTI registers are de-initialized
+ * - ERROR: not applicable
+ */
+uint32_t LL_EXTI_DeInit(void)
+{
+ /* Interrupt mask register set to default reset values */
+#if defined(STM32F030x6) || defined(STM32F031x6) ||defined(STM32F038xx)
+ LL_EXTI_WriteReg(IMR, 0x0FF40000U);
+#elif defined(STM32F070x6) || defined(STM32F042x6) || defined(STM32F048xx)
+ LL_EXTI_WriteReg(IMR, 0x7FF40000U);
+#elif defined(STM32F030x8) || defined(STM32F051x8) || defined(STM32F058xx)
+ LL_EXTI_WriteReg(IMR, 0x0F940000U);
+#else
+ LL_EXTI_WriteReg(IMR, 0x7F840000U);
+#endif
+ /* Event mask register set to default reset values */
+ LL_EXTI_WriteReg(EMR, 0x00000000U);
+ /* Rising Trigger selection register set to default reset values */
+ LL_EXTI_WriteReg(RTSR, 0x00000000U);
+ /* Falling Trigger selection register set to default reset values */
+ LL_EXTI_WriteReg(FTSR, 0x00000000U);
+ /* Software interrupt event register set to default reset values */
+ LL_EXTI_WriteReg(SWIER, 0x00000000U);
+ /* Pending register clear */
+ LL_EXTI_WriteReg(PR, 0x007BFFFFU);
+
+ return SUCCESS;
+}
+
+/**
+ * @brief Initialize the EXTI registers according to the specified parameters in EXTI_InitStruct.
+ * @param EXTI_InitStruct pointer to a @ref LL_EXTI_InitTypeDef structure.
+ * @retval An ErrorStatus enumeration value:
+ * - SUCCESS: EXTI registers are initialized
+ * - ERROR: not applicable
+ */
+uint32_t LL_EXTI_Init(LL_EXTI_InitTypeDef *EXTI_InitStruct)
+{
+ ErrorStatus status = SUCCESS;
+ /* Check the parameters */
+ assert_param(IS_LL_EXTI_LINE_0_31(EXTI_InitStruct->Line_0_31));
+ assert_param(IS_FUNCTIONAL_STATE(EXTI_InitStruct->LineCommand));
+ assert_param(IS_LL_EXTI_MODE(EXTI_InitStruct->Mode));
+
+ /* ENABLE LineCommand */
+ if (EXTI_InitStruct->LineCommand != DISABLE)
+ {
+ assert_param(IS_LL_EXTI_TRIGGER(EXTI_InitStruct->Trigger));
+
+ /* Configure EXTI Lines in range from 0 to 31 */
+ if (EXTI_InitStruct->Line_0_31 != LL_EXTI_LINE_NONE)
+ {
+ switch (EXTI_InitStruct->Mode)
+ {
+ case LL_EXTI_MODE_IT:
+ /* First Disable Event on provided Lines */
+ LL_EXTI_DisableEvent_0_31(EXTI_InitStruct->Line_0_31);
+ /* Then Enable IT on provided Lines */
+ LL_EXTI_EnableIT_0_31(EXTI_InitStruct->Line_0_31);
+ break;
+ case LL_EXTI_MODE_EVENT:
+ /* First Disable IT on provided Lines */
+ LL_EXTI_DisableIT_0_31(EXTI_InitStruct->Line_0_31);
+ /* Then Enable Event on provided Lines */
+ LL_EXTI_EnableEvent_0_31(EXTI_InitStruct->Line_0_31);
+ break;
+ case LL_EXTI_MODE_IT_EVENT:
+ /* Directly Enable IT & Event on provided Lines */
+ LL_EXTI_EnableIT_0_31(EXTI_InitStruct->Line_0_31);
+ LL_EXTI_EnableEvent_0_31(EXTI_InitStruct->Line_0_31);
+ break;
+ default:
+ status = ERROR;
+ break;
+ }
+ if (EXTI_InitStruct->Trigger != LL_EXTI_TRIGGER_NONE)
+ {
+ switch (EXTI_InitStruct->Trigger)
+ {
+ case LL_EXTI_TRIGGER_RISING:
+ /* First Disable Falling Trigger on provided Lines */
+ LL_EXTI_DisableFallingTrig_0_31(EXTI_InitStruct->Line_0_31);
+ /* Then Enable Rising Trigger on provided Lines */
+ LL_EXTI_EnableRisingTrig_0_31(EXTI_InitStruct->Line_0_31);
+ break;
+ case LL_EXTI_TRIGGER_FALLING:
+ /* First Disable Rising Trigger on provided Lines */
+ LL_EXTI_DisableRisingTrig_0_31(EXTI_InitStruct->Line_0_31);
+ /* Then Enable Falling Trigger on provided Lines */
+ LL_EXTI_EnableFallingTrig_0_31(EXTI_InitStruct->Line_0_31);
+ break;
+ case LL_EXTI_TRIGGER_RISING_FALLING:
+ LL_EXTI_EnableRisingTrig_0_31(EXTI_InitStruct->Line_0_31);
+ LL_EXTI_EnableFallingTrig_0_31(EXTI_InitStruct->Line_0_31);
+ break;
+ default:
+ status = ERROR;
+ break;
+ }
+ }
+ }
+ }
+ /* DISABLE LineCommand */
+ else
+ {
+ /* De-configure EXTI Lines in range from 0 to 31 */
+ LL_EXTI_DisableIT_0_31(EXTI_InitStruct->Line_0_31);
+ LL_EXTI_DisableEvent_0_31(EXTI_InitStruct->Line_0_31);
+ }
+ return status;
+}
+
+/**
+ * @brief Set each @ref LL_EXTI_InitTypeDef field to default value.
+ * @param EXTI_InitStruct Pointer to a @ref LL_EXTI_InitTypeDef structure.
+ * @retval None
+ */
+void LL_EXTI_StructInit(LL_EXTI_InitTypeDef *EXTI_InitStruct)
+{
+ EXTI_InitStruct->Line_0_31 = LL_EXTI_LINE_NONE;
+ EXTI_InitStruct->LineCommand = DISABLE;
+ EXTI_InitStruct->Mode = LL_EXTI_MODE_IT;
+ EXTI_InitStruct->Trigger = LL_EXTI_TRIGGER_FALLING;
+}
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+#endif /* defined (EXTI) */
+
+/**
+ * @}
+ */
+
+#endif /* USE_FULL_LL_DRIVER */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_gpio.c b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_gpio.c
new file mode 100644
index 0000000..83d14aa
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_gpio.c
@@ -0,0 +1,277 @@
+/**
+ ******************************************************************************
+ * @file stm32f0xx_ll_gpio.c
+ * @author MCD Application Team
+ * @brief GPIO LL module driver.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2016 STMicroelectronics.
+ * All rights reserved.
+ *
+ * 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
+ *
+ ******************************************************************************
+ */
+
+#if defined(USE_FULL_LL_DRIVER)
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f0xx_ll_gpio.h"
+#include "stm32f0xx_ll_bus.h"
+#ifdef USE_FULL_ASSERT
+#include "stm32_assert.h"
+#else
+#define assert_param(expr) ((void)0U)
+#endif
+
+/** @addtogroup STM32F0xx_LL_Driver
+ * @{
+ */
+
+#if defined (GPIOA) || defined (GPIOB) || defined (GPIOC) || defined (GPIOD) || defined (GPIOE) || defined (GPIOF)
+
+/** @addtogroup GPIO_LL
+ * @{
+ */
+/** MISRA C:2012 deviation rule has been granted for following rules:
+ * Rule-12.2 - Medium: RHS argument is in interval [0,INF] which is out of
+ * range of the shift operator in following API :
+ * LL_GPIO_Init
+ * LL_GPIO_DeInit
+ * LL_GPIO_SetPinMode
+ * LL_GPIO_GetPinMode
+ * LL_GPIO_SetPinSpeed
+ * LL_GPIO_GetPinSpeed
+ * LL_GPIO_SetPinPull
+ * LL_GPIO_GetPinPull
+ * LL_GPIO_GetAFPin_0_7
+ * LL_GPIO_SetAFPin_0_7
+ * LL_GPIO_SetAFPin_8_15
+ * LL_GPIO_GetAFPin_8_15
+ */
+
+/* Private types -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private constants ---------------------------------------------------------*/
+/* Private macros ------------------------------------------------------------*/
+/** @addtogroup GPIO_LL_Private_Macros
+ * @{
+ */
+#define IS_LL_GPIO_PIN(__VALUE__) (((0x00u) < (__VALUE__)) && ((__VALUE__) <= (LL_GPIO_PIN_ALL)))
+
+#define IS_LL_GPIO_MODE(__VALUE__) (((__VALUE__) == LL_GPIO_MODE_INPUT) ||\
+ ((__VALUE__) == LL_GPIO_MODE_OUTPUT) ||\
+ ((__VALUE__) == LL_GPIO_MODE_ALTERNATE) ||\
+ ((__VALUE__) == LL_GPIO_MODE_ANALOG))
+
+#define IS_LL_GPIO_OUTPUT_TYPE(__VALUE__) (((__VALUE__) == LL_GPIO_OUTPUT_PUSHPULL) ||\
+ ((__VALUE__) == LL_GPIO_OUTPUT_OPENDRAIN))
+
+#define IS_LL_GPIO_SPEED(__VALUE__) (((__VALUE__) == LL_GPIO_SPEED_FREQ_LOW) ||\
+ ((__VALUE__) == LL_GPIO_SPEED_FREQ_MEDIUM) ||\
+ ((__VALUE__) == LL_GPIO_SPEED_FREQ_HIGH))
+
+#define IS_LL_GPIO_PULL(__VALUE__) (((__VALUE__) == LL_GPIO_PULL_NO) ||\
+ ((__VALUE__) == LL_GPIO_PULL_UP) ||\
+ ((__VALUE__) == LL_GPIO_PULL_DOWN))
+
+#define IS_LL_GPIO_ALTERNATE(__VALUE__) (((__VALUE__) == LL_GPIO_AF_0 ) ||\
+ ((__VALUE__) == LL_GPIO_AF_1 ) ||\
+ ((__VALUE__) == LL_GPIO_AF_2 ) ||\
+ ((__VALUE__) == LL_GPIO_AF_3 ) ||\
+ ((__VALUE__) == LL_GPIO_AF_4 ) ||\
+ ((__VALUE__) == LL_GPIO_AF_5 ) ||\
+ ((__VALUE__) == LL_GPIO_AF_6 ) ||\
+ ((__VALUE__) == LL_GPIO_AF_7 ))
+/**
+ * @}
+ */
+
+/* Private function prototypes -----------------------------------------------*/
+
+/* Exported functions --------------------------------------------------------*/
+/** @addtogroup GPIO_LL_Exported_Functions
+ * @{
+ */
+
+/** @addtogroup GPIO_LL_EF_Init
+ * @{
+ */
+
+/**
+ * @brief De-initialize GPIO registers (Registers restored to their default values).
+ * @param GPIOx GPIO Port
+ * @retval An ErrorStatus enumeration value:
+ * - SUCCESS: GPIO registers are de-initialized
+ * - ERROR: Wrong GPIO Port
+ */
+ErrorStatus LL_GPIO_DeInit(GPIO_TypeDef *GPIOx)
+{
+ ErrorStatus status = SUCCESS;
+
+ /* Check the parameters */
+ assert_param(IS_GPIO_ALL_INSTANCE(GPIOx));
+
+ /* Force and Release reset on clock of GPIOx Port */
+ if (GPIOx == GPIOA)
+ {
+ LL_AHB1_GRP1_ForceReset(LL_AHB1_GRP1_PERIPH_GPIOA);
+ LL_AHB1_GRP1_ReleaseReset(LL_AHB1_GRP1_PERIPH_GPIOA);
+ }
+ else if (GPIOx == GPIOB)
+ {
+ LL_AHB1_GRP1_ForceReset(LL_AHB1_GRP1_PERIPH_GPIOB);
+ LL_AHB1_GRP1_ReleaseReset(LL_AHB1_GRP1_PERIPH_GPIOB);
+ }
+ else if (GPIOx == GPIOC)
+ {
+ LL_AHB1_GRP1_ForceReset(LL_AHB1_GRP1_PERIPH_GPIOC);
+ LL_AHB1_GRP1_ReleaseReset(LL_AHB1_GRP1_PERIPH_GPIOC);
+ }
+#if defined(GPIOD)
+ else if (GPIOx == GPIOD)
+ {
+ LL_AHB1_GRP1_ForceReset(LL_AHB1_GRP1_PERIPH_GPIOD);
+ LL_AHB1_GRP1_ReleaseReset(LL_AHB1_GRP1_PERIPH_GPIOD);
+ }
+#endif /* GPIOD */
+#if defined(GPIOE)
+ else if (GPIOx == GPIOE)
+ {
+ LL_AHB1_GRP1_ForceReset(LL_AHB1_GRP1_PERIPH_GPIOE);
+ LL_AHB1_GRP1_ReleaseReset(LL_AHB1_GRP1_PERIPH_GPIOE);
+ }
+#endif /* GPIOE */
+#if defined(GPIOF)
+ else if (GPIOx == GPIOF)
+ {
+ LL_AHB1_GRP1_ForceReset(LL_AHB1_GRP1_PERIPH_GPIOF);
+ LL_AHB1_GRP1_ReleaseReset(LL_AHB1_GRP1_PERIPH_GPIOF);
+ }
+#endif /* GPIOF */
+ else
+ {
+ status = ERROR;
+ }
+
+ return (status);
+}
+
+/**
+ * @brief Initialize GPIO registers according to the specified parameters in GPIO_InitStruct.
+ * @param GPIOx GPIO Port
+ * @param GPIO_InitStruct pointer to a @ref LL_GPIO_InitTypeDef structure
+ * that contains the configuration information for the specified GPIO peripheral.
+ * @retval An ErrorStatus enumeration value:
+ * - SUCCESS: GPIO registers are initialized according to GPIO_InitStruct content
+ * - ERROR: Not applicable
+ */
+ErrorStatus LL_GPIO_Init(GPIO_TypeDef *GPIOx, LL_GPIO_InitTypeDef *GPIO_InitStruct)
+{
+ uint32_t pinpos;
+ uint32_t currentpin;
+
+ /* Check the parameters */
+ assert_param(IS_GPIO_ALL_INSTANCE(GPIOx));
+ assert_param(IS_LL_GPIO_PIN(GPIO_InitStruct->Pin));
+ assert_param(IS_LL_GPIO_MODE(GPIO_InitStruct->Mode));
+ assert_param(IS_LL_GPIO_PULL(GPIO_InitStruct->Pull));
+
+ /* ------------------------- Configure the port pins ---------------- */
+ /* Initialize pinpos on first pin set */
+ pinpos = 0;
+
+ /* Configure the port pins */
+ while (((GPIO_InitStruct->Pin) >> pinpos) != 0x00u)
+ {
+ /* Get current io position */
+ currentpin = (GPIO_InitStruct->Pin) & (0x00000001uL << pinpos);
+
+ if (currentpin != 0x00u)
+ {
+ if ((GPIO_InitStruct->Mode == LL_GPIO_MODE_OUTPUT) || (GPIO_InitStruct->Mode == LL_GPIO_MODE_ALTERNATE))
+ {
+ /* Check Speed mode parameters */
+ assert_param(IS_LL_GPIO_SPEED(GPIO_InitStruct->Speed));
+
+ /* Speed mode configuration */
+ LL_GPIO_SetPinSpeed(GPIOx, currentpin, GPIO_InitStruct->Speed);
+
+ /* Check Output mode parameters */
+ assert_param(IS_LL_GPIO_OUTPUT_TYPE(GPIO_InitStruct->OutputType));
+
+ /* Output mode configuration*/
+ LL_GPIO_SetPinOutputType(GPIOx, GPIO_InitStruct->Pin, GPIO_InitStruct->OutputType);
+ }
+
+ /* Pull-up Pull down resistor configuration*/
+ LL_GPIO_SetPinPull(GPIOx, currentpin, GPIO_InitStruct->Pull);
+
+ if (GPIO_InitStruct->Mode == LL_GPIO_MODE_ALTERNATE)
+ {
+ /* Check Alternate parameter */
+ assert_param(IS_LL_GPIO_ALTERNATE(GPIO_InitStruct->Alternate));
+
+ /* Speed mode configuration */
+ if (currentpin < LL_GPIO_PIN_8)
+ {
+ LL_GPIO_SetAFPin_0_7(GPIOx, currentpin, GPIO_InitStruct->Alternate);
+ }
+ else
+ {
+ LL_GPIO_SetAFPin_8_15(GPIOx, currentpin, GPIO_InitStruct->Alternate);
+ }
+ }
+
+ /* Pin Mode configuration */
+ LL_GPIO_SetPinMode(GPIOx, currentpin, GPIO_InitStruct->Mode);
+ }
+ pinpos++;
+ }
+
+ return (SUCCESS);
+}
+
+/**
+ * @brief Set each @ref LL_GPIO_InitTypeDef field to default value.
+ * @param GPIO_InitStruct pointer to a @ref LL_GPIO_InitTypeDef structure
+ * whose fields will be set to default values.
+ * @retval None
+ */
+
+void LL_GPIO_StructInit(LL_GPIO_InitTypeDef *GPIO_InitStruct)
+{
+ /* Reset GPIO init structure parameters values */
+ GPIO_InitStruct->Pin = LL_GPIO_PIN_ALL;
+ GPIO_InitStruct->Mode = LL_GPIO_MODE_ANALOG;
+ GPIO_InitStruct->Speed = LL_GPIO_SPEED_FREQ_LOW;
+ GPIO_InitStruct->OutputType = LL_GPIO_OUTPUT_PUSHPULL;
+ GPIO_InitStruct->Pull = LL_GPIO_PULL_NO;
+ GPIO_InitStruct->Alternate = LL_GPIO_AF_0;
+}
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+#endif /* defined (GPIOA) || defined (GPIOB) || defined (GPIOC) || defined (GPIOD) || defined (GPIOE) || defined (GPIOF) */
+
+/**
+ * @}
+ */
+
+#endif /* USE_FULL_LL_DRIVER */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_rcc.c b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_rcc.c
new file mode 100644
index 0000000..94c157e
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_rcc.c
@@ -0,0 +1,609 @@
+/**
+ ******************************************************************************
+ * @file stm32f0xx_ll_rcc.c
+ * @author MCD Application Team
+ * @brief RCC LL module driver.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2016 STMicroelectronics.
+ * All rights reserved.
+ *
+ * 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
+ *
+ ******************************************************************************
+ */
+
+#if defined(USE_FULL_LL_DRIVER)
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f0xx_ll_rcc.h"
+#ifdef USE_FULL_ASSERT
+ #include "stm32_assert.h"
+#else
+ #define assert_param(expr) ((void)0U)
+#endif /* USE_FULL_ASSERT */
+/** @addtogroup STM32F0xx_LL_Driver
+ * @{
+ */
+
+#if defined(RCC)
+
+/** @defgroup RCC_LL RCC
+ * @{
+ */
+
+/* Private types -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+
+/* Private constants ---------------------------------------------------------*/
+/* Private macros ------------------------------------------------------------*/
+/** @addtogroup RCC_LL_Private_Macros
+ * @{
+ */
+#if defined(RCC_CFGR3_USART2SW) && defined(RCC_CFGR3_USART3SW)
+#define IS_LL_RCC_USART_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_USART1_CLKSOURCE) \
+ || ((__VALUE__) == LL_RCC_USART2_CLKSOURCE) \
+ || ((__VALUE__) == LL_RCC_USART3_CLKSOURCE))
+#elif defined(RCC_CFGR3_USART2SW) && !defined(RCC_CFGR3_USART3SW)
+#define IS_LL_RCC_USART_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_USART1_CLKSOURCE) \
+ || ((__VALUE__) == LL_RCC_USART2_CLKSOURCE))
+#elif defined(RCC_CFGR3_USART3SW) && !defined(RCC_CFGR3_USART2SW)
+#define IS_LL_RCC_USART_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_USART1_CLKSOURCE) \
+ || ((__VALUE__) == LL_RCC_USART3_CLKSOURCE))
+#else
+#define IS_LL_RCC_USART_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_USART1_CLKSOURCE))
+#endif /* RCC_CFGR3_USART2SW && RCC_CFGR3_USART3SW */
+
+#define IS_LL_RCC_I2C_CLKSOURCE(__VALUE__) ((__VALUE__) == LL_RCC_I2C1_CLKSOURCE)
+
+#if defined(USB)
+#define IS_LL_RCC_USB_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_USB_CLKSOURCE))
+#endif /* USB */
+
+#if defined(CEC)
+#define IS_LL_RCC_CEC_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_CEC_CLKSOURCE))
+#endif /* CEC */
+
+/**
+ * @}
+ */
+
+/* Private function prototypes -----------------------------------------------*/
+/** @defgroup RCC_LL_Private_Functions RCC Private functions
+ * @{
+ */
+uint32_t RCC_GetSystemClockFreq(void);
+uint32_t RCC_GetHCLKClockFreq(uint32_t SYSCLK_Frequency);
+uint32_t RCC_GetPCLK1ClockFreq(uint32_t HCLK_Frequency);
+uint32_t RCC_PLL_GetFreqDomain_SYS(void);
+/**
+ * @}
+ */
+
+
+/* Exported functions --------------------------------------------------------*/
+/** @addtogroup RCC_LL_Exported_Functions
+ * @{
+ */
+
+/** @addtogroup RCC_LL_EF_Init
+ * @{
+ */
+
+/**
+ * @brief Reset the RCC clock configuration to the default reset state.
+ * @note The default reset state of the clock configuration is given below:
+ * - HSI ON and used as system clock source
+ * - HSE and PLL OFF
+ * - AHB and APB1 prescaler set to 1.
+ * - CSS, MCO OFF
+ * - All interrupts disabled
+ * @note This function doesn't modify the configuration of the
+ * - Peripheral clocks
+ * - LSI, LSE and RTC clocks
+ * @retval An ErrorStatus enumeration value:
+ * - SUCCESS: RCC registers are de-initialized
+ * - ERROR: not applicable
+ */
+ErrorStatus LL_RCC_DeInit(void)
+{
+ __IO uint32_t vl_mask;
+
+ /* Set HSION bit */
+ LL_RCC_HSI_Enable();
+
+ /* Wait for HSI READY bit */
+ while(LL_RCC_HSI_IsReady() != 1U)
+ {}
+
+ /* Set HSITRIM bits to the reset value*/
+ LL_RCC_HSI_SetCalibTrimming(0x10U);
+
+ /* Reset SW, HPRE, PPRE and MCOSEL bits */
+ vl_mask = 0xFFFFFFFFU;
+ CLEAR_BIT(vl_mask, (RCC_CFGR_SW | RCC_CFGR_HPRE | RCC_CFGR_PPRE | RCC_CFGR_MCOSEL));
+
+ /* Write new value in CFGR register */
+ LL_RCC_WriteReg(CFGR, vl_mask);
+
+ /* Wait till system clock source is ready */
+ while(LL_RCC_GetSysClkSource() != LL_RCC_SYS_CLKSOURCE_STATUS_HSI)
+ {}
+
+ /* Read CR register */
+ vl_mask = LL_RCC_ReadReg(CR);
+
+ /* Reset HSEON, CSSON, PLLON bits */
+ CLEAR_BIT(vl_mask, (RCC_CR_PLLON | RCC_CR_CSSON | RCC_CR_HSEON));
+
+ /* Write new value in CR register */
+ LL_RCC_WriteReg(CR, vl_mask);
+
+ /* Wait for PLL READY bit to be reset */
+ while(LL_RCC_PLL_IsReady() != 0U)
+ {}
+
+ /* Reset HSEBYP bit */
+ LL_RCC_HSE_DisableBypass();
+
+ /* Reset CFGR register */
+ LL_RCC_WriteReg(CFGR, 0x00000000U);
+
+#if defined(RCC_HSI48_SUPPORT)
+ /* Reset CR2 register */
+ LL_RCC_WriteReg(CR2, 0x00000000U);
+
+ /* Disable HSI48 */
+ LL_RCC_HSI48_Disable();
+
+#endif /*RCC_HSI48_SUPPORT*/
+ /* Set HSI14TRIM/HSI14ON/HSI14DIS bits to the reset value*/
+ LL_RCC_HSI14_SetCalibTrimming(0x10U);
+ LL_RCC_HSI14_Disable();
+ LL_RCC_HSI14_EnableADCControl();
+
+ /* Reset CFGR2 register */
+ LL_RCC_WriteReg(CFGR2, 0x00000000U);
+
+ /* Reset CFGR3 register */
+ LL_RCC_WriteReg(CFGR3, 0x00000000U);
+
+ /* Clear pending flags */
+#if defined(RCC_HSI48_SUPPORT)
+ vl_mask = (LL_RCC_CIR_LSIRDYC | LL_RCC_CIR_LSERDYC | LL_RCC_CIR_HSIRDYC | LL_RCC_CIR_HSERDYC |\
+ LL_RCC_CIR_PLLRDYC | LL_RCC_CIR_HSI14RDYC | LL_RCC_CIR_HSI48RDYC | LL_RCC_CIR_CSSC);
+#else
+ vl_mask = (LL_RCC_CIR_LSIRDYC | LL_RCC_CIR_LSERDYC | LL_RCC_CIR_HSIRDYC | LL_RCC_CIR_HSERDYC |\
+ LL_RCC_CIR_PLLRDYC | LL_RCC_CIR_HSI14RDYC | LL_RCC_CIR_CSSC);
+#endif /* RCC_HSI48_SUPPORT */
+
+ /* Write new value in CIR register */
+ LL_RCC_WriteReg(CIR, vl_mask);
+
+ /* Disable all interrupts */
+ LL_RCC_WriteReg(CIR, 0x00000000U);
+
+ /* Clear reset flags */
+ LL_RCC_ClearResetFlags();
+
+ return SUCCESS;
+}
+
+/**
+ * @}
+ */
+
+/** @addtogroup RCC_LL_EF_Get_Freq
+ * @brief Return the frequencies of different on chip clocks; System, AHB and APB1 buses clocks
+ * and different peripheral clocks available on the device.
+ * @note If SYSCLK source is HSI, function returns values based on HSI_VALUE(**)
+ * @note If SYSCLK source is HSE, function returns values based on HSE_VALUE(***)
+ * @note If SYSCLK source is PLL, function returns values based on
+ * HSI_VALUE(**) or HSE_VALUE(***) multiplied/divided by the PLL factors.
+ * @note (**) HSI_VALUE is a defined constant but the real value may vary
+ * depending on the variations in voltage and temperature.
+ * @note (***) HSE_VALUE is a defined constant, user has to ensure that
+ * HSE_VALUE is same as the real frequency of the crystal used.
+ * Otherwise, this function may have wrong result.
+ * @note The result of this function could be incorrect when using fractional
+ * value for HSE crystal.
+ * @note This function can be used by the user application to compute the
+ * baud-rate for the communication peripherals or configure other parameters.
+ * @{
+ */
+
+/**
+ * @brief Return the frequencies of different on chip clocks; System, AHB and APB1 buses clocks
+ * @note Each time SYSCLK, HCLK and/or PCLK1 clock changes, this function
+ * must be called to update structure fields. Otherwise, any
+ * configuration based on this function will be incorrect.
+ * @param RCC_Clocks pointer to a @ref LL_RCC_ClocksTypeDef structure which will hold the clocks frequencies
+ * @retval None
+ */
+void LL_RCC_GetSystemClocksFreq(LL_RCC_ClocksTypeDef *RCC_Clocks)
+{
+ /* Get SYSCLK frequency */
+ RCC_Clocks->SYSCLK_Frequency = RCC_GetSystemClockFreq();
+
+ /* HCLK clock frequency */
+ RCC_Clocks->HCLK_Frequency = RCC_GetHCLKClockFreq(RCC_Clocks->SYSCLK_Frequency);
+
+ /* PCLK1 clock frequency */
+ RCC_Clocks->PCLK1_Frequency = RCC_GetPCLK1ClockFreq(RCC_Clocks->HCLK_Frequency);
+}
+
+/**
+ * @brief Return USARTx clock frequency
+ * @param USARTxSource This parameter can be one of the following values:
+ * @arg @ref LL_RCC_USART1_CLKSOURCE
+ * @arg @ref LL_RCC_USART2_CLKSOURCE (*)
+ * @arg @ref LL_RCC_USART3_CLKSOURCE (*)
+ *
+ * (*) value not defined in all devices.
+ * @retval USART clock frequency (in Hz)
+ * @arg @ref LL_RCC_PERIPH_FREQUENCY_NO indicates that oscillator (HSI or LSE) is not ready
+ */
+uint32_t LL_RCC_GetUSARTClockFreq(uint32_t USARTxSource)
+{
+ uint32_t usart_frequency = LL_RCC_PERIPH_FREQUENCY_NO;
+
+ /* Check parameter */
+ assert_param(IS_LL_RCC_USART_CLKSOURCE(USARTxSource));
+#if defined(RCC_CFGR3_USART1SW)
+ if (USARTxSource == LL_RCC_USART1_CLKSOURCE)
+ {
+ /* USART1CLK clock frequency */
+ switch (LL_RCC_GetUSARTClockSource(USARTxSource))
+ {
+ case LL_RCC_USART1_CLKSOURCE_SYSCLK: /* USART1 Clock is System Clock */
+ usart_frequency = RCC_GetSystemClockFreq();
+ break;
+
+ case LL_RCC_USART1_CLKSOURCE_HSI: /* USART1 Clock is HSI Osc. */
+ if (LL_RCC_HSI_IsReady())
+ {
+ usart_frequency = HSI_VALUE;
+ }
+ break;
+
+ case LL_RCC_USART1_CLKSOURCE_LSE: /* USART1 Clock is LSE Osc. */
+ if (LL_RCC_LSE_IsReady())
+ {
+ usart_frequency = LSE_VALUE;
+ }
+ break;
+
+ case LL_RCC_USART1_CLKSOURCE_PCLK1: /* USART1 Clock is PCLK1 */
+ default:
+ usart_frequency = RCC_GetPCLK1ClockFreq(RCC_GetHCLKClockFreq(RCC_GetSystemClockFreq()));
+ break;
+ }
+ }
+#endif /* RCC_CFGR3_USART1SW */
+
+#if defined(RCC_CFGR3_USART2SW)
+ if (USARTxSource == LL_RCC_USART2_CLKSOURCE)
+ {
+ /* USART2CLK clock frequency */
+ switch (LL_RCC_GetUSARTClockSource(USARTxSource))
+ {
+ case LL_RCC_USART2_CLKSOURCE_SYSCLK: /* USART2 Clock is System Clock */
+ usart_frequency = RCC_GetSystemClockFreq();
+ break;
+
+ case LL_RCC_USART2_CLKSOURCE_HSI: /* USART2 Clock is HSI Osc. */
+ if (LL_RCC_HSI_IsReady())
+ {
+ usart_frequency = HSI_VALUE;
+ }
+ break;
+
+ case LL_RCC_USART2_CLKSOURCE_LSE: /* USART2 Clock is LSE Osc. */
+ if (LL_RCC_LSE_IsReady())
+ {
+ usart_frequency = LSE_VALUE;
+ }
+ break;
+
+ case LL_RCC_USART2_CLKSOURCE_PCLK1: /* USART2 Clock is PCLK1 */
+ default:
+ usart_frequency = RCC_GetPCLK1ClockFreq(RCC_GetHCLKClockFreq(RCC_GetSystemClockFreq()));
+ break;
+ }
+ }
+#endif /* RCC_CFGR3_USART2SW */
+
+#if defined(RCC_CFGR3_USART3SW)
+ if (USARTxSource == LL_RCC_USART3_CLKSOURCE)
+ {
+ /* USART3CLK clock frequency */
+ switch (LL_RCC_GetUSARTClockSource(USARTxSource))
+ {
+ case LL_RCC_USART3_CLKSOURCE_SYSCLK: /* USART3 Clock is System Clock */
+ usart_frequency = RCC_GetSystemClockFreq();
+ break;
+
+ case LL_RCC_USART3_CLKSOURCE_HSI: /* USART3 Clock is HSI Osc. */
+ if (LL_RCC_HSI_IsReady())
+ {
+ usart_frequency = HSI_VALUE;
+ }
+ break;
+
+ case LL_RCC_USART3_CLKSOURCE_LSE: /* USART3 Clock is LSE Osc. */
+ if (LL_RCC_LSE_IsReady())
+ {
+ usart_frequency = LSE_VALUE;
+ }
+ break;
+
+ case LL_RCC_USART3_CLKSOURCE_PCLK1: /* USART3 Clock is PCLK1 */
+ default:
+ usart_frequency = RCC_GetPCLK1ClockFreq(RCC_GetHCLKClockFreq(RCC_GetSystemClockFreq()));
+ break;
+ }
+ }
+
+#endif /* RCC_CFGR3_USART3SW */
+ return usart_frequency;
+}
+
+/**
+ * @brief Return I2Cx clock frequency
+ * @param I2CxSource This parameter can be one of the following values:
+ * @arg @ref LL_RCC_I2C1_CLKSOURCE
+ * @retval I2C clock frequency (in Hz)
+ * @arg @ref LL_RCC_PERIPH_FREQUENCY_NO indicates that HSI oscillator is not ready
+ */
+uint32_t LL_RCC_GetI2CClockFreq(uint32_t I2CxSource)
+{
+ uint32_t i2c_frequency = LL_RCC_PERIPH_FREQUENCY_NO;
+
+ /* Check parameter */
+ assert_param(IS_LL_RCC_I2C_CLKSOURCE(I2CxSource));
+
+ /* I2C1 CLK clock frequency */
+ if (I2CxSource == LL_RCC_I2C1_CLKSOURCE)
+ {
+ switch (LL_RCC_GetI2CClockSource(I2CxSource))
+ {
+ case LL_RCC_I2C1_CLKSOURCE_SYSCLK: /* I2C1 Clock is System Clock */
+ i2c_frequency = RCC_GetSystemClockFreq();
+ break;
+
+ case LL_RCC_I2C1_CLKSOURCE_HSI: /* I2C1 Clock is HSI Osc. */
+ default:
+ if (LL_RCC_HSI_IsReady())
+ {
+ i2c_frequency = HSI_VALUE;
+ }
+ break;
+ }
+ }
+
+ return i2c_frequency;
+}
+
+#if defined(USB)
+/**
+ * @brief Return USBx clock frequency
+ * @param USBxSource This parameter can be one of the following values:
+ * @arg @ref LL_RCC_USB_CLKSOURCE
+ * @retval USB clock frequency (in Hz)
+ * @arg @ref LL_RCC_PERIPH_FREQUENCY_NO indicates that oscillator (HSI48) or PLL is not ready
+ * @arg @ref LL_RCC_PERIPH_FREQUENCY_NA indicates that no clock source selected
+ */
+uint32_t LL_RCC_GetUSBClockFreq(uint32_t USBxSource)
+{
+ uint32_t usb_frequency = LL_RCC_PERIPH_FREQUENCY_NO;
+
+ /* Check parameter */
+ assert_param(IS_LL_RCC_USB_CLKSOURCE(USBxSource));
+
+ /* USBCLK clock frequency */
+ switch (LL_RCC_GetUSBClockSource(USBxSource))
+ {
+ case LL_RCC_USB_CLKSOURCE_PLL: /* PLL clock used as USB clock source */
+ if (LL_RCC_PLL_IsReady())
+ {
+ usb_frequency = RCC_PLL_GetFreqDomain_SYS();
+ }
+ break;
+
+#if defined(RCC_CFGR3_USBSW_HSI48)
+ case LL_RCC_USB_CLKSOURCE_HSI48: /* HSI48 clock used as USB clock source */
+ default:
+ if (LL_RCC_HSI48_IsReady())
+ {
+ usb_frequency = HSI48_VALUE;
+ }
+ break;
+#else
+ case LL_RCC_USB_CLKSOURCE_NONE: /* No clock used as USB clock source */
+ default:
+ usb_frequency = LL_RCC_PERIPH_FREQUENCY_NA;
+ break;
+#endif /* RCC_CFGR3_USBSW_HSI48 */
+ }
+
+ return usb_frequency;
+}
+#endif /* USB */
+
+#if defined(CEC)
+/**
+ * @brief Return CECx clock frequency
+ * @param CECxSource This parameter can be one of the following values:
+ * @arg @ref LL_RCC_CEC_CLKSOURCE
+ * @retval CEC clock frequency (in Hz)
+ * @arg @ref LL_RCC_PERIPH_FREQUENCY_NO indicates that oscillators (HSI or LSE) are not ready
+ */
+uint32_t LL_RCC_GetCECClockFreq(uint32_t CECxSource)
+{
+ uint32_t cec_frequency = LL_RCC_PERIPH_FREQUENCY_NO;
+
+ /* Check parameter */
+ assert_param(IS_LL_RCC_CEC_CLKSOURCE(CECxSource));
+
+ /* CECCLK clock frequency */
+ switch (LL_RCC_GetCECClockSource(CECxSource))
+ {
+ case LL_RCC_CEC_CLKSOURCE_HSI_DIV244: /* HSI / 244 clock used as CEC clock source */
+ if (LL_RCC_HSI_IsReady())
+ {
+ cec_frequency = HSI_VALUE / 244U;
+ }
+ break;
+
+ case LL_RCC_CEC_CLKSOURCE_LSE: /* LSE clock used as CEC clock source */
+ default:
+ if (LL_RCC_LSE_IsReady())
+ {
+ cec_frequency = LSE_VALUE;
+ }
+ break;
+ }
+
+ return cec_frequency;
+}
+#endif /* CEC */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/** @addtogroup RCC_LL_Private_Functions
+ * @{
+ */
+
+/**
+ * @brief Return SYSTEM clock frequency
+ * @retval SYSTEM clock frequency (in Hz)
+ */
+uint32_t RCC_GetSystemClockFreq(void)
+{
+ uint32_t frequency = 0U;
+
+ /* Get SYSCLK source -------------------------------------------------------*/
+ switch (LL_RCC_GetSysClkSource())
+ {
+ case LL_RCC_SYS_CLKSOURCE_STATUS_HSI: /* HSI used as system clock source */
+ frequency = HSI_VALUE;
+ break;
+
+ case LL_RCC_SYS_CLKSOURCE_STATUS_HSE: /* HSE used as system clock source */
+ frequency = HSE_VALUE;
+ break;
+
+ case LL_RCC_SYS_CLKSOURCE_STATUS_PLL: /* PLL used as system clock source */
+ frequency = RCC_PLL_GetFreqDomain_SYS();
+ break;
+
+#if defined(RCC_HSI48_SUPPORT)
+ case LL_RCC_SYS_CLKSOURCE_STATUS_HSI48:/* HSI48 used as system clock source */
+ frequency = HSI48_VALUE;
+ break;
+#endif /* RCC_HSI48_SUPPORT */
+
+ default:
+ frequency = HSI_VALUE;
+ break;
+ }
+
+ return frequency;
+}
+
+/**
+ * @brief Return HCLK clock frequency
+ * @param SYSCLK_Frequency SYSCLK clock frequency
+ * @retval HCLK clock frequency (in Hz)
+ */
+uint32_t RCC_GetHCLKClockFreq(uint32_t SYSCLK_Frequency)
+{
+ /* HCLK clock frequency */
+ return __LL_RCC_CALC_HCLK_FREQ(SYSCLK_Frequency, LL_RCC_GetAHBPrescaler());
+}
+
+/**
+ * @brief Return PCLK1 clock frequency
+ * @param HCLK_Frequency HCLK clock frequency
+ * @retval PCLK1 clock frequency (in Hz)
+ */
+uint32_t RCC_GetPCLK1ClockFreq(uint32_t HCLK_Frequency)
+{
+ /* PCLK1 clock frequency */
+ return __LL_RCC_CALC_PCLK1_FREQ(HCLK_Frequency, LL_RCC_GetAPB1Prescaler());
+}
+/**
+ * @brief Return PLL clock frequency used for system domain
+ * @retval PLL clock frequency (in Hz)
+ */
+uint32_t RCC_PLL_GetFreqDomain_SYS(void)
+{
+ uint32_t pllinputfreq = 0U, pllsource = 0U;
+
+ /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLL divider) * PLL Multiplicator */
+
+ /* Get PLL source */
+ pllsource = LL_RCC_PLL_GetMainSource();
+
+ switch (pllsource)
+ {
+#if defined(RCC_PLLSRC_PREDIV1_SUPPORT)
+ case LL_RCC_PLLSOURCE_HSI: /* HSI used as PLL clock source */
+ pllinputfreq = HSI_VALUE;
+#else
+ case LL_RCC_PLLSOURCE_HSI_DIV_2: /* HSI used as PLL clock source */
+ pllinputfreq = HSI_VALUE / 2U;
+#endif /* RCC_PLLSRC_PREDIV1_SUPPORT */
+ break;
+
+#if defined(RCC_HSI48_SUPPORT)
+ case LL_RCC_PLLSOURCE_HSI48: /* HSI48 used as PLL clock source */
+ pllinputfreq = HSI48_VALUE;
+ break;
+#endif /* RCC_HSI48_SUPPORT */
+
+ case LL_RCC_PLLSOURCE_HSE: /* HSE used as PLL clock source */
+ pllinputfreq = HSE_VALUE;
+ break;
+
+ default:
+#if defined(RCC_PLLSRC_PREDIV1_SUPPORT)
+ pllinputfreq = HSI_VALUE;
+#else
+ pllinputfreq = HSI_VALUE / 2U;
+#endif /* RCC_PLLSRC_PREDIV1_SUPPORT */
+ break;
+ }
+#if defined(RCC_PLLSRC_PREDIV1_SUPPORT)
+ return __LL_RCC_CALC_PLLCLK_FREQ(pllinputfreq, LL_RCC_PLL_GetMultiplicator(), LL_RCC_PLL_GetPrediv());
+#else
+ return __LL_RCC_CALC_PLLCLK_FREQ((pllinputfreq / (LL_RCC_PLL_GetPrediv() + 1U)), LL_RCC_PLL_GetMultiplicator());
+#endif /* RCC_PLLSRC_PREDIV1_SUPPORT */
+}
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+#endif /* defined(RCC) */
+
+/**
+ * @}
+ */
+
+#endif /* USE_FULL_LL_DRIVER */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_spi.c b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_spi.c
new file mode 100644
index 0000000..7d48f0f
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_spi.c
@@ -0,0 +1,537 @@
+/**
+ ******************************************************************************
+ * @file stm32f0xx_ll_spi.c
+ * @author MCD Application Team
+ * @brief SPI LL module driver.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2016 STMicroelectronics.
+ * All rights reserved.
+ *
+ * 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
+ *
+ ******************************************************************************
+ */
+#if defined(USE_FULL_LL_DRIVER)
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f0xx_ll_spi.h"
+#include "stm32f0xx_ll_bus.h"
+#include "stm32f0xx_ll_rcc.h"
+
+#ifdef USE_FULL_ASSERT
+#include "stm32_assert.h"
+#else
+#define assert_param(expr) ((void)0U)
+#endif /* USE_FULL_ASSERT */
+
+/** @addtogroup STM32F0xx_LL_Driver
+ * @{
+ */
+
+#if defined (SPI1) || defined (SPI2)
+
+/** @addtogroup SPI_LL
+ * @{
+ */
+
+/* Private types -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+
+/* Private constants ---------------------------------------------------------*/
+/** @defgroup SPI_LL_Private_Constants SPI Private Constants
+ * @{
+ */
+/* SPI registers Masks */
+#define SPI_CR1_CLEAR_MASK (SPI_CR1_CPHA | SPI_CR1_CPOL | SPI_CR1_MSTR | \
+ SPI_CR1_BR | SPI_CR1_LSBFIRST | SPI_CR1_SSI | \
+ SPI_CR1_SSM | SPI_CR1_RXONLY | SPI_CR1_CRCL | \
+ SPI_CR1_CRCNEXT | SPI_CR1_CRCEN | SPI_CR1_BIDIOE | \
+ SPI_CR1_BIDIMODE)
+/**
+ * @}
+ */
+
+/* Private macros ------------------------------------------------------------*/
+/** @defgroup SPI_LL_Private_Macros SPI Private Macros
+ * @{
+ */
+#define IS_LL_SPI_TRANSFER_DIRECTION(__VALUE__) (((__VALUE__) == LL_SPI_FULL_DUPLEX) \
+ || ((__VALUE__) == LL_SPI_SIMPLEX_RX) \
+ || ((__VALUE__) == LL_SPI_HALF_DUPLEX_RX) \
+ || ((__VALUE__) == LL_SPI_HALF_DUPLEX_TX))
+
+#define IS_LL_SPI_MODE(__VALUE__) (((__VALUE__) == LL_SPI_MODE_MASTER) \
+ || ((__VALUE__) == LL_SPI_MODE_SLAVE))
+
+#define IS_LL_SPI_DATAWIDTH(__VALUE__) (((__VALUE__) == LL_SPI_DATAWIDTH_4BIT) \
+ || ((__VALUE__) == LL_SPI_DATAWIDTH_5BIT) \
+ || ((__VALUE__) == LL_SPI_DATAWIDTH_6BIT) \
+ || ((__VALUE__) == LL_SPI_DATAWIDTH_7BIT) \
+ || ((__VALUE__) == LL_SPI_DATAWIDTH_8BIT) \
+ || ((__VALUE__) == LL_SPI_DATAWIDTH_9BIT) \
+ || ((__VALUE__) == LL_SPI_DATAWIDTH_10BIT) \
+ || ((__VALUE__) == LL_SPI_DATAWIDTH_11BIT) \
+ || ((__VALUE__) == LL_SPI_DATAWIDTH_12BIT) \
+ || ((__VALUE__) == LL_SPI_DATAWIDTH_13BIT) \
+ || ((__VALUE__) == LL_SPI_DATAWIDTH_14BIT) \
+ || ((__VALUE__) == LL_SPI_DATAWIDTH_15BIT) \
+ || ((__VALUE__) == LL_SPI_DATAWIDTH_16BIT))
+
+#define IS_LL_SPI_POLARITY(__VALUE__) (((__VALUE__) == LL_SPI_POLARITY_LOW) \
+ || ((__VALUE__) == LL_SPI_POLARITY_HIGH))
+
+#define IS_LL_SPI_PHASE(__VALUE__) (((__VALUE__) == LL_SPI_PHASE_1EDGE) \
+ || ((__VALUE__) == LL_SPI_PHASE_2EDGE))
+
+#define IS_LL_SPI_NSS(__VALUE__) (((__VALUE__) == LL_SPI_NSS_SOFT) \
+ || ((__VALUE__) == LL_SPI_NSS_HARD_INPUT) \
+ || ((__VALUE__) == LL_SPI_NSS_HARD_OUTPUT))
+
+#define IS_LL_SPI_BAUDRATE(__VALUE__) (((__VALUE__) == LL_SPI_BAUDRATEPRESCALER_DIV2) \
+ || ((__VALUE__) == LL_SPI_BAUDRATEPRESCALER_DIV4) \
+ || ((__VALUE__) == LL_SPI_BAUDRATEPRESCALER_DIV8) \
+ || ((__VALUE__) == LL_SPI_BAUDRATEPRESCALER_DIV16) \
+ || ((__VALUE__) == LL_SPI_BAUDRATEPRESCALER_DIV32) \
+ || ((__VALUE__) == LL_SPI_BAUDRATEPRESCALER_DIV64) \
+ || ((__VALUE__) == LL_SPI_BAUDRATEPRESCALER_DIV128) \
+ || ((__VALUE__) == LL_SPI_BAUDRATEPRESCALER_DIV256))
+
+#define IS_LL_SPI_BITORDER(__VALUE__) (((__VALUE__) == LL_SPI_LSB_FIRST) \
+ || ((__VALUE__) == LL_SPI_MSB_FIRST))
+
+#define IS_LL_SPI_CRCCALCULATION(__VALUE__) (((__VALUE__) == LL_SPI_CRCCALCULATION_ENABLE) \
+ || ((__VALUE__) == LL_SPI_CRCCALCULATION_DISABLE))
+
+#define IS_LL_SPI_CRC_POLYNOMIAL(__VALUE__) ((__VALUE__) >= 0x1U)
+
+/**
+ * @}
+ */
+
+/* Private function prototypes -----------------------------------------------*/
+
+/* Exported functions --------------------------------------------------------*/
+/** @addtogroup SPI_LL_Exported_Functions
+ * @{
+ */
+
+/** @addtogroup SPI_LL_EF_Init
+ * @{
+ */
+
+/**
+ * @brief De-initialize the SPI registers to their default reset values.
+ * @param SPIx SPI Instance
+ * @retval An ErrorStatus enumeration value:
+ * - SUCCESS: SPI registers are de-initialized
+ * - ERROR: SPI registers are not de-initialized
+ */
+ErrorStatus LL_SPI_DeInit(SPI_TypeDef *SPIx)
+{
+ ErrorStatus status = ERROR;
+
+ /* Check the parameters */
+ assert_param(IS_SPI_ALL_INSTANCE(SPIx));
+
+#if defined(SPI1)
+ if (SPIx == SPI1)
+ {
+ /* Force reset of SPI clock */
+ LL_APB1_GRP2_ForceReset(LL_APB1_GRP2_PERIPH_SPI1);
+
+ /* Release reset of SPI clock */
+ LL_APB1_GRP2_ReleaseReset(LL_APB1_GRP2_PERIPH_SPI1);
+
+ status = SUCCESS;
+ }
+#endif /* SPI1 */
+#if defined(SPI2)
+ if (SPIx == SPI2)
+ {
+ /* Force reset of SPI clock */
+ LL_APB1_GRP1_ForceReset(LL_APB1_GRP1_PERIPH_SPI2);
+
+ /* Release reset of SPI clock */
+ LL_APB1_GRP1_ReleaseReset(LL_APB1_GRP1_PERIPH_SPI2);
+
+ status = SUCCESS;
+ }
+#endif /* SPI2 */
+
+ return status;
+}
+
+/**
+ * @brief Initialize the SPI registers according to the specified parameters in SPI_InitStruct.
+ * @note As some bits in SPI configuration registers can only be written when the SPI is disabled (SPI_CR1_SPE bit =0),
+ * SPI peripheral should be in disabled state prior calling this function. Otherwise, ERROR result will be returned.
+ * @param SPIx SPI Instance
+ * @param SPI_InitStruct pointer to a @ref LL_SPI_InitTypeDef structure
+ * @retval An ErrorStatus enumeration value. (Return always SUCCESS)
+ */
+ErrorStatus LL_SPI_Init(SPI_TypeDef *SPIx, LL_SPI_InitTypeDef *SPI_InitStruct)
+{
+ ErrorStatus status = ERROR;
+
+ /* Check the SPI Instance SPIx*/
+ assert_param(IS_SPI_ALL_INSTANCE(SPIx));
+
+ /* Check the SPI parameters from SPI_InitStruct*/
+ assert_param(IS_LL_SPI_TRANSFER_DIRECTION(SPI_InitStruct->TransferDirection));
+ assert_param(IS_LL_SPI_MODE(SPI_InitStruct->Mode));
+ assert_param(IS_LL_SPI_DATAWIDTH(SPI_InitStruct->DataWidth));
+ assert_param(IS_LL_SPI_POLARITY(SPI_InitStruct->ClockPolarity));
+ assert_param(IS_LL_SPI_PHASE(SPI_InitStruct->ClockPhase));
+ assert_param(IS_LL_SPI_NSS(SPI_InitStruct->NSS));
+ assert_param(IS_LL_SPI_BAUDRATE(SPI_InitStruct->BaudRate));
+ assert_param(IS_LL_SPI_BITORDER(SPI_InitStruct->BitOrder));
+ assert_param(IS_LL_SPI_CRCCALCULATION(SPI_InitStruct->CRCCalculation));
+
+ if (LL_SPI_IsEnabled(SPIx) == 0x00000000U)
+ {
+ /*---------------------------- SPIx CR1 Configuration ------------------------
+ * Configure SPIx CR1 with parameters:
+ * - TransferDirection: SPI_CR1_BIDIMODE, SPI_CR1_BIDIOE and SPI_CR1_RXONLY bits
+ * - Master/Slave Mode: SPI_CR1_MSTR bit
+ * - ClockPolarity: SPI_CR1_CPOL bit
+ * - ClockPhase: SPI_CR1_CPHA bit
+ * - NSS management: SPI_CR1_SSM bit
+ * - BaudRate prescaler: SPI_CR1_BR[2:0] bits
+ * - BitOrder: SPI_CR1_LSBFIRST bit
+ * - CRCCalculation: SPI_CR1_CRCEN bit
+ */
+ MODIFY_REG(SPIx->CR1,
+ SPI_CR1_CLEAR_MASK,
+ SPI_InitStruct->TransferDirection | SPI_InitStruct->Mode |
+ SPI_InitStruct->ClockPolarity | SPI_InitStruct->ClockPhase |
+ SPI_InitStruct->NSS | SPI_InitStruct->BaudRate |
+ SPI_InitStruct->BitOrder | SPI_InitStruct->CRCCalculation);
+
+ /*---------------------------- SPIx CR2 Configuration ------------------------
+ * Configure SPIx CR2 with parameters:
+ * - DataWidth: DS[3:0] bits
+ * - NSS management: SSOE bit
+ */
+ MODIFY_REG(SPIx->CR2,
+ SPI_CR2_DS | SPI_CR2_SSOE,
+ SPI_InitStruct->DataWidth | (SPI_InitStruct->NSS >> 16U));
+
+ /* Set Rx FIFO to Quarter (1 Byte) in case of 8 Bits mode. No DataPacking by default */
+ if (SPI_InitStruct->DataWidth < LL_SPI_DATAWIDTH_9BIT)
+ {
+ LL_SPI_SetRxFIFOThreshold(SPIx, LL_SPI_RX_FIFO_TH_QUARTER);
+ }
+
+ /*---------------------------- SPIx CRCPR Configuration ----------------------
+ * Configure SPIx CRCPR with parameters:
+ * - CRCPoly: CRCPOLY[15:0] bits
+ */
+ if (SPI_InitStruct->CRCCalculation == LL_SPI_CRCCALCULATION_ENABLE)
+ {
+ assert_param(IS_LL_SPI_CRC_POLYNOMIAL(SPI_InitStruct->CRCPoly));
+ LL_SPI_SetCRCPolynomial(SPIx, SPI_InitStruct->CRCPoly);
+ }
+ status = SUCCESS;
+ }
+
+#if defined (SPI_I2S_SUPPORT)
+ /* Activate the SPI mode (Reset I2SMOD bit in I2SCFGR register) */
+ CLEAR_BIT(SPIx->I2SCFGR, SPI_I2SCFGR_I2SMOD);
+#endif /* SPI_I2S_SUPPORT */
+ return status;
+}
+
+/**
+ * @brief Set each @ref LL_SPI_InitTypeDef field to default value.
+ * @param SPI_InitStruct pointer to a @ref LL_SPI_InitTypeDef structure
+ * whose fields will be set to default values.
+ * @retval None
+ */
+void LL_SPI_StructInit(LL_SPI_InitTypeDef *SPI_InitStruct)
+{
+ /* Set SPI_InitStruct fields to default values */
+ SPI_InitStruct->TransferDirection = LL_SPI_FULL_DUPLEX;
+ SPI_InitStruct->Mode = LL_SPI_MODE_SLAVE;
+ SPI_InitStruct->DataWidth = LL_SPI_DATAWIDTH_8BIT;
+ SPI_InitStruct->ClockPolarity = LL_SPI_POLARITY_LOW;
+ SPI_InitStruct->ClockPhase = LL_SPI_PHASE_1EDGE;
+ SPI_InitStruct->NSS = LL_SPI_NSS_HARD_INPUT;
+ SPI_InitStruct->BaudRate = LL_SPI_BAUDRATEPRESCALER_DIV2;
+ SPI_InitStruct->BitOrder = LL_SPI_MSB_FIRST;
+ SPI_InitStruct->CRCCalculation = LL_SPI_CRCCALCULATION_DISABLE;
+ SPI_InitStruct->CRCPoly = 7U;
+}
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+#if defined(SPI_I2S_SUPPORT)
+/** @addtogroup I2S_LL
+ * @{
+ */
+
+/* Private types -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private constants ---------------------------------------------------------*/
+/** @defgroup I2S_LL_Private_Constants I2S Private Constants
+ * @{
+ */
+/* I2S registers Masks */
+#define I2S_I2SCFGR_CLEAR_MASK (SPI_I2SCFGR_CHLEN | SPI_I2SCFGR_DATLEN | \
+ SPI_I2SCFGR_CKPOL | SPI_I2SCFGR_I2SSTD | \
+ SPI_I2SCFGR_I2SCFG | SPI_I2SCFGR_I2SMOD )
+
+#define I2S_I2SPR_CLEAR_MASK 0x0002U
+/**
+ * @}
+ */
+/* Private macros ------------------------------------------------------------*/
+/** @defgroup I2S_LL_Private_Macros I2S Private Macros
+ * @{
+ */
+
+#define IS_LL_I2S_DATAFORMAT(__VALUE__) (((__VALUE__) == LL_I2S_DATAFORMAT_16B) \
+ || ((__VALUE__) == LL_I2S_DATAFORMAT_16B_EXTENDED) \
+ || ((__VALUE__) == LL_I2S_DATAFORMAT_24B) \
+ || ((__VALUE__) == LL_I2S_DATAFORMAT_32B))
+
+#define IS_LL_I2S_CPOL(__VALUE__) (((__VALUE__) == LL_I2S_POLARITY_LOW) \
+ || ((__VALUE__) == LL_I2S_POLARITY_HIGH))
+
+#define IS_LL_I2S_STANDARD(__VALUE__) (((__VALUE__) == LL_I2S_STANDARD_PHILIPS) \
+ || ((__VALUE__) == LL_I2S_STANDARD_MSB) \
+ || ((__VALUE__) == LL_I2S_STANDARD_LSB) \
+ || ((__VALUE__) == LL_I2S_STANDARD_PCM_SHORT) \
+ || ((__VALUE__) == LL_I2S_STANDARD_PCM_LONG))
+
+#define IS_LL_I2S_MODE(__VALUE__) (((__VALUE__) == LL_I2S_MODE_SLAVE_TX) \
+ || ((__VALUE__) == LL_I2S_MODE_SLAVE_RX) \
+ || ((__VALUE__) == LL_I2S_MODE_MASTER_TX) \
+ || ((__VALUE__) == LL_I2S_MODE_MASTER_RX))
+
+#define IS_LL_I2S_MCLK_OUTPUT(__VALUE__) (((__VALUE__) == LL_I2S_MCLK_OUTPUT_ENABLE) \
+ || ((__VALUE__) == LL_I2S_MCLK_OUTPUT_DISABLE))
+
+#define IS_LL_I2S_AUDIO_FREQ(__VALUE__) ((((__VALUE__) >= LL_I2S_AUDIOFREQ_8K) \
+ && ((__VALUE__) <= LL_I2S_AUDIOFREQ_192K)) \
+ || ((__VALUE__) == LL_I2S_AUDIOFREQ_DEFAULT))
+
+#define IS_LL_I2S_PRESCALER_LINEAR(__VALUE__) ((__VALUE__) >= 0x2U)
+
+#define IS_LL_I2S_PRESCALER_PARITY(__VALUE__) (((__VALUE__) == LL_I2S_PRESCALER_PARITY_EVEN) \
+ || ((__VALUE__) == LL_I2S_PRESCALER_PARITY_ODD))
+/**
+ * @}
+ */
+
+/* Private function prototypes -----------------------------------------------*/
+
+/* Exported functions --------------------------------------------------------*/
+/** @addtogroup I2S_LL_Exported_Functions
+ * @{
+ */
+
+/** @addtogroup I2S_LL_EF_Init
+ * @{
+ */
+
+/**
+ * @brief De-initialize the SPI/I2S registers to their default reset values.
+ * @param SPIx SPI Instance
+ * @retval An ErrorStatus enumeration value:
+ * - SUCCESS: SPI registers are de-initialized
+ * - ERROR: SPI registers are not de-initialized
+ */
+ErrorStatus LL_I2S_DeInit(SPI_TypeDef *SPIx)
+{
+ return LL_SPI_DeInit(SPIx);
+}
+
+/**
+ * @brief Initializes the SPI/I2S registers according to the specified parameters in I2S_InitStruct.
+ * @note As some bits in SPI configuration registers can only be written when the SPI is disabled (SPI_CR1_SPE bit =0),
+ * SPI peripheral should be in disabled state prior calling this function. Otherwise, ERROR result will be returned.
+ * @param SPIx SPI Instance
+ * @param I2S_InitStruct pointer to a @ref LL_I2S_InitTypeDef structure
+ * @retval An ErrorStatus enumeration value:
+ * - SUCCESS: SPI registers are Initialized
+ * - ERROR: SPI registers are not Initialized
+ */
+ErrorStatus LL_I2S_Init(SPI_TypeDef *SPIx, LL_I2S_InitTypeDef *I2S_InitStruct)
+{
+ uint32_t i2sdiv = 2U;
+ uint32_t i2sodd = 0U;
+ uint32_t packetlength = 1U;
+ uint32_t tmp;
+ LL_RCC_ClocksTypeDef rcc_clocks;
+ uint32_t sourceclock;
+ ErrorStatus status = ERROR;
+
+ /* Check the I2S parameters */
+ assert_param(IS_I2S_ALL_INSTANCE(SPIx));
+ assert_param(IS_LL_I2S_MODE(I2S_InitStruct->Mode));
+ assert_param(IS_LL_I2S_STANDARD(I2S_InitStruct->Standard));
+ assert_param(IS_LL_I2S_DATAFORMAT(I2S_InitStruct->DataFormat));
+ assert_param(IS_LL_I2S_MCLK_OUTPUT(I2S_InitStruct->MCLKOutput));
+ assert_param(IS_LL_I2S_AUDIO_FREQ(I2S_InitStruct->AudioFreq));
+ assert_param(IS_LL_I2S_CPOL(I2S_InitStruct->ClockPolarity));
+
+ if (LL_I2S_IsEnabled(SPIx) == 0x00000000U)
+ {
+ /*---------------------------- SPIx I2SCFGR Configuration --------------------
+ * Configure SPIx I2SCFGR with parameters:
+ * - Mode: SPI_I2SCFGR_I2SCFG[1:0] bit
+ * - Standard: SPI_I2SCFGR_I2SSTD[1:0] and SPI_I2SCFGR_PCMSYNC bits
+ * - DataFormat: SPI_I2SCFGR_CHLEN and SPI_I2SCFGR_DATLEN bits
+ * - ClockPolarity: SPI_I2SCFGR_CKPOL bit
+ */
+
+ /* Write to SPIx I2SCFGR */
+ MODIFY_REG(SPIx->I2SCFGR,
+ I2S_I2SCFGR_CLEAR_MASK,
+ I2S_InitStruct->Mode | I2S_InitStruct->Standard |
+ I2S_InitStruct->DataFormat | I2S_InitStruct->ClockPolarity |
+ SPI_I2SCFGR_I2SMOD);
+
+ /*---------------------------- SPIx I2SPR Configuration ----------------------
+ * Configure SPIx I2SPR with parameters:
+ * - MCLKOutput: SPI_I2SPR_MCKOE bit
+ * - AudioFreq: SPI_I2SPR_I2SDIV[7:0] and SPI_I2SPR_ODD bits
+ */
+
+ /* If the requested audio frequency is not the default, compute the prescaler (i2sodd, i2sdiv)
+ * else, default values are used: i2sodd = 0U, i2sdiv = 2U.
+ */
+ if (I2S_InitStruct->AudioFreq != LL_I2S_AUDIOFREQ_DEFAULT)
+ {
+ /* Check the frame length (For the Prescaler computing)
+ * Default value: LL_I2S_DATAFORMAT_16B (packetlength = 1U).
+ */
+ if (I2S_InitStruct->DataFormat != LL_I2S_DATAFORMAT_16B)
+ {
+ /* Packet length is 32 bits */
+ packetlength = 2U;
+ }
+
+ /* I2S Clock source is System clock: Get System Clock frequency */
+ LL_RCC_GetSystemClocksFreq(&rcc_clocks);
+
+ /* Get the source clock value: based on System Clock value */
+ sourceclock = rcc_clocks.SYSCLK_Frequency;
+
+ /* Compute the Real divider depending on the MCLK output state with a floating point */
+ if (I2S_InitStruct->MCLKOutput == LL_I2S_MCLK_OUTPUT_ENABLE)
+ {
+ /* MCLK output is enabled */
+ tmp = (((((sourceclock / 256U) * 10U) / I2S_InitStruct->AudioFreq)) + 5U);
+ }
+ else
+ {
+ /* MCLK output is disabled */
+ tmp = (((((sourceclock / (32U * packetlength)) * 10U) / I2S_InitStruct->AudioFreq)) + 5U);
+ }
+
+ /* Remove the floating point */
+ tmp = tmp / 10U;
+
+ /* Check the parity of the divider */
+ i2sodd = (tmp & (uint16_t)0x0001U);
+
+ /* Compute the i2sdiv prescaler */
+ i2sdiv = ((tmp - i2sodd) / 2U);
+
+ /* Get the Mask for the Odd bit (SPI_I2SPR[8]) register */
+ i2sodd = (i2sodd << 8U);
+ }
+
+ /* Test if the divider is 1 or 0 or greater than 0xFF */
+ if ((i2sdiv < 2U) || (i2sdiv > 0xFFU))
+ {
+ /* Set the default values */
+ i2sdiv = 2U;
+ i2sodd = 0U;
+ }
+
+ /* Write to SPIx I2SPR register the computed value */
+ WRITE_REG(SPIx->I2SPR, i2sdiv | i2sodd | I2S_InitStruct->MCLKOutput);
+
+ status = SUCCESS;
+ }
+ return status;
+}
+
+/**
+ * @brief Set each @ref LL_I2S_InitTypeDef field to default value.
+ * @param I2S_InitStruct pointer to a @ref LL_I2S_InitTypeDef structure
+ * whose fields will be set to default values.
+ * @retval None
+ */
+void LL_I2S_StructInit(LL_I2S_InitTypeDef *I2S_InitStruct)
+{
+ /*--------------- Reset I2S init structure parameters values -----------------*/
+ I2S_InitStruct->Mode = LL_I2S_MODE_SLAVE_TX;
+ I2S_InitStruct->Standard = LL_I2S_STANDARD_PHILIPS;
+ I2S_InitStruct->DataFormat = LL_I2S_DATAFORMAT_16B;
+ I2S_InitStruct->MCLKOutput = LL_I2S_MCLK_OUTPUT_DISABLE;
+ I2S_InitStruct->AudioFreq = LL_I2S_AUDIOFREQ_DEFAULT;
+ I2S_InitStruct->ClockPolarity = LL_I2S_POLARITY_LOW;
+}
+
+/**
+ * @brief Set linear and parity prescaler.
+ * @note To calculate value of PrescalerLinear(I2SDIV[7:0] bits) and PrescalerParity(ODD bit)\n
+ * Check Audio frequency table and formulas inside Reference Manual (SPI/I2S).
+ * @param SPIx SPI Instance
+ * @param PrescalerLinear value Min_Data=0x02 and Max_Data=0xFF.
+ * @param PrescalerParity This parameter can be one of the following values:
+ * @arg @ref LL_I2S_PRESCALER_PARITY_EVEN
+ * @arg @ref LL_I2S_PRESCALER_PARITY_ODD
+ * @retval None
+ */
+void LL_I2S_ConfigPrescaler(SPI_TypeDef *SPIx, uint32_t PrescalerLinear, uint32_t PrescalerParity)
+{
+ /* Check the I2S parameters */
+ assert_param(IS_I2S_ALL_INSTANCE(SPIx));
+ assert_param(IS_LL_I2S_PRESCALER_LINEAR(PrescalerLinear));
+ assert_param(IS_LL_I2S_PRESCALER_PARITY(PrescalerParity));
+
+ /* Write to SPIx I2SPR */
+ MODIFY_REG(SPIx->I2SPR, SPI_I2SPR_I2SDIV | SPI_I2SPR_ODD, PrescalerLinear | (PrescalerParity << 8U));
+}
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+#endif /* SPI_I2S_SUPPORT */
+
+#endif /* defined (SPI1) || defined (SPI2) */
+
+/**
+ * @}
+ */
+
+#endif /* USE_FULL_LL_DRIVER */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_tim.c b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_tim.c
new file mode 100644
index 0000000..0ca5508
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_tim.c
@@ -0,0 +1,1170 @@
+/**
+ ******************************************************************************
+ * @file stm32f0xx_ll_tim.c
+ * @author MCD Application Team
+ * @brief TIM LL module driver.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2016 STMicroelectronics.
+ * All rights reserved.
+ *
+ * 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
+ *
+ ******************************************************************************
+ */
+#if defined(USE_FULL_LL_DRIVER)
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f0xx_ll_tim.h"
+#include "stm32f0xx_ll_bus.h"
+
+#ifdef USE_FULL_ASSERT
+#include "stm32_assert.h"
+#else
+#define assert_param(expr) ((void)0U)
+#endif /* USE_FULL_ASSERT */
+
+/** @addtogroup STM32F0xx_LL_Driver
+ * @{
+ */
+
+#if defined (TIM1) || defined (TIM2) || defined (TIM3) || defined (TIM14) || defined (TIM15) || defined (TIM16) || defined (TIM17) || defined (TIM6) || defined (TIM7)
+
+/** @addtogroup TIM_LL
+ * @{
+ */
+
+/* Private types -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private constants ---------------------------------------------------------*/
+/* Private macros ------------------------------------------------------------*/
+/** @addtogroup TIM_LL_Private_Macros
+ * @{
+ */
+#define IS_LL_TIM_COUNTERMODE(__VALUE__) (((__VALUE__) == LL_TIM_COUNTERMODE_UP) \
+ || ((__VALUE__) == LL_TIM_COUNTERMODE_DOWN) \
+ || ((__VALUE__) == LL_TIM_COUNTERMODE_CENTER_UP) \
+ || ((__VALUE__) == LL_TIM_COUNTERMODE_CENTER_DOWN) \
+ || ((__VALUE__) == LL_TIM_COUNTERMODE_CENTER_UP_DOWN))
+
+#define IS_LL_TIM_CLOCKDIVISION(__VALUE__) (((__VALUE__) == LL_TIM_CLOCKDIVISION_DIV1) \
+ || ((__VALUE__) == LL_TIM_CLOCKDIVISION_DIV2) \
+ || ((__VALUE__) == LL_TIM_CLOCKDIVISION_DIV4))
+
+#define IS_LL_TIM_OCMODE(__VALUE__) (((__VALUE__) == LL_TIM_OCMODE_FROZEN) \
+ || ((__VALUE__) == LL_TIM_OCMODE_ACTIVE) \
+ || ((__VALUE__) == LL_TIM_OCMODE_INACTIVE) \
+ || ((__VALUE__) == LL_TIM_OCMODE_TOGGLE) \
+ || ((__VALUE__) == LL_TIM_OCMODE_FORCED_INACTIVE) \
+ || ((__VALUE__) == LL_TIM_OCMODE_FORCED_ACTIVE) \
+ || ((__VALUE__) == LL_TIM_OCMODE_PWM1) \
+ || ((__VALUE__) == LL_TIM_OCMODE_PWM2))
+
+#define IS_LL_TIM_OCSTATE(__VALUE__) (((__VALUE__) == LL_TIM_OCSTATE_DISABLE) \
+ || ((__VALUE__) == LL_TIM_OCSTATE_ENABLE))
+
+#define IS_LL_TIM_OCPOLARITY(__VALUE__) (((__VALUE__) == LL_TIM_OCPOLARITY_HIGH) \
+ || ((__VALUE__) == LL_TIM_OCPOLARITY_LOW))
+
+#define IS_LL_TIM_OCIDLESTATE(__VALUE__) (((__VALUE__) == LL_TIM_OCIDLESTATE_LOW) \
+ || ((__VALUE__) == LL_TIM_OCIDLESTATE_HIGH))
+
+#define IS_LL_TIM_ACTIVEINPUT(__VALUE__) (((__VALUE__) == LL_TIM_ACTIVEINPUT_DIRECTTI) \
+ || ((__VALUE__) == LL_TIM_ACTIVEINPUT_INDIRECTTI) \
+ || ((__VALUE__) == LL_TIM_ACTIVEINPUT_TRC))
+
+#define IS_LL_TIM_ICPSC(__VALUE__) (((__VALUE__) == LL_TIM_ICPSC_DIV1) \
+ || ((__VALUE__) == LL_TIM_ICPSC_DIV2) \
+ || ((__VALUE__) == LL_TIM_ICPSC_DIV4) \
+ || ((__VALUE__) == LL_TIM_ICPSC_DIV8))
+
+#define IS_LL_TIM_IC_FILTER(__VALUE__) (((__VALUE__) == LL_TIM_IC_FILTER_FDIV1) \
+ || ((__VALUE__) == LL_TIM_IC_FILTER_FDIV1_N2) \
+ || ((__VALUE__) == LL_TIM_IC_FILTER_FDIV1_N4) \
+ || ((__VALUE__) == LL_TIM_IC_FILTER_FDIV1_N8) \
+ || ((__VALUE__) == LL_TIM_IC_FILTER_FDIV2_N6) \
+ || ((__VALUE__) == LL_TIM_IC_FILTER_FDIV2_N8) \
+ || ((__VALUE__) == LL_TIM_IC_FILTER_FDIV4_N6) \
+ || ((__VALUE__) == LL_TIM_IC_FILTER_FDIV4_N8) \
+ || ((__VALUE__) == LL_TIM_IC_FILTER_FDIV8_N6) \
+ || ((__VALUE__) == LL_TIM_IC_FILTER_FDIV8_N8) \
+ || ((__VALUE__) == LL_TIM_IC_FILTER_FDIV16_N5) \
+ || ((__VALUE__) == LL_TIM_IC_FILTER_FDIV16_N6) \
+ || ((__VALUE__) == LL_TIM_IC_FILTER_FDIV16_N8) \
+ || ((__VALUE__) == LL_TIM_IC_FILTER_FDIV32_N5) \
+ || ((__VALUE__) == LL_TIM_IC_FILTER_FDIV32_N6) \
+ || ((__VALUE__) == LL_TIM_IC_FILTER_FDIV32_N8))
+
+#define IS_LL_TIM_IC_POLARITY(__VALUE__) (((__VALUE__) == LL_TIM_IC_POLARITY_RISING) \
+ || ((__VALUE__) == LL_TIM_IC_POLARITY_FALLING) \
+ || ((__VALUE__) == LL_TIM_IC_POLARITY_BOTHEDGE))
+
+#define IS_LL_TIM_ENCODERMODE(__VALUE__) (((__VALUE__) == LL_TIM_ENCODERMODE_X2_TI1) \
+ || ((__VALUE__) == LL_TIM_ENCODERMODE_X2_TI2) \
+ || ((__VALUE__) == LL_TIM_ENCODERMODE_X4_TI12))
+
+#define IS_LL_TIM_IC_POLARITY_ENCODER(__VALUE__) (((__VALUE__) == LL_TIM_IC_POLARITY_RISING) \
+ || ((__VALUE__) == LL_TIM_IC_POLARITY_FALLING))
+
+#define IS_LL_TIM_OSSR_STATE(__VALUE__) (((__VALUE__) == LL_TIM_OSSR_DISABLE) \
+ || ((__VALUE__) == LL_TIM_OSSR_ENABLE))
+
+#define IS_LL_TIM_OSSI_STATE(__VALUE__) (((__VALUE__) == LL_TIM_OSSI_DISABLE) \
+ || ((__VALUE__) == LL_TIM_OSSI_ENABLE))
+
+#define IS_LL_TIM_LOCK_LEVEL(__VALUE__) (((__VALUE__) == LL_TIM_LOCKLEVEL_OFF) \
+ || ((__VALUE__) == LL_TIM_LOCKLEVEL_1) \
+ || ((__VALUE__) == LL_TIM_LOCKLEVEL_2) \
+ || ((__VALUE__) == LL_TIM_LOCKLEVEL_3))
+
+#define IS_LL_TIM_BREAK_STATE(__VALUE__) (((__VALUE__) == LL_TIM_BREAK_DISABLE) \
+ || ((__VALUE__) == LL_TIM_BREAK_ENABLE))
+
+#define IS_LL_TIM_BREAK_POLARITY(__VALUE__) (((__VALUE__) == LL_TIM_BREAK_POLARITY_LOW) \
+ || ((__VALUE__) == LL_TIM_BREAK_POLARITY_HIGH))
+
+#define IS_LL_TIM_AUTOMATIC_OUTPUT_STATE(__VALUE__) (((__VALUE__) == LL_TIM_AUTOMATICOUTPUT_DISABLE) \
+ || ((__VALUE__) == LL_TIM_AUTOMATICOUTPUT_ENABLE))
+/**
+ * @}
+ */
+
+
+/* Private function prototypes -----------------------------------------------*/
+/** @defgroup TIM_LL_Private_Functions TIM Private Functions
+ * @{
+ */
+static ErrorStatus OC1Config(TIM_TypeDef *TIMx, LL_TIM_OC_InitTypeDef *TIM_OCInitStruct);
+static ErrorStatus OC2Config(TIM_TypeDef *TIMx, LL_TIM_OC_InitTypeDef *TIM_OCInitStruct);
+static ErrorStatus OC3Config(TIM_TypeDef *TIMx, LL_TIM_OC_InitTypeDef *TIM_OCInitStruct);
+static ErrorStatus OC4Config(TIM_TypeDef *TIMx, LL_TIM_OC_InitTypeDef *TIM_OCInitStruct);
+static ErrorStatus IC1Config(TIM_TypeDef *TIMx, LL_TIM_IC_InitTypeDef *TIM_ICInitStruct);
+static ErrorStatus IC2Config(TIM_TypeDef *TIMx, LL_TIM_IC_InitTypeDef *TIM_ICInitStruct);
+static ErrorStatus IC3Config(TIM_TypeDef *TIMx, LL_TIM_IC_InitTypeDef *TIM_ICInitStruct);
+static ErrorStatus IC4Config(TIM_TypeDef *TIMx, LL_TIM_IC_InitTypeDef *TIM_ICInitStruct);
+/**
+ * @}
+ */
+
+/* Exported functions --------------------------------------------------------*/
+/** @addtogroup TIM_LL_Exported_Functions
+ * @{
+ */
+
+/** @addtogroup TIM_LL_EF_Init
+ * @{
+ */
+
+/**
+ * @brief Set TIMx registers to their reset values.
+ * @param TIMx Timer instance
+ * @retval An ErrorStatus enumeration value:
+ * - SUCCESS: TIMx registers are de-initialized
+ * - ERROR: invalid TIMx instance
+ */
+ErrorStatus LL_TIM_DeInit(TIM_TypeDef *TIMx)
+{
+ ErrorStatus result = SUCCESS;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_INSTANCE(TIMx));
+
+ if (TIMx == TIM1)
+ {
+ LL_APB1_GRP2_ForceReset(LL_APB1_GRP2_PERIPH_TIM1);
+ LL_APB1_GRP2_ReleaseReset(LL_APB1_GRP2_PERIPH_TIM1);
+ }
+#if defined (TIM2)
+ else if (TIMx == TIM2)
+ {
+ LL_APB1_GRP1_ForceReset(LL_APB1_GRP1_PERIPH_TIM2);
+ LL_APB1_GRP1_ReleaseReset(LL_APB1_GRP1_PERIPH_TIM2);
+ }
+#endif /* TIM2 */
+#if defined(TIM3)
+ else if (TIMx == TIM3)
+ {
+ LL_APB1_GRP1_ForceReset(LL_APB1_GRP1_PERIPH_TIM3);
+ LL_APB1_GRP1_ReleaseReset(LL_APB1_GRP1_PERIPH_TIM3);
+ }
+#endif /* TIM3 */
+#if defined(TIM5)
+ else if (TIMx == TIM5)
+ {
+ LL_APB1_GRP1_ForceReset(LL_APB1_GRP1_PERIPH_TIM5);
+ LL_APB1_GRP1_ReleaseReset(LL_APB1_GRP1_PERIPH_TIM5);
+ }
+#endif /* TIM5 */
+#if defined (TIM6)
+ else if (TIMx == TIM6)
+ {
+ LL_APB1_GRP1_ForceReset(LL_APB1_GRP1_PERIPH_TIM6);
+ LL_APB1_GRP1_ReleaseReset(LL_APB1_GRP1_PERIPH_TIM6);
+ }
+#endif /* TIM6 */
+#if defined (TIM7)
+ else if (TIMx == TIM7)
+ {
+ LL_APB1_GRP1_ForceReset(LL_APB1_GRP1_PERIPH_TIM7);
+ LL_APB1_GRP1_ReleaseReset(LL_APB1_GRP1_PERIPH_TIM7);
+ }
+#endif /* TIM7 */
+#if defined(TIM8)
+ else if (TIMx == TIM8)
+ {
+ LL_APB2_GRP1_ForceReset(LL_APB2_GRP1_PERIPH_TIM8);
+ LL_APB2_GRP1_ReleaseReset(LL_APB2_GRP1_PERIPH_TIM8);
+ }
+#endif /* TIM8 */
+#if defined (TIM14)
+ else if (TIMx == TIM14)
+ {
+ LL_APB1_GRP1_ForceReset(LL_APB1_GRP1_PERIPH_TIM14);
+ LL_APB1_GRP1_ReleaseReset(LL_APB1_GRP1_PERIPH_TIM14);
+ }
+#endif /* TIM14 */
+#if defined (TIM15)
+ else if (TIMx == TIM15)
+ {
+ LL_APB1_GRP2_ForceReset(LL_APB1_GRP2_PERIPH_TIM15);
+ LL_APB1_GRP2_ReleaseReset(LL_APB1_GRP2_PERIPH_TIM15);
+ }
+#endif /* TIM15 */
+#if defined (TIM16)
+ else if (TIMx == TIM16)
+ {
+ LL_APB1_GRP2_ForceReset(LL_APB1_GRP2_PERIPH_TIM16);
+ LL_APB1_GRP2_ReleaseReset(LL_APB1_GRP2_PERIPH_TIM16);
+ }
+#endif /* TIM16 */
+#if defined(TIM17)
+ else if (TIMx == TIM17)
+ {
+ LL_APB1_GRP2_ForceReset(LL_APB1_GRP2_PERIPH_TIM17);
+ LL_APB1_GRP2_ReleaseReset(LL_APB1_GRP2_PERIPH_TIM17);
+ }
+#endif /* TIM17 */
+ else
+ {
+ result = ERROR;
+ }
+
+ return result;
+}
+
+/**
+ * @brief Set the fields of the time base unit configuration data structure
+ * to their default values.
+ * @param TIM_InitStruct pointer to a @ref LL_TIM_InitTypeDef structure (time base unit configuration data structure)
+ * @retval None
+ */
+void LL_TIM_StructInit(LL_TIM_InitTypeDef *TIM_InitStruct)
+{
+ /* Set the default configuration */
+ TIM_InitStruct->Prescaler = (uint16_t)0x0000;
+ TIM_InitStruct->CounterMode = LL_TIM_COUNTERMODE_UP;
+ TIM_InitStruct->Autoreload = 0xFFFFFFFFU;
+ TIM_InitStruct->ClockDivision = LL_TIM_CLOCKDIVISION_DIV1;
+ TIM_InitStruct->RepetitionCounter = 0x00000000U;
+}
+
+/**
+ * @brief Configure the TIMx time base unit.
+ * @param TIMx Timer Instance
+ * @param TIM_InitStruct pointer to a @ref LL_TIM_InitTypeDef structure
+ * (TIMx time base unit configuration data structure)
+ * @retval An ErrorStatus enumeration value:
+ * - SUCCESS: TIMx registers are de-initialized
+ * - ERROR: not applicable
+ */
+ErrorStatus LL_TIM_Init(TIM_TypeDef *TIMx, LL_TIM_InitTypeDef *TIM_InitStruct)
+{
+ uint32_t tmpcr1;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_INSTANCE(TIMx));
+ assert_param(IS_LL_TIM_COUNTERMODE(TIM_InitStruct->CounterMode));
+ assert_param(IS_LL_TIM_CLOCKDIVISION(TIM_InitStruct->ClockDivision));
+
+ tmpcr1 = LL_TIM_ReadReg(TIMx, CR1);
+
+ if (IS_TIM_COUNTER_MODE_SELECT_INSTANCE(TIMx))
+ {
+ /* Select the Counter Mode */
+ MODIFY_REG(tmpcr1, (TIM_CR1_DIR | TIM_CR1_CMS), TIM_InitStruct->CounterMode);
+ }
+
+ if (IS_TIM_CLOCK_DIVISION_INSTANCE(TIMx))
+ {
+ /* Set the clock division */
+ MODIFY_REG(tmpcr1, TIM_CR1_CKD, TIM_InitStruct->ClockDivision);
+ }
+
+ /* Write to TIMx CR1 */
+ LL_TIM_WriteReg(TIMx, CR1, tmpcr1);
+
+ /* Set the Autoreload value */
+ LL_TIM_SetAutoReload(TIMx, TIM_InitStruct->Autoreload);
+
+ /* Set the Prescaler value */
+ LL_TIM_SetPrescaler(TIMx, TIM_InitStruct->Prescaler);
+
+ if (IS_TIM_REPETITION_COUNTER_INSTANCE(TIMx))
+ {
+ /* Set the Repetition Counter value */
+ LL_TIM_SetRepetitionCounter(TIMx, TIM_InitStruct->RepetitionCounter);
+ }
+
+ /* Generate an update event to reload the Prescaler
+ and the repetition counter value (if applicable) immediately */
+ LL_TIM_GenerateEvent_UPDATE(TIMx);
+
+ return SUCCESS;
+}
+
+/**
+ * @brief Set the fields of the TIMx output channel configuration data
+ * structure to their default values.
+ * @param TIM_OC_InitStruct pointer to a @ref LL_TIM_OC_InitTypeDef structure
+ * (the output channel configuration data structure)
+ * @retval None
+ */
+void LL_TIM_OC_StructInit(LL_TIM_OC_InitTypeDef *TIM_OC_InitStruct)
+{
+ /* Set the default configuration */
+ TIM_OC_InitStruct->OCMode = LL_TIM_OCMODE_FROZEN;
+ TIM_OC_InitStruct->OCState = LL_TIM_OCSTATE_DISABLE;
+ TIM_OC_InitStruct->OCNState = LL_TIM_OCSTATE_DISABLE;
+ TIM_OC_InitStruct->CompareValue = 0x00000000U;
+ TIM_OC_InitStruct->OCPolarity = LL_TIM_OCPOLARITY_HIGH;
+ TIM_OC_InitStruct->OCNPolarity = LL_TIM_OCPOLARITY_HIGH;
+ TIM_OC_InitStruct->OCIdleState = LL_TIM_OCIDLESTATE_LOW;
+ TIM_OC_InitStruct->OCNIdleState = LL_TIM_OCIDLESTATE_LOW;
+}
+
+/**
+ * @brief Configure the TIMx output channel.
+ * @param TIMx Timer Instance
+ * @param Channel This parameter can be one of the following values:
+ * @arg @ref LL_TIM_CHANNEL_CH1
+ * @arg @ref LL_TIM_CHANNEL_CH2
+ * @arg @ref LL_TIM_CHANNEL_CH3
+ * @arg @ref LL_TIM_CHANNEL_CH4
+ * @param TIM_OC_InitStruct pointer to a @ref LL_TIM_OC_InitTypeDef structure (TIMx output channel configuration
+ * data structure)
+ * @retval An ErrorStatus enumeration value:
+ * - SUCCESS: TIMx output channel is initialized
+ * - ERROR: TIMx output channel is not initialized
+ */
+ErrorStatus LL_TIM_OC_Init(TIM_TypeDef *TIMx, uint32_t Channel, LL_TIM_OC_InitTypeDef *TIM_OC_InitStruct)
+{
+ ErrorStatus result = ERROR;
+
+ switch (Channel)
+ {
+ case LL_TIM_CHANNEL_CH1:
+ result = OC1Config(TIMx, TIM_OC_InitStruct);
+ break;
+ case LL_TIM_CHANNEL_CH2:
+ result = OC2Config(TIMx, TIM_OC_InitStruct);
+ break;
+ case LL_TIM_CHANNEL_CH3:
+ result = OC3Config(TIMx, TIM_OC_InitStruct);
+ break;
+ case LL_TIM_CHANNEL_CH4:
+ result = OC4Config(TIMx, TIM_OC_InitStruct);
+ break;
+ default:
+ break;
+ }
+
+ return result;
+}
+
+/**
+ * @brief Set the fields of the TIMx input channel configuration data
+ * structure to their default values.
+ * @param TIM_ICInitStruct pointer to a @ref LL_TIM_IC_InitTypeDef structure (the input channel configuration
+ * data structure)
+ * @retval None
+ */
+void LL_TIM_IC_StructInit(LL_TIM_IC_InitTypeDef *TIM_ICInitStruct)
+{
+ /* Set the default configuration */
+ TIM_ICInitStruct->ICPolarity = LL_TIM_IC_POLARITY_RISING;
+ TIM_ICInitStruct->ICActiveInput = LL_TIM_ACTIVEINPUT_DIRECTTI;
+ TIM_ICInitStruct->ICPrescaler = LL_TIM_ICPSC_DIV1;
+ TIM_ICInitStruct->ICFilter = LL_TIM_IC_FILTER_FDIV1;
+}
+
+/**
+ * @brief Configure the TIMx input channel.
+ * @param TIMx Timer Instance
+ * @param Channel This parameter can be one of the following values:
+ * @arg @ref LL_TIM_CHANNEL_CH1
+ * @arg @ref LL_TIM_CHANNEL_CH2
+ * @arg @ref LL_TIM_CHANNEL_CH3
+ * @arg @ref LL_TIM_CHANNEL_CH4
+ * @param TIM_IC_InitStruct pointer to a @ref LL_TIM_IC_InitTypeDef structure (TIMx input channel configuration data
+ * structure)
+ * @retval An ErrorStatus enumeration value:
+ * - SUCCESS: TIMx output channel is initialized
+ * - ERROR: TIMx output channel is not initialized
+ */
+ErrorStatus LL_TIM_IC_Init(TIM_TypeDef *TIMx, uint32_t Channel, LL_TIM_IC_InitTypeDef *TIM_IC_InitStruct)
+{
+ ErrorStatus result = ERROR;
+
+ switch (Channel)
+ {
+ case LL_TIM_CHANNEL_CH1:
+ result = IC1Config(TIMx, TIM_IC_InitStruct);
+ break;
+ case LL_TIM_CHANNEL_CH2:
+ result = IC2Config(TIMx, TIM_IC_InitStruct);
+ break;
+ case LL_TIM_CHANNEL_CH3:
+ result = IC3Config(TIMx, TIM_IC_InitStruct);
+ break;
+ case LL_TIM_CHANNEL_CH4:
+ result = IC4Config(TIMx, TIM_IC_InitStruct);
+ break;
+ default:
+ break;
+ }
+
+ return result;
+}
+
+/**
+ * @brief Fills each TIM_EncoderInitStruct field with its default value
+ * @param TIM_EncoderInitStruct pointer to a @ref LL_TIM_ENCODER_InitTypeDef structure (encoder interface
+ * configuration data structure)
+ * @retval None
+ */
+void LL_TIM_ENCODER_StructInit(LL_TIM_ENCODER_InitTypeDef *TIM_EncoderInitStruct)
+{
+ /* Set the default configuration */
+ TIM_EncoderInitStruct->EncoderMode = LL_TIM_ENCODERMODE_X2_TI1;
+ TIM_EncoderInitStruct->IC1Polarity = LL_TIM_IC_POLARITY_RISING;
+ TIM_EncoderInitStruct->IC1ActiveInput = LL_TIM_ACTIVEINPUT_DIRECTTI;
+ TIM_EncoderInitStruct->IC1Prescaler = LL_TIM_ICPSC_DIV1;
+ TIM_EncoderInitStruct->IC1Filter = LL_TIM_IC_FILTER_FDIV1;
+ TIM_EncoderInitStruct->IC2Polarity = LL_TIM_IC_POLARITY_RISING;
+ TIM_EncoderInitStruct->IC2ActiveInput = LL_TIM_ACTIVEINPUT_DIRECTTI;
+ TIM_EncoderInitStruct->IC2Prescaler = LL_TIM_ICPSC_DIV1;
+ TIM_EncoderInitStruct->IC2Filter = LL_TIM_IC_FILTER_FDIV1;
+}
+
+/**
+ * @brief Configure the encoder interface of the timer instance.
+ * @param TIMx Timer Instance
+ * @param TIM_EncoderInitStruct pointer to a @ref LL_TIM_ENCODER_InitTypeDef structure (TIMx encoder interface
+ * configuration data structure)
+ * @retval An ErrorStatus enumeration value:
+ * - SUCCESS: TIMx registers are de-initialized
+ * - ERROR: not applicable
+ */
+ErrorStatus LL_TIM_ENCODER_Init(TIM_TypeDef *TIMx, LL_TIM_ENCODER_InitTypeDef *TIM_EncoderInitStruct)
+{
+ uint32_t tmpccmr1;
+ uint32_t tmpccer;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_ENCODER_INTERFACE_INSTANCE(TIMx));
+ assert_param(IS_LL_TIM_ENCODERMODE(TIM_EncoderInitStruct->EncoderMode));
+ assert_param(IS_LL_TIM_IC_POLARITY_ENCODER(TIM_EncoderInitStruct->IC1Polarity));
+ assert_param(IS_LL_TIM_ACTIVEINPUT(TIM_EncoderInitStruct->IC1ActiveInput));
+ assert_param(IS_LL_TIM_ICPSC(TIM_EncoderInitStruct->IC1Prescaler));
+ assert_param(IS_LL_TIM_IC_FILTER(TIM_EncoderInitStruct->IC1Filter));
+ assert_param(IS_LL_TIM_IC_POLARITY_ENCODER(TIM_EncoderInitStruct->IC2Polarity));
+ assert_param(IS_LL_TIM_ACTIVEINPUT(TIM_EncoderInitStruct->IC2ActiveInput));
+ assert_param(IS_LL_TIM_ICPSC(TIM_EncoderInitStruct->IC2Prescaler));
+ assert_param(IS_LL_TIM_IC_FILTER(TIM_EncoderInitStruct->IC2Filter));
+
+ /* Disable the CC1 and CC2: Reset the CC1E and CC2E Bits */
+ TIMx->CCER &= (uint32_t)~(TIM_CCER_CC1E | TIM_CCER_CC2E);
+
+ /* Get the TIMx CCMR1 register value */
+ tmpccmr1 = LL_TIM_ReadReg(TIMx, CCMR1);
+
+ /* Get the TIMx CCER register value */
+ tmpccer = LL_TIM_ReadReg(TIMx, CCER);
+
+ /* Configure TI1 */
+ tmpccmr1 &= (uint32_t)~(TIM_CCMR1_CC1S | TIM_CCMR1_IC1F | TIM_CCMR1_IC1PSC);
+ tmpccmr1 |= (uint32_t)(TIM_EncoderInitStruct->IC1ActiveInput >> 16U);
+ tmpccmr1 |= (uint32_t)(TIM_EncoderInitStruct->IC1Filter >> 16U);
+ tmpccmr1 |= (uint32_t)(TIM_EncoderInitStruct->IC1Prescaler >> 16U);
+
+ /* Configure TI2 */
+ tmpccmr1 &= (uint32_t)~(TIM_CCMR1_CC2S | TIM_CCMR1_IC2F | TIM_CCMR1_IC2PSC);
+ tmpccmr1 |= (uint32_t)(TIM_EncoderInitStruct->IC2ActiveInput >> 8U);
+ tmpccmr1 |= (uint32_t)(TIM_EncoderInitStruct->IC2Filter >> 8U);
+ tmpccmr1 |= (uint32_t)(TIM_EncoderInitStruct->IC2Prescaler >> 8U);
+
+ /* Set TI1 and TI2 polarity and enable TI1 and TI2 */
+ tmpccer &= (uint32_t)~(TIM_CCER_CC1P | TIM_CCER_CC1NP | TIM_CCER_CC2P | TIM_CCER_CC2NP);
+ tmpccer |= (uint32_t)(TIM_EncoderInitStruct->IC1Polarity);
+ tmpccer |= (uint32_t)(TIM_EncoderInitStruct->IC2Polarity << 4U);
+ tmpccer |= (uint32_t)(TIM_CCER_CC1E | TIM_CCER_CC2E);
+
+ /* Set encoder mode */
+ LL_TIM_SetEncoderMode(TIMx, TIM_EncoderInitStruct->EncoderMode);
+
+ /* Write to TIMx CCMR1 */
+ LL_TIM_WriteReg(TIMx, CCMR1, tmpccmr1);
+
+ /* Write to TIMx CCER */
+ LL_TIM_WriteReg(TIMx, CCER, tmpccer);
+
+ return SUCCESS;
+}
+
+/**
+ * @brief Set the fields of the TIMx Hall sensor interface configuration data
+ * structure to their default values.
+ * @param TIM_HallSensorInitStruct pointer to a @ref LL_TIM_HALLSENSOR_InitTypeDef structure (HALL sensor interface
+ * configuration data structure)
+ * @retval None
+ */
+void LL_TIM_HALLSENSOR_StructInit(LL_TIM_HALLSENSOR_InitTypeDef *TIM_HallSensorInitStruct)
+{
+ /* Set the default configuration */
+ TIM_HallSensorInitStruct->IC1Polarity = LL_TIM_IC_POLARITY_RISING;
+ TIM_HallSensorInitStruct->IC1Prescaler = LL_TIM_ICPSC_DIV1;
+ TIM_HallSensorInitStruct->IC1Filter = LL_TIM_IC_FILTER_FDIV1;
+ TIM_HallSensorInitStruct->CommutationDelay = 0U;
+}
+
+/**
+ * @brief Configure the Hall sensor interface of the timer instance.
+ * @note TIMx CH1, CH2 and CH3 inputs connected through a XOR
+ * to the TI1 input channel
+ * @note TIMx slave mode controller is configured in reset mode.
+ Selected internal trigger is TI1F_ED.
+ * @note Channel 1 is configured as input, IC1 is mapped on TRC.
+ * @note Captured value stored in TIMx_CCR1 correspond to the time elapsed
+ * between 2 changes on the inputs. It gives information about motor speed.
+ * @note Channel 2 is configured in output PWM 2 mode.
+ * @note Compare value stored in TIMx_CCR2 corresponds to the commutation delay.
+ * @note OC2REF is selected as trigger output on TRGO.
+ * @note LL_TIM_IC_POLARITY_BOTHEDGE must not be used for TI1 when it is used
+ * when TIMx operates in Hall sensor interface mode.
+ * @param TIMx Timer Instance
+ * @param TIM_HallSensorInitStruct pointer to a @ref LL_TIM_HALLSENSOR_InitTypeDef structure (TIMx HALL sensor
+ * interface configuration data structure)
+ * @retval An ErrorStatus enumeration value:
+ * - SUCCESS: TIMx registers are de-initialized
+ * - ERROR: not applicable
+ */
+ErrorStatus LL_TIM_HALLSENSOR_Init(TIM_TypeDef *TIMx, LL_TIM_HALLSENSOR_InitTypeDef *TIM_HallSensorInitStruct)
+{
+ uint32_t tmpcr2;
+ uint32_t tmpccmr1;
+ uint32_t tmpccer;
+ uint32_t tmpsmcr;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_HALL_SENSOR_INTERFACE_INSTANCE(TIMx));
+ assert_param(IS_LL_TIM_IC_POLARITY_ENCODER(TIM_HallSensorInitStruct->IC1Polarity));
+ assert_param(IS_LL_TIM_ICPSC(TIM_HallSensorInitStruct->IC1Prescaler));
+ assert_param(IS_LL_TIM_IC_FILTER(TIM_HallSensorInitStruct->IC1Filter));
+
+ /* Disable the CC1 and CC2: Reset the CC1E and CC2E Bits */
+ TIMx->CCER &= (uint32_t)~(TIM_CCER_CC1E | TIM_CCER_CC2E);
+
+ /* Get the TIMx CR2 register value */
+ tmpcr2 = LL_TIM_ReadReg(TIMx, CR2);
+
+ /* Get the TIMx CCMR1 register value */
+ tmpccmr1 = LL_TIM_ReadReg(TIMx, CCMR1);
+
+ /* Get the TIMx CCER register value */
+ tmpccer = LL_TIM_ReadReg(TIMx, CCER);
+
+ /* Get the TIMx SMCR register value */
+ tmpsmcr = LL_TIM_ReadReg(TIMx, SMCR);
+
+ /* Connect TIMx_CH1, CH2 and CH3 pins to the TI1 input */
+ tmpcr2 |= TIM_CR2_TI1S;
+
+ /* OC2REF signal is used as trigger output (TRGO) */
+ tmpcr2 |= LL_TIM_TRGO_OC2REF;
+
+ /* Configure the slave mode controller */
+ tmpsmcr &= (uint32_t)~(TIM_SMCR_TS | TIM_SMCR_SMS);
+ tmpsmcr |= LL_TIM_TS_TI1F_ED;
+ tmpsmcr |= LL_TIM_SLAVEMODE_RESET;
+
+ /* Configure input channel 1 */
+ tmpccmr1 &= (uint32_t)~(TIM_CCMR1_CC1S | TIM_CCMR1_IC1F | TIM_CCMR1_IC1PSC);
+ tmpccmr1 |= (uint32_t)(LL_TIM_ACTIVEINPUT_TRC >> 16U);
+ tmpccmr1 |= (uint32_t)(TIM_HallSensorInitStruct->IC1Filter >> 16U);
+ tmpccmr1 |= (uint32_t)(TIM_HallSensorInitStruct->IC1Prescaler >> 16U);
+
+ /* Configure input channel 2 */
+ tmpccmr1 &= (uint32_t)~(TIM_CCMR1_OC2M | TIM_CCMR1_OC2FE | TIM_CCMR1_OC2PE | TIM_CCMR1_OC2CE);
+ tmpccmr1 |= (uint32_t)(LL_TIM_OCMODE_PWM2 << 8U);
+
+ /* Set Channel 1 polarity and enable Channel 1 and Channel2 */
+ tmpccer &= (uint32_t)~(TIM_CCER_CC1P | TIM_CCER_CC1NP | TIM_CCER_CC2P | TIM_CCER_CC2NP);
+ tmpccer |= (uint32_t)(TIM_HallSensorInitStruct->IC1Polarity);
+ tmpccer |= (uint32_t)(TIM_CCER_CC1E | TIM_CCER_CC2E);
+
+ /* Write to TIMx CR2 */
+ LL_TIM_WriteReg(TIMx, CR2, tmpcr2);
+
+ /* Write to TIMx SMCR */
+ LL_TIM_WriteReg(TIMx, SMCR, tmpsmcr);
+
+ /* Write to TIMx CCMR1 */
+ LL_TIM_WriteReg(TIMx, CCMR1, tmpccmr1);
+
+ /* Write to TIMx CCER */
+ LL_TIM_WriteReg(TIMx, CCER, tmpccer);
+
+ /* Write to TIMx CCR2 */
+ LL_TIM_OC_SetCompareCH2(TIMx, TIM_HallSensorInitStruct->CommutationDelay);
+
+ return SUCCESS;
+}
+
+/**
+ * @brief Set the fields of the Break and Dead Time configuration data structure
+ * to their default values.
+ * @param TIM_BDTRInitStruct pointer to a @ref LL_TIM_BDTR_InitTypeDef structure (Break and Dead Time configuration
+ * data structure)
+ * @retval None
+ */
+void LL_TIM_BDTR_StructInit(LL_TIM_BDTR_InitTypeDef *TIM_BDTRInitStruct)
+{
+ /* Set the default configuration */
+ TIM_BDTRInitStruct->OSSRState = LL_TIM_OSSR_DISABLE;
+ TIM_BDTRInitStruct->OSSIState = LL_TIM_OSSI_DISABLE;
+ TIM_BDTRInitStruct->LockLevel = LL_TIM_LOCKLEVEL_OFF;
+ TIM_BDTRInitStruct->DeadTime = (uint8_t)0x00;
+ TIM_BDTRInitStruct->BreakState = LL_TIM_BREAK_DISABLE;
+ TIM_BDTRInitStruct->BreakPolarity = LL_TIM_BREAK_POLARITY_LOW;
+ TIM_BDTRInitStruct->AutomaticOutput = LL_TIM_AUTOMATICOUTPUT_DISABLE;
+}
+
+/**
+ * @brief Configure the Break and Dead Time feature of the timer instance.
+ * @note As the bits AOE, BKP, BKE, OSSR, OSSI and DTG[7:0] can be write-locked
+ * depending on the LOCK configuration, it can be necessary to configure all of
+ * them during the first write access to the TIMx_BDTR register.
+ * @note Macro IS_TIM_BREAK_INSTANCE(TIMx) can be used to check whether or not
+ * a timer instance provides a break input.
+ * @param TIMx Timer Instance
+ * @param TIM_BDTRInitStruct pointer to a @ref LL_TIM_BDTR_InitTypeDef structure (Break and Dead Time configuration
+ * data structure)
+ * @retval An ErrorStatus enumeration value:
+ * - SUCCESS: Break and Dead Time is initialized
+ * - ERROR: not applicable
+ */
+ErrorStatus LL_TIM_BDTR_Init(TIM_TypeDef *TIMx, LL_TIM_BDTR_InitTypeDef *TIM_BDTRInitStruct)
+{
+ uint32_t tmpbdtr = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_BREAK_INSTANCE(TIMx));
+ assert_param(IS_LL_TIM_OSSR_STATE(TIM_BDTRInitStruct->OSSRState));
+ assert_param(IS_LL_TIM_OSSI_STATE(TIM_BDTRInitStruct->OSSIState));
+ assert_param(IS_LL_TIM_LOCK_LEVEL(TIM_BDTRInitStruct->LockLevel));
+ assert_param(IS_LL_TIM_BREAK_STATE(TIM_BDTRInitStruct->BreakState));
+ assert_param(IS_LL_TIM_BREAK_POLARITY(TIM_BDTRInitStruct->BreakPolarity));
+ assert_param(IS_LL_TIM_AUTOMATIC_OUTPUT_STATE(TIM_BDTRInitStruct->AutomaticOutput));
+
+ /* Set the Lock level, the Break enable Bit and the Polarity, the OSSR State,
+ the OSSI State, the dead time value and the Automatic Output Enable Bit */
+
+ /* Set the BDTR bits */
+ MODIFY_REG(tmpbdtr, TIM_BDTR_DTG, TIM_BDTRInitStruct->DeadTime);
+ MODIFY_REG(tmpbdtr, TIM_BDTR_LOCK, TIM_BDTRInitStruct->LockLevel);
+ MODIFY_REG(tmpbdtr, TIM_BDTR_OSSI, TIM_BDTRInitStruct->OSSIState);
+ MODIFY_REG(tmpbdtr, TIM_BDTR_OSSR, TIM_BDTRInitStruct->OSSRState);
+ MODIFY_REG(tmpbdtr, TIM_BDTR_BKE, TIM_BDTRInitStruct->BreakState);
+ MODIFY_REG(tmpbdtr, TIM_BDTR_BKP, TIM_BDTRInitStruct->BreakPolarity);
+ MODIFY_REG(tmpbdtr, TIM_BDTR_AOE, TIM_BDTRInitStruct->AutomaticOutput);
+ MODIFY_REG(tmpbdtr, TIM_BDTR_MOE, TIM_BDTRInitStruct->AutomaticOutput);
+
+ /* Set TIMx_BDTR */
+ LL_TIM_WriteReg(TIMx, BDTR, tmpbdtr);
+
+ return SUCCESS;
+}
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/** @addtogroup TIM_LL_Private_Functions TIM Private Functions
+ * @brief Private functions
+ * @{
+ */
+/**
+ * @brief Configure the TIMx output channel 1.
+ * @param TIMx Timer Instance
+ * @param TIM_OCInitStruct pointer to the the TIMx output channel 1 configuration data structure
+ * @retval An ErrorStatus enumeration value:
+ * - SUCCESS: TIMx registers are de-initialized
+ * - ERROR: not applicable
+ */
+static ErrorStatus OC1Config(TIM_TypeDef *TIMx, LL_TIM_OC_InitTypeDef *TIM_OCInitStruct)
+{
+ uint32_t tmpccmr1;
+ uint32_t tmpccer;
+ uint32_t tmpcr2;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_CC1_INSTANCE(TIMx));
+ assert_param(IS_LL_TIM_OCMODE(TIM_OCInitStruct->OCMode));
+ assert_param(IS_LL_TIM_OCSTATE(TIM_OCInitStruct->OCState));
+ assert_param(IS_LL_TIM_OCPOLARITY(TIM_OCInitStruct->OCPolarity));
+ assert_param(IS_LL_TIM_OCSTATE(TIM_OCInitStruct->OCNState));
+ assert_param(IS_LL_TIM_OCPOLARITY(TIM_OCInitStruct->OCNPolarity));
+
+ /* Disable the Channel 1: Reset the CC1E Bit */
+ CLEAR_BIT(TIMx->CCER, TIM_CCER_CC1E);
+
+ /* Get the TIMx CCER register value */
+ tmpccer = LL_TIM_ReadReg(TIMx, CCER);
+
+ /* Get the TIMx CR2 register value */
+ tmpcr2 = LL_TIM_ReadReg(TIMx, CR2);
+
+ /* Get the TIMx CCMR1 register value */
+ tmpccmr1 = LL_TIM_ReadReg(TIMx, CCMR1);
+
+ /* Reset Capture/Compare selection Bits */
+ CLEAR_BIT(tmpccmr1, TIM_CCMR1_CC1S);
+
+ /* Set the Output Compare Mode */
+ MODIFY_REG(tmpccmr1, TIM_CCMR1_OC1M, TIM_OCInitStruct->OCMode);
+
+ /* Set the Output Compare Polarity */
+ MODIFY_REG(tmpccer, TIM_CCER_CC1P, TIM_OCInitStruct->OCPolarity);
+
+ /* Set the Output State */
+ MODIFY_REG(tmpccer, TIM_CCER_CC1E, TIM_OCInitStruct->OCState);
+
+ if (IS_TIM_BREAK_INSTANCE(TIMx))
+ {
+ assert_param(IS_LL_TIM_OCIDLESTATE(TIM_OCInitStruct->OCNIdleState));
+ assert_param(IS_LL_TIM_OCIDLESTATE(TIM_OCInitStruct->OCIdleState));
+
+ /* Set the complementary output Polarity */
+ MODIFY_REG(tmpccer, TIM_CCER_CC1NP, TIM_OCInitStruct->OCNPolarity << 2U);
+
+ /* Set the complementary output State */
+ MODIFY_REG(tmpccer, TIM_CCER_CC1NE, TIM_OCInitStruct->OCNState << 2U);
+
+ /* Set the Output Idle state */
+ MODIFY_REG(tmpcr2, TIM_CR2_OIS1, TIM_OCInitStruct->OCIdleState);
+
+ /* Set the complementary output Idle state */
+ MODIFY_REG(tmpcr2, TIM_CR2_OIS1N, TIM_OCInitStruct->OCNIdleState << 1U);
+ }
+
+ /* Write to TIMx CR2 */
+ LL_TIM_WriteReg(TIMx, CR2, tmpcr2);
+
+ /* Write to TIMx CCMR1 */
+ LL_TIM_WriteReg(TIMx, CCMR1, tmpccmr1);
+
+ /* Set the Capture Compare Register value */
+ LL_TIM_OC_SetCompareCH1(TIMx, TIM_OCInitStruct->CompareValue);
+
+ /* Write to TIMx CCER */
+ LL_TIM_WriteReg(TIMx, CCER, tmpccer);
+
+ return SUCCESS;
+}
+
+/**
+ * @brief Configure the TIMx output channel 2.
+ * @param TIMx Timer Instance
+ * @param TIM_OCInitStruct pointer to the the TIMx output channel 2 configuration data structure
+ * @retval An ErrorStatus enumeration value:
+ * - SUCCESS: TIMx registers are de-initialized
+ * - ERROR: not applicable
+ */
+static ErrorStatus OC2Config(TIM_TypeDef *TIMx, LL_TIM_OC_InitTypeDef *TIM_OCInitStruct)
+{
+ uint32_t tmpccmr1;
+ uint32_t tmpccer;
+ uint32_t tmpcr2;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_CC2_INSTANCE(TIMx));
+ assert_param(IS_LL_TIM_OCMODE(TIM_OCInitStruct->OCMode));
+ assert_param(IS_LL_TIM_OCSTATE(TIM_OCInitStruct->OCState));
+ assert_param(IS_LL_TIM_OCPOLARITY(TIM_OCInitStruct->OCPolarity));
+ assert_param(IS_LL_TIM_OCSTATE(TIM_OCInitStruct->OCNState));
+ assert_param(IS_LL_TIM_OCPOLARITY(TIM_OCInitStruct->OCNPolarity));
+
+ /* Disable the Channel 2: Reset the CC2E Bit */
+ CLEAR_BIT(TIMx->CCER, TIM_CCER_CC2E);
+
+ /* Get the TIMx CCER register value */
+ tmpccer = LL_TIM_ReadReg(TIMx, CCER);
+
+ /* Get the TIMx CR2 register value */
+ tmpcr2 = LL_TIM_ReadReg(TIMx, CR2);
+
+ /* Get the TIMx CCMR1 register value */
+ tmpccmr1 = LL_TIM_ReadReg(TIMx, CCMR1);
+
+ /* Reset Capture/Compare selection Bits */
+ CLEAR_BIT(tmpccmr1, TIM_CCMR1_CC2S);
+
+ /* Select the Output Compare Mode */
+ MODIFY_REG(tmpccmr1, TIM_CCMR1_OC2M, TIM_OCInitStruct->OCMode << 8U);
+
+ /* Set the Output Compare Polarity */
+ MODIFY_REG(tmpccer, TIM_CCER_CC2P, TIM_OCInitStruct->OCPolarity << 4U);
+
+ /* Set the Output State */
+ MODIFY_REG(tmpccer, TIM_CCER_CC2E, TIM_OCInitStruct->OCState << 4U);
+
+ if (IS_TIM_BREAK_INSTANCE(TIMx))
+ {
+ assert_param(IS_LL_TIM_OCIDLESTATE(TIM_OCInitStruct->OCNIdleState));
+ assert_param(IS_LL_TIM_OCIDLESTATE(TIM_OCInitStruct->OCIdleState));
+
+ /* Set the complementary output Polarity */
+ MODIFY_REG(tmpccer, TIM_CCER_CC2NP, TIM_OCInitStruct->OCNPolarity << 6U);
+
+ /* Set the complementary output State */
+ MODIFY_REG(tmpccer, TIM_CCER_CC2NE, TIM_OCInitStruct->OCNState << 6U);
+
+ /* Set the Output Idle state */
+ MODIFY_REG(tmpcr2, TIM_CR2_OIS2, TIM_OCInitStruct->OCIdleState << 2U);
+
+ /* Set the complementary output Idle state */
+ MODIFY_REG(tmpcr2, TIM_CR2_OIS2N, TIM_OCInitStruct->OCNIdleState << 3U);
+ }
+
+ /* Write to TIMx CR2 */
+ LL_TIM_WriteReg(TIMx, CR2, tmpcr2);
+
+ /* Write to TIMx CCMR1 */
+ LL_TIM_WriteReg(TIMx, CCMR1, tmpccmr1);
+
+ /* Set the Capture Compare Register value */
+ LL_TIM_OC_SetCompareCH2(TIMx, TIM_OCInitStruct->CompareValue);
+
+ /* Write to TIMx CCER */
+ LL_TIM_WriteReg(TIMx, CCER, tmpccer);
+
+ return SUCCESS;
+}
+
+/**
+ * @brief Configure the TIMx output channel 3.
+ * @param TIMx Timer Instance
+ * @param TIM_OCInitStruct pointer to the the TIMx output channel 3 configuration data structure
+ * @retval An ErrorStatus enumeration value:
+ * - SUCCESS: TIMx registers are de-initialized
+ * - ERROR: not applicable
+ */
+static ErrorStatus OC3Config(TIM_TypeDef *TIMx, LL_TIM_OC_InitTypeDef *TIM_OCInitStruct)
+{
+ uint32_t tmpccmr2;
+ uint32_t tmpccer;
+ uint32_t tmpcr2;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_CC3_INSTANCE(TIMx));
+ assert_param(IS_LL_TIM_OCMODE(TIM_OCInitStruct->OCMode));
+ assert_param(IS_LL_TIM_OCSTATE(TIM_OCInitStruct->OCState));
+ assert_param(IS_LL_TIM_OCPOLARITY(TIM_OCInitStruct->OCPolarity));
+ assert_param(IS_LL_TIM_OCSTATE(TIM_OCInitStruct->OCNState));
+ assert_param(IS_LL_TIM_OCPOLARITY(TIM_OCInitStruct->OCNPolarity));
+
+ /* Disable the Channel 3: Reset the CC3E Bit */
+ CLEAR_BIT(TIMx->CCER, TIM_CCER_CC3E);
+
+ /* Get the TIMx CCER register value */
+ tmpccer = LL_TIM_ReadReg(TIMx, CCER);
+
+ /* Get the TIMx CR2 register value */
+ tmpcr2 = LL_TIM_ReadReg(TIMx, CR2);
+
+ /* Get the TIMx CCMR2 register value */
+ tmpccmr2 = LL_TIM_ReadReg(TIMx, CCMR2);
+
+ /* Reset Capture/Compare selection Bits */
+ CLEAR_BIT(tmpccmr2, TIM_CCMR2_CC3S);
+
+ /* Select the Output Compare Mode */
+ MODIFY_REG(tmpccmr2, TIM_CCMR2_OC3M, TIM_OCInitStruct->OCMode);
+
+ /* Set the Output Compare Polarity */
+ MODIFY_REG(tmpccer, TIM_CCER_CC3P, TIM_OCInitStruct->OCPolarity << 8U);
+
+ /* Set the Output State */
+ MODIFY_REG(tmpccer, TIM_CCER_CC3E, TIM_OCInitStruct->OCState << 8U);
+
+ if (IS_TIM_BREAK_INSTANCE(TIMx))
+ {
+ assert_param(IS_LL_TIM_OCIDLESTATE(TIM_OCInitStruct->OCNIdleState));
+ assert_param(IS_LL_TIM_OCIDLESTATE(TIM_OCInitStruct->OCIdleState));
+
+ /* Set the complementary output Polarity */
+ MODIFY_REG(tmpccer, TIM_CCER_CC3NP, TIM_OCInitStruct->OCNPolarity << 10U);
+
+ /* Set the complementary output State */
+ MODIFY_REG(tmpccer, TIM_CCER_CC3NE, TIM_OCInitStruct->OCNState << 10U);
+
+ /* Set the Output Idle state */
+ MODIFY_REG(tmpcr2, TIM_CR2_OIS3, TIM_OCInitStruct->OCIdleState << 4U);
+
+ /* Set the complementary output Idle state */
+ MODIFY_REG(tmpcr2, TIM_CR2_OIS3N, TIM_OCInitStruct->OCNIdleState << 5U);
+ }
+
+ /* Write to TIMx CR2 */
+ LL_TIM_WriteReg(TIMx, CR2, tmpcr2);
+
+ /* Write to TIMx CCMR2 */
+ LL_TIM_WriteReg(TIMx, CCMR2, tmpccmr2);
+
+ /* Set the Capture Compare Register value */
+ LL_TIM_OC_SetCompareCH3(TIMx, TIM_OCInitStruct->CompareValue);
+
+ /* Write to TIMx CCER */
+ LL_TIM_WriteReg(TIMx, CCER, tmpccer);
+
+ return SUCCESS;
+}
+
+/**
+ * @brief Configure the TIMx output channel 4.
+ * @param TIMx Timer Instance
+ * @param TIM_OCInitStruct pointer to the the TIMx output channel 4 configuration data structure
+ * @retval An ErrorStatus enumeration value:
+ * - SUCCESS: TIMx registers are de-initialized
+ * - ERROR: not applicable
+ */
+static ErrorStatus OC4Config(TIM_TypeDef *TIMx, LL_TIM_OC_InitTypeDef *TIM_OCInitStruct)
+{
+ uint32_t tmpccmr2;
+ uint32_t tmpccer;
+ uint32_t tmpcr2;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_CC4_INSTANCE(TIMx));
+ assert_param(IS_LL_TIM_OCMODE(TIM_OCInitStruct->OCMode));
+ assert_param(IS_LL_TIM_OCSTATE(TIM_OCInitStruct->OCState));
+ assert_param(IS_LL_TIM_OCPOLARITY(TIM_OCInitStruct->OCPolarity));
+ assert_param(IS_LL_TIM_OCPOLARITY(TIM_OCInitStruct->OCNPolarity));
+ assert_param(IS_LL_TIM_OCSTATE(TIM_OCInitStruct->OCNState));
+
+ /* Disable the Channel 4: Reset the CC4E Bit */
+ CLEAR_BIT(TIMx->CCER, TIM_CCER_CC4E);
+
+ /* Get the TIMx CCER register value */
+ tmpccer = LL_TIM_ReadReg(TIMx, CCER);
+
+ /* Get the TIMx CR2 register value */
+ tmpcr2 = LL_TIM_ReadReg(TIMx, CR2);
+
+ /* Get the TIMx CCMR2 register value */
+ tmpccmr2 = LL_TIM_ReadReg(TIMx, CCMR2);
+
+ /* Reset Capture/Compare selection Bits */
+ CLEAR_BIT(tmpccmr2, TIM_CCMR2_CC4S);
+
+ /* Select the Output Compare Mode */
+ MODIFY_REG(tmpccmr2, TIM_CCMR2_OC4M, TIM_OCInitStruct->OCMode << 8U);
+
+ /* Set the Output Compare Polarity */
+ MODIFY_REG(tmpccer, TIM_CCER_CC4P, TIM_OCInitStruct->OCPolarity << 12U);
+
+ /* Set the Output State */
+ MODIFY_REG(tmpccer, TIM_CCER_CC4E, TIM_OCInitStruct->OCState << 12U);
+
+ if (IS_TIM_BREAK_INSTANCE(TIMx))
+ {
+ assert_param(IS_LL_TIM_OCIDLESTATE(TIM_OCInitStruct->OCNIdleState));
+ assert_param(IS_LL_TIM_OCIDLESTATE(TIM_OCInitStruct->OCIdleState));
+
+ /* Set the Output Idle state */
+ MODIFY_REG(tmpcr2, TIM_CR2_OIS4, TIM_OCInitStruct->OCIdleState << 6U);
+ }
+
+ /* Write to TIMx CR2 */
+ LL_TIM_WriteReg(TIMx, CR2, tmpcr2);
+
+ /* Write to TIMx CCMR2 */
+ LL_TIM_WriteReg(TIMx, CCMR2, tmpccmr2);
+
+ /* Set the Capture Compare Register value */
+ LL_TIM_OC_SetCompareCH4(TIMx, TIM_OCInitStruct->CompareValue);
+
+ /* Write to TIMx CCER */
+ LL_TIM_WriteReg(TIMx, CCER, tmpccer);
+
+ return SUCCESS;
+}
+
+
+/**
+ * @brief Configure the TIMx input channel 1.
+ * @param TIMx Timer Instance
+ * @param TIM_ICInitStruct pointer to the the TIMx input channel 1 configuration data structure
+ * @retval An ErrorStatus enumeration value:
+ * - SUCCESS: TIMx registers are de-initialized
+ * - ERROR: not applicable
+ */
+static ErrorStatus IC1Config(TIM_TypeDef *TIMx, LL_TIM_IC_InitTypeDef *TIM_ICInitStruct)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_CC1_INSTANCE(TIMx));
+ assert_param(IS_LL_TIM_IC_POLARITY(TIM_ICInitStruct->ICPolarity));
+ assert_param(IS_LL_TIM_ACTIVEINPUT(TIM_ICInitStruct->ICActiveInput));
+ assert_param(IS_LL_TIM_ICPSC(TIM_ICInitStruct->ICPrescaler));
+ assert_param(IS_LL_TIM_IC_FILTER(TIM_ICInitStruct->ICFilter));
+
+ /* Disable the Channel 1: Reset the CC1E Bit */
+ TIMx->CCER &= (uint32_t)~TIM_CCER_CC1E;
+
+ /* Select the Input and set the filter and the prescaler value */
+ MODIFY_REG(TIMx->CCMR1,
+ (TIM_CCMR1_CC1S | TIM_CCMR1_IC1F | TIM_CCMR1_IC1PSC),
+ (TIM_ICInitStruct->ICActiveInput | TIM_ICInitStruct->ICFilter | TIM_ICInitStruct->ICPrescaler) >> 16U);
+
+ /* Select the Polarity and set the CC1E Bit */
+ MODIFY_REG(TIMx->CCER,
+ (TIM_CCER_CC1P | TIM_CCER_CC1NP),
+ (TIM_ICInitStruct->ICPolarity | TIM_CCER_CC1E));
+
+ return SUCCESS;
+}
+
+/**
+ * @brief Configure the TIMx input channel 2.
+ * @param TIMx Timer Instance
+ * @param TIM_ICInitStruct pointer to the the TIMx input channel 2 configuration data structure
+ * @retval An ErrorStatus enumeration value:
+ * - SUCCESS: TIMx registers are de-initialized
+ * - ERROR: not applicable
+ */
+static ErrorStatus IC2Config(TIM_TypeDef *TIMx, LL_TIM_IC_InitTypeDef *TIM_ICInitStruct)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_CC2_INSTANCE(TIMx));
+ assert_param(IS_LL_TIM_IC_POLARITY(TIM_ICInitStruct->ICPolarity));
+ assert_param(IS_LL_TIM_ACTIVEINPUT(TIM_ICInitStruct->ICActiveInput));
+ assert_param(IS_LL_TIM_ICPSC(TIM_ICInitStruct->ICPrescaler));
+ assert_param(IS_LL_TIM_IC_FILTER(TIM_ICInitStruct->ICFilter));
+
+ /* Disable the Channel 2: Reset the CC2E Bit */
+ TIMx->CCER &= (uint32_t)~TIM_CCER_CC2E;
+
+ /* Select the Input and set the filter and the prescaler value */
+ MODIFY_REG(TIMx->CCMR1,
+ (TIM_CCMR1_CC2S | TIM_CCMR1_IC2F | TIM_CCMR1_IC2PSC),
+ (TIM_ICInitStruct->ICActiveInput | TIM_ICInitStruct->ICFilter | TIM_ICInitStruct->ICPrescaler) >> 8U);
+
+ /* Select the Polarity and set the CC2E Bit */
+ MODIFY_REG(TIMx->CCER,
+ (TIM_CCER_CC2P | TIM_CCER_CC2NP),
+ ((TIM_ICInitStruct->ICPolarity << 4U) | TIM_CCER_CC2E));
+
+ return SUCCESS;
+}
+
+/**
+ * @brief Configure the TIMx input channel 3.
+ * @param TIMx Timer Instance
+ * @param TIM_ICInitStruct pointer to the the TIMx input channel 3 configuration data structure
+ * @retval An ErrorStatus enumeration value:
+ * - SUCCESS: TIMx registers are de-initialized
+ * - ERROR: not applicable
+ */
+static ErrorStatus IC3Config(TIM_TypeDef *TIMx, LL_TIM_IC_InitTypeDef *TIM_ICInitStruct)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_CC3_INSTANCE(TIMx));
+ assert_param(IS_LL_TIM_IC_POLARITY(TIM_ICInitStruct->ICPolarity));
+ assert_param(IS_LL_TIM_ACTIVEINPUT(TIM_ICInitStruct->ICActiveInput));
+ assert_param(IS_LL_TIM_ICPSC(TIM_ICInitStruct->ICPrescaler));
+ assert_param(IS_LL_TIM_IC_FILTER(TIM_ICInitStruct->ICFilter));
+
+ /* Disable the Channel 3: Reset the CC3E Bit */
+ TIMx->CCER &= (uint32_t)~TIM_CCER_CC3E;
+
+ /* Select the Input and set the filter and the prescaler value */
+ MODIFY_REG(TIMx->CCMR2,
+ (TIM_CCMR2_CC3S | TIM_CCMR2_IC3F | TIM_CCMR2_IC3PSC),
+ (TIM_ICInitStruct->ICActiveInput | TIM_ICInitStruct->ICFilter | TIM_ICInitStruct->ICPrescaler) >> 16U);
+
+ /* Select the Polarity and set the CC3E Bit */
+ MODIFY_REG(TIMx->CCER,
+ (TIM_CCER_CC3P | TIM_CCER_CC3NP),
+ ((TIM_ICInitStruct->ICPolarity << 8U) | TIM_CCER_CC3E));
+
+ return SUCCESS;
+}
+
+/**
+ * @brief Configure the TIMx input channel 4.
+ * @param TIMx Timer Instance
+ * @param TIM_ICInitStruct pointer to the the TIMx input channel 4 configuration data structure
+ * @retval An ErrorStatus enumeration value:
+ * - SUCCESS: TIMx registers are de-initialized
+ * - ERROR: not applicable
+ */
+static ErrorStatus IC4Config(TIM_TypeDef *TIMx, LL_TIM_IC_InitTypeDef *TIM_ICInitStruct)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_CC4_INSTANCE(TIMx));
+ assert_param(IS_LL_TIM_IC_POLARITY(TIM_ICInitStruct->ICPolarity));
+ assert_param(IS_LL_TIM_ACTIVEINPUT(TIM_ICInitStruct->ICActiveInput));
+ assert_param(IS_LL_TIM_ICPSC(TIM_ICInitStruct->ICPrescaler));
+ assert_param(IS_LL_TIM_IC_FILTER(TIM_ICInitStruct->ICFilter));
+
+ /* Disable the Channel 4: Reset the CC4E Bit */
+ TIMx->CCER &= (uint32_t)~TIM_CCER_CC4E;
+
+ /* Select the Input and set the filter and the prescaler value */
+ MODIFY_REG(TIMx->CCMR2,
+ (TIM_CCMR2_CC4S | TIM_CCMR2_IC4F | TIM_CCMR2_IC4PSC),
+ (TIM_ICInitStruct->ICActiveInput | TIM_ICInitStruct->ICFilter | TIM_ICInitStruct->ICPrescaler) >> 8U);
+
+ /* Select the Polarity and set the CC2E Bit */
+ MODIFY_REG(TIMx->CCER,
+ (TIM_CCER_CC4P | TIM_CCER_CC4NP),
+ ((TIM_ICInitStruct->ICPolarity << 12U) | TIM_CCER_CC4E));
+
+ return SUCCESS;
+}
+
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+#endif /* TIM1 || TIM2 || TIM3 || TIM14 || TIM15 || TIM16 || TIM17 || TIM6 || TIM7 */
+
+/**
+ * @}
+ */
+
+#endif /* USE_FULL_LL_DRIVER */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_utils.c b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_utils.c
new file mode 100644
index 0000000..59a78ee
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_utils.c
@@ -0,0 +1,622 @@
+/**
+ ******************************************************************************
+ * @file stm32f0xx_ll_utils.c
+ * @author MCD Application Team
+ * @brief UTILS LL module driver.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2016 STMicroelectronics.
+ * All rights reserved.
+ *
+ * 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 "stm32f0xx_ll_rcc.h"
+#include "stm32f0xx_ll_utils.h"
+#include "stm32f0xx_ll_system.h"
+#ifdef USE_FULL_ASSERT
+#include "stm32_assert.h"
+#else
+#define assert_param(expr) ((void)0U)
+#endif
+
+/** @addtogroup STM32F0xx_LL_Driver
+ * @{
+ */
+
+/** @addtogroup UTILS_LL
+ * @{
+ */
+
+/* Private types -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private constants ---------------------------------------------------------*/
+/** @addtogroup UTILS_LL_Private_Constants
+ * @{
+ */
+
+/* Defines used for PLL range */
+#define UTILS_PLL_OUTPUT_MIN 16000000U /*!< Frequency min for PLL output, in Hz */
+#define UTILS_PLL_OUTPUT_MAX 48000000U /*!< Frequency max for PLL output, in Hz */
+
+/* Defines used for HSE range */
+#define UTILS_HSE_FREQUENCY_MIN 4000000U /*!< Frequency min for HSE frequency, in Hz */
+#define UTILS_HSE_FREQUENCY_MAX 32000000U /*!< Frequency max for HSE frequency, in Hz */
+
+/* Defines used for FLASH latency according to SYSCLK Frequency */
+#define UTILS_LATENCY1_FREQ 24000000U /*!< SYSCLK frequency to set FLASH latency 1 */
+/**
+ * @}
+ */
+/* Private macros ------------------------------------------------------------*/
+/** @addtogroup UTILS_LL_Private_Macros
+ * @{
+ */
+#define IS_LL_UTILS_SYSCLK_DIV(__VALUE__) (((__VALUE__) == LL_RCC_SYSCLK_DIV_1) \
+ || ((__VALUE__) == LL_RCC_SYSCLK_DIV_2) \
+ || ((__VALUE__) == LL_RCC_SYSCLK_DIV_4) \
+ || ((__VALUE__) == LL_RCC_SYSCLK_DIV_8) \
+ || ((__VALUE__) == LL_RCC_SYSCLK_DIV_16) \
+ || ((__VALUE__) == LL_RCC_SYSCLK_DIV_64) \
+ || ((__VALUE__) == LL_RCC_SYSCLK_DIV_128) \
+ || ((__VALUE__) == LL_RCC_SYSCLK_DIV_256) \
+ || ((__VALUE__) == LL_RCC_SYSCLK_DIV_512))
+
+#define IS_LL_UTILS_APB1_DIV(__VALUE__) (((__VALUE__) == LL_RCC_APB1_DIV_1) \
+ || ((__VALUE__) == LL_RCC_APB1_DIV_2) \
+ || ((__VALUE__) == LL_RCC_APB1_DIV_4) \
+ || ((__VALUE__) == LL_RCC_APB1_DIV_8) \
+ || ((__VALUE__) == LL_RCC_APB1_DIV_16))
+
+#define IS_LL_UTILS_PLLMUL_VALUE(__VALUE__) (((__VALUE__) == LL_RCC_PLL_MUL_2) \
+ || ((__VALUE__) == LL_RCC_PLL_MUL_3) \
+ || ((__VALUE__) == LL_RCC_PLL_MUL_4) \
+ || ((__VALUE__) == LL_RCC_PLL_MUL_5) \
+ || ((__VALUE__) == LL_RCC_PLL_MUL_6) \
+ || ((__VALUE__) == LL_RCC_PLL_MUL_7) \
+ || ((__VALUE__) == LL_RCC_PLL_MUL_8) \
+ || ((__VALUE__) == LL_RCC_PLL_MUL_9) \
+ || ((__VALUE__) == LL_RCC_PLL_MUL_10) \
+ || ((__VALUE__) == LL_RCC_PLL_MUL_11) \
+ || ((__VALUE__) == LL_RCC_PLL_MUL_12) \
+ || ((__VALUE__) == LL_RCC_PLL_MUL_13) \
+ || ((__VALUE__) == LL_RCC_PLL_MUL_14) \
+ || ((__VALUE__) == LL_RCC_PLL_MUL_15) \
+ || ((__VALUE__) == LL_RCC_PLL_MUL_16))
+
+#define IS_LL_UTILS_PREDIV_VALUE(__VALUE__) (((__VALUE__) == LL_RCC_PREDIV_DIV_1) || ((__VALUE__) == LL_RCC_PREDIV_DIV_2) || \
+ ((__VALUE__) == LL_RCC_PREDIV_DIV_3) || ((__VALUE__) == LL_RCC_PREDIV_DIV_4) || \
+ ((__VALUE__) == LL_RCC_PREDIV_DIV_5) || ((__VALUE__) == LL_RCC_PREDIV_DIV_6) || \
+ ((__VALUE__) == LL_RCC_PREDIV_DIV_7) || ((__VALUE__) == LL_RCC_PREDIV_DIV_8) || \
+ ((__VALUE__) == LL_RCC_PREDIV_DIV_9) || ((__VALUE__) == LL_RCC_PREDIV_DIV_10) || \
+ ((__VALUE__) == LL_RCC_PREDIV_DIV_11) || ((__VALUE__) == LL_RCC_PREDIV_DIV_12) || \
+ ((__VALUE__) == LL_RCC_PREDIV_DIV_13) || ((__VALUE__) == LL_RCC_PREDIV_DIV_14) || \
+ ((__VALUE__) == LL_RCC_PREDIV_DIV_15) || ((__VALUE__) == LL_RCC_PREDIV_DIV_16))
+
+#define IS_LL_UTILS_PLL_FREQUENCY(__VALUE__) ((UTILS_PLL_OUTPUT_MIN <= (__VALUE__)) && ((__VALUE__) <= UTILS_PLL_OUTPUT_MAX))
+
+
+#define IS_LL_UTILS_HSE_BYPASS(__STATE__) (((__STATE__) == LL_UTILS_HSEBYPASS_ON) \
+ || ((__STATE__) == LL_UTILS_HSEBYPASS_OFF))
+
+#define IS_LL_UTILS_HSE_FREQUENCY(__FREQUENCY__) (((__FREQUENCY__) >= UTILS_HSE_FREQUENCY_MIN) && ((__FREQUENCY__) <= UTILS_HSE_FREQUENCY_MAX))
+/**
+ * @}
+ */
+/* Private function prototypes -----------------------------------------------*/
+/** @defgroup UTILS_LL_Private_Functions UTILS Private functions
+ * @{
+ */
+static uint32_t UTILS_GetPLLOutputFrequency(uint32_t PLL_InputFrequency,
+ LL_UTILS_PLLInitTypeDef *UTILS_PLLInitStruct);
+static ErrorStatus UTILS_EnablePLLAndSwitchSystem(uint32_t SYSCLK_Frequency, LL_UTILS_ClkInitTypeDef *UTILS_ClkInitStruct);
+static ErrorStatus UTILS_PLL_IsBusy(void);
+/**
+ * @}
+ */
+
+/* Exported functions --------------------------------------------------------*/
+/** @addtogroup UTILS_LL_Exported_Functions
+ * @{
+ */
+
+/** @addtogroup UTILS_LL_EF_DELAY
+ * @{
+ */
+
+/**
+ * @brief This function configures the Cortex-M SysTick source to have 1ms time base.
+ * @note When a RTOS is used, it is recommended to avoid changing the Systick
+ * configuration by calling this function, for a delay use rather osDelay RTOS service.
+ * @param HCLKFrequency HCLK frequency in Hz
+ * @note HCLK frequency can be calculated thanks to RCC helper macro or function @ref LL_RCC_GetSystemClocksFreq
+ * @retval None
+ */
+void LL_Init1msTick(uint32_t HCLKFrequency)
+{
+ /* Use frequency provided in argument */
+ LL_InitTick(HCLKFrequency, 1000U);
+}
+
+/**
+ * @brief This function provides accurate delay (in milliseconds) based
+ * on SysTick counter flag
+ * @note When a RTOS is used, it is recommended to avoid using blocking delay
+ * and use rather osDelay service.
+ * @note To respect 1ms timebase, user should call @ref LL_Init1msTick function which
+ * will configure Systick to 1ms
+ * @param Delay specifies the delay time length, in milliseconds.
+ * @retval None
+ */
+void LL_mDelay(uint32_t Delay)
+{
+ __IO uint32_t tmp = SysTick->CTRL; /* Clear the COUNTFLAG first */
+ /* Add this code to indicate that local variable is not used */
+ ((void)tmp);
+
+ /* Add a period to guaranty minimum wait */
+ if (Delay < LL_MAX_DELAY)
+ {
+ Delay++;
+ }
+
+ while (Delay)
+ {
+ if ((SysTick->CTRL & SysTick_CTRL_COUNTFLAG_Msk) != 0U)
+ {
+ Delay--;
+ }
+ }
+}
+
+/**
+ * @}
+ */
+
+/** @addtogroup UTILS_EF_SYSTEM
+ * @brief System Configuration functions
+ *
+ @verbatim
+ ===============================================================================
+ ##### System Configuration functions #####
+ ===============================================================================
+ [..]
+ System, AHB and APB buses clocks configuration
+
+ (+) The maximum frequency of the SYSCLK, HCLK, PCLK1 and PCLK2 is 48000000 Hz.
+ @endverbatim
+ @internal
+ Depending on the SYSCLK frequency, the flash latency should be adapted accordingly:
+ (++) +-----------------------------------------------+
+ (++) | Latency | SYSCLK clock frequency (MHz) |
+ (++) |---------------|-------------------------------|
+ (++) |0WS(1CPU cycle)| 0 < SYSCLK <= 24 |
+ (++) |---------------|-------------------------------|
+ (++) |1WS(2CPU cycle)| 24 < SYSCLK <= 48 |
+ (++) +-----------------------------------------------+
+ @endinternal
+ * @{
+ */
+
+/**
+ * @brief This function sets directly SystemCoreClock CMSIS variable.
+ * @note Variable can be calculated also through SystemCoreClockUpdate function.
+ * @param HCLKFrequency HCLK frequency in Hz (can be calculated thanks to RCC helper macro)
+ * @retval None
+ */
+void LL_SetSystemCoreClock(uint32_t HCLKFrequency)
+{
+ /* HCLK clock frequency */
+ SystemCoreClock = HCLKFrequency;
+}
+
+/**
+ * @brief Update number of Flash wait states in line with new frequency and current
+ voltage range.
+ * @param Frequency SYSCLK frequency
+ * @retval An ErrorStatus enumeration value:
+ * - SUCCESS: Latency has been modified
+ * - ERROR: Latency cannot be modified
+ */
+#if defined(FLASH_ACR_LATENCY)
+ErrorStatus LL_SetFlashLatency(uint32_t Frequency)
+{
+ uint32_t timeout;
+ uint32_t getlatency;
+ uint32_t latency;
+ ErrorStatus status = SUCCESS;
+
+ /* Frequency cannot be equal to 0 */
+ if (Frequency == 0U)
+ {
+ status = ERROR;
+ }
+ else
+ {
+ if (Frequency > UTILS_LATENCY1_FREQ)
+ {
+ /* 24 < SYSCLK <= 48 => 1WS (2 CPU cycles) */
+ latency = LL_FLASH_LATENCY_1;
+ }
+ else
+ {
+ /* else SYSCLK < 24MHz default LL_FLASH_LATENCY_0 0WS */
+ latency = LL_FLASH_LATENCY_0;
+ }
+ if (status != ERROR)
+ {
+ LL_FLASH_SetLatency(latency);
+
+ /* Check that the new number of wait states is taken into account to access the Flash
+ memory by reading the FLASH_ACR register */
+ timeout = 2;
+ do
+ {
+ /* Wait for Flash latency to be updated */
+ getlatency = LL_FLASH_GetLatency();
+ timeout--;
+ } while ((getlatency != latency) && (timeout > 0));
+
+ if(getlatency != latency)
+ {
+ status = ERROR;
+ }
+ else
+ {
+ status = SUCCESS;
+ }
+ }
+ }
+
+ return status;
+}
+#endif /* FLASH_ACR_LATENCY */
+
+/**
+ * @brief This function configures system clock with HSI as clock source of the PLL
+ * @note The application need to ensure that PLL is disabled.
+ * @note Function is based on the following formula:
+ * - PLL output frequency = ((HSI frequency / PREDIV) * PLLMUL)
+ * - PREDIV: Set to 2 for few devices
+ * - PLLMUL: The application software must set correctly the PLL multiplication factor to
+ * be in the range 16-48MHz
+ * @note FLASH latency can be modified through this function.
+ * @param UTILS_PLLInitStruct pointer to a @ref LL_UTILS_PLLInitTypeDef structure that contains
+ * the configuration information for the PLL.
+ * @param UTILS_ClkInitStruct pointer to a @ref LL_UTILS_ClkInitTypeDef structure that contains
+ * the configuration information for the BUS prescalers.
+ * @retval An ErrorStatus enumeration value:
+ * - SUCCESS: Max frequency configuration done
+ * - ERROR: Max frequency configuration not done
+ */
+ErrorStatus LL_PLL_ConfigSystemClock_HSI(LL_UTILS_PLLInitTypeDef *UTILS_PLLInitStruct,
+ LL_UTILS_ClkInitTypeDef *UTILS_ClkInitStruct)
+{
+ ErrorStatus status = SUCCESS;
+ uint32_t pllfreq = 0U;
+
+ /* Check if one of the PLL is enabled */
+ if (UTILS_PLL_IsBusy() == SUCCESS)
+ {
+#if defined(RCC_PLLSRC_PREDIV1_SUPPORT)
+ /* Check PREDIV value */
+ assert_param(IS_LL_UTILS_PREDIV_VALUE(UTILS_PLLInitStruct->PLLDiv));
+#else
+ /* Force PREDIV value to 2 */
+ UTILS_PLLInitStruct->Prediv = LL_RCC_PREDIV_DIV_2;
+#endif /*RCC_PLLSRC_PREDIV1_SUPPORT*/
+ /* Calculate the new PLL output frequency */
+ pllfreq = UTILS_GetPLLOutputFrequency(HSI_VALUE, UTILS_PLLInitStruct);
+
+ /* Enable HSI if not enabled */
+ if (LL_RCC_HSI_IsReady() != 1U)
+ {
+ LL_RCC_HSI_Enable();
+ while (LL_RCC_HSI_IsReady() != 1U)
+ {
+ /* Wait for HSI ready */
+ }
+ }
+
+ /* Configure PLL */
+#if defined(RCC_PLLSRC_PREDIV1_SUPPORT)
+ LL_RCC_PLL_ConfigDomain_SYS(LL_RCC_PLLSOURCE_HSI, UTILS_PLLInitStruct->PLLMul, UTILS_PLLInitStruct->PLLDiv);
+#else
+ LL_RCC_PLL_ConfigDomain_SYS(LL_RCC_PLLSOURCE_HSI_DIV_2, UTILS_PLLInitStruct->PLLMul);
+#endif /*RCC_PLLSRC_PREDIV1_SUPPORT*/
+
+ /* Enable PLL and switch system clock to PLL */
+ status = UTILS_EnablePLLAndSwitchSystem(pllfreq, UTILS_ClkInitStruct);
+ }
+ else
+ {
+ /* Current PLL configuration cannot be modified */
+ status = ERROR;
+ }
+
+ return status;
+}
+
+#if defined(RCC_CFGR_SW_HSI48)
+/**
+ * @brief This function configures system clock with HSI48 as clock source of the PLL
+ * @note The application need to ensure that PLL is disabled.
+ * @note Function is based on the following formula:
+ * - PLL output frequency = ((HSI48 frequency / PREDIV) * PLLMUL)
+ * - PLLMUL: The application software must set correctly the PLL multiplication factor to
+ * be in the range 16-48MHz
+ * @param UTILS_PLLInitStruct pointer to a @ref LL_UTILS_PLLInitTypeDef structure that contains
+ * the configuration information for the PLL.
+ * @param UTILS_ClkInitStruct pointer to a @ref LL_UTILS_ClkInitTypeDef structure that contains
+ * the configuration information for the BUS prescalers.
+ * @retval An ErrorStatus enumeration value:
+ * - SUCCESS: Max frequency configuration done
+ * - ERROR: Max frequency configuration not done
+ */
+ErrorStatus LL_PLL_ConfigSystemClock_HSI48(LL_UTILS_PLLInitTypeDef *UTILS_PLLInitStruct,
+ LL_UTILS_ClkInitTypeDef *UTILS_ClkInitStruct)
+{
+ ErrorStatus status = SUCCESS;
+ uint32_t pllfreq = 0U;
+
+ /* Check if one of the PLL is enabled */
+ if (UTILS_PLL_IsBusy() == SUCCESS)
+ {
+ /* Check PREDIV value */
+ assert_param(IS_LL_UTILS_PREDIV_VALUE(UTILS_PLLInitStruct->PLLDiv));
+
+ /* Calculate the new PLL output frequency */
+ pllfreq = UTILS_GetPLLOutputFrequency(HSI48_VALUE, UTILS_PLLInitStruct);
+
+ /* Enable HSI48 if not enabled */
+ if (LL_RCC_HSI48_IsReady() != 1U)
+ {
+ LL_RCC_HSI48_Enable();
+ while (LL_RCC_HSI48_IsReady() != 1U)
+ {
+ /* Wait for HSI48 ready */
+ }
+ }
+
+ /* Configure PLL */
+ LL_RCC_PLL_ConfigDomain_SYS(LL_RCC_PLLSOURCE_HSI48, UTILS_PLLInitStruct->PLLMul, UTILS_PLLInitStruct->PLLDiv);
+
+ /* Enable PLL and switch system clock to PLL */
+ status = UTILS_EnablePLLAndSwitchSystem(pllfreq, UTILS_ClkInitStruct);
+ }
+ else
+ {
+ /* Current PLL configuration cannot be modified */
+ status = ERROR;
+ }
+
+ return status;
+}
+
+#endif /*RCC_CFGR_SW_HSI48*/
+/**
+ * @brief This function configures system clock with HSE as clock source of the PLL
+ * @note The application need to ensure that PLL is disabled.
+ * @note Function is based on the following formula:
+ * - PLL output frequency = ((HSE frequency / PREDIV) * PLLMUL)
+ * - PLLMUL: The application software must set correctly the PLL multiplication factor to
+ * be in the range 16-48MHz
+ * @note FLASH latency can be modified through this function.
+ * @param HSEFrequency Value between Min_Data = 4000000 and Max_Data = 32000000
+ * @param HSEBypass This parameter can be one of the following values:
+ * @arg @ref LL_UTILS_HSEBYPASS_ON
+ * @arg @ref LL_UTILS_HSEBYPASS_OFF
+ * @param UTILS_PLLInitStruct pointer to a @ref LL_UTILS_PLLInitTypeDef structure that contains
+ * the configuration information for the PLL.
+ * @param UTILS_ClkInitStruct pointer to a @ref LL_UTILS_ClkInitTypeDef structure that contains
+ * the configuration information for the BUS prescalers.
+ * @retval An ErrorStatus enumeration value:
+ * - SUCCESS: Max frequency configuration done
+ * - ERROR: Max frequency configuration not done
+ */
+ErrorStatus LL_PLL_ConfigSystemClock_HSE(uint32_t HSEFrequency, uint32_t HSEBypass,
+ LL_UTILS_PLLInitTypeDef *UTILS_PLLInitStruct, LL_UTILS_ClkInitTypeDef *UTILS_ClkInitStruct)
+{
+ ErrorStatus status = SUCCESS;
+ uint32_t pllfreq = 0U;
+
+ /* Check the parameters */
+ assert_param(IS_LL_UTILS_HSE_FREQUENCY(HSEFrequency));
+ assert_param(IS_LL_UTILS_HSE_BYPASS(HSEBypass));
+
+ /* Check if one of the PLL is enabled */
+ if (UTILS_PLL_IsBusy() == SUCCESS)
+ {
+ /* Check PREDIV value */
+#if defined(RCC_PLLSRC_PREDIV1_SUPPORT)
+ assert_param(IS_LL_UTILS_PREDIV_VALUE(UTILS_PLLInitStruct->PLLDiv));
+#else
+ assert_param(IS_LL_UTILS_PREDIV_VALUE(UTILS_PLLInitStruct->Prediv));
+#endif /*RCC_PLLSRC_PREDIV1_SUPPORT*/
+
+ /* Calculate the new PLL output frequency */
+ pllfreq = UTILS_GetPLLOutputFrequency(HSEFrequency, UTILS_PLLInitStruct);
+
+ /* Enable HSE if not enabled */
+ if (LL_RCC_HSE_IsReady() != 1U)
+ {
+ /* Check if need to enable HSE bypass feature or not */
+ if (HSEBypass == LL_UTILS_HSEBYPASS_ON)
+ {
+ LL_RCC_HSE_EnableBypass();
+ }
+ else
+ {
+ LL_RCC_HSE_DisableBypass();
+ }
+
+ /* Enable HSE */
+ LL_RCC_HSE_Enable();
+ while (LL_RCC_HSE_IsReady() != 1U)
+ {
+ /* Wait for HSE ready */
+ }
+ }
+
+ /* Configure PLL */
+#if defined(RCC_PLLSRC_PREDIV1_SUPPORT)
+ LL_RCC_PLL_ConfigDomain_SYS(LL_RCC_PLLSOURCE_HSE, UTILS_PLLInitStruct->PLLMul, UTILS_PLLInitStruct->PLLDiv);
+#else
+ LL_RCC_PLL_ConfigDomain_SYS((RCC_CFGR_PLLSRC_HSE_PREDIV | UTILS_PLLInitStruct->Prediv), UTILS_PLLInitStruct->PLLMul);
+#endif /*RCC_PLLSRC_PREDIV1_SUPPORT*/
+
+ /* Enable PLL and switch system clock to PLL */
+ status = UTILS_EnablePLLAndSwitchSystem(pllfreq, UTILS_ClkInitStruct);
+ }
+ else
+ {
+ /* Current PLL configuration cannot be modified */
+ status = ERROR;
+ }
+
+ return status;
+}
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/** @addtogroup UTILS_LL_Private_Functions
+ * @{
+ */
+/**
+ * @brief Function to check that PLL can be modified
+ * @param PLL_InputFrequency PLL input frequency (in Hz)
+ * @param UTILS_PLLInitStruct pointer to a @ref LL_UTILS_PLLInitTypeDef structure that contains
+ * the configuration information for the PLL.
+ * @retval PLL output frequency (in Hz)
+ */
+static uint32_t UTILS_GetPLLOutputFrequency(uint32_t PLL_InputFrequency, LL_UTILS_PLLInitTypeDef *UTILS_PLLInitStruct)
+{
+ uint32_t pllfreq = 0U;
+
+ /* Check the parameters */
+ assert_param(IS_LL_UTILS_PLLMUL_VALUE(UTILS_PLLInitStruct->PLLMul));
+
+ /* Check different PLL parameters according to RM */
+ /* The application software must set correctly the PLL multiplication factor to
+ be in the range 16-48MHz */
+#if defined(RCC_PLLSRC_PREDIV1_SUPPORT)
+ pllfreq = __LL_RCC_CALC_PLLCLK_FREQ(PLL_InputFrequency, UTILS_PLLInitStruct->PLLMul, UTILS_PLLInitStruct->PLLDiv);
+#else
+ pllfreq = __LL_RCC_CALC_PLLCLK_FREQ(PLL_InputFrequency / (UTILS_PLLInitStruct->Prediv + 1U), UTILS_PLLInitStruct->PLLMul);
+#endif /*RCC_PLLSRC_PREDIV1_SUPPORT*/
+ assert_param(IS_LL_UTILS_PLL_FREQUENCY(pllfreq));
+
+ return pllfreq;
+}
+
+/**
+ * @brief Function to check that PLL can be modified
+ * @retval An ErrorStatus enumeration value:
+ * - SUCCESS: PLL modification can be done
+ * - ERROR: PLL is busy
+ */
+static ErrorStatus UTILS_PLL_IsBusy(void)
+{
+ ErrorStatus status = SUCCESS;
+
+ /* Check if PLL is busy*/
+ if (LL_RCC_PLL_IsReady() != 0U)
+ {
+ /* PLL configuration cannot be modified */
+ status = ERROR;
+ }
+
+ return status;
+}
+
+/**
+ * @brief Function to enable PLL and switch system clock to PLL
+ * @param SYSCLK_Frequency SYSCLK frequency
+ * @param UTILS_ClkInitStruct pointer to a @ref LL_UTILS_ClkInitTypeDef structure that contains
+ * the configuration information for the BUS prescalers.
+ * @retval An ErrorStatus enumeration value:
+ * - SUCCESS: No problem to switch system to PLL
+ * - ERROR: Problem to switch system to PLL
+ */
+static ErrorStatus UTILS_EnablePLLAndSwitchSystem(uint32_t SYSCLK_Frequency, LL_UTILS_ClkInitTypeDef *UTILS_ClkInitStruct)
+{
+ ErrorStatus status = SUCCESS;
+ uint32_t sysclk_frequency_current = 0U;
+
+ assert_param(IS_LL_UTILS_SYSCLK_DIV(UTILS_ClkInitStruct->AHBCLKDivider));
+ assert_param(IS_LL_UTILS_APB1_DIV(UTILS_ClkInitStruct->APB1CLKDivider));
+
+ /* Calculate current SYSCLK frequency */
+ sysclk_frequency_current = (SystemCoreClock << AHBPrescTable[LL_RCC_GetAHBPrescaler() >> RCC_POSITION_HPRE]);
+
+ /* Increasing the number of wait states because of higher CPU frequency */
+ if (sysclk_frequency_current < SYSCLK_Frequency)
+ {
+ /* Set FLASH latency to highest latency */
+ status = LL_SetFlashLatency(SYSCLK_Frequency);
+ }
+
+ /* Update system clock configuration */
+ if (status == SUCCESS)
+ {
+ /* Enable PLL */
+ LL_RCC_PLL_Enable();
+ while (LL_RCC_PLL_IsReady() != 1U)
+ {
+ /* Wait for PLL ready */
+ }
+
+ /* Sysclk activation on the main PLL */
+ LL_RCC_SetAHBPrescaler(UTILS_ClkInitStruct->AHBCLKDivider);
+ LL_RCC_SetSysClkSource(LL_RCC_SYS_CLKSOURCE_PLL);
+ while (LL_RCC_GetSysClkSource() != LL_RCC_SYS_CLKSOURCE_STATUS_PLL)
+ {
+ /* Wait for system clock switch to PLL */
+ }
+
+ /* Set APB1 & APB2 prescaler*/
+ LL_RCC_SetAPB1Prescaler(UTILS_ClkInitStruct->APB1CLKDivider);
+ }
+
+ /* Decreasing the number of wait states because of lower CPU frequency */
+ if (sysclk_frequency_current > SYSCLK_Frequency)
+ {
+ /* Set FLASH latency to lowest latency */
+ status = LL_SetFlashLatency(SYSCLK_Frequency);
+ }
+
+ /* Update SystemCoreClock variable */
+ if (status == SUCCESS)
+ {
+ LL_SetSystemCoreClock(__LL_RCC_CALC_HCLK_FREQ(SYSCLK_Frequency, UTILS_ClkInitStruct->AHBCLKDivider));
+ }
+
+ return status;
+}
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/peripherals/cc48x6/firmware/Inc/crc.h b/peripherals/cc48x6/firmware/Inc/crc.h
new file mode 100644
index 0000000..120d9a5
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Inc/crc.h
@@ -0,0 +1,52 @@
+/* USER CODE BEGIN Header */
+/**
+ ******************************************************************************
+ * @file crc.h
+ * @brief This file contains all the function prototypes for
+ * the crc.c file
+ ******************************************************************************
+ * @attention
+ *
+ * Copyright (c) 2022 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software is licensed under terms that can be found in the LICENSE file
+ * in the root directory of this software component.
+ * If no LICENSE file comes with this software, it is provided AS-IS.
+ *
+ ******************************************************************************
+ */
+/* USER CODE END Header */
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __CRC_H__
+#define __CRC_H__
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "main.h"
+
+/* USER CODE BEGIN Includes */
+
+/* USER CODE END Includes */
+
+extern CRC_HandleTypeDef hcrc;
+
+/* USER CODE BEGIN Private defines */
+
+/* USER CODE END Private defines */
+
+void MX_CRC_Init(void);
+
+/* USER CODE BEGIN Prototypes */
+
+/* USER CODE END Prototypes */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __CRC_H__ */
+
diff --git a/peripherals/cc48x6/firmware/Inc/dma.h b/peripherals/cc48x6/firmware/Inc/dma.h
new file mode 100644
index 0000000..d343621
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Inc/dma.h
@@ -0,0 +1,52 @@
+/* USER CODE BEGIN Header */
+/**
+ ******************************************************************************
+ * @file dma.h
+ * @brief This file contains all the function prototypes for
+ * the dma.c file
+ ******************************************************************************
+ * @attention
+ *
+ * Copyright (c) 2022 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software is licensed under terms that can be found in the LICENSE file
+ * in the root directory of this software component.
+ * If no LICENSE file comes with this software, it is provided AS-IS.
+ *
+ ******************************************************************************
+ */
+/* USER CODE END Header */
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __DMA_H__
+#define __DMA_H__
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "main.h"
+
+/* DMA memory to memory transfer handles -------------------------------------*/
+
+/* USER CODE BEGIN Includes */
+
+/* USER CODE END Includes */
+
+/* USER CODE BEGIN Private defines */
+
+/* USER CODE END Private defines */
+
+void MX_DMA_Init(void);
+
+/* USER CODE BEGIN Prototypes */
+
+/* USER CODE END Prototypes */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __DMA_H__ */
+
diff --git a/peripherals/cc48x6/firmware/Inc/gpio.h b/peripherals/cc48x6/firmware/Inc/gpio.h
new file mode 100644
index 0000000..45e27b1
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Inc/gpio.h
@@ -0,0 +1,49 @@
+/* USER CODE BEGIN Header */
+/**
+ ******************************************************************************
+ * @file gpio.h
+ * @brief This file contains all the function prototypes for
+ * the gpio.c file
+ ******************************************************************************
+ * @attention
+ *
+ * Copyright (c) 2022 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software is licensed under terms that can be found in the LICENSE file
+ * in the root directory of this software component.
+ * If no LICENSE file comes with this software, it is provided AS-IS.
+ *
+ ******************************************************************************
+ */
+/* USER CODE END Header */
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __GPIO_H__
+#define __GPIO_H__
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "main.h"
+
+/* USER CODE BEGIN Includes */
+
+/* USER CODE END Includes */
+
+/* USER CODE BEGIN Private defines */
+
+/* USER CODE END Private defines */
+
+void MX_GPIO_Init(void);
+
+/* USER CODE BEGIN Prototypes */
+
+/* USER CODE END Prototypes */
+
+#ifdef __cplusplus
+}
+#endif
+#endif /*__ GPIO_H__ */
+
diff --git a/peripherals/cc48x6/firmware/Inc/main.h b/peripherals/cc48x6/firmware/Inc/main.h
new file mode 100644
index 0000000..9dc4ec5
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Inc/main.h
@@ -0,0 +1,77 @@
+/* USER CODE BEGIN Header */
+/**
+ ******************************************************************************
+ * @file : main.h
+ * @brief : Header for main.c file.
+ * This file contains the common defines of the application.
+ ******************************************************************************
+ * @attention
+ *
+ * Copyright (c) 2022 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software is licensed under terms that can be found in the LICENSE file
+ * in the root directory of this software component.
+ * If no LICENSE file comes with this software, it is provided AS-IS.
+ *
+ ******************************************************************************
+ */
+/* USER CODE END Header */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __MAIN_H
+#define __MAIN_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f0xx_hal.h"
+
+/* Private includes ----------------------------------------------------------*/
+/* USER CODE BEGIN Includes */
+
+/* USER CODE END Includes */
+
+/* Exported types ------------------------------------------------------------*/
+/* USER CODE BEGIN ET */
+
+/* USER CODE END ET */
+
+/* Exported constants --------------------------------------------------------*/
+/* USER CODE BEGIN EC */
+
+/* USER CODE END EC */
+
+/* Exported macro ------------------------------------------------------------*/
+/* USER CODE BEGIN EM */
+
+/* USER CODE END EM */
+
+/* Exported functions prototypes ---------------------------------------------*/
+void Error_Handler(void);
+
+/* USER CODE BEGIN EFP */
+
+/* USER CODE END EFP */
+
+/* Private defines -----------------------------------------------------------*/
+#define INIT_IN_Pin GPIO_PIN_13
+#define INIT_IN_GPIO_Port GPIOC
+#define INIT_OUT_Pin GPIO_PIN_14
+#define INIT_OUT_GPIO_Port GPIOC
+#define SPI_INT_Pin GPIO_PIN_15
+#define SPI_INT_GPIO_Port GPIOC
+#define SPI_INT_EXTI_IRQn EXTI4_15_IRQn
+#define SIGNAL_LED_Pin GPIO_PIN_3
+#define SIGNAL_LED_GPIO_Port GPIOA
+/* USER CODE BEGIN Private defines */
+
+/* USER CODE END Private defines */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __MAIN_H */
diff --git a/peripherals/cc48x6/firmware/Inc/spi.h b/peripherals/cc48x6/firmware/Inc/spi.h
new file mode 100644
index 0000000..523d5b0
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Inc/spi.h
@@ -0,0 +1,54 @@
+/* USER CODE BEGIN Header */
+/**
+ ******************************************************************************
+ * @file spi.h
+ * @brief This file contains all the function prototypes for
+ * the spi.c file
+ ******************************************************************************
+ * @attention
+ *
+ * Copyright (c) 2022 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software is licensed under terms that can be found in the LICENSE file
+ * in the root directory of this software component.
+ * If no LICENSE file comes with this software, it is provided AS-IS.
+ *
+ ******************************************************************************
+ */
+/* USER CODE END Header */
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __SPI_H__
+#define __SPI_H__
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "main.h"
+
+/* USER CODE BEGIN Includes */
+
+/* USER CODE END Includes */
+
+extern SPI_HandleTypeDef hspi1;
+extern SPI_HandleTypeDef hspi2;
+
+/* USER CODE BEGIN Private defines */
+
+/* USER CODE END Private defines */
+
+void MX_SPI1_Init(void);
+void MX_SPI2_Init(void);
+
+/* USER CODE BEGIN Prototypes */
+
+/* USER CODE END Prototypes */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __SPI_H__ */
+
diff --git a/peripherals/cc48x6/firmware/Inc/stm32f0xx_hal_conf.h b/peripherals/cc48x6/firmware/Inc/stm32f0xx_hal_conf.h
new file mode 100644
index 0000000..f3620ac
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Inc/stm32f0xx_hal_conf.h
@@ -0,0 +1,322 @@
+/* USER CODE BEGIN Header */
+/**
+ ******************************************************************************
+ * @file stm32f0xx_hal_conf.h
+ * @brief HAL configuration file.
+ ******************************************************************************
+ * @attention
+ *
+ * Copyright (c) 2016 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software is licensed under terms that can be found in the LICENSE file
+ * in the root directory of this software component.
+ * If no LICENSE file comes with this software, it is provided AS-IS.
+ *
+ ******************************************************************************
+ */
+/* USER CODE END Header */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F0xx_HAL_CONF_H
+#define __STM32F0xx_HAL_CONF_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+
+/* ########################## Module Selection ############################## */
+/**
+ * @brief This is the list of modules to be used in the HAL driver
+ */
+#define HAL_MODULE_ENABLED
+ /*#define HAL_ADC_MODULE_ENABLED */
+/*#define HAL_CRYP_MODULE_ENABLED */
+/*#define HAL_CAN_MODULE_ENABLED */
+/*#define HAL_CEC_MODULE_ENABLED */
+/*#define HAL_COMP_MODULE_ENABLED */
+#define HAL_CRC_MODULE_ENABLED
+/*#define HAL_CRYP_MODULE_ENABLED */
+/*#define HAL_TSC_MODULE_ENABLED */
+/*#define HAL_DAC_MODULE_ENABLED */
+/*#define HAL_I2S_MODULE_ENABLED */
+/*#define HAL_IWDG_MODULE_ENABLED */
+/*#define HAL_LCD_MODULE_ENABLED */
+/*#define HAL_LPTIM_MODULE_ENABLED */
+/*#define HAL_RNG_MODULE_ENABLED */
+/*#define HAL_RTC_MODULE_ENABLED */
+#define HAL_SPI_MODULE_ENABLED
+#define HAL_TIM_MODULE_ENABLED
+/*#define HAL_UART_MODULE_ENABLED */
+/*#define HAL_USART_MODULE_ENABLED */
+/*#define HAL_IRDA_MODULE_ENABLED */
+/*#define HAL_SMARTCARD_MODULE_ENABLED */
+/*#define HAL_SMBUS_MODULE_ENABLED */
+/*#define HAL_WWDG_MODULE_ENABLED */
+/*#define HAL_PCD_MODULE_ENABLED */
+#define HAL_CORTEX_MODULE_ENABLED
+#define HAL_DMA_MODULE_ENABLED
+#define HAL_FLASH_MODULE_ENABLED
+#define HAL_GPIO_MODULE_ENABLED
+#define HAL_EXTI_MODULE_ENABLED
+#define HAL_PWR_MODULE_ENABLED
+#define HAL_RCC_MODULE_ENABLED
+#define HAL_I2C_MODULE_ENABLED
+
+/* ########################## HSE/HSI Values adaptation ##################### */
+/**
+ * @brief Adjust the value of External High Speed oscillator (HSE) used in your application.
+ * This value is used by the RCC HAL module to compute the system frequency
+ * (when HSE is used as system clock source, directly or through the PLL).
+ */
+#if !defined (HSE_VALUE)
+ #define HSE_VALUE ((uint32_t)8000000) /*!< Value of the External oscillator in Hz */
+#endif /* HSE_VALUE */
+
+/**
+ * @brief In the following line adjust the External High Speed oscillator (HSE) Startup
+ * Timeout value
+ */
+#if !defined (HSE_STARTUP_TIMEOUT)
+ #define HSE_STARTUP_TIMEOUT ((uint32_t)100) /*!< Time out for HSE start up, in ms */
+#endif /* HSE_STARTUP_TIMEOUT */
+
+/**
+ * @brief Internal High Speed oscillator (HSI) value.
+ * This value is used by the RCC HAL module to compute the system frequency
+ * (when HSI is used as system clock source, directly or through the PLL).
+ */
+#if !defined (HSI_VALUE)
+ #define HSI_VALUE ((uint32_t)8000000) /*!< Value of the Internal oscillator in Hz*/
+#endif /* HSI_VALUE */
+
+/**
+ * @brief In the following line adjust the Internal High Speed oscillator (HSI) Startup
+ * Timeout value
+ */
+#if !defined (HSI_STARTUP_TIMEOUT)
+ #define HSI_STARTUP_TIMEOUT ((uint32_t)5000) /*!< Time out for HSI start up */
+#endif /* HSI_STARTUP_TIMEOUT */
+
+/**
+ * @brief Internal High Speed oscillator for ADC (HSI14) value.
+ */
+#if !defined (HSI14_VALUE)
+#define HSI14_VALUE ((uint32_t)14000000) /*!< Value of the Internal High Speed oscillator for ADC in Hz.
+ The real value may vary depending on the variations
+ in voltage and temperature. */
+#endif /* HSI14_VALUE */
+
+/**
+ * @brief Internal High Speed oscillator for USB (HSI48) value.
+ */
+#if !defined (HSI48_VALUE)
+ #define HSI48_VALUE ((uint32_t)48000000) /*!< Value of the Internal High Speed oscillator for USB in Hz.
+ The real value may vary depending on the variations
+ in voltage and temperature. */
+#endif /* HSI48_VALUE */
+
+/**
+ * @brief Internal Low Speed oscillator (LSI) value.
+ */
+#if !defined (LSI_VALUE)
+ #define LSI_VALUE ((uint32_t)40000)
+#endif /* LSI_VALUE */ /*!< Value of the Internal Low Speed oscillator in Hz
+ The real value may vary depending on the variations
+ in voltage and temperature. */
+/**
+ * @brief External Low Speed oscillator (LSI) value.
+ */
+#if !defined (LSE_VALUE)
+ #define LSE_VALUE ((uint32_t)32768) /*!< Value of the External Low Speed oscillator in Hz */
+#endif /* LSE_VALUE */
+
+/**
+ * @brief Time out for LSE start up value in ms.
+ */
+#if !defined (LSE_STARTUP_TIMEOUT)
+ #define LSE_STARTUP_TIMEOUT ((uint32_t)5000) /*!< Time out for LSE start up, in ms */
+#endif /* LSE_STARTUP_TIMEOUT */
+
+/* Tip: To avoid modifying this file each time you need to use different HSE,
+ === you can define the HSE value in your toolchain compiler preprocessor. */
+
+/* ########################### System Configuration ######################### */
+/**
+ * @brief This is the HAL system configuration section
+ */
+#define VDD_VALUE ((uint32_t)3300) /*!< Value of VDD in mv */
+#define TICK_INT_PRIORITY ((uint32_t)3) /*!< tick interrupt priority (lowest by default) */
+ /* Warning: Must be set to higher priority for HAL_Delay() */
+ /* and HAL_GetTick() usage under interrupt context */
+#define USE_RTOS 0
+#define PREFETCH_ENABLE 1
+#define INSTRUCTION_CACHE_ENABLE 0
+#define DATA_CACHE_ENABLE 0
+#define USE_SPI_CRC 0U
+
+#define USE_HAL_ADC_REGISTER_CALLBACKS 0U /* ADC register callback disabled */
+#define USE_HAL_CAN_REGISTER_CALLBACKS 0U /* CAN register callback disabled */
+#define USE_HAL_COMP_REGISTER_CALLBACKS 0U /* COMP register callback disabled */
+#define USE_HAL_CEC_REGISTER_CALLBACKS 0U /* CEC register callback disabled */
+#define USE_HAL_DAC_REGISTER_CALLBACKS 0U /* DAC register callback disabled */
+#define USE_HAL_I2C_REGISTER_CALLBACKS 0U /* I2C register callback disabled */
+#define USE_HAL_SMBUS_REGISTER_CALLBACKS 0U /* SMBUS register callback disabled */
+#define USE_HAL_UART_REGISTER_CALLBACKS 0U /* UART register callback disabled */
+#define USE_HAL_USART_REGISTER_CALLBACKS 0U /* USART register callback disabled */
+#define USE_HAL_IRDA_REGISTER_CALLBACKS 0U /* IRDA register callback disabled */
+#define USE_HAL_SMARTCARD_REGISTER_CALLBACKS 0U /* SMARTCARD register callback disabled */
+#define USE_HAL_WWDG_REGISTER_CALLBACKS 0U /* WWDG register callback disabled */
+#define USE_HAL_RTC_REGISTER_CALLBACKS 0U /* RTC register callback disabled */
+#define USE_HAL_SPI_REGISTER_CALLBACKS 0U /* SPI register callback disabled */
+#define USE_HAL_I2S_REGISTER_CALLBACKS 0U /* I2S register callback disabled */
+#define USE_HAL_TIM_REGISTER_CALLBACKS 0U /* TIM register callback disabled */
+#define USE_HAL_TSC_REGISTER_CALLBACKS 0U /* TSC register callback disabled */
+#define USE_HAL_PCD_REGISTER_CALLBACKS 0U /* PCD register callback disabled */
+
+/* ########################## Assert Selection ############################## */
+/**
+ * @brief Uncomment the line below to expanse the "assert_param" macro in the
+ * HAL drivers code
+ */
+/* #define USE_FULL_ASSERT 1U */
+
+/* Includes ------------------------------------------------------------------*/
+/**
+ * @brief Include module's header file
+ */
+
+#ifdef HAL_RCC_MODULE_ENABLED
+ #include "stm32f0xx_hal_rcc.h"
+#endif /* HAL_RCC_MODULE_ENABLED */
+
+#ifdef HAL_GPIO_MODULE_ENABLED
+ #include "stm32f0xx_hal_gpio.h"
+#endif /* HAL_GPIO_MODULE_ENABLED */
+
+#ifdef HAL_EXTI_MODULE_ENABLED
+ #include "stm32f0xx_hal_exti.h"
+#endif /* HAL_EXTI_MODULE_ENABLED */
+
+#ifdef HAL_DMA_MODULE_ENABLED
+ #include "stm32f0xx_hal_dma.h"
+#endif /* HAL_DMA_MODULE_ENABLED */
+
+#ifdef HAL_CORTEX_MODULE_ENABLED
+ #include "stm32f0xx_hal_cortex.h"
+#endif /* HAL_CORTEX_MODULE_ENABLED */
+
+#ifdef HAL_ADC_MODULE_ENABLED
+ #include "stm32f0xx_hal_adc.h"
+#endif /* HAL_ADC_MODULE_ENABLED */
+
+#ifdef HAL_CAN_MODULE_ENABLED
+ #include "stm32f0xx_hal_can.h"
+#endif /* HAL_CAN_MODULE_ENABLED */
+
+#ifdef HAL_CEC_MODULE_ENABLED
+ #include "stm32f0xx_hal_cec.h"
+#endif /* HAL_CEC_MODULE_ENABLED */
+
+#ifdef HAL_COMP_MODULE_ENABLED
+ #include "stm32f0xx_hal_comp.h"
+#endif /* HAL_COMP_MODULE_ENABLED */
+
+#ifdef HAL_CRC_MODULE_ENABLED
+ #include "stm32f0xx_hal_crc.h"
+#endif /* HAL_CRC_MODULE_ENABLED */
+
+#ifdef HAL_DAC_MODULE_ENABLED
+ #include "stm32f0xx_hal_dac.h"
+#endif /* HAL_DAC_MODULE_ENABLED */
+
+#ifdef HAL_FLASH_MODULE_ENABLED
+ #include "stm32f0xx_hal_flash.h"
+#endif /* HAL_FLASH_MODULE_ENABLED */
+
+#ifdef HAL_I2C_MODULE_ENABLED
+ #include "stm32f0xx_hal_i2c.h"
+#endif /* HAL_I2C_MODULE_ENABLED */
+
+#ifdef HAL_I2S_MODULE_ENABLED
+ #include "stm32f0xx_hal_i2s.h"
+#endif /* HAL_I2S_MODULE_ENABLED */
+
+#ifdef HAL_IRDA_MODULE_ENABLED
+ #include "stm32f0xx_hal_irda.h"
+#endif /* HAL_IRDA_MODULE_ENABLED */
+
+#ifdef HAL_IWDG_MODULE_ENABLED
+ #include "stm32f0xx_hal_iwdg.h"
+#endif /* HAL_IWDG_MODULE_ENABLED */
+
+#ifdef HAL_PCD_MODULE_ENABLED
+ #include "stm32f0xx_hal_pcd.h"
+#endif /* HAL_PCD_MODULE_ENABLED */
+
+#ifdef HAL_PWR_MODULE_ENABLED
+ #include "stm32f0xx_hal_pwr.h"
+#endif /* HAL_PWR_MODULE_ENABLED */
+
+#ifdef HAL_RTC_MODULE_ENABLED
+ #include "stm32f0xx_hal_rtc.h"
+#endif /* HAL_RTC_MODULE_ENABLED */
+
+#ifdef HAL_SMARTCARD_MODULE_ENABLED
+ #include "stm32f0xx_hal_smartcard.h"
+#endif /* HAL_SMARTCARD_MODULE_ENABLED */
+
+#ifdef HAL_SMBUS_MODULE_ENABLED
+ #include "stm32f0xx_hal_smbus.h"
+#endif /* HAL_SMBUS_MODULE_ENABLED */
+
+#ifdef HAL_SPI_MODULE_ENABLED
+ #include "stm32f0xx_hal_spi.h"
+#endif /* HAL_SPI_MODULE_ENABLED */
+
+#ifdef HAL_TIM_MODULE_ENABLED
+ #include "stm32f0xx_hal_tim.h"
+#endif /* HAL_TIM_MODULE_ENABLED */
+
+#ifdef HAL_TSC_MODULE_ENABLED
+ #include "stm32f0xx_hal_tsc.h"
+#endif /* HAL_TSC_MODULE_ENABLED */
+
+#ifdef HAL_UART_MODULE_ENABLED
+ #include "stm32f0xx_hal_uart.h"
+#endif /* HAL_UART_MODULE_ENABLED */
+
+#ifdef HAL_USART_MODULE_ENABLED
+ #include "stm32f0xx_hal_usart.h"
+#endif /* HAL_USART_MODULE_ENABLED */
+
+#ifdef HAL_WWDG_MODULE_ENABLED
+ #include "stm32f0xx_hal_wwdg.h"
+#endif /* HAL_WWDG_MODULE_ENABLED */
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef USE_FULL_ASSERT
+/**
+ * @brief The assert_param macro is used for function's parameters check.
+ * @param expr If expr is false, it calls assert_failed function
+ * which reports the name of the source file and the source
+ * line number of the call that failed.
+ * If expr is true, it returns no value.
+ * @retval None
+ */
+ #define assert_param(expr) ((expr) ? (void)0U : assert_failed((uint8_t *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(uint8_t* file, uint32_t line);
+#else
+ #define assert_param(expr) ((void)0U)
+#endif /* USE_FULL_ASSERT */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __STM32F0xx_HAL_CONF_H */
+
diff --git a/peripherals/cc48x6/firmware/Inc/stm32f0xx_it.h b/peripherals/cc48x6/firmware/Inc/stm32f0xx_it.h
new file mode 100644
index 0000000..858d932
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Inc/stm32f0xx_it.h
@@ -0,0 +1,64 @@
+/* USER CODE BEGIN Header */
+/**
+ ******************************************************************************
+ * @file stm32f0xx_it.h
+ * @brief This file contains the headers of the interrupt handlers.
+ ******************************************************************************
+ * @attention
+ *
+ * Copyright (c) 2022 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software is licensed under terms that can be found in the LICENSE file
+ * in the root directory of this software component.
+ * If no LICENSE file comes with this software, it is provided AS-IS.
+ *
+ ******************************************************************************
+ */
+/* USER CODE END Header */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F0xx_IT_H
+#define __STM32F0xx_IT_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Private includes ----------------------------------------------------------*/
+/* USER CODE BEGIN Includes */
+
+/* USER CODE END Includes */
+
+/* Exported types ------------------------------------------------------------*/
+/* USER CODE BEGIN ET */
+
+/* USER CODE END ET */
+
+/* Exported constants --------------------------------------------------------*/
+/* USER CODE BEGIN EC */
+
+/* USER CODE END EC */
+
+/* Exported macro ------------------------------------------------------------*/
+/* USER CODE BEGIN EM */
+
+/* USER CODE END EM */
+
+/* Exported functions prototypes ---------------------------------------------*/
+void NMI_Handler(void);
+void HardFault_Handler(void);
+void SVC_Handler(void);
+void PendSV_Handler(void);
+void SysTick_Handler(void);
+void EXTI4_15_IRQHandler(void);
+void DMA1_Channel4_5_IRQHandler(void);
+/* USER CODE BEGIN EFP */
+
+/* USER CODE END EFP */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __STM32F0xx_IT_H */
diff --git a/peripherals/cc48x6/firmware/Inc/tim.h b/peripherals/cc48x6/firmware/Inc/tim.h
new file mode 100644
index 0000000..45b9bb3
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Inc/tim.h
@@ -0,0 +1,56 @@
+/* USER CODE BEGIN Header */
+/**
+ ******************************************************************************
+ * @file tim.h
+ * @brief This file contains all the function prototypes for
+ * the tim.c file
+ ******************************************************************************
+ * @attention
+ *
+ * Copyright (c) 2022 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software is licensed under terms that can be found in the LICENSE file
+ * in the root directory of this software component.
+ * If no LICENSE file comes with this software, it is provided AS-IS.
+ *
+ ******************************************************************************
+ */
+/* USER CODE END Header */
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __TIM_H__
+#define __TIM_H__
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "main.h"
+
+/* USER CODE BEGIN Includes */
+
+/* USER CODE END Includes */
+
+extern TIM_HandleTypeDef htim1;
+extern TIM_HandleTypeDef htim3;
+
+/* USER CODE BEGIN Private defines */
+
+/* USER CODE END Private defines */
+
+void MX_TIM1_Init(void);
+void MX_TIM3_Init(void);
+
+void HAL_TIM_MspPostInit(TIM_HandleTypeDef *htim);
+
+/* USER CODE BEGIN Prototypes */
+
+/* USER CODE END Prototypes */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __TIM_H__ */
+
diff --git a/peripherals/cc48x6/firmware/Makefile b/peripherals/cc48x6/firmware/Makefile
new file mode 100644
index 0000000..c5223e0
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Makefile
@@ -0,0 +1,206 @@
+##########################################################################################################################
+# File automatically-generated by tool: [projectgenerator] version: [3.15.2] date: [Thu Jan 19 05:11:09 CET 2023]
+##########################################################################################################################
+
+# ------------------------------------------------
+# Generic Makefile (based on gcc)
+#
+# ChangeLog :
+# 2017-02-10 - Several enhancements + project update mode
+# 2015-07-22 - first version
+# ------------------------------------------------
+
+######################################
+# target
+######################################
+TARGET = stm32f030c8t_test
+
+
+######################################
+# building variables
+######################################
+# debug build?
+DEBUG = 1
+# optimization
+OPT = -O3
+
+
+#######################################
+# paths
+#######################################
+# Build path
+BUILD_DIR = build
+
+######################################
+# source
+######################################
+# C sources
+C_SOURCES = \
+Src/main.c \
+Src/gpio.c \
+Src/crc.c \
+Src/spi.c \
+Src/tim.c \
+Src/stm32f0xx_it.c \
+Src/stm32f0xx_hal_msp.c \
+Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_crc.c \
+Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_crc_ex.c \
+Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_rcc.c \
+Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_rcc_ex.c \
+Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal.c \
+Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_i2c.c \
+Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_i2c_ex.c \
+Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_gpio.c \
+Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_dma.c \
+Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_cortex.c \
+Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_pwr.c \
+Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_pwr_ex.c \
+Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_flash.c \
+Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_flash_ex.c \
+Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_exti.c \
+Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_spi.c \
+Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_spi_ex.c \
+Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_tim.c \
+Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_hal_tim_ex.c \
+Src/system_stm32f0xx.c \
+Src/dma.c \
+Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_rcc.c \
+Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_utils.c \
+Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_exti.c \
+Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_gpio.c \
+Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_dma.c \
+Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_spi.c \
+Drivers/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_tim.c
+
+# ASM sources
+ASM_SOURCES = \
+startup_stm32f030x8.s
+
+
+#######################################
+# binaries
+#######################################
+PREFIX = arm-none-eabi-
+# The gcc compiler bin path can be either defined in make command via GCC_PATH variable (> make GCC_PATH=xxx)
+# either it can be added to the PATH environment variable.
+ifdef GCC_PATH
+CC = $(GCC_PATH)/$(PREFIX)gcc
+AS = $(GCC_PATH)/$(PREFIX)gcc -x assembler-with-cpp
+CP = $(GCC_PATH)/$(PREFIX)objcopy
+SZ = $(GCC_PATH)/$(PREFIX)size
+else
+CC = $(PREFIX)gcc
+AS = $(PREFIX)gcc -x assembler-with-cpp
+CP = $(PREFIX)objcopy
+SZ = $(PREFIX)size
+endif
+HEX = $(CP) -O ihex
+BIN = $(CP) -O binary -S
+
+#######################################
+# CFLAGS
+#######################################
+# cpu
+CPU = -mcpu=cortex-m0
+
+# fpu
+# NONE for Cortex-M0/M0+/M3
+
+# float-abi
+
+
+# mcu
+MCU = $(CPU) -mthumb $(FPU) $(FLOAT-ABI)
+
+# macros for gcc
+# AS defines
+AS_DEFS =
+
+# C defines
+C_DEFS = \
+-DUSE_HAL_DRIVER \
+-DSTM32F030x8
+
+
+# AS includes
+AS_INCLUDES =
+
+# C includes
+C_INCLUDES = \
+-IInc \
+-IDrivers/STM32F0xx_HAL_Driver/Inc \
+-IDrivers/STM32F0xx_HAL_Driver/Inc/Legacy \
+-IDrivers/CMSIS/Device/ST/STM32F0xx/Include \
+-IDrivers/CMSIS/Include
+
+
+# compile gcc flags
+ASFLAGS = $(MCU) $(AS_DEFS) $(AS_INCLUDES) $(OPT) -Wall -fdata-sections -ffunction-sections
+
+CFLAGS = $(MCU) $(C_DEFS) $(C_INCLUDES) $(OPT) -Wall -fdata-sections -ffunction-sections
+
+ifeq ($(DEBUG), 1)
+CFLAGS += -g -gdwarf-2
+endif
+
+
+# Generate dependency information
+CFLAGS += -MMD -MP -MF"$(@:%.o=%.d)"
+
+
+#######################################
+# LDFLAGS
+#######################################
+# link script
+LDSCRIPT = STM32F030C8Tx_FLASH.ld
+
+# libraries
+LIBS = -lc -lm -lnosys
+LIBDIR =
+LDFLAGS = $(MCU) -specs=nano.specs -T$(LDSCRIPT) $(LIBDIR) $(LIBS) -Wl,-Map=$(BUILD_DIR)/$(TARGET).map,--cref -Wl,--gc-sections
+
+# default action: build all
+all: $(BUILD_DIR)/$(TARGET).elf $(BUILD_DIR)/$(TARGET).hex $(BUILD_DIR)/$(TARGET).bin
+
+
+#######################################
+# build the application
+#######################################
+# list of objects
+OBJECTS = $(addprefix $(BUILD_DIR)/,$(notdir $(C_SOURCES:.c=.o)))
+vpath %.c $(sort $(dir $(C_SOURCES)))
+# list of ASM program objects
+OBJECTS += $(addprefix $(BUILD_DIR)/,$(notdir $(ASM_SOURCES:.s=.o)))
+vpath %.s $(sort $(dir $(ASM_SOURCES)))
+
+$(BUILD_DIR)/%.o: %.c Makefile | $(BUILD_DIR)
+ $(CC) -c $(CFLAGS) -Wa,-a,-ad,-alms=$(BUILD_DIR)/$(notdir $(<:.c=.lst)) $< -o $@
+
+$(BUILD_DIR)/%.o: %.s Makefile | $(BUILD_DIR)
+ $(AS) -c $(CFLAGS) $< -o $@
+
+$(BUILD_DIR)/$(TARGET).elf: $(OBJECTS) Makefile
+ $(CC) $(OBJECTS) $(LDFLAGS) -o $@
+ $(SZ) $@
+
+$(BUILD_DIR)/%.hex: $(BUILD_DIR)/%.elf | $(BUILD_DIR)
+ $(HEX) $< $@
+
+$(BUILD_DIR)/%.bin: $(BUILD_DIR)/%.elf | $(BUILD_DIR)
+ $(BIN) $< $@
+
+$(BUILD_DIR):
+ mkdir $@
+
+#######################################
+# clean up
+#######################################
+clean:
+ -rm -fR $(BUILD_DIR)
+
+#######################################
+# dependencies
+#######################################
+-include $(wildcard $(BUILD_DIR)/*.d)
+
+# *** EOF ***
diff --git a/peripherals/cc48x6/firmware/STM32F030C8Tx_FLASH.ld b/peripherals/cc48x6/firmware/STM32F030C8Tx_FLASH.ld
new file mode 100644
index 0000000..7975554
--- /dev/null
+++ b/peripherals/cc48x6/firmware/STM32F030C8Tx_FLASH.ld
@@ -0,0 +1,189 @@
+/*
+******************************************************************************
+**
+
+** File : LinkerScript.ld
+**
+** Author : Auto-generated by System Workbench for STM32
+**
+** Abstract : Linker script for STM32F030C8Tx series
+** 64Kbytes FLASH and 8Kbytes RAM
+**
+** Set heap size, stack size and stack location according
+** to application requirements.
+**
+** Set memory bank area and size if external memory is used.
+**
+** Target : STMicroelectronics STM32
+**
+** Distribution: The file is distributed “as is,” without any warranty
+** of any kind.
+**
+*****************************************************************************
+** @attention
+**
+** © COPYRIGHT(c) 2019 STMicroelectronics
+**
+** 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.
+**
+*****************************************************************************
+*/
+
+/* Entry Point */
+ENTRY(Reset_Handler)
+
+/* Highest address of the user mode stack */
+_estack = 0x20002000; /* end of RAM */
+/* Generate a link error if heap and stack don't fit into RAM */
+_Min_Heap_Size = 0x200; /* required amount of heap */
+_Min_Stack_Size = 0x400; /* required amount of stack */
+
+/* Specify the memory areas */
+MEMORY
+{
+RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 8K
+FLASH (rx) : ORIGIN = 0x8000000, LENGTH = 64K
+}
+
+/* Define output sections */
+SECTIONS
+{
+ /* The startup code goes first into FLASH */
+ .isr_vector :
+ {
+ . = ALIGN(4);
+ KEEP(*(.isr_vector)) /* Startup code */
+ . = ALIGN(4);
+ } >FLASH
+
+ /* The program code and other data goes into FLASH */
+ .text :
+ {
+ . = ALIGN(4);
+ *(.text) /* .text sections (code) */
+ *(.text*) /* .text* sections (code) */
+ *(.glue_7) /* glue arm to thumb code */
+ *(.glue_7t) /* glue thumb to arm code */
+ *(.eh_frame)
+
+ KEEP (*(.init))
+ KEEP (*(.fini))
+
+ . = ALIGN(4);
+ _etext = .; /* define a global symbols at end of code */
+ } >FLASH
+
+ /* Constant data goes into FLASH */
+ .rodata :
+ {
+ . = ALIGN(4);
+ *(.rodata) /* .rodata sections (constants, strings, etc.) */
+ *(.rodata*) /* .rodata* sections (constants, strings, etc.) */
+ . = ALIGN(4);
+ } >FLASH
+
+ .ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH
+ .ARM : {
+ __exidx_start = .;
+ *(.ARM.exidx*)
+ __exidx_end = .;
+ } >FLASH
+
+ .preinit_array :
+ {
+ PROVIDE_HIDDEN (__preinit_array_start = .);
+ KEEP (*(.preinit_array*))
+ PROVIDE_HIDDEN (__preinit_array_end = .);
+ } >FLASH
+ .init_array :
+ {
+ PROVIDE_HIDDEN (__init_array_start = .);
+ KEEP (*(SORT(.init_array.*)))
+ KEEP (*(.init_array*))
+ PROVIDE_HIDDEN (__init_array_end = .);
+ } >FLASH
+ .fini_array :
+ {
+ PROVIDE_HIDDEN (__fini_array_start = .);
+ KEEP (*(SORT(.fini_array.*)))
+ KEEP (*(.fini_array*))
+ PROVIDE_HIDDEN (__fini_array_end = .);
+ } >FLASH
+
+ /* used by the startup to initialize data */
+ _sidata = LOADADDR(.data);
+
+ /* Initialized data sections goes into RAM, load LMA copy after code */
+ .data :
+ {
+ . = ALIGN(4);
+ _sdata = .; /* create a global symbol at data start */
+ *(.data) /* .data sections */
+ *(.data*) /* .data* sections */
+
+ . = ALIGN(4);
+ _edata = .; /* define a global symbol at data end */
+ } >RAM AT> FLASH
+
+
+ /* Uninitialized data section */
+ . = ALIGN(4);
+ .bss :
+ {
+ /* This is used by the startup in order to initialize the .bss secion */
+ _sbss = .; /* define a global symbol at bss start */
+ __bss_start__ = _sbss;
+ *(.bss)
+ *(.bss*)
+ *(COMMON)
+
+ . = ALIGN(4);
+ _ebss = .; /* define a global symbol at bss end */
+ __bss_end__ = _ebss;
+ } >RAM
+
+ /* User_heap_stack section, used to check that there is enough RAM left */
+ ._user_heap_stack :
+ {
+ . = ALIGN(8);
+ PROVIDE ( end = . );
+ PROVIDE ( _end = . );
+ . = . + _Min_Heap_Size;
+ . = . + _Min_Stack_Size;
+ . = ALIGN(8);
+ } >RAM
+
+
+
+ /* Remove information from the standard libraries */
+ /DISCARD/ :
+ {
+ libc.a ( * )
+ libm.a ( * )
+ libgcc.a ( * )
+ }
+
+ .ARM.attributes 0 : { *(.ARM.attributes) }
+}
+
+
diff --git a/peripherals/cc48x6/firmware/Src/crc.c b/peripherals/cc48x6/firmware/Src/crc.c
new file mode 100644
index 0000000..b7289a0
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Src/crc.c
@@ -0,0 +1,89 @@
+/* USER CODE BEGIN Header */
+/**
+ ******************************************************************************
+ * @file crc.c
+ * @brief This file provides code for the configuration
+ * of the CRC instances.
+ ******************************************************************************
+ * @attention
+ *
+ * Copyright (c) 2022 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software is licensed under terms that can be found in the LICENSE file
+ * in the root directory of this software component.
+ * If no LICENSE file comes with this software, it is provided AS-IS.
+ *
+ ******************************************************************************
+ */
+/* USER CODE END Header */
+/* Includes ------------------------------------------------------------------*/
+#include "crc.h"
+
+/* USER CODE BEGIN 0 */
+
+/* USER CODE END 0 */
+
+CRC_HandleTypeDef hcrc;
+
+/* CRC init function */
+void MX_CRC_Init(void)
+{
+
+ /* USER CODE BEGIN CRC_Init 0 */
+
+ /* USER CODE END CRC_Init 0 */
+
+ /* USER CODE BEGIN CRC_Init 1 */
+
+ /* USER CODE END CRC_Init 1 */
+ hcrc.Instance = CRC;
+ hcrc.Init.DefaultInitValueUse = DEFAULT_INIT_VALUE_ENABLE;
+ hcrc.Init.InputDataInversionMode = CRC_INPUTDATA_INVERSION_NONE;
+ hcrc.Init.OutputDataInversionMode = CRC_OUTPUTDATA_INVERSION_DISABLE;
+ hcrc.InputDataFormat = CRC_INPUTDATA_FORMAT_BYTES;
+ if (HAL_CRC_Init(&hcrc) != HAL_OK)
+ {
+ Error_Handler();
+ }
+ /* USER CODE BEGIN CRC_Init 2 */
+
+ /* USER CODE END CRC_Init 2 */
+
+}
+
+void HAL_CRC_MspInit(CRC_HandleTypeDef* crcHandle)
+{
+
+ if(crcHandle->Instance==CRC)
+ {
+ /* USER CODE BEGIN CRC_MspInit 0 */
+
+ /* USER CODE END CRC_MspInit 0 */
+ /* CRC clock enable */
+ __HAL_RCC_CRC_CLK_ENABLE();
+ /* USER CODE BEGIN CRC_MspInit 1 */
+
+ /* USER CODE END CRC_MspInit 1 */
+ }
+}
+
+void HAL_CRC_MspDeInit(CRC_HandleTypeDef* crcHandle)
+{
+
+ if(crcHandle->Instance==CRC)
+ {
+ /* USER CODE BEGIN CRC_MspDeInit 0 */
+
+ /* USER CODE END CRC_MspDeInit 0 */
+ /* Peripheral clock disable */
+ __HAL_RCC_CRC_CLK_DISABLE();
+ /* USER CODE BEGIN CRC_MspDeInit 1 */
+
+ /* USER CODE END CRC_MspDeInit 1 */
+ }
+}
+
+/* USER CODE BEGIN 1 */
+
+/* USER CODE END 1 */
diff --git a/peripherals/cc48x6/firmware/Src/dma.c b/peripherals/cc48x6/firmware/Src/dma.c
new file mode 100644
index 0000000..a954666
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Src/dma.c
@@ -0,0 +1,55 @@
+/* USER CODE BEGIN Header */
+/**
+ ******************************************************************************
+ * @file dma.c
+ * @brief This file provides code for the configuration
+ * of all the requested memory to memory DMA transfers.
+ ******************************************************************************
+ * @attention
+ *
+ * Copyright (c) 2022 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software is licensed under terms that can be found in the LICENSE file
+ * in the root directory of this software component.
+ * If no LICENSE file comes with this software, it is provided AS-IS.
+ *
+ ******************************************************************************
+ */
+/* USER CODE END Header */
+
+/* Includes ------------------------------------------------------------------*/
+#include "dma.h"
+
+/* USER CODE BEGIN 0 */
+
+/* USER CODE END 0 */
+
+/*----------------------------------------------------------------------------*/
+/* Configure DMA */
+/*----------------------------------------------------------------------------*/
+
+/* USER CODE BEGIN 1 */
+
+/* USER CODE END 1 */
+
+/**
+ * Enable DMA controller clock
+ */
+void MX_DMA_Init(void)
+{
+
+ /* DMA controller clock enable */
+ __HAL_RCC_DMA1_CLK_ENABLE();
+
+ /* DMA interrupt init */
+ /* DMA1_Channel4_5_IRQn interrupt configuration */
+ HAL_NVIC_SetPriority(DMA1_Channel4_5_IRQn, 0, 0);
+ HAL_NVIC_EnableIRQ(DMA1_Channel4_5_IRQn);
+
+}
+
+/* USER CODE BEGIN 2 */
+
+/* USER CODE END 2 */
+
diff --git a/peripherals/cc48x6/firmware/Src/gpio.c b/peripherals/cc48x6/firmware/Src/gpio.c
new file mode 100644
index 0000000..bd607e1
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Src/gpio.c
@@ -0,0 +1,119 @@
+/* USER CODE BEGIN Header */
+/**
+ ******************************************************************************
+ * @file gpio.c
+ * @brief This file provides code for the configuration
+ * of all used GPIO pins.
+ ******************************************************************************
+ * @attention
+ *
+ * Copyright (c) 2022 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software is licensed under terms that can be found in the LICENSE file
+ * in the root directory of this software component.
+ * If no LICENSE file comes with this software, it is provided AS-IS.
+ *
+ ******************************************************************************
+ */
+/* USER CODE END Header */
+
+/* Includes ------------------------------------------------------------------*/
+#include "gpio.h"
+
+/* USER CODE BEGIN 0 */
+
+/* USER CODE END 0 */
+
+/*----------------------------------------------------------------------------*/
+/* Configure GPIO */
+/*----------------------------------------------------------------------------*/
+/* USER CODE BEGIN 1 */
+
+/* USER CODE END 1 */
+
+/** Configure pins as
+ * Analog
+ * Input
+ * Output
+ * EVENT_OUT
+ * EXTI
+ * Free pins are configured automatically as Analog (this feature is enabled through
+ * the Code Generation settings)
+*/
+void MX_GPIO_Init(void)
+{
+
+ GPIO_InitTypeDef GPIO_InitStruct = {0};
+
+ /* GPIO Ports Clock Enable */
+ __HAL_RCC_GPIOC_CLK_ENABLE();
+ __HAL_RCC_GPIOF_CLK_ENABLE();
+ __HAL_RCC_GPIOA_CLK_ENABLE();
+ __HAL_RCC_GPIOB_CLK_ENABLE();
+
+ /*Configure GPIO pin Output Level */
+ HAL_GPIO_WritePin(INIT_OUT_GPIO_Port, INIT_OUT_Pin, GPIO_PIN_RESET);
+
+ /*Configure GPIO pin Output Level */
+ HAL_GPIO_WritePin(SIGNAL_LED_GPIO_Port, SIGNAL_LED_Pin, GPIO_PIN_RESET);
+
+ /*Configure GPIO pin : PtPin */
+ GPIO_InitStruct.Pin = INIT_IN_Pin;
+ GPIO_InitStruct.Mode = GPIO_MODE_INPUT;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ HAL_GPIO_Init(INIT_IN_GPIO_Port, &GPIO_InitStruct);
+
+ /*Configure GPIO pin : PtPin */
+ GPIO_InitStruct.Pin = INIT_OUT_Pin;
+ GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
+ HAL_GPIO_Init(INIT_OUT_GPIO_Port, &GPIO_InitStruct);
+
+ /*Configure GPIO pin : PtPin */
+ GPIO_InitStruct.Pin = SPI_INT_Pin;
+ GPIO_InitStruct.Mode = GPIO_MODE_IT_RISING;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ HAL_GPIO_Init(SPI_INT_GPIO_Port, &GPIO_InitStruct);
+
+ /*Configure GPIO pins : PF0 PF1 PF6 PF7 */
+ GPIO_InitStruct.Pin = GPIO_PIN_0|GPIO_PIN_1|GPIO_PIN_6|GPIO_PIN_7;
+ GPIO_InitStruct.Mode = GPIO_MODE_ANALOG;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ HAL_GPIO_Init(GPIOF, &GPIO_InitStruct);
+
+ /*Configure GPIO pins : PA0 PA1 PA2 PA12
+ PA15 */
+ GPIO_InitStruct.Pin = GPIO_PIN_0|GPIO_PIN_1|GPIO_PIN_2|GPIO_PIN_12
+ |GPIO_PIN_15;
+ GPIO_InitStruct.Mode = GPIO_MODE_ANALOG;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
+
+ /*Configure GPIO pin : PtPin */
+ GPIO_InitStruct.Pin = SIGNAL_LED_Pin;
+ GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
+ HAL_GPIO_Init(SIGNAL_LED_GPIO_Port, &GPIO_InitStruct);
+
+ /*Configure GPIO pins : PB0 PB1 PB2 PB10
+ PB11 PB12 PB3 PB6
+ PB7 PB8 PB9 */
+ GPIO_InitStruct.Pin = GPIO_PIN_0|GPIO_PIN_1|GPIO_PIN_2|GPIO_PIN_10
+ |GPIO_PIN_11|GPIO_PIN_12|GPIO_PIN_3|GPIO_PIN_6
+ |GPIO_PIN_7|GPIO_PIN_8|GPIO_PIN_9;
+ GPIO_InitStruct.Mode = GPIO_MODE_ANALOG;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
+
+ /* EXTI interrupt init*/
+ HAL_NVIC_SetPriority(EXTI4_15_IRQn, 0, 0);
+ HAL_NVIC_EnableIRQ(EXTI4_15_IRQn);
+
+}
+
+/* USER CODE BEGIN 2 */
+
+/* USER CODE END 2 */
diff --git a/peripherals/cc48x6/firmware/Src/main.c b/peripherals/cc48x6/firmware/Src/main.c
new file mode 100644
index 0000000..1fdef79
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Src/main.c
@@ -0,0 +1,383 @@
+/* USER CODE BEGIN Header */
+/**
+ ******************************************************************************
+ * @file : main.c
+ * @brief : Main program body
+ ******************************************************************************
+ * @attention
+ *
+ * Copyright (c) 2022 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software is licensed under terms that can be found in the LICENSE file
+ * in the root directory of this software component.
+ * If no LICENSE file comes with this software, it is provided AS-IS.
+ *
+ ******************************************************************************
+ */
+/* USER CODE END Header */
+/* Includes ------------------------------------------------------------------*/
+#include "main.h"
+#include "crc.h"
+#include "dma.h"
+#include "tim.h"
+#include "gpio.h"
+
+/* Private includes ----------------------------------------------------------*/
+/* USER CODE BEGIN Includes */
+#include
+#include "spi.h"
+#include "stm32f0xx_ll_spi.h"
+/* USER CODE END Includes */
+
+/* Private typedef -----------------------------------------------------------*/
+/* USER CODE BEGIN PTD */
+
+/* USER CODE END PTD */
+
+/* Private define ------------------------------------------------------------*/
+/* USER CODE BEGIN PD */
+/* USER CODE END PD */
+
+/* Private macro -------------------------------------------------------------*/
+/* USER CODE BEGIN PM */
+
+/* USER CODE END PM */
+
+/* Private variables ---------------------------------------------------------*/
+
+/* USER CODE BEGIN PV */
+
+/* USER CODE END PV */
+
+/* Private function prototypes -----------------------------------------------*/
+void SystemClock_Config(void);
+/* USER CODE BEGIN PFP */
+
+/* USER CODE END PFP */
+
+/* Private user code ---------------------------------------------------------*/
+/* USER CODE BEGIN 0 */
+
+
+const uint16_t version = 42;
+
+bool toggle = false;
+uint16_t counter = 0;
+
+bool dirty = true;
+//uint16_t mem[12] = {0xFFF, 0xFF, 0xFFF, 0xFF, 0xFFF, 0xFF, 0xFFF, 0xFF, 0xFFF, 0xFF, 0xFFF, 0xFF};
+//uint16_t mem[12] = {0x300, 0x40, 0x300, 0x40, 0x300, 0x40, 0x300, 0x40, 0x300, 0x40, 0x300, 0x40};
+uint16_t mem[12] = {0xFFF, 0xFF, 0xFFF, 0xFF, 0xFFF, 0xFF, 0xFFF, 0xFF, 0xFFF, 0xFF, 0xFFF, 0xFF};
+
+uint16_t conf[8] = {version, 0, 0, 0, 0, 0, 0, 0};
+
+#define BUFFER_SIZE 64
+uint16_t RX_Buffer[BUFFER_SIZE] = {0};
+uint16_t TX_Buffer[BUFFER_SIZE] = {0};
+
+void HAL_GPIO_EXTI_Callback(uint16_t GPIO_Pin) {
+ if(GPIO_Pin == SPI_INT_Pin) {
+ hspi2.Instance->CR1 |= SPI_CR1_SSI;
+ HAL_GPIO_WritePin(INIT_OUT_GPIO_Port, INIT_OUT_Pin, GPIO_PIN_SET);
+ for (volatile int i = 0; i < 3; i++);
+ hspi2.Instance->CR1 &= ~SPI_CR1_SSI;
+ HAL_GPIO_WritePin(INIT_OUT_GPIO_Port, INIT_OUT_Pin, GPIO_PIN_RESET);
+ }
+}
+
+void HAL_SPI_CpltCallback(SPI_HandleTypeDef *hspi) {
+
+ if(RX_Buffer[0]) {
+ union {
+ struct {
+ unsigned data: 12;
+ unsigned chan: 4;
+ } __attribute__((packed));
+ uint16_t raw;
+
+ } frame = {.raw=RX_Buffer[0]};
+
+ toggle = !toggle;
+ counter++;
+
+ if(toggle) {
+ HAL_GPIO_WritePin(SIGNAL_LED_GPIO_Port, SIGNAL_LED_Pin, GPIO_PIN_SET);
+ } else {
+ HAL_GPIO_WritePin(SIGNAL_LED_GPIO_Port, SIGNAL_LED_Pin, GPIO_PIN_RESET);
+ }
+
+ if(frame.chan <= 6 && frame.chan >= 1) {
+ frame.chan--;
+ if(frame.data > 0x300) {
+ mem[frame.chan * 2 + 1] = 0xFF;
+ mem[frame.chan * 2] = frame.data;
+ } else {
+ mem[frame.chan * 2 + 1] = (frame.data * 0xFF) / 0x300;
+ mem[frame.chan * 2] = 0x300;
+ }
+
+ dirty = true;
+ TX_Buffer[0] = RX_Buffer[0];
+
+ } else if(frame.chan == 15 && frame.data < 8) {
+ TX_Buffer[0] = conf[frame.data];
+ } else {
+ TX_Buffer[0] = 0;
+ }
+
+ }
+
+ HAL_SPI_TransmitReceive_DMA(&hspi2, TX_Buffer, RX_Buffer, 1);
+
+ HAL_GPIO_WritePin(INIT_OUT_GPIO_Port, INIT_OUT_Pin, GPIO_PIN_SET);
+ for (volatile int i = 0; i < 3; i++);
+ HAL_GPIO_WritePin(INIT_OUT_GPIO_Port, INIT_OUT_Pin, GPIO_PIN_RESET);
+
+}
+
+void HAL_SPI_RxCpltCallback(SPI_HandleTypeDef *hspi) {
+ HAL_SPI_CpltCallback(hspi);
+}
+
+void HAL_SPI_TxRxCpltCallback(SPI_HandleTypeDef *hspi) {
+ HAL_SPI_CpltCallback(hspi);
+}
+
+void HAL_SPI_TxCpltCallback(SPI_HandleTypeDef *hspi) {
+ HAL_SPI_Transmit_DMA(&hspi2, (uint8_t *) TX_Buffer, 2);
+}
+
+void setDAC(uint8_t channel, uint16_t val) {
+ uint16_t frame = (val & 0x0FFF) | (0x7000 & (channel << 12));
+ HAL_SPI_Transmit(&hspi1, (uint8_t * ) & frame, 1, 100);
+}
+
+/* USER CODE END 0 */
+
+/**
+ * @brief The application entry point.
+ * @retval int
+ */
+int main(void) {
+ /* USER CODE BEGIN 1 */
+
+ /* USER CODE END 1 */
+
+ /* MCU Configuration--------------------------------------------------------*/
+
+ /* Reset of all peripherals, Initializes the Flash interface and the Systick. */
+ HAL_Init();
+
+ /* USER CODE BEGIN Init */
+
+ /* USER CODE END Init */
+
+ /* Configure the system clock */
+ SystemClock_Config();
+
+ /* USER CODE BEGIN SysInit */
+
+ /* USER CODE END SysInit */
+
+ /* Initialize all configured peripherals */
+ MX_GPIO_Init();
+ MX_CRC_Init();
+ MX_TIM1_Init();
+ MX_DMA_Init();
+ MX_TIM3_Init();
+ /* USER CODE BEGIN 2 */
+ MX_SPI1_Init();
+ MX_SPI2_Init();
+
+ TIM1->ARR = 254;
+ TIM1->CCR1 = 10;
+ TIM1->CCR2 = 10;
+ TIM1->CCR3 = 10;
+ TIM1->CCR4 = 10;
+ TIM1->CCMR1 = 0x6868;
+ TIM1->CCMR2 = 0x6868;
+ TIM1->CCER = 0x1111;
+ TIM1->EGR |= TIM_EGR_UG;
+ TIM1->BDTR |= TIM_BDTR_MOE;
+ TIM1->CR1 |= TIM_CR1_CEN;
+
+ TIM3->ARR = 254;
+ TIM3->CCR1 = 10;
+ TIM3->CCR2 = 10;
+
+ TIM3->CCMR1 = 0x6868;
+ TIM3->CCER = 0x1111;
+ TIM3->EGR |= TIM_EGR_UG;
+ TIM3->BDTR |= TIM_BDTR_MOE;
+ TIM3->CR1 |= TIM_CR1_CEN;
+
+ HAL_GPIO_WritePin(SIGNAL_LED_GPIO_Port, SIGNAL_LED_Pin, GPIO_PIN_RESET);
+
+ uint16_t frame = 0b1001000000000000;
+ HAL_SPI_Transmit(&hspi1, (uint8_t * ) & frame, 1, 100);
+
+ for (int i = 0; i < 6; ++i) {
+ setDAC(i, mem[i * 2]);
+ }
+
+ TIM1->CCR1 = 0xFF & mem[1];
+ TIM1->CCR2 = 0xFF & mem[3];
+ TIM1->CCR3 = 0xFF & mem[5];
+ TIM1->CCR4 = 0xFF & mem[7];
+ TIM3->CCR1 = 0xFF & mem[9];
+ TIM3->CCR2 = 0xFF & mem[11];
+
+ HAL_GPIO_WritePin(SIGNAL_LED_GPIO_Port, SIGNAL_LED_Pin, GPIO_PIN_SET);
+
+ HAL_SPI_Receive_DMA(&hspi2, (uint8_t *) RX_Buffer, 1);
+
+
+
+
+
+ /* USER CODE END 2 */
+
+ /* Infinite loop */
+ /* USER CODE BEGIN WHILE */
+ while (1) {
+ /* USER CODE END WHILE */
+
+ /* USER CODE BEGIN 3 */
+
+
+#if 1
+ //if(dirty) {
+ for (int i = 0; i < 6; ++i) {
+ setDAC(i, mem[i * 2]);
+ }
+
+ TIM1->CCR1 = 0xFF & mem[1];
+ TIM1->CCR2 = 0xFF & mem[3];
+ TIM1->CCR3 = 0xFF & mem[5];
+ TIM1->CCR4 = 0xFF & mem[7];
+ TIM3->CCR1 = 0xFF & mem[9];
+ TIM3->CCR2 = 0xFF & mem[11];
+
+ dirty = false;
+
+ //}
+
+#else
+
+ setDAC(0, 50 << 4);
+ setDAC(1, 50 << 4);
+ setDAC(2, 50 << 4);
+ setDAC(3, 50 << 4);
+ setDAC(4, 50 << 4);
+ setDAC(5, 50 << 4);
+
+ HAL_GPIO_WritePin(SIGNAL_LED_GPIO_Port, SIGNAL_LED_Pin, GPIO_PIN_SET);
+
+ for (int i = 0; i < sizeof(pwm_lookup); i++) {
+ uint8_t j = pwm_lookup[i];
+
+ TIM1->CCR1 = j;
+ TIM1->CCR2 = j;
+ TIM1->CCR3 = j;
+ TIM1->CCR4 = j;
+ TIM3->CCR1 = j;
+ TIM3->CCR2 = j;
+
+ HAL_Delay(5);
+ }
+
+ TIM1->CCR1 = 256;
+ TIM1->CCR2 = 256;
+ TIM1->CCR3 = 256;
+ TIM1->CCR4 = 256;
+ TIM3->CCR1 = 256;
+ TIM3->CCR2 = 256;
+ for (int i = 50; i < 256; i++) {
+ setDAC(0, i << 4);
+ setDAC(1, i << 4);
+ setDAC(2, i << 4);
+ setDAC(3, i << 4);
+ setDAC(4, i << 4);
+ setDAC(5, i << 4);
+ HAL_Delay(5);
+ }
+
+ HAL_GPIO_WritePin(SIGNAL_LED_GPIO_Port, SIGNAL_LED_Pin, GPIO_PIN_RESET);
+
+ HAL_Delay(200);
+
+#endif
+
+ }
+ /* USER CODE END 3 */
+}
+
+/**
+ * @brief System Clock Configuration
+ * @retval None
+ */
+void SystemClock_Config(void) {
+ RCC_OscInitTypeDef RCC_OscInitStruct = {0};
+ RCC_ClkInitTypeDef RCC_ClkInitStruct = {0};
+
+ /** Initializes the RCC Oscillators according to the specified parameters
+ * in the RCC_OscInitTypeDef structure.
+ */
+ RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI;
+ RCC_OscInitStruct.HSIState = RCC_HSI_ON;
+ RCC_OscInitStruct.HSICalibrationValue = RCC_HSICALIBRATION_DEFAULT;
+ RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
+ RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSI;
+ RCC_OscInitStruct.PLL.PLLMUL = RCC_PLL_MUL12;
+ RCC_OscInitStruct.PLL.PREDIV = RCC_PREDIV_DIV1;
+ if(HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK) {
+ Error_Handler();
+ }
+ /** Initializes the CPU, AHB and APB buses clocks
+ */
+ RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_SYSCLK
+ | RCC_CLOCKTYPE_PCLK1;
+ RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
+ RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;
+ RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV1;
+
+ if(HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_1) != HAL_OK) {
+ Error_Handler();
+ }
+}
+
+/* USER CODE BEGIN 4 */
+
+/* USER CODE END 4 */
+
+/**
+ * @brief This function is executed in case of error occurrence.
+ * @retval None
+ */
+void Error_Handler(void) {
+ /* USER CODE BEGIN Error_Handler_Debug */
+ /* User can add his own implementation to report the HAL error return state */
+ __disable_irq();
+ while (1) {
+ }
+ /* USER CODE END Error_Handler_Debug */
+}
+
+#ifdef USE_FULL_ASSERT
+/**
+ * @brief Reports the name of the source file and the source line number
+ * where the assert_param error has occurred.
+ * @param file: pointer to the source file name
+ * @param line: assert_param error line source number
+ * @retval None
+ */
+void assert_failed(uint8_t *file, uint32_t line)
+{
+ /* USER CODE BEGIN 6 */
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+ /* USER CODE END 6 */
+}
+#endif /* USE_FULL_ASSERT */
+
diff --git a/peripherals/cc48x6/firmware/Src/spi.c b/peripherals/cc48x6/firmware/Src/spi.c
new file mode 100644
index 0000000..420e9b1
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Src/spi.c
@@ -0,0 +1,239 @@
+/* USER CODE BEGIN Header */
+/**
+ ******************************************************************************
+ * @file spi.c
+ * @brief This file provides code for the configuration
+ * of the SPI instances.
+ ******************************************************************************
+ * @attention
+ *
+ * Copyright (c) 2022 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software is licensed under terms that can be found in the LICENSE file
+ * in the root directory of this software component.
+ * If no LICENSE file comes with this software, it is provided AS-IS.
+ *
+ ******************************************************************************
+ */
+/* USER CODE END Header */
+/* Includes ------------------------------------------------------------------*/
+#include "spi.h"
+
+/* USER CODE BEGIN 0 */
+
+/* USER CODE END 0 */
+
+SPI_HandleTypeDef hspi1;
+SPI_HandleTypeDef hspi2;
+DMA_HandleTypeDef hdma_spi2_rx;
+DMA_HandleTypeDef hdma_spi2_tx;
+
+/* SPI1 init function */
+void MX_SPI1_Init(void)
+{
+
+ /* USER CODE BEGIN SPI1_Init 0 */
+
+ /* USER CODE END SPI1_Init 0 */
+
+ /* USER CODE BEGIN SPI1_Init 1 */
+
+ /* USER CODE END SPI1_Init 1 */
+ hspi1.Instance = SPI1;
+ hspi1.Init.Mode = SPI_MODE_MASTER;
+ hspi1.Init.Direction = SPI_DIRECTION_2LINES;
+ hspi1.Init.DataSize = SPI_DATASIZE_16BIT;
+ hspi1.Init.CLKPolarity = SPI_POLARITY_LOW;
+ hspi1.Init.CLKPhase = SPI_PHASE_1EDGE;
+ hspi1.Init.NSS = SPI_NSS_HARD_OUTPUT;
+ hspi1.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_16;
+ hspi1.Init.FirstBit = SPI_FIRSTBIT_MSB;
+ hspi1.Init.TIMode = SPI_TIMODE_DISABLE;
+ hspi1.Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE;
+ hspi1.Init.CRCPolynomial = 7;
+ hspi1.Init.CRCLength = SPI_CRC_LENGTH_DATASIZE;
+ hspi1.Init.NSSPMode = SPI_NSS_PULSE_ENABLE;
+ if (HAL_SPI_Init(&hspi1) != HAL_OK)
+ {
+ Error_Handler();
+ }
+ /* USER CODE BEGIN SPI1_Init 2 */
+
+ /* USER CODE END SPI1_Init 2 */
+
+}
+/* SPI2 init function */
+void MX_SPI2_Init(void)
+{
+
+ /* USER CODE BEGIN SPI2_Init 0 */
+
+ /* USER CODE END SPI2_Init 0 */
+
+ /* USER CODE BEGIN SPI2_Init 1 */
+
+ /* USER CODE END SPI2_Init 1 */
+ hspi2.Instance = SPI2;
+ hspi2.Init.Mode = SPI_MODE_SLAVE;
+ hspi2.Init.Direction = SPI_DIRECTION_2LINES;
+ hspi2.Init.DataSize = SPI_DATASIZE_16BIT;
+ hspi2.Init.CLKPolarity = SPI_POLARITY_LOW;
+ hspi2.Init.CLKPhase = SPI_PHASE_1EDGE;
+ hspi2.Init.NSS = SPI_NSS_SOFT;
+ hspi2.Init.FirstBit = SPI_FIRSTBIT_MSB;
+ hspi2.Init.TIMode = SPI_TIMODE_DISABLE;
+ hspi2.Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE;
+ hspi2.Init.CRCPolynomial = 7;
+ hspi2.Init.CRCLength = SPI_CRC_LENGTH_DATASIZE;
+ hspi2.Init.NSSPMode = SPI_NSS_PULSE_DISABLE;
+ if (HAL_SPI_Init(&hspi2) != HAL_OK)
+ {
+ Error_Handler();
+ }
+ /* USER CODE BEGIN SPI2_Init 2 */
+
+ /* USER CODE END SPI2_Init 2 */
+
+}
+
+void HAL_SPI_MspInit(SPI_HandleTypeDef* spiHandle)
+{
+
+ GPIO_InitTypeDef GPIO_InitStruct = {0};
+ if(spiHandle->Instance==SPI1)
+ {
+ /* USER CODE BEGIN SPI1_MspInit 0 */
+
+ /* USER CODE END SPI1_MspInit 0 */
+ /* SPI1 clock enable */
+ __HAL_RCC_SPI1_CLK_ENABLE();
+
+ __HAL_RCC_GPIOA_CLK_ENABLE();
+ /**SPI1 GPIO Configuration
+ PA4 ------> SPI1_NSS
+ PA5 ------> SPI1_SCK
+ PA6 ------> SPI1_MISO
+ PA7 ------> SPI1_MOSI
+ */
+ GPIO_InitStruct.Pin = GPIO_PIN_4|GPIO_PIN_5|GPIO_PIN_6|GPIO_PIN_7;
+ GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
+ GPIO_InitStruct.Alternate = GPIO_AF0_SPI1;
+ HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
+
+ /* USER CODE BEGIN SPI1_MspInit 1 */
+
+ /* USER CODE END SPI1_MspInit 1 */
+ }
+ else if(spiHandle->Instance==SPI2)
+ {
+ /* USER CODE BEGIN SPI2_MspInit 0 */
+
+ /* USER CODE END SPI2_MspInit 0 */
+ /* SPI2 clock enable */
+ __HAL_RCC_SPI2_CLK_ENABLE();
+
+ __HAL_RCC_GPIOB_CLK_ENABLE();
+ /**SPI2 GPIO Configuration
+ PB13 ------> SPI2_SCK
+ PB14 ------> SPI2_MISO
+ PB15 ------> SPI2_MOSI
+ */
+ GPIO_InitStruct.Pin = GPIO_PIN_13|GPIO_PIN_14|GPIO_PIN_15;
+ GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
+ GPIO_InitStruct.Alternate = GPIO_AF0_SPI2;
+ HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
+
+ /* SPI2 DMA Init */
+ /* SPI2_RX Init */
+ hdma_spi2_rx.Instance = DMA1_Channel4;
+ hdma_spi2_rx.Init.Direction = DMA_PERIPH_TO_MEMORY;
+ hdma_spi2_rx.Init.PeriphInc = DMA_PINC_DISABLE;
+ hdma_spi2_rx.Init.MemInc = DMA_MINC_ENABLE;
+ hdma_spi2_rx.Init.PeriphDataAlignment = DMA_PDATAALIGN_HALFWORD;
+ hdma_spi2_rx.Init.MemDataAlignment = DMA_MDATAALIGN_HALFWORD;
+ hdma_spi2_rx.Init.Mode = DMA_NORMAL;
+ hdma_spi2_rx.Init.Priority = DMA_PRIORITY_LOW;
+ if (HAL_DMA_Init(&hdma_spi2_rx) != HAL_OK)
+ {
+ Error_Handler();
+ }
+
+ __HAL_LINKDMA(spiHandle,hdmarx,hdma_spi2_rx);
+
+ /* SPI2_TX Init */
+ hdma_spi2_tx.Instance = DMA1_Channel5;
+ hdma_spi2_tx.Init.Direction = DMA_MEMORY_TO_PERIPH;
+ hdma_spi2_tx.Init.PeriphInc = DMA_PINC_DISABLE;
+ hdma_spi2_tx.Init.MemInc = DMA_MINC_ENABLE;
+ hdma_spi2_tx.Init.PeriphDataAlignment = DMA_PDATAALIGN_HALFWORD;
+ hdma_spi2_tx.Init.MemDataAlignment = DMA_MDATAALIGN_HALFWORD;
+ hdma_spi2_tx.Init.Mode = DMA_NORMAL;
+ hdma_spi2_tx.Init.Priority = DMA_PRIORITY_LOW;
+ if (HAL_DMA_Init(&hdma_spi2_tx) != HAL_OK)
+ {
+ Error_Handler();
+ }
+
+ __HAL_LINKDMA(spiHandle,hdmatx,hdma_spi2_tx);
+
+ /* USER CODE BEGIN SPI2_MspInit 1 */
+
+ /* USER CODE END SPI2_MspInit 1 */
+ }
+}
+
+void HAL_SPI_MspDeInit(SPI_HandleTypeDef* spiHandle)
+{
+
+ if(spiHandle->Instance==SPI1)
+ {
+ /* USER CODE BEGIN SPI1_MspDeInit 0 */
+
+ /* USER CODE END SPI1_MspDeInit 0 */
+ /* Peripheral clock disable */
+ __HAL_RCC_SPI1_CLK_DISABLE();
+
+ /**SPI1 GPIO Configuration
+ PA4 ------> SPI1_NSS
+ PA5 ------> SPI1_SCK
+ PA6 ------> SPI1_MISO
+ PA7 ------> SPI1_MOSI
+ */
+ HAL_GPIO_DeInit(GPIOA, GPIO_PIN_4|GPIO_PIN_5|GPIO_PIN_6|GPIO_PIN_7);
+
+ /* USER CODE BEGIN SPI1_MspDeInit 1 */
+
+ /* USER CODE END SPI1_MspDeInit 1 */
+ }
+ else if(spiHandle->Instance==SPI2)
+ {
+ /* USER CODE BEGIN SPI2_MspDeInit 0 */
+
+ /* USER CODE END SPI2_MspDeInit 0 */
+ /* Peripheral clock disable */
+ __HAL_RCC_SPI2_CLK_DISABLE();
+
+ /**SPI2 GPIO Configuration
+ PB13 ------> SPI2_SCK
+ PB14 ------> SPI2_MISO
+ PB15 ------> SPI2_MOSI
+ */
+ HAL_GPIO_DeInit(GPIOB, GPIO_PIN_13|GPIO_PIN_14|GPIO_PIN_15);
+
+ /* SPI2 DMA DeInit */
+ HAL_DMA_DeInit(spiHandle->hdmarx);
+ HAL_DMA_DeInit(spiHandle->hdmatx);
+ /* USER CODE BEGIN SPI2_MspDeInit 1 */
+
+ /* USER CODE END SPI2_MspDeInit 1 */
+ }
+}
+
+/* USER CODE BEGIN 1 */
+
+/* USER CODE END 1 */
diff --git a/peripherals/cc48x6/firmware/Src/stm32f0xx_hal_msp.c b/peripherals/cc48x6/firmware/Src/stm32f0xx_hal_msp.c
new file mode 100644
index 0000000..d50e5cd
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Src/stm32f0xx_hal_msp.c
@@ -0,0 +1,82 @@
+/* USER CODE BEGIN Header */
+/**
+ ******************************************************************************
+ * @file stm32f0xx_hal_msp.c
+ * @brief This file provides code for the MSP Initialization
+ * and de-Initialization codes.
+ ******************************************************************************
+ * @attention
+ *
+ * Copyright (c) 2022 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software is licensed under terms that can be found in the LICENSE file
+ * in the root directory of this software component.
+ * If no LICENSE file comes with this software, it is provided AS-IS.
+ *
+ ******************************************************************************
+ */
+/* USER CODE END Header */
+
+/* Includes ------------------------------------------------------------------*/
+#include "main.h"
+/* USER CODE BEGIN Includes */
+
+/* USER CODE END Includes */
+
+/* Private typedef -----------------------------------------------------------*/
+/* USER CODE BEGIN TD */
+
+/* USER CODE END TD */
+
+/* Private define ------------------------------------------------------------*/
+/* USER CODE BEGIN Define */
+
+/* USER CODE END Define */
+
+/* Private macro -------------------------------------------------------------*/
+/* USER CODE BEGIN Macro */
+
+/* USER CODE END Macro */
+
+/* Private variables ---------------------------------------------------------*/
+/* USER CODE BEGIN PV */
+
+/* USER CODE END PV */
+
+/* Private function prototypes -----------------------------------------------*/
+/* USER CODE BEGIN PFP */
+
+/* USER CODE END PFP */
+
+/* External functions --------------------------------------------------------*/
+/* USER CODE BEGIN ExternalFunctions */
+
+/* USER CODE END ExternalFunctions */
+
+/* USER CODE BEGIN 0 */
+
+/* USER CODE END 0 */
+/**
+ * Initializes the Global MSP.
+ */
+void HAL_MspInit(void)
+{
+ /* USER CODE BEGIN MspInit 0 */
+
+ /* USER CODE END MspInit 0 */
+
+ __HAL_RCC_SYSCFG_CLK_ENABLE();
+ __HAL_RCC_PWR_CLK_ENABLE();
+
+ /* System interrupt init*/
+
+ /* USER CODE BEGIN MspInit 1 */
+
+ /* USER CODE END MspInit 1 */
+}
+
+/* USER CODE BEGIN 1 */
+
+/* USER CODE END 1 */
+
diff --git a/peripherals/cc48x6/firmware/Src/stm32f0xx_it.c b/peripherals/cc48x6/firmware/Src/stm32f0xx_it.c
new file mode 100644
index 0000000..bfe798e
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Src/stm32f0xx_it.c
@@ -0,0 +1,168 @@
+/* USER CODE BEGIN Header */
+/**
+ ******************************************************************************
+ * @file stm32f0xx_it.c
+ * @brief Interrupt Service Routines.
+ ******************************************************************************
+ * @attention
+ *
+ * Copyright (c) 2022 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software is licensed under terms that can be found in the LICENSE file
+ * in the root directory of this software component.
+ * If no LICENSE file comes with this software, it is provided AS-IS.
+ *
+ ******************************************************************************
+ */
+/* USER CODE END Header */
+
+/* Includes ------------------------------------------------------------------*/
+#include "main.h"
+#include "stm32f0xx_it.h"
+/* Private includes ----------------------------------------------------------*/
+/* USER CODE BEGIN Includes */
+/* USER CODE END Includes */
+
+/* Private typedef -----------------------------------------------------------*/
+/* USER CODE BEGIN TD */
+
+/* USER CODE END TD */
+
+/* Private define ------------------------------------------------------------*/
+/* USER CODE BEGIN PD */
+
+/* USER CODE END PD */
+
+/* Private macro -------------------------------------------------------------*/
+/* USER CODE BEGIN PM */
+
+/* USER CODE END PM */
+
+/* Private variables ---------------------------------------------------------*/
+/* USER CODE BEGIN PV */
+
+/* USER CODE END PV */
+
+/* Private function prototypes -----------------------------------------------*/
+/* USER CODE BEGIN PFP */
+
+/* USER CODE END PFP */
+
+/* Private user code ---------------------------------------------------------*/
+/* USER CODE BEGIN 0 */
+
+/* USER CODE END 0 */
+
+/* External variables --------------------------------------------------------*/
+extern DMA_HandleTypeDef hdma_spi2_rx;
+extern DMA_HandleTypeDef hdma_spi2_tx;
+/* USER CODE BEGIN EV */
+
+/* USER CODE END EV */
+
+/******************************************************************************/
+/* Cortex-M0 Processor Interruption and Exception Handlers */
+/******************************************************************************/
+/**
+ * @brief This function handles Non maskable interrupt.
+ */
+void NMI_Handler(void) {
+ /* USER CODE BEGIN NonMaskableInt_IRQn 0 */
+
+ /* USER CODE END NonMaskableInt_IRQn 0 */
+ /* USER CODE BEGIN NonMaskableInt_IRQn 1 */
+ while (1) {
+ }
+ /* USER CODE END NonMaskableInt_IRQn 1 */
+}
+
+/**
+ * @brief This function handles Hard fault interrupt.
+ */
+void HardFault_Handler(void) {
+ /* USER CODE BEGIN HardFault_IRQn 0 */
+
+ /* USER CODE END HardFault_IRQn 0 */
+ while (1) {
+ /* USER CODE BEGIN W1_HardFault_IRQn 0 */
+ /* USER CODE END W1_HardFault_IRQn 0 */
+ }
+}
+
+/**
+ * @brief This function handles System service call via SWI instruction.
+ */
+void SVC_Handler(void) {
+ /* USER CODE BEGIN SVC_IRQn 0 */
+
+ /* USER CODE END SVC_IRQn 0 */
+ /* USER CODE BEGIN SVC_IRQn 1 */
+
+ /* USER CODE END SVC_IRQn 1 */
+}
+
+/**
+ * @brief This function handles Pendable request for system service.
+ */
+void PendSV_Handler(void) {
+ /* USER CODE BEGIN PendSV_IRQn 0 */
+
+ /* USER CODE END PendSV_IRQn 0 */
+ /* USER CODE BEGIN PendSV_IRQn 1 */
+
+ /* 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 */
+}
+
+/******************************************************************************/
+/* STM32F0xx Peripheral Interrupt Handlers */
+/* Add here the Interrupt Handlers for the used peripherals. */
+/* For the available peripheral interrupt handler names, */
+/* please refer to the startup file (startup_stm32f0xx.s). */
+/******************************************************************************/
+
+/**
+ * @brief This function handles EXTI line 4 to 15 interrupts.
+ */
+void EXTI4_15_IRQHandler(void) {
+ /* USER CODE BEGIN EXTI4_15_IRQn 0 */
+
+ /* USER CODE END EXTI4_15_IRQn 0 */
+ HAL_GPIO_EXTI_IRQHandler(SPI_INT_Pin);
+ // HAL_GPIO_EXTI_Callback(SPI_INT_Pin);
+
+ /* USER CODE BEGIN EXTI4_15_IRQn 1 */
+
+ /* USER CODE END EXTI4_15_IRQn 1 */
+}
+
+/**
+ * @brief This function handles DMA1 channel 4 and 5 interrupts.
+ */
+void DMA1_Channel4_5_IRQHandler(void) {
+ /* USER CODE BEGIN DMA1_Channel4_5_IRQn 0 */
+ /* USER CODE END DMA1_Channel4_5_IRQn 0 */
+ HAL_DMA_IRQHandler(&hdma_spi2_rx);
+ HAL_DMA_IRQHandler(&hdma_spi2_tx);
+ /* USER CODE BEGIN DMA1_Channel4_5_IRQn 1 */
+
+ /* USER CODE END DMA1_Channel4_5_IRQn 1 */
+}
+
+/* USER CODE BEGIN 1 */
+
+/* USER CODE END 1 */
+
diff --git a/peripherals/cc48x6/firmware/Src/system_stm32f0xx.c b/peripherals/cc48x6/firmware/Src/system_stm32f0xx.c
new file mode 100644
index 0000000..4761a85
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Src/system_stm32f0xx.c
@@ -0,0 +1,247 @@
+/**
+ ******************************************************************************
+ * @file system_stm32f0xx.c
+ * @author MCD Application Team
+ * @brief CMSIS Cortex-M0 Device Peripheral Access Layer System Source File.
+ *
+ * 1. This file provides two functions and one global variable to be called from
+ * user application:
+ * - SystemInit(): This function is called at startup just after reset and
+ * before branch to main program. This call is made inside
+ * the "startup_stm32f0xx.s" file.
+ *
+ * - SystemCoreClock variable: Contains the core clock (HCLK), it can be used
+ * by the user application to setup the SysTick
+ * timer or configure other parameters.
+ *
+ * - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must
+ * be called whenever the core clock is changed
+ * during program execution.
+ *
+ *
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2016 STMicroelectronics.
+ * All rights reserved.
+ *
+ * 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
+ *
+ ******************************************************************************
+ */
+
+/** @addtogroup CMSIS
+ * @{
+ */
+
+/** @addtogroup stm32f0xx_system
+ * @{
+ */
+
+/** @addtogroup STM32F0xx_System_Private_Includes
+ * @{
+ */
+
+#include "stm32f0xx.h"
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F0xx_System_Private_TypesDefinitions
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F0xx_System_Private_Defines
+ * @{
+ */
+#if !defined (HSE_VALUE)
+ #define HSE_VALUE ((uint32_t)8000000) /*!< Default value of the External oscillator in Hz.
+ This value can be provided and adapted by the user application. */
+#endif /* HSE_VALUE */
+
+#if !defined (HSI_VALUE)
+ #define HSI_VALUE ((uint32_t)8000000) /*!< Default value of the Internal oscillator in Hz.
+ This value can be provided and adapted by the user application. */
+#endif /* HSI_VALUE */
+
+#if !defined (HSI48_VALUE)
+#define HSI48_VALUE ((uint32_t)48000000) /*!< Default value of the HSI48 Internal oscillator in Hz.
+ This value can be provided and adapted by the user application. */
+#endif /* HSI48_VALUE */
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F0xx_System_Private_Macros
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F0xx_System_Private_Variables
+ * @{
+ */
+ /* This variable is updated in three ways:
+ 1) by calling CMSIS function SystemCoreClockUpdate()
+ 2) by calling HAL API function HAL_RCC_GetHCLKFreq()
+ 3) each time HAL_RCC_ClockConfig() is called to configure the system clock frequency
+ Note: If you use this function to configure the system clock; then there
+ is no need to call the 2 first functions listed above, since SystemCoreClock
+ variable is updated automatically.
+ */
+uint32_t SystemCoreClock = 8000000;
+
+const uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9};
+const uint8_t APBPrescTable[8] = {0, 0, 0, 0, 1, 2, 3, 4};
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F0xx_System_Private_FunctionPrototypes
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F0xx_System_Private_Functions
+ * @{
+ */
+
+/**
+ * @brief Setup the microcontroller system
+ * @param None
+ * @retval None
+ */
+void SystemInit(void)
+{
+ /* NOTE :SystemInit(): This function is called at startup just after reset and
+ before branch to main program. This call is made inside
+ the "startup_stm32f0xx.s" file.
+ User can setups the default system clock (System clock source, PLL Multiplier
+ and Divider factors, AHB/APBx prescalers and Flash settings).
+ */
+}
+
+/**
+ * @brief Update SystemCoreClock variable according to Clock Register Values.
+ * The SystemCoreClock variable contains the core clock (HCLK), it can
+ * be used by the user application to setup the SysTick timer or configure
+ * other parameters.
+ *
+ * @note Each time the core clock (HCLK) changes, this function must be called
+ * to update SystemCoreClock variable value. Otherwise, any configuration
+ * based on this variable will be incorrect.
+ *
+ * @note - The system frequency computed by this function is not the real
+ * frequency in the chip. It is calculated based on the predefined
+ * constant and the selected clock source:
+ *
+ * - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(*)
+ *
+ * - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(**)
+ *
+ * - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(**)
+ * or HSI_VALUE(*) multiplied/divided by the PLL factors.
+ *
+ * (*) HSI_VALUE is a constant defined in stm32f0xx_hal_conf.h file (default value
+ * 8 MHz) but the real value may vary depending on the variations
+ * in voltage and temperature.
+ *
+ * (**) HSE_VALUE is a constant defined in stm32f0xx_hal_conf.h file (its value
+ * depends on the application requirements), user has to ensure that HSE_VALUE
+ * is same as the real frequency of the crystal used. Otherwise, this function
+ * may have wrong result.
+ *
+ * - The result of this function could be not correct when using fractional
+ * value for HSE crystal.
+ *
+ * @param None
+ * @retval None
+ */
+void SystemCoreClockUpdate (void)
+{
+ uint32_t tmp = 0, pllmull = 0, pllsource = 0, predivfactor = 0;
+
+ /* Get SYSCLK source -------------------------------------------------------*/
+ tmp = RCC->CFGR & RCC_CFGR_SWS;
+
+ switch (tmp)
+ {
+ case RCC_CFGR_SWS_HSI: /* HSI used as system clock */
+ SystemCoreClock = HSI_VALUE;
+ break;
+ case RCC_CFGR_SWS_HSE: /* HSE used as system clock */
+ SystemCoreClock = HSE_VALUE;
+ break;
+ case RCC_CFGR_SWS_PLL: /* PLL used as system clock */
+ /* Get PLL clock source and multiplication factor ----------------------*/
+ pllmull = RCC->CFGR & RCC_CFGR_PLLMUL;
+ pllsource = RCC->CFGR & RCC_CFGR_PLLSRC;
+ pllmull = ( pllmull >> 18) + 2;
+ predivfactor = (RCC->CFGR2 & RCC_CFGR2_PREDIV) + 1;
+
+ if (pllsource == RCC_CFGR_PLLSRC_HSE_PREDIV)
+ {
+ /* HSE used as PLL clock source : SystemCoreClock = HSE/PREDIV * PLLMUL */
+ SystemCoreClock = (HSE_VALUE/predivfactor) * pllmull;
+ }
+#if defined(STM32F042x6) || defined(STM32F048xx) || defined(STM32F072xB) || defined(STM32F078xx) || defined(STM32F091xC) || defined(STM32F098xx)
+ else if (pllsource == RCC_CFGR_PLLSRC_HSI48_PREDIV)
+ {
+ /* HSI48 used as PLL clock source : SystemCoreClock = HSI48/PREDIV * PLLMUL */
+ SystemCoreClock = (HSI48_VALUE/predivfactor) * pllmull;
+ }
+#endif /* STM32F042x6 || STM32F048xx || STM32F072xB || STM32F078xx || STM32F091xC || STM32F098xx */
+ else
+ {
+#if defined(STM32F042x6) || defined(STM32F048xx) || defined(STM32F070x6) \
+ || defined(STM32F078xx) || defined(STM32F071xB) || defined(STM32F072xB) \
+ || defined(STM32F070xB) || defined(STM32F091xC) || defined(STM32F098xx) || defined(STM32F030xC)
+ /* HSI used as PLL clock source : SystemCoreClock = HSI/PREDIV * PLLMUL */
+ SystemCoreClock = (HSI_VALUE/predivfactor) * pllmull;
+#else
+ /* HSI used as PLL clock source : SystemCoreClock = HSI/2 * PLLMUL */
+ SystemCoreClock = (HSI_VALUE >> 1) * pllmull;
+#endif /* STM32F042x6 || STM32F048xx || STM32F070x6 ||
+ STM32F071xB || STM32F072xB || STM32F078xx || STM32F070xB ||
+ STM32F091xC || STM32F098xx || STM32F030xC */
+ }
+ break;
+ default: /* HSI used as system clock */
+ SystemCoreClock = HSI_VALUE;
+ break;
+ }
+ /* Compute HCLK clock frequency ----------------*/
+ /* Get HCLK prescaler */
+ tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)];
+ /* HCLK clock frequency */
+ SystemCoreClock >>= tmp;
+}
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
+
diff --git a/peripherals/cc48x6/firmware/Src/tim.c b/peripherals/cc48x6/firmware/Src/tim.c
new file mode 100644
index 0000000..4e674f1
--- /dev/null
+++ b/peripherals/cc48x6/firmware/Src/tim.c
@@ -0,0 +1,258 @@
+/* USER CODE BEGIN Header */
+/**
+ ******************************************************************************
+ * @file tim.c
+ * @brief This file provides code for the configuration
+ * of the TIM instances.
+ ******************************************************************************
+ * @attention
+ *
+ * Copyright (c) 2022 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software is licensed under terms that can be found in the LICENSE file
+ * in the root directory of this software component.
+ * If no LICENSE file comes with this software, it is provided AS-IS.
+ *
+ ******************************************************************************
+ */
+/* USER CODE END Header */
+/* Includes ------------------------------------------------------------------*/
+#include "tim.h"
+
+/* USER CODE BEGIN 0 */
+
+/* USER CODE END 0 */
+
+TIM_HandleTypeDef htim1;
+TIM_HandleTypeDef htim3;
+
+/* TIM1 init function */
+void MX_TIM1_Init(void)
+{
+
+ /* USER CODE BEGIN TIM1_Init 0 */
+
+ /* USER CODE END TIM1_Init 0 */
+
+ TIM_MasterConfigTypeDef sMasterConfig = {0};
+ TIM_OC_InitTypeDef sConfigOC = {0};
+ TIM_BreakDeadTimeConfigTypeDef sBreakDeadTimeConfig = {0};
+
+ /* USER CODE BEGIN TIM1_Init 1 */
+
+ /* USER CODE END TIM1_Init 1 */
+ htim1.Instance = TIM1;
+ htim1.Init.Prescaler = 0;
+ htim1.Init.CounterMode = TIM_COUNTERMODE_UP;
+ htim1.Init.Period = 65535;
+ htim1.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
+ htim1.Init.RepetitionCounter = 0;
+ htim1.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;
+ if (HAL_TIM_PWM_Init(&htim1) != HAL_OK)
+ {
+ Error_Handler();
+ }
+ sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET;
+ sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE;
+ if (HAL_TIMEx_MasterConfigSynchronization(&htim1, &sMasterConfig) != HAL_OK)
+ {
+ Error_Handler();
+ }
+ sConfigOC.OCMode = TIM_OCMODE_PWM1;
+ sConfigOC.Pulse = 0;
+ sConfigOC.OCPolarity = TIM_OCPOLARITY_HIGH;
+ sConfigOC.OCNPolarity = TIM_OCNPOLARITY_HIGH;
+ sConfigOC.OCFastMode = TIM_OCFAST_DISABLE;
+ sConfigOC.OCIdleState = TIM_OCIDLESTATE_RESET;
+ sConfigOC.OCNIdleState = TIM_OCNIDLESTATE_RESET;
+ if (HAL_TIM_PWM_ConfigChannel(&htim1, &sConfigOC, TIM_CHANNEL_1) != HAL_OK)
+ {
+ Error_Handler();
+ }
+ if (HAL_TIM_PWM_ConfigChannel(&htim1, &sConfigOC, TIM_CHANNEL_2) != HAL_OK)
+ {
+ Error_Handler();
+ }
+ if (HAL_TIM_PWM_ConfigChannel(&htim1, &sConfigOC, TIM_CHANNEL_3) != HAL_OK)
+ {
+ Error_Handler();
+ }
+ if (HAL_TIM_PWM_ConfigChannel(&htim1, &sConfigOC, TIM_CHANNEL_4) != HAL_OK)
+ {
+ Error_Handler();
+ }
+ sBreakDeadTimeConfig.OffStateRunMode = TIM_OSSR_DISABLE;
+ sBreakDeadTimeConfig.OffStateIDLEMode = TIM_OSSI_DISABLE;
+ sBreakDeadTimeConfig.LockLevel = TIM_LOCKLEVEL_OFF;
+ sBreakDeadTimeConfig.DeadTime = 0;
+ sBreakDeadTimeConfig.BreakState = TIM_BREAK_DISABLE;
+ sBreakDeadTimeConfig.BreakPolarity = TIM_BREAKPOLARITY_HIGH;
+ sBreakDeadTimeConfig.AutomaticOutput = TIM_AUTOMATICOUTPUT_DISABLE;
+ if (HAL_TIMEx_ConfigBreakDeadTime(&htim1, &sBreakDeadTimeConfig) != HAL_OK)
+ {
+ Error_Handler();
+ }
+ /* USER CODE BEGIN TIM1_Init 2 */
+
+ /* USER CODE END TIM1_Init 2 */
+ HAL_TIM_MspPostInit(&htim1);
+
+}
+/* TIM3 init function */
+void MX_TIM3_Init(void)
+{
+
+ /* USER CODE BEGIN TIM3_Init 0 */
+
+ /* USER CODE END TIM3_Init 0 */
+
+ TIM_MasterConfigTypeDef sMasterConfig = {0};
+ TIM_OC_InitTypeDef sConfigOC = {0};
+
+ /* USER CODE BEGIN TIM3_Init 1 */
+
+ /* USER CODE END TIM3_Init 1 */
+ htim3.Instance = TIM3;
+ htim3.Init.Prescaler = 0;
+ htim3.Init.CounterMode = TIM_COUNTERMODE_UP;
+ htim3.Init.Period = 65535;
+ htim3.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
+ htim3.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;
+ if (HAL_TIM_PWM_Init(&htim3) != HAL_OK)
+ {
+ Error_Handler();
+ }
+ sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET;
+ sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE;
+ if (HAL_TIMEx_MasterConfigSynchronization(&htim3, &sMasterConfig) != HAL_OK)
+ {
+ Error_Handler();
+ }
+ sConfigOC.OCMode = TIM_OCMODE_PWM1;
+ sConfigOC.Pulse = 0;
+ sConfigOC.OCPolarity = TIM_OCPOLARITY_HIGH;
+ sConfigOC.OCFastMode = TIM_OCFAST_DISABLE;
+ if (HAL_TIM_PWM_ConfigChannel(&htim3, &sConfigOC, TIM_CHANNEL_1) != HAL_OK)
+ {
+ Error_Handler();
+ }
+ if (HAL_TIM_PWM_ConfigChannel(&htim3, &sConfigOC, TIM_CHANNEL_2) != HAL_OK)
+ {
+ Error_Handler();
+ }
+ /* USER CODE BEGIN TIM3_Init 2 */
+
+ /* USER CODE END TIM3_Init 2 */
+ HAL_TIM_MspPostInit(&htim3);
+
+}
+
+void HAL_TIM_PWM_MspInit(TIM_HandleTypeDef* tim_pwmHandle)
+{
+
+ if(tim_pwmHandle->Instance==TIM1)
+ {
+ /* USER CODE BEGIN TIM1_MspInit 0 */
+
+ /* USER CODE END TIM1_MspInit 0 */
+ /* TIM1 clock enable */
+ __HAL_RCC_TIM1_CLK_ENABLE();
+ /* USER CODE BEGIN TIM1_MspInit 1 */
+
+ /* USER CODE END TIM1_MspInit 1 */
+ }
+ else if(tim_pwmHandle->Instance==TIM3)
+ {
+ /* USER CODE BEGIN TIM3_MspInit 0 */
+
+ /* USER CODE END TIM3_MspInit 0 */
+ /* TIM3 clock enable */
+ __HAL_RCC_TIM3_CLK_ENABLE();
+ /* USER CODE BEGIN TIM3_MspInit 1 */
+
+ /* USER CODE END TIM3_MspInit 1 */
+ }
+}
+void HAL_TIM_MspPostInit(TIM_HandleTypeDef* timHandle)
+{
+
+ GPIO_InitTypeDef GPIO_InitStruct = {0};
+ if(timHandle->Instance==TIM1)
+ {
+ /* USER CODE BEGIN TIM1_MspPostInit 0 */
+
+ /* USER CODE END TIM1_MspPostInit 0 */
+ __HAL_RCC_GPIOA_CLK_ENABLE();
+ /**TIM1 GPIO Configuration
+ PA8 ------> TIM1_CH1
+ PA9 ------> TIM1_CH2
+ PA10 ------> TIM1_CH3
+ PA11 ------> TIM1_CH4
+ */
+ GPIO_InitStruct.Pin = GPIO_PIN_8|GPIO_PIN_9|GPIO_PIN_10|GPIO_PIN_11;
+ GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
+ GPIO_InitStruct.Alternate = GPIO_AF2_TIM1;
+ HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
+
+ /* USER CODE BEGIN TIM1_MspPostInit 1 */
+
+ /* USER CODE END TIM1_MspPostInit 1 */
+ }
+ else if(timHandle->Instance==TIM3)
+ {
+ /* USER CODE BEGIN TIM3_MspPostInit 0 */
+
+ /* USER CODE END TIM3_MspPostInit 0 */
+
+ __HAL_RCC_GPIOB_CLK_ENABLE();
+ /**TIM3 GPIO Configuration
+ PB4 ------> TIM3_CH1
+ PB5 ------> TIM3_CH2
+ */
+ GPIO_InitStruct.Pin = GPIO_PIN_4|GPIO_PIN_5;
+ GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
+ GPIO_InitStruct.Alternate = GPIO_AF1_TIM3;
+ HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
+
+ /* USER CODE BEGIN TIM3_MspPostInit 1 */
+
+ /* USER CODE END TIM3_MspPostInit 1 */
+ }
+
+}
+
+void HAL_TIM_PWM_MspDeInit(TIM_HandleTypeDef* tim_pwmHandle)
+{
+
+ if(tim_pwmHandle->Instance==TIM1)
+ {
+ /* USER CODE BEGIN TIM1_MspDeInit 0 */
+
+ /* USER CODE END TIM1_MspDeInit 0 */
+ /* Peripheral clock disable */
+ __HAL_RCC_TIM1_CLK_DISABLE();
+ /* USER CODE BEGIN TIM1_MspDeInit 1 */
+
+ /* USER CODE END TIM1_MspDeInit 1 */
+ }
+ else if(tim_pwmHandle->Instance==TIM3)
+ {
+ /* USER CODE BEGIN TIM3_MspDeInit 0 */
+
+ /* USER CODE END TIM3_MspDeInit 0 */
+ /* Peripheral clock disable */
+ __HAL_RCC_TIM3_CLK_DISABLE();
+ /* USER CODE BEGIN TIM3_MspDeInit 1 */
+
+ /* USER CODE END TIM3_MspDeInit 1 */
+ }
+}
+
+/* USER CODE BEGIN 1 */
+
+/* USER CODE END 1 */
diff --git a/peripherals/cc48x6/firmware/startup_stm32f030x8.s b/peripherals/cc48x6/firmware/startup_stm32f030x8.s
new file mode 100644
index 0000000..252d953
--- /dev/null
+++ b/peripherals/cc48x6/firmware/startup_stm32f030x8.s
@@ -0,0 +1,273 @@
+/**
+ ******************************************************************************
+ * @file startup_stm32f030x8.s
+ * @author MCD Application Team
+ * @brief STM32F030x8 devices vector table for GCC toolchain.
+ * This module performs:
+ * - Set the initial SP
+ * - Set the initial PC == Reset_Handler,
+ * - Set the vector table entries with the exceptions ISR address
+ * - Branches to main in the C library (which eventually
+ * calls main()).
+ * After Reset the Cortex-M0 processor is in Thread mode,
+ * priority is Privileged, and the Stack is set to Main.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2016 STMicroelectronics.
+ * All rights reserved.
+ *
+ * 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
+ *
+ ******************************************************************************
+ */
+
+ .syntax unified
+ .cpu cortex-m0
+ .fpu softvfp
+ .thumb
+
+.global g_pfnVectors
+.global Default_Handler
+
+/* start address for the initialization values of the .data section.
+defined in linker script */
+.word _sidata
+/* start address for the .data section. defined in linker script */
+.word _sdata
+/* end address for the .data section. defined in linker script */
+.word _edata
+/* start address for the .bss section. defined in linker script */
+.word _sbss
+/* end address for the .bss section. defined in linker script */
+.word _ebss
+
+ .section .text.Reset_Handler
+ .weak Reset_Handler
+ .type Reset_Handler, %function
+Reset_Handler:
+ ldr r0, =_estack
+ mov sp, r0 /* set stack pointer */
+
+/* Copy the data segment initializers from flash to SRAM */
+ ldr r0, =_sdata
+ ldr r1, =_edata
+ ldr r2, =_sidata
+ movs r3, #0
+ b LoopCopyDataInit
+
+CopyDataInit:
+ ldr r4, [r2, r3]
+ str r4, [r0, r3]
+ adds r3, r3, #4
+
+LoopCopyDataInit:
+ adds r4, r0, r3
+ cmp r4, r1
+ bcc CopyDataInit
+
+/* Zero fill the bss segment. */
+ ldr r2, =_sbss
+ ldr r4, =_ebss
+ movs r3, #0
+ b LoopFillZerobss
+
+FillZerobss:
+ str r3, [r2]
+ adds r2, r2, #4
+
+LoopFillZerobss:
+ cmp r2, r4
+ bcc FillZerobss
+
+/* Call the clock system intitialization function.*/
+ bl SystemInit
+/* Call static constructors */
+ bl __libc_init_array
+/* Call the application's entry point.*/
+ bl main
+
+LoopForever:
+ b LoopForever
+
+
+.size Reset_Handler, .-Reset_Handler
+
+/**
+ * @brief This is the code that gets called when the processor receives an
+ * unexpected interrupt. This simply enters an infinite loop, preserving
+ * the system state for examination by a debugger.
+ *
+ * @param None
+ * @retval : None
+*/
+ .section .text.Default_Handler,"ax",%progbits
+Default_Handler:
+Infinite_Loop:
+ b Infinite_Loop
+ .size Default_Handler, .-Default_Handler
+/******************************************************************************
+*
+* The minimal vector table for a Cortex M0. Note that the proper constructs
+* must be placed on this to ensure that it ends up at physical address
+* 0x0000.0000.
+*
+******************************************************************************/
+ .section .isr_vector,"a",%progbits
+ .type g_pfnVectors, %object
+ .size g_pfnVectors, .-g_pfnVectors
+
+
+g_pfnVectors:
+ .word _estack
+ .word Reset_Handler
+ .word NMI_Handler
+ .word HardFault_Handler
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word SVC_Handler
+ .word 0
+ .word 0
+ .word PendSV_Handler
+ .word SysTick_Handler
+ .word WWDG_IRQHandler /* Window WatchDog */
+ .word 0 /* Reserved */
+ .word RTC_IRQHandler /* RTC through the EXTI line */
+ .word FLASH_IRQHandler /* FLASH */
+ .word RCC_IRQHandler /* RCC */
+ .word EXTI0_1_IRQHandler /* EXTI Line 0 and 1 */
+ .word EXTI2_3_IRQHandler /* EXTI Line 2 and 3 */
+ .word EXTI4_15_IRQHandler /* EXTI Line 4 to 15 */
+ .word 0 /* Reserved */
+ .word DMA1_Channel1_IRQHandler /* DMA1 Channel 1 */
+ .word DMA1_Channel2_3_IRQHandler /* DMA1 Channel 2 and Channel 3 */
+ .word DMA1_Channel4_5_IRQHandler /* DMA1 Channel 4 and Channel 5 */
+ .word ADC1_IRQHandler /* ADC1 */
+ .word TIM1_BRK_UP_TRG_COM_IRQHandler /* TIM1 Break, Update, Trigger and Commutation */
+ .word TIM1_CC_IRQHandler /* TIM1 Capture Compare */
+ .word 0 /* Reserved */
+ .word TIM3_IRQHandler /* TIM3 */
+ .word TIM6_IRQHandler /* TIM6 */
+ .word 0 /* Reserved */
+ .word TIM14_IRQHandler /* TIM14 */
+ .word TIM15_IRQHandler /* TIM15 */
+ .word TIM16_IRQHandler /* TIM16 */
+ .word TIM17_IRQHandler /* TIM17 */
+ .word I2C1_IRQHandler /* I2C1 */
+ .word I2C2_IRQHandler /* I2C2 */
+ .word SPI1_IRQHandler /* SPI1 */
+ .word SPI2_IRQHandler /* SPI2 */
+ .word USART1_IRQHandler /* USART1 */
+ .word USART2_IRQHandler /* USART2 */
+ .word 0 /* Reserved */
+ .word 0 /* Reserved */
+ .word 0 /* Reserved */
+
+/*******************************************************************************
+*
+* Provide weak aliases for each Exception handler to the Default_Handler.
+* As they are weak aliases, any function with the same name will override
+* this definition.
+*
+*******************************************************************************/
+
+ .weak NMI_Handler
+ .thumb_set NMI_Handler,Default_Handler
+
+ .weak HardFault_Handler
+ .thumb_set HardFault_Handler,Default_Handler
+
+ .weak SVC_Handler
+ .thumb_set SVC_Handler,Default_Handler
+
+ .weak PendSV_Handler
+ .thumb_set PendSV_Handler,Default_Handler
+
+ .weak SysTick_Handler
+ .thumb_set SysTick_Handler,Default_Handler
+
+ .weak WWDG_IRQHandler
+ .thumb_set WWDG_IRQHandler,Default_Handler
+
+ .weak RTC_IRQHandler
+ .thumb_set RTC_IRQHandler,Default_Handler
+
+ .weak FLASH_IRQHandler
+ .thumb_set FLASH_IRQHandler,Default_Handler
+
+ .weak RCC_IRQHandler
+ .thumb_set RCC_IRQHandler,Default_Handler
+
+ .weak EXTI0_1_IRQHandler
+ .thumb_set EXTI0_1_IRQHandler,Default_Handler
+
+ .weak EXTI2_3_IRQHandler
+ .thumb_set EXTI2_3_IRQHandler,Default_Handler
+
+ .weak EXTI4_15_IRQHandler
+ .thumb_set EXTI4_15_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel1_IRQHandler
+ .thumb_set DMA1_Channel1_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel2_3_IRQHandler
+ .thumb_set DMA1_Channel2_3_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel4_5_IRQHandler
+ .thumb_set DMA1_Channel4_5_IRQHandler,Default_Handler
+
+ .weak ADC1_IRQHandler
+ .thumb_set ADC1_IRQHandler,Default_Handler
+
+ .weak TIM1_BRK_UP_TRG_COM_IRQHandler
+ .thumb_set TIM1_BRK_UP_TRG_COM_IRQHandler,Default_Handler
+
+ .weak TIM1_CC_IRQHandler
+ .thumb_set TIM1_CC_IRQHandler,Default_Handler
+
+ .weak TIM3_IRQHandler
+ .thumb_set TIM3_IRQHandler,Default_Handler
+
+ .weak TIM6_IRQHandler
+ .thumb_set TIM6_IRQHandler,Default_Handler
+
+ .weak TIM14_IRQHandler
+ .thumb_set TIM14_IRQHandler,Default_Handler
+
+ .weak TIM15_IRQHandler
+ .thumb_set TIM15_IRQHandler,Default_Handler
+
+ .weak TIM16_IRQHandler
+ .thumb_set TIM16_IRQHandler,Default_Handler
+
+ .weak TIM17_IRQHandler
+ .thumb_set TIM17_IRQHandler,Default_Handler
+
+ .weak I2C1_IRQHandler
+ .thumb_set I2C1_IRQHandler,Default_Handler
+
+ .weak I2C2_IRQHandler
+ .thumb_set I2C2_IRQHandler,Default_Handler
+
+ .weak SPI1_IRQHandler
+ .thumb_set SPI1_IRQHandler,Default_Handler
+
+ .weak SPI2_IRQHandler
+ .thumb_set SPI2_IRQHandler,Default_Handler
+
+ .weak USART1_IRQHandler
+ .thumb_set USART1_IRQHandler,Default_Handler
+
+ .weak USART2_IRQHandler
+ .thumb_set USART2_IRQHandler,Default_Handler
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
+