summaryrefslogtreecommitdiffhomepage
path: root/CMSIS
diff options
context:
space:
mode:
Diffstat (limited to 'CMSIS')
-rw-r--r--CMSIS/MK02F12810.h6290
-rw-r--r--CMSIS/MK02F12810_features.h2013
-rw-r--r--CMSIS/arm_common_tables.h121
-rw-r--r--CMSIS/arm_const_structs.h66
-rw-r--r--CMSIS/arm_math.h7157
-rw-r--r--CMSIS/cmsis_armcc.h870
-rw-r--r--CMSIS/cmsis_armclang.h1877
-rw-r--r--CMSIS/cmsis_compiler.h266
-rw-r--r--CMSIS/cmsis_gcc.h2088
-rw-r--r--CMSIS/cmsis_iccarm.h913
-rw-r--r--CMSIS/cmsis_version.h39
-rw-r--r--CMSIS/core_armv8mbl.h1896
-rw-r--r--CMSIS/core_armv8mml.h2960
-rw-r--r--CMSIS/core_cm4.h2118
-rw-r--r--CMSIS/fsl_device_registers.h64
-rw-r--r--CMSIS/mpu_armv7.h197
-rw-r--r--CMSIS/mpu_armv8.h333
-rw-r--r--CMSIS/system_MK02F12810.c229
-rw-r--r--CMSIS/system_MK02F12810.h166
19 files changed, 29663 insertions, 0 deletions
diff --git a/CMSIS/MK02F12810.h b/CMSIS/MK02F12810.h
new file mode 100644
index 0000000..00f9eff
--- /dev/null
+++ b/CMSIS/MK02F12810.h
@@ -0,0 +1,6290 @@
+/*
+** ###################################################################
+** Processors: MK02FN128VFM10
+** MK02FN128VLF10
+** MK02FN128VLH10
+** MK02FN64VFM10
+** MK02FN64VLF10
+** MK02FN64VLH10
+**
+** Compilers: Keil ARM C/C++ Compiler
+** Freescale C/C++ for Embedded ARM
+** GNU C Compiler
+** IAR ANSI C/C++ Compiler for ARM
+** MCUXpresso Compiler
+**
+** Reference manual: K02P64M100SFARM, Rev. 0, February 14, 2014
+** Version: rev. 0.5, 2015-02-19
+** Build: b171205
+**
+** Abstract:
+** CMSIS Peripheral Access Layer for MK02F12810
+**
+** The Clear BSD License
+** Copyright 1997-2016 Freescale Semiconductor, Inc.
+** Copyright 2016-2017 NXP
+** All rights reserved.
+**
+** Redistribution and use in source and binary forms, with or without
+** modification, are permitted (subject to the limitations in the
+** disclaimer below) provided that the following conditions are met:
+**
+** * Redistributions of source code must retain the above copyright
+** notice, this list of conditions and the following disclaimer.
+**
+** * 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.
+**
+** * Neither the name of the copyright holder nor the names of its
+** contributors may be used to endorse or promote products derived from
+** this software without specific prior written permission.
+**
+** NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE
+** GRANTED BY THIS LICENSE. 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.
+**
+** http: www.nxp.com
+** mail: support@nxp.com
+**
+** Revisions:
+** - rev. 0.1 (2014-02-24)
+** Initial version
+** - rev. 0.2 (2014-07-15)
+** Module access macro module_BASES replaced by module_BASE_PTRS.
+** Update of system and startup files.
+** - rev. 0.3 (2014-08-28)
+** Update of system files - default clock configuration changed.
+** Update of startup files - possibility to override DefaultISR added.
+** - rev. 0.4 (2014-10-14)
+** Interrupt INT_LPTimer renamed to INT_LPTMR0, interrupt INT_Watchdog renamed to INT_WDOG_EWM.
+** - rev. 0.5 (2015-02-19)
+** Renamed interrupt vector LLW to LLWU.
+**
+** ###################################################################
+*/
+
+/*!
+ * @file MK02F12810.h
+ * @version 0.5
+ * @date 2015-02-19
+ * @brief CMSIS Peripheral Access Layer for MK02F12810
+ *
+ * CMSIS Peripheral Access Layer for MK02F12810
+ */
+
+#ifndef _MK02F12810_H_
+#define _MK02F12810_H_ /**< Symbol preventing repeated inclusion */
+
+/** Memory map major version (memory maps with equal major version number are
+ * compatible) */
+#define MCU_MEM_MAP_VERSION 0x0000U
+/** Memory map minor version */
+#define MCU_MEM_MAP_VERSION_MINOR 0x0005U
+
+/**
+ * @brief Macro to calculate address of an aliased word in the peripheral
+ * bitband area for a peripheral register and bit (bit band region 0x40000000 to
+ * 0x400FFFFF).
+ * @param Reg Register to access.
+ * @param Bit Bit number to access.
+ * @return Address of the aliased word in the peripheral bitband area.
+ */
+#define BITBAND_REGADDR(Reg,Bit) (0x42000000u + (32u*((uint32_t)&(Reg) - (uint32_t)0x40000000u)) + (4u*((uint32_t)(Bit))))
+/**
+ * @brief Macro to access a single bit of a peripheral register (bit band region
+ * 0x40000000 to 0x400FFFFF) using the bit-band alias region access. Can
+ * be used for peripherals with 32bit access allowed.
+ * @param Reg Register to access.
+ * @param Bit Bit number to access.
+ * @return Value of the targeted bit in the bit band region.
+ */
+#define BITBAND_REG32(Reg,Bit) (*((uint32_t volatile*)(BITBAND_REGADDR((Reg),(Bit)))))
+#define BITBAND_REG(Reg,Bit) (BITBAND_REG32((Reg),(Bit)))
+/**
+ * @brief Macro to access a single bit of a peripheral register (bit band region
+ * 0x40000000 to 0x400FFFFF) using the bit-band alias region access. Can
+ * be used for peripherals with 16bit access allowed.
+ * @param Reg Register to access.
+ * @param Bit Bit number to access.
+ * @return Value of the targeted bit in the bit band region.
+ */
+#define BITBAND_REG16(Reg,Bit) (*((uint16_t volatile*)(BITBAND_REGADDR((Reg),(Bit)))))
+/**
+ * @brief Macro to access a single bit of a peripheral register (bit band region
+ * 0x40000000 to 0x400FFFFF) using the bit-band alias region access. Can
+ * be used for peripherals with 8bit access allowed.
+ * @param Reg Register to access.
+ * @param Bit Bit number to access.
+ * @return Value of the targeted bit in the bit band region.
+ */
+#define BITBAND_REG8(Reg,Bit) (*((uint8_t volatile*)(BITBAND_REGADDR((Reg),(Bit)))))
+
+/* ----------------------------------------------------------------------------
+ -- Interrupt vector numbers
+ ---------------------------------------------------------------------------- */
+
+/*!
+ * @addtogroup Interrupt_vector_numbers Interrupt vector numbers
+ * @{
+ */
+
+/** Interrupt Number Definitions */
+#define NUMBER_OF_INT_VECTORS 90 /**< Number of interrupts in the Vector table */
+
+typedef enum IRQn {
+ /* Auxiliary constants */
+ NotAvail_IRQn = -128, /**< Not available device specific interrupt */
+
+ /* Core interrupts */
+ NonMaskableInt_IRQn = -14, /**< Non Maskable Interrupt */
+ HardFault_IRQn = -13, /**< Cortex-M4 SV Hard Fault Interrupt */
+ MemoryManagement_IRQn = -12, /**< Cortex-M4 Memory Management Interrupt */
+ BusFault_IRQn = -11, /**< Cortex-M4 Bus Fault Interrupt */
+ UsageFault_IRQn = -10, /**< Cortex-M4 Usage Fault Interrupt */
+ SVCall_IRQn = -5, /**< Cortex-M4 SV Call Interrupt */
+ DebugMonitor_IRQn = -4, /**< Cortex-M4 Debug Monitor Interrupt */
+ PendSV_IRQn = -2, /**< Cortex-M4 Pend SV Interrupt */
+ SysTick_IRQn = -1, /**< Cortex-M4 System Tick Interrupt */
+
+ /* Device specific interrupts */
+ DMA0_IRQn = 0, /**< DMA Channel 0 Transfer Complete */
+ DMA1_IRQn = 1, /**< DMA Channel 1 Transfer Complete */
+ DMA2_IRQn = 2, /**< DMA Channel 2 Transfer Complete */
+ DMA3_IRQn = 3, /**< DMA Channel 3 Transfer Complete */
+ Reserved20_IRQn = 4, /**< Reserved interrupt 20 */
+ Reserved21_IRQn = 5, /**< Reserved interrupt 21 */
+ Reserved22_IRQn = 6, /**< Reserved interrupt 22 */
+ Reserved23_IRQn = 7, /**< Reserved interrupt 23 */
+ Reserved24_IRQn = 8, /**< Reserved interrupt 24 */
+ Reserved25_IRQn = 9, /**< Reserved interrupt 25 */
+ Reserved26_IRQn = 10, /**< Reserved interrupt 26 */
+ Reserved27_IRQn = 11, /**< Reserved interrupt 27 */
+ Reserved28_IRQn = 12, /**< Reserved interrupt 28 */
+ Reserved29_IRQn = 13, /**< Reserved interrupt 29 */
+ Reserved30_IRQn = 14, /**< Reserved interrupt 30 */
+ Reserved31_IRQn = 15, /**< Reserved interrupt 31 */
+ DMA_Error_IRQn = 16, /**< DMA Error Interrupt */
+ MCM_IRQn = 17, /**< Normal Interrupt */
+ FTF_IRQn = 18, /**< FTFA Command complete interrupt */
+ Read_Collision_IRQn = 19, /**< Read Collision Interrupt */
+ LVD_LVW_IRQn = 20, /**< Low Voltage Detect, Low Voltage Warning */
+ LLWU_IRQn = 21, /**< Low Leakage Wakeup Unit */
+ WDOG_EWM_IRQn = 22, /**< WDOG Interrupt */
+ Reserved39_IRQn = 23, /**< Reserved Interrupt 39 */
+ I2C0_IRQn = 24, /**< I2C0 interrupt */
+ Reserved41_IRQn = 25, /**< Reserved Interrupt 41 */
+ SPI0_IRQn = 26, /**< SPI0 Interrupt */
+ Reserved43_IRQn = 27, /**< Reserved Interrupt 43 */
+ Reserved44_IRQn = 28, /**< Reserved Interrupt 44 */
+ Reserved45_IRQn = 29, /**< Reserved interrupt 45 */
+ Reserved46_IRQn = 30, /**< Reserved interrupt 46 */
+ UART0_RX_TX_IRQn = 31, /**< UART0 Receive/Transmit interrupt */
+ UART0_ERR_IRQn = 32, /**< UART0 Error interrupt */
+ UART1_RX_TX_IRQn = 33, /**< UART1 Receive/Transmit interrupt */
+ UART1_ERR_IRQn = 34, /**< UART1 Error interrupt */
+ Reserved51_IRQn = 35, /**< Reserved interrupt 51 */
+ Reserved52_IRQn = 36, /**< Reserved interrupt 52 */
+ Reserved53_IRQn = 37, /**< Reserved interrupt 53 */
+ Reserved54_IRQn = 38, /**< Reserved interrupt 54 */
+ ADC0_IRQn = 39, /**< ADC0 interrupt */
+ CMP0_IRQn = 40, /**< CMP0 interrupt */
+ CMP1_IRQn = 41, /**< CMP1 interrupt */
+ FTM0_IRQn = 42, /**< FTM0 fault, overflow and channels interrupt */
+ FTM1_IRQn = 43, /**< FTM1 fault, overflow and channels interrupt */
+ FTM2_IRQn = 44, /**< FTM2 fault, overflow and channels interrupt */
+ Reserved61_IRQn = 45, /**< Reserved interrupt 61 */
+ Reserved62_IRQn = 46, /**< Reserved interrupt 62 */
+ Reserved63_IRQn = 47, /**< Reserved interrupt 63 */
+ PIT0_IRQn = 48, /**< PIT timer channel 0 interrupt */
+ PIT1_IRQn = 49, /**< PIT timer channel 1 interrupt */
+ PIT2_IRQn = 50, /**< PIT timer channel 2 interrupt */
+ PIT3_IRQn = 51, /**< PIT timer channel 3 interrupt */
+ PDB0_IRQn = 52, /**< PDB0 Interrupt */
+ Reserved69_IRQn = 53, /**< Reserved interrupt 69 */
+ Reserved70_IRQn = 54, /**< Reserved interrupt 70 */
+ Reserved71_IRQn = 55, /**< Reserved interrupt 71 */
+ DAC0_IRQn = 56, /**< DAC0 interrupt */
+ MCG_IRQn = 57, /**< MCG Interrupt */
+ LPTMR0_IRQn = 58, /**< LPTimer interrupt */
+ PORTA_IRQn = 59, /**< Port A interrupt */
+ PORTB_IRQn = 60, /**< Port B interrupt */
+ PORTC_IRQn = 61, /**< Port C interrupt */
+ PORTD_IRQn = 62, /**< Port D interrupt */
+ PORTE_IRQn = 63, /**< Port E interrupt */
+ SWI_IRQn = 64, /**< Software interrupt */
+ Reserved81_IRQn = 65, /**< Reserved interrupt 81 */
+ Reserved82_IRQn = 66, /**< Reserved interrupt 82 */
+ Reserved83_IRQn = 67, /**< Reserved interrupt 83 */
+ Reserved84_IRQn = 68, /**< Reserved interrupt 84 */
+ Reserved85_IRQn = 69, /**< Reserved interrupt 85 */
+ Reserved86_IRQn = 70, /**< Reserved interrupt 86 */
+ Reserved87_IRQn = 71, /**< Reserved interrupt 87 */
+ Reserved88_IRQn = 72, /**< Reserved interrupt 88 */
+ Reserved89_IRQn = 73 /**< Reserved interrupt 89 */
+} IRQn_Type;
+
+/*!
+ * @}
+ */ /* end of group Interrupt_vector_numbers */
+
+
+/* ----------------------------------------------------------------------------
+ -- Cortex M4 Core Configuration
+ ---------------------------------------------------------------------------- */
+
+/*!
+ * @addtogroup Cortex_Core_Configuration Cortex M4 Core Configuration
+ * @{
+ */
+
+#define __MPU_PRESENT 0 /**< Defines if an MPU is present or not */
+#define __NVIC_PRIO_BITS 4 /**< Number of priority bits implemented in the NVIC */
+#define __Vendor_SysTickConfig 0 /**< Vendor specific implementation of SysTickConfig is defined */
+#define __FPU_PRESENT 1 /**< Defines if an FPU is present or not */
+
+#include "core_cm4.h" /* Core Peripheral Access Layer */
+#include "system_MK02F12810.h" /* Device specific configuration file */
+
+/*!
+ * @}
+ */ /* end of group Cortex_Core_Configuration */
+
+
+/* ----------------------------------------------------------------------------
+ -- Mapping Information
+ ---------------------------------------------------------------------------- */
+
+/*!
+ * @addtogroup Mapping_Information Mapping Information
+ * @{
+ */
+
+/** Mapping Information */
+/*!
+ * @addtogroup edma_request
+ * @{
+ */
+
+/*******************************************************************************
+ * Definitions
+ ******************************************************************************/
+
+/*!
+ * @brief Structure for the DMA hardware request
+ *
+ * Defines the structure for the DMA hardware request collections. The user can configure the
+ * hardware request into DMAMUX to trigger the DMA transfer accordingly. The index
+ * of the hardware request varies according to the to SoC.
+ */
+typedef enum _dma_request_source
+{
+ kDmaRequestMux0Disable = 0|0x100U, /**< DMAMUX TriggerDisabled. */
+ kDmaRequestMux0Reserved1 = 1|0x100U, /**< Reserved1 */
+ kDmaRequestMux0UART0Rx = 2|0x100U, /**< UART0 Receive. */
+ kDmaRequestMux0UART0Tx = 3|0x100U, /**< UART0 Transmit. */
+ kDmaRequestMux0UART1Rx = 4|0x100U, /**< UART1 Receive. */
+ kDmaRequestMux0UART1Tx = 5|0x100U, /**< UART1 Transmit. */
+ kDmaRequestMux0Reserved6 = 6|0x100U, /**< Reserved6 */
+ kDmaRequestMux0Reserved7 = 7|0x100U, /**< Reserved7 */
+ kDmaRequestMux0Reserved8 = 8|0x100U, /**< Reserved8 */
+ kDmaRequestMux0Reserved9 = 9|0x100U, /**< Reserved9 */
+ kDmaRequestMux0Reserved10 = 10|0x100U, /**< Reserved10 */
+ kDmaRequestMux0Reserved11 = 11|0x100U, /**< Reserved11 */
+ kDmaRequestMux0Reserved12 = 12|0x100U, /**< Reserved12 */
+ kDmaRequestMux0Reserved13 = 13|0x100U, /**< Reserved13 */
+ kDmaRequestMux0SPI0Rx = 14|0x100U, /**< SPI0 Receive. */
+ kDmaRequestMux0SPI0Tx = 15|0x100U, /**< SPI0 Transmit. */
+ kDmaRequestMux0Reserved16 = 16|0x100U, /**< Reserved16 */
+ kDmaRequestMux0Reserved17 = 17|0x100U, /**< Reserved17 */
+ kDmaRequestMux0I2C0 = 18|0x100U, /**< I2C0. */
+ kDmaRequestMux0Reserved19 = 19|0x100U, /**< Reserved19 */
+ kDmaRequestMux0FTM0Channel0 = 20|0x100U, /**< FTM0 C0V. */
+ kDmaRequestMux0FTM0Channel1 = 21|0x100U, /**< FTM0 C1V. */
+ kDmaRequestMux0FTM0Channel2 = 22|0x100U, /**< FTM0 C2V. */
+ kDmaRequestMux0FTM0Channel3 = 23|0x100U, /**< FTM0 C3V. */
+ kDmaRequestMux0FTM0Channel4 = 24|0x100U, /**< FTM0 C4V. */
+ kDmaRequestMux0FTM0Channel5 = 25|0x100U, /**< FTM0 C5V. */
+ kDmaRequestMux0Reserved26 = 26|0x100U, /**< Reserved26 */
+ kDmaRequestMux0Reserved27 = 27|0x100U, /**< Reserved27 */
+ kDmaRequestMux0FTM1Channel0 = 28|0x100U, /**< FTM1 C0V. */
+ kDmaRequestMux0FTM1Channel1 = 29|0x100U, /**< FTM1 C1V. */
+ kDmaRequestMux0FTM2Channel0 = 30|0x100U, /**< FTM2 C0V. */
+ kDmaRequestMux0FTM2Channel1 = 31|0x100U, /**< FTM2 C1V. */
+ kDmaRequestMux0Reserved32 = 32|0x100U, /**< Reserved32 */
+ kDmaRequestMux0Reserved33 = 33|0x100U, /**< Reserved33 */
+ kDmaRequestMux0Reserved34 = 34|0x100U, /**< Reserved34 */
+ kDmaRequestMux0Reserved35 = 35|0x100U, /**< Reserved35 */
+ kDmaRequestMux0Reserved36 = 36|0x100U, /**< Reserved36 */
+ kDmaRequestMux0Reserved37 = 37|0x100U, /**< Reserved37 */
+ kDmaRequestMux0Reserved38 = 38|0x100U, /**< Reserved38 */
+ kDmaRequestMux0Reserved39 = 39|0x100U, /**< Reserved39 */
+ kDmaRequestMux0ADC0 = 40|0x100U, /**< ADC0. */
+ kDmaRequestMux0Reserved41 = 41|0x100U, /**< Reserved41 */
+ kDmaRequestMux0CMP0 = 42|0x100U, /**< CMP0. */
+ kDmaRequestMux0CMP1 = 43|0x100U, /**< CMP1. */
+ kDmaRequestMux0Reserved44 = 44|0x100U, /**< Reserved44 */
+ kDmaRequestMux0DAC0 = 45|0x100U, /**< DAC0. */
+ kDmaRequestMux0Reserved46 = 46|0x100U, /**< Reserved46 */
+ kDmaRequestMux0Reserved47 = 47|0x100U, /**< Reserved47 */
+ kDmaRequestMux0PDB = 48|0x100U, /**< PDB0. */
+ kDmaRequestMux0PortA = 49|0x100U, /**< PTA. */
+ kDmaRequestMux0PortB = 50|0x100U, /**< PTB. */
+ kDmaRequestMux0PortC = 51|0x100U, /**< PTC. */
+ kDmaRequestMux0PortD = 52|0x100U, /**< PTD. */
+ kDmaRequestMux0PortE = 53|0x100U, /**< PTE. */
+ kDmaRequestMux0Reserved54 = 54|0x100U, /**< Reserved54 */
+ kDmaRequestMux0Reserved55 = 55|0x100U, /**< Reserved55 */
+ kDmaRequestMux0Reserved56 = 56|0x100U, /**< Reserved56 */
+ kDmaRequestMux0Reserved57 = 57|0x100U, /**< Reserved57 */
+ kDmaRequestMux0Reserved58 = 58|0x100U, /**< Reserved58 */
+ kDmaRequestMux0Reserved59 = 59|0x100U, /**< Reserved59 */
+ kDmaRequestMux0AlwaysOn60 = 60|0x100U, /**< DMAMUX Always Enabled slot. */
+ kDmaRequestMux0AlwaysOn61 = 61|0x100U, /**< DMAMUX Always Enabled slot. */
+ kDmaRequestMux0AlwaysOn62 = 62|0x100U, /**< DMAMUX Always Enabled slot. */
+ kDmaRequestMux0AlwaysOn63 = 63|0x100U, /**< DMAMUX Always Enabled slot. */
+} dma_request_source_t;
+
+/* @} */
+
+
+/*!
+ * @}
+ */ /* end of group Mapping_Information */
+
+
+/* ----------------------------------------------------------------------------
+ -- Device Peripheral Access Layer
+ ---------------------------------------------------------------------------- */
+
+/*!
+ * @addtogroup Peripheral_access_layer Device Peripheral Access Layer
+ * @{
+ */
+
+
+/*
+** Start of section using anonymous unions
+*/
+
+#if defined(__ARMCC_VERSION)
+ #if (__ARMCC_VERSION >= 6010050)
+ #pragma clang diagnostic push
+ #else
+ #pragma push
+ #pragma anon_unions
+ #endif
+#elif defined(__CWCC__)
+ #pragma push
+ #pragma cpp_extensions on
+#elif defined(__GNUC__)
+ /* anonymous unions are enabled by default */
+#elif defined(__IAR_SYSTEMS_ICC__)
+ #pragma language=extended
+#else
+ #error Not supported compiler type
+#endif
+
+/* ----------------------------------------------------------------------------
+ -- ADC Peripheral Access Layer
+ ---------------------------------------------------------------------------- */
+
+/*!
+ * @addtogroup ADC_Peripheral_Access_Layer ADC Peripheral Access Layer
+ * @{
+ */
+
+/** ADC - Register Layout Typedef */
+typedef struct {
+ __IO uint32_t SC1[2]; /**< ADC Status and Control Registers 1, array offset: 0x0, array step: 0x4 */
+ __IO uint32_t CFG1; /**< ADC Configuration Register 1, offset: 0x8 */
+ __IO uint32_t CFG2; /**< ADC Configuration Register 2, offset: 0xC */
+ __I uint32_t R[2]; /**< ADC Data Result Register, array offset: 0x10, array step: 0x4 */
+ __IO uint32_t CV1; /**< Compare Value Registers, offset: 0x18 */
+ __IO uint32_t CV2; /**< Compare Value Registers, offset: 0x1C */
+ __IO uint32_t SC2; /**< Status and Control Register 2, offset: 0x20 */
+ __IO uint32_t SC3; /**< Status and Control Register 3, offset: 0x24 */
+ __IO uint32_t OFS; /**< ADC Offset Correction Register, offset: 0x28 */
+ __IO uint32_t PG; /**< ADC Plus-Side Gain Register, offset: 0x2C */
+ __IO uint32_t MG; /**< ADC Minus-Side Gain Register, offset: 0x30 */
+ __IO uint32_t CLPD; /**< ADC Plus-Side General Calibration Value Register, offset: 0x34 */
+ __IO uint32_t CLPS; /**< ADC Plus-Side General Calibration Value Register, offset: 0x38 */
+ __IO uint32_t CLP4; /**< ADC Plus-Side General Calibration Value Register, offset: 0x3C */
+ __IO uint32_t CLP3; /**< ADC Plus-Side General Calibration Value Register, offset: 0x40 */
+ __IO uint32_t CLP2; /**< ADC Plus-Side General Calibration Value Register, offset: 0x44 */
+ __IO uint32_t CLP1; /**< ADC Plus-Side General Calibration Value Register, offset: 0x48 */
+ __IO uint32_t CLP0; /**< ADC Plus-Side General Calibration Value Register, offset: 0x4C */
+ uint8_t RESERVED_0[4];
+ __IO uint32_t CLMD; /**< ADC Minus-Side General Calibration Value Register, offset: 0x54 */
+ __IO uint32_t CLMS; /**< ADC Minus-Side General Calibration Value Register, offset: 0x58 */
+ __IO uint32_t CLM4; /**< ADC Minus-Side General Calibration Value Register, offset: 0x5C */
+ __IO uint32_t CLM3; /**< ADC Minus-Side General Calibration Value Register, offset: 0x60 */
+ __IO uint32_t CLM2; /**< ADC Minus-Side General Calibration Value Register, offset: 0x64 */
+ __IO uint32_t CLM1; /**< ADC Minus-Side General Calibration Value Register, offset: 0x68 */
+ __IO uint32_t CLM0; /**< ADC Minus-Side General Calibration Value Register, offset: 0x6C */
+} ADC_Type;
+
+/* ----------------------------------------------------------------------------
+ -- ADC Register Masks
+ ---------------------------------------------------------------------------- */
+
+/*!
+ * @addtogroup ADC_Register_Masks ADC Register Masks
+ * @{
+ */
+
+/*! @name SC1 - ADC Status and Control Registers 1 */
+#define ADC_SC1_ADCH_MASK (0x1FU)
+#define ADC_SC1_ADCH_SHIFT (0U)
+#define ADC_SC1_ADCH(x) (((uint32_t)(((uint32_t)(x)) << ADC_SC1_ADCH_SHIFT)) & ADC_SC1_ADCH_MASK)
+#define ADC_SC1_DIFF_MASK (0x20U)
+#define ADC_SC1_DIFF_SHIFT (5U)
+#define ADC_SC1_DIFF(x) (((uint32_t)(((uint32_t)(x)) << ADC_SC1_DIFF_SHIFT)) & ADC_SC1_DIFF_MASK)
+#define ADC_SC1_AIEN_MASK (0x40U)
+#define ADC_SC1_AIEN_SHIFT (6U)
+#define ADC_SC1_AIEN(x) (((uint32_t)(((uint32_t)(x)) << ADC_SC1_AIEN_SHIFT)) & ADC_SC1_AIEN_MASK)
+#define ADC_SC1_COCO_MASK (0x80U)
+#define ADC_SC1_COCO_SHIFT (7U)
+#define ADC_SC1_COCO(x) (((uint32_t)(((uint32_t)(x)) << ADC_SC1_COCO_SHIFT)) & ADC_SC1_COCO_MASK)
+
+/* The count of ADC_SC1 */
+#define ADC_SC1_COUNT (2U)
+
+/*! @name CFG1 - ADC Configuration Register 1 */
+#define ADC_CFG1_ADICLK_MASK (0x3U)
+#define ADC_CFG1_ADICLK_SHIFT (0U)
+#define ADC_CFG1_ADICLK(x) (((uint32_t)(((uint32_t)(x)) << ADC_CFG1_ADICLK_SHIFT)) & ADC_CFG1_ADICLK_MASK)
+#define ADC_CFG1_MODE_MASK (0xCU)
+#define ADC_CFG1_MODE_SHIFT (2U)
+#define ADC_CFG1_MODE(x) (((uint32_t)(((uint32_t)(x)) << ADC_CFG1_MODE_SHIFT)) & ADC_CFG1_MODE_MASK)
+#define ADC_CFG1_ADLSMP_MASK (0x10U)
+#define ADC_CFG1_ADLSMP_SHIFT (4U)
+#define ADC_CFG1_ADLSMP(x) (((uint32_t)(((uint32_t)(x)) << ADC_CFG1_ADLSMP_SHIFT)) & ADC_CFG1_ADLSMP_MASK)
+#define ADC_CFG1_ADIV_MASK (0x60U)
+#define ADC_CFG1_ADIV_SHIFT (5U)
+#define ADC_CFG1_ADIV(x) (((uint32_t)(((uint32_t)(x)) << ADC_CFG1_ADIV_SHIFT)) & ADC_CFG1_ADIV_MASK)
+#define ADC_CFG1_ADLPC_MASK (0x80U)
+#define ADC_CFG1_ADLPC_SHIFT (7U)
+#define ADC_CFG1_ADLPC(x) (((uint32_t)(((uint32_t)(x)) << ADC_CFG1_ADLPC_SHIFT)) & ADC_CFG1_ADLPC_MASK)
+
+/*! @name CFG2 - ADC Configuration Register 2 */
+#define ADC_CFG2_ADLSTS_MASK (0x3U)
+#define ADC_CFG2_ADLSTS_SHIFT (0U)
+#define ADC_CFG2_ADLSTS(x) (((uint32_t)(((uint32_t)(x)) << ADC_CFG2_ADLSTS_SHIFT)) & ADC_CFG2_ADLSTS_MASK)
+#define ADC_CFG2_ADHSC_MASK (0x4U)
+#define ADC_CFG2_ADHSC_SHIFT (2U)
+#define ADC_CFG2_ADHSC(x) (((uint32_t)(((uint32_t)(x)) << ADC_CFG2_ADHSC_SHIFT)) & ADC_CFG2_ADHSC_MASK)
+#define ADC_CFG2_ADACKEN_MASK (0x8U)
+#define ADC_CFG2_ADACKEN_SHIFT (3U)
+#define ADC_CFG2_ADACKEN(x) (((uint32_t)(((uint32_t)(x)) << ADC_CFG2_ADACKEN_SHIFT)) & ADC_CFG2_ADACKEN_MASK)
+#define ADC_CFG2_MUXSEL_MASK (0x10U)
+#define ADC_CFG2_MUXSEL_SHIFT (4U)
+#define ADC_CFG2_MUXSEL(x) (((uint32_t)(((uint32_t)(x)) << ADC_CFG2_MUXSEL_SHIFT)) & ADC_CFG2_MUXSEL_MASK)
+
+/*! @name R - ADC Data Result Register */
+#define ADC_R_D_MASK (0xFFFFU)
+#define ADC_R_D_SHIFT (0U)
+#define ADC_R_D(x) (((uint32_t)(((uint32_t)(x)) << ADC_R_D_SHIFT)) & ADC_R_D_MASK)
+
+/* The count of ADC_R */
+#define ADC_R_COUNT (2U)
+
+/*! @name CV1 - Compare Value Registers */
+#define ADC_CV1_CV_MASK (0xFFFFU)
+#define ADC_CV1_CV_SHIFT (0U)
+#define ADC_CV1_CV(x) (((uint32_t)(((uint32_t)(x)) << ADC_CV1_CV_SHIFT)) & ADC_CV1_CV_MASK)
+
+/*! @name CV2 - Compare Value Registers */
+#define ADC_CV2_CV_MASK (0xFFFFU)
+#define ADC_CV2_CV_SHIFT (0U)
+#define ADC_CV2_CV(x) (((uint32_t)(((uint32_t)(x)) << ADC_CV2_CV_SHIFT)) & ADC_CV2_CV_MASK)
+
+/*! @name SC2 - Status and Control Register 2 */
+#define ADC_SC2_REFSEL_MASK (0x3U)
+#define ADC_SC2_REFSEL_SHIFT (0U)
+#define ADC_SC2_REFSEL(x) (((uint32_t)(((uint32_t)(x)) << ADC_SC2_REFSEL_SHIFT)) & ADC_SC2_REFSEL_MASK)
+#define ADC_SC2_DMAEN_MASK (0x4U)
+#define ADC_SC2_DMAEN_SHIFT (2U)
+#define ADC_SC2_DMAEN(x) (((uint32_t)(((uint32_t)(x)) << ADC_SC2_DMAEN_SHIFT)) & ADC_SC2_DMAEN_MASK)
+#define ADC_SC2_ACREN_MASK (0x8U)
+#define ADC_SC2_ACREN_SHIFT (3U)
+#define ADC_SC2_ACREN(x) (((uint32_t)(((uint32_t)(x)) << ADC_SC2_ACREN_SHIFT)) & ADC_SC2_ACREN_MASK)
+#define ADC_SC2_ACFGT_MASK (0x10U)
+#define ADC_SC2_ACFGT_SHIFT (4U)
+#define ADC_SC2_ACFGT(x) (((uint32_t)(((uint32_t)(x)) << ADC_SC2_ACFGT_SHIFT)) & ADC_SC2_ACFGT_MASK)
+#define ADC_SC2_ACFE_MASK (0x20U)
+#define ADC_SC2_ACFE_SHIFT (5U)
+#define ADC_SC2_ACFE(x) (((uint32_t)(((uint32_t)(x)) << ADC_SC2_ACFE_SHIFT)) & ADC_SC2_ACFE_MASK)
+#define ADC_SC2_ADTRG_MASK (0x40U)
+#define ADC_SC2_ADTRG_SHIFT (6U)
+#define ADC_SC2_ADTRG(x) (((uint32_t)(((uint32_t)(x)) << ADC_SC2_ADTRG_SHIFT)) & ADC_SC2_ADTRG_MASK)
+#define ADC_SC2_ADACT_MASK (0x80U)
+#define ADC_SC2_ADACT_SHIFT (7U)
+#define ADC_SC2_ADACT(x) (((uint32_t)(((uint32_t)(x)) << ADC_SC2_ADACT_SHIFT)) & ADC_SC2_ADACT_MASK)
+
+/*! @name SC3 - Status and Control Register 3 */
+#define ADC_SC3_AVGS_MASK (0x3U)
+#define ADC_SC3_AVGS_SHIFT (0U)
+#define ADC_SC3_AVGS(x) (((uint32_t)(((uint32_t)(x)) << ADC_SC3_AVGS_SHIFT)) & ADC_SC3_AVGS_MASK)
+#define ADC_SC3_AVGE_MASK (0x4U)
+#define ADC_SC3_AVGE_SHIFT (2U)
+#define ADC_SC3_AVGE(x) (((uint32_t)(((uint32_t)(x)) << ADC_SC3_AVGE_SHIFT)) & ADC_SC3_AVGE_MASK)
+#define ADC_SC3_ADCO_MASK (0x8U)
+#define ADC_SC3_ADCO_SHIFT (3U)
+#define ADC_SC3_ADCO(x) (((uint32_t)(((uint32_t)(x)) << ADC_SC3_ADCO_SHIFT)) & ADC_SC3_ADCO_MASK)
+#define ADC_SC3_CALF_MASK (0x40U)
+#define ADC_SC3_CALF_SHIFT (6U)
+#define ADC_SC3_CALF(x) (((uint32_t)(((uint32_t)(x)) << ADC_SC3_CALF_SHIFT)) & ADC_SC3_CALF_MASK)
+#define ADC_SC3_CAL_MASK (0x80U)
+#define ADC_SC3_CAL_SHIFT (7U)
+#define ADC_SC3_CAL(x) (((uint32_t)(((uint32_t)(x)) << ADC_SC3_CAL_SHIFT)) & ADC_SC3_CAL_MASK)
+
+/*! @name OFS - ADC Offset Correction Register */
+#define ADC_OFS_OFS_MASK (0xFFFFU)
+#define ADC_OFS_OFS_SHIFT (0U)
+#define ADC_OFS_OFS(x) (((uint32_t)(((uint32_t)(x)) << ADC_OFS_OFS_SHIFT)) & ADC_OFS_OFS_MASK)
+
+/*! @name PG - ADC Plus-Side Gain Register */
+#define ADC_PG_PG_MASK (0xFFFFU)
+#define ADC_PG_PG_SHIFT (0U)
+#define ADC_PG_PG(x) (((uint32_t)(((uint32_t)(x)) << ADC_PG_PG_SHIFT)) & ADC_PG_PG_MASK)
+
+/*! @name MG - ADC Minus-Side Gain Register */
+#define ADC_MG_MG_MASK (0xFFFFU)
+#define ADC_MG_MG_SHIFT (0U)
+#define ADC_MG_MG(x) (((uint32_t)(((uint32_t)(x)) << ADC_MG_MG_SHIFT)) & ADC_MG_MG_MASK)
+
+/*! @name CLPD - ADC Plus-Side General Calibration Value Register */
+#define ADC_CLPD_CLPD_MASK (0x3FU)
+#define ADC_CLPD_CLPD_SHIFT (0U)
+#define ADC_CLPD_CLPD(x) (((uint32_t)(((uint32_t)(x)) << ADC_CLPD_CLPD_SHIFT)) & ADC_CLPD_CLPD_MASK)
+
+/*! @name CLPS - ADC Plus-Side General Calibration Value Register */
+#define ADC_CLPS_CLPS_MASK (0x3FU)
+#define ADC_CLPS_CLPS_SHIFT (0U)
+#define ADC_CLPS_CLPS(x) (((uint32_t)(((uint32_t)(x)) << ADC_CLPS_CLPS_SHIFT)) & ADC_CLPS_CLPS_MASK)
+
+/*! @name CLP4 - ADC Plus-Side General Calibration Value Register */
+#define ADC_CLP4_CLP4_MASK (0x3FFU)
+#define ADC_CLP4_CLP4_SHIFT (0U)
+#define ADC_CLP4_CLP4(x) (((uint32_t)(((uint32_t)(x)) << ADC_CLP4_CLP4_SHIFT)) & ADC_CLP4_CLP4_MASK)
+
+/*! @name CLP3 - ADC Plus-Side General Calibration Value Register */
+#define ADC_CLP3_CLP3_MASK (0x1FFU)
+#define ADC_CLP3_CLP3_SHIFT (0U)
+#define ADC_CLP3_CLP3(x) (((uint32_t)(((uint32_t)(x)) << ADC_CLP3_CLP3_SHIFT)) & ADC_CLP3_CLP3_MASK)
+
+/*! @name CLP2 - ADC Plus-Side General Calibration Value Register */
+#define ADC_CLP2_CLP2_MASK (0xFFU)
+#define ADC_CLP2_CLP2_SHIFT (0U)
+#define ADC_CLP2_CLP2(x) (((uint32_t)(((uint32_t)(x)) << ADC_CLP2_CLP2_SHIFT)) & ADC_CLP2_CLP2_MASK)
+
+/*! @name CLP1 - ADC Plus-Side General Calibration Value Register */
+#define ADC_CLP1_CLP1_MASK (0x7FU)
+#define ADC_CLP1_CLP1_SHIFT (0U)
+#define ADC_CLP1_CLP1(x) (((uint32_t)(((uint32_t)(x)) << ADC_CLP1_CLP1_SHIFT)) & ADC_CLP1_CLP1_MASK)
+
+/*! @name CLP0 - ADC Plus-Side General Calibration Value Register */
+#define ADC_CLP0_CLP0_MASK (0x3FU)
+#define ADC_CLP0_CLP0_SHIFT (0U)
+#define ADC_CLP0_CLP0(x) (((uint32_t)(((uint32_t)(x)) << ADC_CLP0_CLP0_SHIFT)) & ADC_CLP0_CLP0_MASK)
+
+/*! @name CLMD - ADC Minus-Side General Calibration Value Register */
+#define ADC_CLMD_CLMD_MASK (0x3FU)
+#define ADC_CLMD_CLMD_SHIFT (0U)
+#define ADC_CLMD_CLMD(x) (((uint32_t)(((uint32_t)(x)) << ADC_CLMD_CLMD_SHIFT)) & ADC_CLMD_CLMD_MASK)
+
+/*! @name CLMS - ADC Minus-Side General Calibration Value Register */
+#define ADC_CLMS_CLMS_MASK (0x3FU)
+#define ADC_CLMS_CLMS_SHIFT (0U)
+#define ADC_CLMS_CLMS(x) (((uint32_t)(((uint32_t)(x)) << ADC_CLMS_CLMS_SHIFT)) & ADC_CLMS_CLMS_MASK)
+
+/*! @name CLM4 - ADC Minus-Side General Calibration Value Register */
+#define ADC_CLM4_CLM4_MASK (0x3FFU)
+#define ADC_CLM4_CLM4_SHIFT (0U)
+#define ADC_CLM4_CLM4(x) (((uint32_t)(((uint32_t)(x)) << ADC_CLM4_CLM4_SHIFT)) & ADC_CLM4_CLM4_MASK)
+
+/*! @name CLM3 - ADC Minus-Side General Calibration Value Register */
+#define ADC_CLM3_CLM3_MASK (0x1FFU)
+#define ADC_CLM3_CLM3_SHIFT (0U)
+#define ADC_CLM3_CLM3(x) (((uint32_t)(((uint32_t)(x)) << ADC_CLM3_CLM3_SHIFT)) & ADC_CLM3_CLM3_MASK)
+
+/*! @name CLM2 - ADC Minus-Side General Calibration Value Register */
+#define ADC_CLM2_CLM2_MASK (0xFFU)
+#define ADC_CLM2_CLM2_SHIFT (0U)
+#define ADC_CLM2_CLM2(x) (((uint32_t)(((uint32_t)(x)) << ADC_CLM2_CLM2_SHIFT)) & ADC_CLM2_CLM2_MASK)
+
+/*! @name CLM1 - ADC Minus-Side General Calibration Value Register */
+#define ADC_CLM1_CLM1_MASK (0x7FU)
+#define ADC_CLM1_CLM1_SHIFT (0U)
+#define ADC_CLM1_CLM1(x) (((uint32_t)(((uint32_t)(x)) << ADC_CLM1_CLM1_SHIFT)) & ADC_CLM1_CLM1_MASK)
+
+/*! @name CLM0 - ADC Minus-Side General Calibration Value Register */
+#define ADC_CLM0_CLM0_MASK (0x3FU)
+#define ADC_CLM0_CLM0_SHIFT (0U)
+#define ADC_CLM0_CLM0(x) (((uint32_t)(((uint32_t)(x)) << ADC_CLM0_CLM0_SHIFT)) & ADC_CLM0_CLM0_MASK)
+
+
+/*!
+ * @}
+ */ /* end of group ADC_Register_Masks */
+
+
+/* ADC - Peripheral instance base addresses */
+/** Peripheral ADC0 base address */
+#define ADC0_BASE (0x4003B000u)
+/** Peripheral ADC0 base pointer */
+#define ADC0 ((ADC_Type *)ADC0_BASE)
+/** Array initializer of ADC peripheral base addresses */
+#define ADC_BASE_ADDRS { ADC0_BASE }
+/** Array initializer of ADC peripheral base pointers */
+#define ADC_BASE_PTRS { ADC0 }
+/** Interrupt vectors for the ADC peripheral type */
+#define ADC_IRQS { ADC0_IRQn }
+
+/*!
+ * @}
+ */ /* end of group ADC_Peripheral_Access_Layer */
+
+
+/* ----------------------------------------------------------------------------
+ -- CMP Peripheral Access Layer
+ ---------------------------------------------------------------------------- */
+
+/*!
+ * @addtogroup CMP_Peripheral_Access_Layer CMP Peripheral Access Layer
+ * @{
+ */
+
+/** CMP - Register Layout Typedef */
+typedef struct {
+ __IO uint8_t CR0; /**< CMP Control Register 0, offset: 0x0 */
+ __IO uint8_t CR1; /**< CMP Control Register 1, offset: 0x1 */
+ __IO uint8_t FPR; /**< CMP Filter Period Register, offset: 0x2 */
+ __IO uint8_t SCR; /**< CMP Status and Control Register, offset: 0x3 */
+ __IO uint8_t DACCR; /**< DAC Control Register, offset: 0x4 */
+ __IO uint8_t MUXCR; /**< MUX Control Register, offset: 0x5 */
+} CMP_Type;
+
+/* ----------------------------------------------------------------------------
+ -- CMP Register Masks
+ ---------------------------------------------------------------------------- */
+
+/*!
+ * @addtogroup CMP_Register_Masks CMP Register Masks
+ * @{
+ */
+
+/*! @name CR0 - CMP Control Register 0 */
+#define CMP_CR0_HYSTCTR_MASK (0x3U)
+#define CMP_CR0_HYSTCTR_SHIFT (0U)
+#define CMP_CR0_HYSTCTR(x) (((uint8_t)(((uint8_t)(x)) << CMP_CR0_HYSTCTR_SHIFT)) & CMP_CR0_HYSTCTR_MASK)
+#define CMP_CR0_FILTER_CNT_MASK (0x70U)
+#define CMP_CR0_FILTER_CNT_SHIFT (4U)
+#define CMP_CR0_FILTER_CNT(x) (((uint8_t)(((uint8_t)(x)) << CMP_CR0_FILTER_CNT_SHIFT)) & CMP_CR0_FILTER_CNT_MASK)
+
+/*! @name CR1 - CMP Control Register 1 */
+#define CMP_CR1_EN_MASK (0x1U)
+#define CMP_CR1_EN_SHIFT (0U)
+#define CMP_CR1_EN(x) (((uint8_t)(((uint8_t)(x)) << CMP_CR1_EN_SHIFT)) & CMP_CR1_EN_MASK)
+#define CMP_CR1_OPE_MASK (0x2U)
+#define CMP_CR1_OPE_SHIFT (1U)
+#define CMP_CR1_OPE(x) (((uint8_t)(((uint8_t)(x)) << CMP_CR1_OPE_SHIFT)) & CMP_CR1_OPE_MASK)
+#define CMP_CR1_COS_MASK (0x4U)
+#define CMP_CR1_COS_SHIFT (2U)
+#define CMP_CR1_COS(x) (((uint8_t)(((uint8_t)(x)) << CMP_CR1_COS_SHIFT)) & CMP_CR1_COS_MASK)
+#define CMP_CR1_INV_MASK (0x8U)
+#define CMP_CR1_INV_SHIFT (3U)
+#define CMP_CR1_INV(x) (((uint8_t)(((uint8_t)(x)) << CMP_CR1_INV_SHIFT)) & CMP_CR1_INV_MASK)
+#define CMP_CR1_PMODE_MASK (0x10U)
+#define CMP_CR1_PMODE_SHIFT (4U)
+#define CMP_CR1_PMODE(x) (((uint8_t)(((uint8_t)(x)) << CMP_CR1_PMODE_SHIFT)) & CMP_CR1_PMODE_MASK)
+#define CMP_CR1_TRIGM_MASK (0x20U)
+#define CMP_CR1_TRIGM_SHIFT (5U)
+#define CMP_CR1_TRIGM(x) (((uint8_t)(((uint8_t)(x)) << CMP_CR1_TRIGM_SHIFT)) & CMP_CR1_TRIGM_MASK)
+#define CMP_CR1_WE_MASK (0x40U)
+#define CMP_CR1_WE_SHIFT (6U)
+#define CMP_CR1_WE(x) (((uint8_t)(((uint8_t)(x)) << CMP_CR1_WE_SHIFT)) & CMP_CR1_WE_MASK)
+#define CMP_CR1_SE_MASK (0x80U)
+#define CMP_CR1_SE_SHIFT (7U)
+#define CMP_CR1_SE(x) (((uint8_t)(((uint8_t)(x)) << CMP_CR1_SE_SHIFT)) & CMP_CR1_SE_MASK)
+
+/*! @name FPR - CMP Filter Period Register */
+#define CMP_FPR_FILT_PER_MASK (0xFFU)
+#define CMP_FPR_FILT_PER_SHIFT (0U)
+#define CMP_FPR_FILT_PER(x) (((uint8_t)(((uint8_t)(x)) << CMP_FPR_FILT_PER_SHIFT)) & CMP_FPR_FILT_PER_MASK)
+
+/*! @name SCR - CMP Status and Control Register */
+#define CMP_SCR_COUT_MASK (0x1U)
+#define CMP_SCR_COUT_SHIFT (0U)
+#define CMP_SCR_COUT(x) (((uint8_t)(((uint8_t)(x)) << CMP_SCR_COUT_SHIFT)) & CMP_SCR_COUT_MASK)
+#define CMP_SCR_CFF_MASK (0x2U)
+#define CMP_SCR_CFF_SHIFT (1U)
+#define CMP_SCR_CFF(x) (((uint8_t)(((uint8_t)(x)) << CMP_SCR_CFF_SHIFT)) & CMP_SCR_CFF_MASK)
+#define CMP_SCR_CFR_MASK (0x4U)
+#define CMP_SCR_CFR_SHIFT (2U)
+#define CMP_SCR_CFR(x) (((uint8_t)(((uint8_t)(x)) << CMP_SCR_CFR_SHIFT)) & CMP_SCR_CFR_MASK)
+#define CMP_SCR_IEF_MASK (0x8U)
+#define CMP_SCR_IEF_SHIFT (3U)
+#define CMP_SCR_IEF(x) (((uint8_t)(((uint8_t)(x)) << CMP_SCR_IEF_SHIFT)) & CMP_SCR_IEF_MASK)
+#define CMP_SCR_IER_MASK (0x10U)
+#define CMP_SCR_IER_SHIFT (4U)
+#define CMP_SCR_IER(x) (((uint8_t)(((uint8_t)(x)) << CMP_SCR_IER_SHIFT)) & CMP_SCR_IER_MASK)
+#define CMP_SCR_DMAEN_MASK (0x40U)
+#define CMP_SCR_DMAEN_SHIFT (6U)
+#define CMP_SCR_DMAEN(x) (((uint8_t)(((uint8_t)(x)) << CMP_SCR_DMAEN_SHIFT)) & CMP_SCR_DMAEN_MASK)
+
+/*! @name DACCR - DAC Control Register */
+#define CMP_DACCR_VOSEL_MASK (0x3FU)
+#define CMP_DACCR_VOSEL_SHIFT (0U)
+#define CMP_DACCR_VOSEL(x) (((uint8_t)(((uint8_t)(x)) << CMP_DACCR_VOSEL_SHIFT)) & CMP_DACCR_VOSEL_MASK)
+#define CMP_DACCR_VRSEL_MASK (0x40U)
+#define CMP_DACCR_VRSEL_SHIFT (6U)
+#define CMP_DACCR_VRSEL(x) (((uint8_t)(((uint8_t)(x)) << CMP_DACCR_VRSEL_SHIFT)) & CMP_DACCR_VRSEL_MASK)
+#define CMP_DACCR_DACEN_MASK (0x80U)
+#define CMP_DACCR_DACEN_SHIFT (7U)
+#define CMP_DACCR_DACEN(x) (((uint8_t)(((uint8_t)(x)) << CMP_DACCR_DACEN_SHIFT)) & CMP_DACCR_DACEN_MASK)
+
+/*! @name MUXCR - MUX Control Register */
+#define CMP_MUXCR_MSEL_MASK (0x7U)
+#define CMP_MUXCR_MSEL_SHIFT (0U)
+#define CMP_MUXCR_MSEL(x) (((uint8_t)(((uint8_t)(x)) << CMP_MUXCR_MSEL_SHIFT)) & CMP_MUXCR_MSEL_MASK)
+#define CMP_MUXCR_PSEL_MASK (0x38U)
+#define CMP_MUXCR_PSEL_SHIFT (3U)
+#define CMP_MUXCR_PSEL(x) (((uint8_t)(((uint8_t)(x)) << CMP_MUXCR_PSEL_SHIFT)) & CMP_MUXCR_PSEL_MASK)
+
+
+/*!
+ * @}
+ */ /* end of group CMP_Register_Masks */
+
+
+/* CMP - Peripheral instance base addresses */
+/** Peripheral CMP0 base address */
+#define CMP0_BASE (0x40073000u)
+/** Peripheral CMP0 base pointer */
+#define CMP0 ((CMP_Type *)CMP0_BASE)
+/** Peripheral CMP1 base address */
+#define CMP1_BASE (0x40073008u)
+/** Peripheral CMP1 base pointer */
+#define CMP1 ((CMP_Type *)CMP1_BASE)
+/** Array initializer of CMP peripheral base addresses */
+#define CMP_BASE_ADDRS { CMP0_BASE, CMP1_BASE }
+/** Array initializer of CMP peripheral base pointers */
+#define CMP_BASE_PTRS { CMP0, CMP1 }
+/** Interrupt vectors for the CMP peripheral type */
+#define CMP_IRQS { CMP0_IRQn, CMP1_IRQn }
+
+/*!
+ * @}
+ */ /* end of group CMP_Peripheral_Access_Layer */
+
+
+/* ----------------------------------------------------------------------------
+ -- CRC Peripheral Access Layer
+ ---------------------------------------------------------------------------- */
+
+/*!
+ * @addtogroup CRC_Peripheral_Access_Layer CRC Peripheral Access Layer
+ * @{
+ */
+
+/** CRC - Register Layout Typedef */
+typedef struct {
+ union { /* offset: 0x0 */
+ struct { /* offset: 0x0 */
+ __IO uint16_t DATAL; /**< CRC_DATAL register., offset: 0x0 */
+ __IO uint16_t DATAH; /**< CRC_DATAH register., offset: 0x2 */
+ } ACCESS16BIT;
+ __IO uint32_t DATA; /**< CRC Data register, offset: 0x0 */
+ struct { /* offset: 0x0 */
+ __IO uint8_t DATALL; /**< CRC_DATALL register., offset: 0x0 */
+ __IO uint8_t DATALU; /**< CRC_DATALU register., offset: 0x1 */
+ __IO uint8_t DATAHL; /**< CRC_DATAHL register., offset: 0x2 */
+ __IO uint8_t DATAHU; /**< CRC_DATAHU register., offset: 0x3 */
+ } ACCESS8BIT;
+ };
+ union { /* offset: 0x4 */
+ struct { /* offset: 0x4 */
+ __IO uint16_t GPOLYL; /**< CRC_GPOLYL register., offset: 0x4 */
+ __IO uint16_t GPOLYH; /**< CRC_GPOLYH register., offset: 0x6 */
+ } GPOLY_ACCESS16BIT;
+ __IO uint32_t GPOLY; /**< CRC Polynomial register, offset: 0x4 */
+ struct { /* offset: 0x4 */
+ __IO uint8_t GPOLYLL; /**< CRC_GPOLYLL register., offset: 0x4 */
+ __IO uint8_t GPOLYLU; /**< CRC_GPOLYLU register., offset: 0x5 */
+ __IO uint8_t GPOLYHL; /**< CRC_GPOLYHL register., offset: 0x6 */
+ __IO uint8_t GPOLYHU; /**< CRC_GPOLYHU register., offset: 0x7 */
+ } GPOLY_ACCESS8BIT;
+ };
+ union { /* offset: 0x8 */
+ __IO uint32_t CTRL; /**< CRC Control register, offset: 0x8 */
+ struct { /* offset: 0x8 */
+ uint8_t RESERVED_0[3];
+ __IO uint8_t CTRLHU; /**< CRC_CTRLHU register., offset: 0xB */
+ } CTRL_ACCESS8BIT;
+ };
+} CRC_Type;
+
+/* ----------------------------------------------------------------------------
+ -- CRC Register Masks
+ ---------------------------------------------------------------------------- */
+
+/*!
+ * @addtogroup CRC_Register_Masks CRC Register Masks
+ * @{
+ */
+
+/*! @name DATAL - CRC_DATAL register. */
+#define CRC_DATAL_DATAL_MASK (0xFFFFU)
+#define CRC_DATAL_DATAL_SHIFT (0U)
+#define CRC_DATAL_DATAL(x) (((uint16_t)(((uint16_t)(x)) << CRC_DATAL_DATAL_SHIFT)) & CRC_DATAL_DATAL_MASK)
+
+/*! @name DATAH - CRC_DATAH register. */
+#define CRC_DATAH_DATAH_MASK (0xFFFFU)
+#define CRC_DATAH_DATAH_SHIFT (0U)
+#define CRC_DATAH_DATAH(x) (((uint16_t)(((uint16_t)(x)) << CRC_DATAH_DATAH_SHIFT)) & CRC_DATAH_DATAH_MASK)
+
+/*! @name DATA - CRC Data register */
+#define CRC_DATA_LL_MASK (0xFFU)
+#define CRC_DATA_LL_SHIFT (0U)
+#define CRC_DATA_LL(x) (((uint32_t)(((uint32_t)(x)) << CRC_DATA_LL_SHIFT)) & CRC_DATA_LL_MASK)
+#define CRC_DATA_LU_MASK (0xFF00U)
+#define CRC_DATA_LU_SHIFT (8U)
+#define CRC_DATA_LU(x) (((uint32_t)(((uint32_t)(x)) << CRC_DATA_LU_SHIFT)) & CRC_DATA_LU_MASK)
+#define CRC_DATA_HL_MASK (0xFF0000U)
+#define CRC_DATA_HL_SHIFT (16U)
+#define CRC_DATA_HL(x) (((uint32_t)(((uint32_t)(x)) << CRC_DATA_HL_SHIFT)) & CRC_DATA_HL_MASK)
+#define CRC_DATA_HU_MASK (0xFF000000U)
+#define CRC_DATA_HU_SHIFT (24U)
+#define CRC_DATA_HU(x) (((uint32_t)(((uint32_t)(x)) << CRC_DATA_HU_SHIFT)) & CRC_DATA_HU_MASK)
+
+/*! @name DATALL - CRC_DATALL register. */
+#define CRC_DATALL_DATALL_MASK (0xFFU)
+#define CRC_DATALL_DATALL_SHIFT (0U)
+#define CRC_DATALL_DATALL(x) (((uint8_t)(((uint8_t)(x)) << CRC_DATALL_DATALL_SHIFT)) & CRC_DATALL_DATALL_MASK)
+
+/*! @name DATALU - CRC_DATALU register. */
+#define CRC_DATALU_DATALU_MASK (0xFFU)
+#define CRC_DATALU_DATALU_SHIFT (0U)
+#define CRC_DATALU_DATALU(x) (((uint8_t)(((uint8_t)(x)) << CRC_DATALU_DATALU_SHIFT)) & CRC_DATALU_DATALU_MASK)
+
+/*! @name DATAHL - CRC_DATAHL register. */
+#define CRC_DATAHL_DATAHL_MASK (0xFFU)
+#define CRC_DATAHL_DATAHL_SHIFT (0U)
+#define CRC_DATAHL_DATAHL(x) (((uint8_t)(((uint8_t)(x)) << CRC_DATAHL_DATAHL_SHIFT)) & CRC_DATAHL_DATAHL_MASK)
+
+/*! @name DATAHU - CRC_DATAHU register. */
+#define CRC_DATAHU_DATAHU_MASK (0xFFU)
+#define CRC_DATAHU_DATAHU_SHIFT (0U)
+#define CRC_DATAHU_DATAHU(x) (((uint8_t)(((uint8_t)(x)) << CRC_DATAHU_DATAHU_SHIFT)) & CRC_DATAHU_DATAHU_MASK)
+
+/*! @name GPOLYL - CRC_GPOLYL register. */
+#define CRC_GPOLYL_GPOLYL_MASK (0xFFFFU)
+#define CRC_GPOLYL_GPOLYL_SHIFT (0U)
+#define CRC_GPOLYL_GPOLYL(x) (((uint16_t)(((uint16_t)(x)) << CRC_GPOLYL_GPOLYL_SHIFT)) & CRC_GPOLYL_GPOLYL_MASK)
+
+/*! @name GPOLYH - CRC_GPOLYH register. */
+#define CRC_GPOLYH_GPOLYH_MASK (0xFFFFU)
+#define CRC_GPOLYH_GPOLYH_SHIFT (0U)
+#define CRC_GPOLYH_GPOLYH(x) (((uint16_t)(((uint16_t)(x)) << CRC_GPOLYH_GPOLYH_SHIFT)) & CRC_GPOLYH_GPOLYH_MASK)
+
+/*! @name GPOLY - CRC Polynomial register */
+#define CRC_GPOLY_LOW_MASK (0xFFFFU)
+#define CRC_GPOLY_LOW_SHIFT (0U)
+#define CRC_GPOLY_LOW(x) (((uint32_t)(((uint32_t)(x)) << CRC_GPOLY_LOW_SHIFT)) & CRC_GPOLY_LOW_MASK)
+#define CRC_GPOLY_HIGH_MASK (0xFFFF0000U)
+#define CRC_GPOLY_HIGH_SHIFT (16U)
+#define CRC_GPOLY_HIGH(x) (((uint32_t)(((uint32_t)(x)) << CRC_GPOLY_HIGH_SHIFT)) & CRC_GPOLY_HIGH_MASK)
+
+/*! @name GPOLYLL - CRC_GPOLYLL register. */
+#define CRC_GPOLYLL_GPOLYLL_MASK (0xFFU)
+#define CRC_GPOLYLL_GPOLYLL_SHIFT (0U)
+#define CRC_GPOLYLL_GPOLYLL(x) (((uint8_t)(((uint8_t)(x)) << CRC_GPOLYLL_GPOLYLL_SHIFT)) & CRC_GPOLYLL_GPOLYLL_MASK)
+
+/*! @name GPOLYLU - CRC_GPOLYLU register. */
+#define CRC_GPOLYLU_GPOLYLU_MASK (0xFFU)
+#define CRC_GPOLYLU_GPOLYLU_SHIFT (0U)
+#define CRC_GPOLYLU_GPOLYLU(x) (((uint8_t)(((uint8_t)(x)) << CRC_GPOLYLU_GPOLYLU_SHIFT)) & CRC_GPOLYLU_GPOLYLU_MASK)
+
+/*! @name GPOLYHL - CRC_GPOLYHL register. */
+#define CRC_GPOLYHL_GPOLYHL_MASK (0xFFU)
+#define CRC_GPOLYHL_GPOLYHL_SHIFT (0U)
+#define CRC_GPOLYHL_GPOLYHL(x) (((uint8_t)(((uint8_t)(x)) << CRC_GPOLYHL_GPOLYHL_SHIFT)) & CRC_GPOLYHL_GPOLYHL_MASK)
+
+/*! @name GPOLYHU - CRC_GPOLYHU register. */
+#define CRC_GPOLYHU_GPOLYHU_MASK (0xFFU)
+#define CRC_GPOLYHU_GPOLYHU_SHIFT (0U)
+#define CRC_GPOLYHU_GPOLYHU(x) (((uint8_t)(((uint8_t)(x)) << CRC_GPOLYHU_GPOLYHU_SHIFT)) & CRC_GPOLYHU_GPOLYHU_MASK)
+
+/*! @name CTRL - CRC Control register */
+#define CRC_CTRL_TCRC_MASK (0x1000000U)
+#define CRC_CTRL_TCRC_SHIFT (24U)
+#define CRC_CTRL_TCRC(x) (((uint32_t)(((uint32_t)(x)) << CRC_CTRL_TCRC_SHIFT)) & CRC_CTRL_TCRC_MASK)
+#define CRC_CTRL_WAS_MASK (0x2000000U)
+#define CRC_CTRL_WAS_SHIFT (25U)
+#define CRC_CTRL_WAS(x) (((uint32_t)(((uint32_t)(x)) << CRC_CTRL_WAS_SHIFT)) & CRC_CTRL_WAS_MASK)
+#define CRC_CTRL_FXOR_MASK (0x4000000U)
+#define CRC_CTRL_FXOR_SHIFT (26U)
+#define CRC_CTRL_FXOR(x) (((uint32_t)(((uint32_t)(x)) << CRC_CTRL_FXOR_SHIFT)) & CRC_CTRL_FXOR_MASK)
+#define CRC_CTRL_TOTR_MASK (0x30000000U)
+#define CRC_CTRL_TOTR_SHIFT (28U)
+#define CRC_CTRL_TOTR(x) (((uint32_t)(((uint32_t)(x)) << CRC_CTRL_TOTR_SHIFT)) & CRC_CTRL_TOTR_MASK)
+#define CRC_CTRL_TOT_MASK (0xC0000000U)
+#define CRC_CTRL_TOT_SHIFT (30U)
+#define CRC_CTRL_TOT(x) (((uint32_t)(((uint32_t)(x)) << CRC_CTRL_TOT_SHIFT)) & CRC_CTRL_TOT_MASK)
+
+/*! @name CTRLHU - CRC_CTRLHU register. */
+#define CRC_CTRLHU_TCRC_MASK (0x1U)
+#define CRC_CTRLHU_TCRC_SHIFT (0U)
+#define CRC_CTRLHU_TCRC(x) (((uint8_t)(((uint8_t)(x)) << CRC_CTRLHU_TCRC_SHIFT)) & CRC_CTRLHU_TCRC_MASK)
+#define CRC_CTRLHU_WAS_MASK (0x2U)
+#define CRC_CTRLHU_WAS_SHIFT (1U)
+#define CRC_CTRLHU_WAS(x) (((uint8_t)(((uint8_t)(x)) << CRC_CTRLHU_WAS_SHIFT)) & CRC_CTRLHU_WAS_MASK)
+#define CRC_CTRLHU_FXOR_MASK (0x4U)
+#define CRC_CTRLHU_FXOR_SHIFT (2U)
+#define CRC_CTRLHU_FXOR(x) (((uint8_t)(((uint8_t)(x)) << CRC_CTRLHU_FXOR_SHIFT)) & CRC_CTRLHU_FXOR_MASK)
+#define CRC_CTRLHU_TOTR_MASK (0x30U)
+#define CRC_CTRLHU_TOTR_SHIFT (4U)
+#define CRC_CTRLHU_TOTR(x) (((uint8_t)(((uint8_t)(x)) << CRC_CTRLHU_TOTR_SHIFT)) & CRC_CTRLHU_TOTR_MASK)
+#define CRC_CTRLHU_TOT_MASK (0xC0U)
+#define CRC_CTRLHU_TOT_SHIFT (6U)
+#define CRC_CTRLHU_TOT(x) (((uint8_t)(((uint8_t)(x)) << CRC_CTRLHU_TOT_SHIFT)) & CRC_CTRLHU_TOT_MASK)
+
+
+/*!
+ * @}
+ */ /* end of group CRC_Register_Masks */
+
+
+/* CRC - Peripheral instance base addresses */
+/** Peripheral CRC base address */
+#define CRC_BASE (0x40032000u)
+/** Peripheral CRC base pointer */
+#define CRC0 ((CRC_Type *)CRC_BASE)
+/** Array initializer of CRC peripheral base addresses */
+#define CRC_BASE_ADDRS { CRC_BASE }
+/** Array initializer of CRC peripheral base pointers */
+#define CRC_BASE_PTRS { CRC0 }
+
+/*!
+ * @}
+ */ /* end of group CRC_Peripheral_Access_Layer */
+
+
+/* ----------------------------------------------------------------------------
+ -- DAC Peripheral Access Layer
+ ---------------------------------------------------------------------------- */
+
+/*!
+ * @addtogroup DAC_Peripheral_Access_Layer DAC Peripheral Access Layer
+ * @{
+ */
+
+/** DAC - Register Layout Typedef */
+typedef struct {
+ struct { /* offset: 0x0, array step: 0x2 */
+ __IO uint8_t DATL; /**< DAC Data Low Register, array offset: 0x0, array step: 0x2 */
+ __IO uint8_t DATH; /**< DAC Data High Register, array offset: 0x1, array step: 0x2 */
+ } DAT[16];
+ __IO uint8_t SR; /**< DAC Status Register, offset: 0x20 */
+ __IO uint8_t C0; /**< DAC Control Register, offset: 0x21 */
+ __IO uint8_t C1; /**< DAC Control Register 1, offset: 0x22 */
+ __IO uint8_t C2; /**< DAC Control Register 2, offset: 0x23 */
+} DAC_Type;
+
+/* ----------------------------------------------------------------------------
+ -- DAC Register Masks
+ ---------------------------------------------------------------------------- */
+
+/*!
+ * @addtogroup DAC_Register_Masks DAC Register Masks
+ * @{
+ */
+
+/*! @name DATL - DAC Data Low Register */
+#define DAC_DATL_DATA0_MASK (0xFFU)
+#define DAC_DATL_DATA0_SHIFT (0U)
+#define DAC_DATL_DATA0(x) (((uint8_t)(((uint8_t)(x)) << DAC_DATL_DATA0_SHIFT)) & DAC_DATL_DATA0_MASK)
+
+/* The count of DAC_DATL */
+#define DAC_DATL_COUNT (16U)
+
+/*! @name DATH - DAC Data High Register */
+#define DAC_DATH_DATA1_MASK (0xFU)
+#define DAC_DATH_DATA1_SHIFT (0U)
+#define DAC_DATH_DATA1(x) (((uint8_t)(((uint8_t)(x)) << DAC_DATH_DATA1_SHIFT)) & DAC_DATH_DATA1_MASK)
+
+/* The count of DAC_DATH */
+#define DAC_DATH_COUNT (16U)
+
+/*! @name SR - DAC Status Register */
+#define DAC_SR_DACBFRPBF_MASK (0x1U)
+#define DAC_SR_DACBFRPBF_SHIFT (0U)
+#define DAC_SR_DACBFRPBF(x) (((uint8_t)(((uint8_t)(x)) << DAC_SR_DACBFRPBF_SHIFT)) & DAC_SR_DACBFRPBF_MASK)
+#define DAC_SR_DACBFRPTF_MASK (0x2U)
+#define DAC_SR_DACBFRPTF_SHIFT (1U)
+#define DAC_SR_DACBFRPTF(x) (((uint8_t)(((uint8_t)(x)) << DAC_SR_DACBFRPTF_SHIFT)) & DAC_SR_DACBFRPTF_MASK)
+#define DAC_SR_DACBFWMF_MASK (0x4U)
+#define DAC_SR_DACBFWMF_SHIFT (2U)
+#define DAC_SR_DACBFWMF(x) (((uint8_t)(((uint8_t)(x)) << DAC_SR_DACBFWMF_SHIFT)) & DAC_SR_DACBFWMF_MASK)
+
+/*! @name C0 - DAC Control Register */
+#define DAC_C0_DACBBIEN_MASK (0x1U)
+#define DAC_C0_DACBBIEN_SHIFT (0U)
+#define DAC_C0_DACBBIEN(x) (((uint8_t)(((uint8_t)(x)) << DAC_C0_DACBBIEN_SHIFT)) & DAC_C0_DACBBIEN_MASK)
+#define DAC_C0_DACBTIEN_MASK (0x2U)
+#define DAC_C0_DACBTIEN_SHIFT (1U)
+#define DAC_C0_DACBTIEN(x) (((uint8_t)(((uint8_t)(x)) << DAC_C0_DACBTIEN_SHIFT)) & DAC_C0_DACBTIEN_MASK)
+#define DAC_C0_DACBWIEN_MASK (0x4U)
+#define DAC_C0_DACBWIEN_SHIFT (2U)
+#define DAC_C0_DACBWIEN(x) (((uint8_t)(((uint8_t)(x)) << DAC_C0_DACBWIEN_SHIFT)) & DAC_C0_DACBWIEN_MASK)
+#define DAC_C0_LPEN_MASK (0x8U)
+#define DAC_C0_LPEN_SHIFT (3U)
+#define DAC_C0_LPEN(x) (((uint8_t)(((uint8_t)(x)) << DAC_C0_LPEN_SHIFT)) & DAC_C0_LPEN_MASK)
+#define DAC_C0_DACSWTRG_MASK (0x10U)
+#define DAC_C0_DACSWTRG_SHIFT (4U)
+#define DAC_C0_DACSWTRG(x) (((uint8_t)(((uint8_t)(x)) << DAC_C0_DACSWTRG_SHIFT)) & DAC_C0_DACSWTRG_MASK)
+#define DAC_C0_DACTRGSEL_MASK (0x20U)
+#define DAC_C0_DACTRGSEL_SHIFT (5U)
+#define DAC_C0_DACTRGSEL(x) (((uint8_t)(((uint8_t)(x)) << DAC_C0_DACTRGSEL_SHIFT)) & DAC_C0_DACTRGSEL_MASK)
+#define DAC_C0_DACRFS_MASK (0x40U)
+#define DAC_C0_DACRFS_SHIFT (6U)
+#define DAC_C0_DACRFS(x) (((uint8_t)(((uint8_t)(x)) << DAC_C0_DACRFS_SHIFT)) & DAC_C0_DACRFS_MASK)
+#define DAC_C0_DACEN_MASK (0x80U)
+#define DAC_C0_DACEN_SHIFT (7U)
+#define DAC_C0_DACEN(x) (((uint8_t)(((uint8_t)(x)) << DAC_C0_DACEN_SHIFT)) & DAC_C0_DACEN_MASK)
+
+/*! @name C1 - DAC Control Register 1 */
+#define DAC_C1_DACBFEN_MASK (0x1U)
+#define DAC_C1_DACBFEN_SHIFT (0U)
+#define DAC_C1_DACBFEN(x) (((uint8_t)(((uint8_t)(x)) << DAC_C1_DACBFEN_SHIFT)) & DAC_C1_DACBFEN_MASK)
+#define DAC_C1_DACBFMD_MASK (0x6U)
+#define DAC_C1_DACBFMD_SHIFT (1U)
+#define DAC_C1_DACBFMD(x) (((uint8_t)(((uint8_t)(x)) << DAC_C1_DACBFMD_SHIFT)) & DAC_C1_DACBFMD_MASK)
+#define DAC_C1_DACBFWM_MASK (0x18U)
+#define DAC_C1_DACBFWM_SHIFT (3U)
+#define DAC_C1_DACBFWM(x) (((uint8_t)(((uint8_t)(x)) << DAC_C1_DACBFWM_SHIFT)) & DAC_C1_DACBFWM_MASK)
+#define DAC_C1_DMAEN_MASK (0x80U)
+#define DAC_C1_DMAEN_SHIFT (7U)
+#define DAC_C1_DMAEN(x) (((uint8_t)(((uint8_t)(x)) << DAC_C1_DMAEN_SHIFT)) & DAC_C1_DMAEN_MASK)
+
+/*! @name C2 - DAC Control Register 2 */
+#define DAC_C2_DACBFUP_MASK (0xFU)
+#define DAC_C2_DACBFUP_SHIFT (0U)
+#define DAC_C2_DACBFUP(x) (((uint8_t)(((uint8_t)(x)) << DAC_C2_DACBFUP_SHIFT)) & DAC_C2_DACBFUP_MASK)
+#define DAC_C2_DACBFRP_MASK (0xF0U)
+#define DAC_C2_DACBFRP_SHIFT (4U)
+#define DAC_C2_DACBFRP(x) (((uint8_t)(((uint8_t)(x)) << DAC_C2_DACBFRP_SHIFT)) & DAC_C2_DACBFRP_MASK)
+
+
+/*!
+ * @}
+ */ /* end of group DAC_Register_Masks */
+
+
+/* DAC - Peripheral instance base addresses */
+/** Peripheral DAC0 base address */
+#define DAC0_BASE (0x4003F000u)
+/** Peripheral DAC0 base pointer */
+#define DAC0 ((DAC_Type *)DAC0_BASE)
+/** Array initializer of DAC peripheral base addresses */
+#define DAC_BASE_ADDRS { DAC0_BASE }
+/** Array initializer of DAC peripheral base pointers */
+#define DAC_BASE_PTRS { DAC0 }
+/** Interrupt vectors for the DAC peripheral type */
+#define DAC_IRQS { DAC0_IRQn }
+
+/*!
+ * @}
+ */ /* end of group DAC_Peripheral_Access_Layer */
+
+
+/* ----------------------------------------------------------------------------
+ -- DMA Peripheral Access Layer
+ ---------------------------------------------------------------------------- */
+
+/*!
+ * @addtogroup DMA_Peripheral_Access_Layer DMA Peripheral Access Layer
+ * @{
+ */
+
+/** DMA - Register Layout Typedef */
+typedef struct {
+ __IO uint32_t CR; /**< Control Register, offset: 0x0 */
+ __I uint32_t ES; /**< Error Status Register, offset: 0x4 */
+ uint8_t RESERVED_0[4];
+ __IO uint32_t ERQ; /**< Enable Request Register, offset: 0xC */
+ uint8_t RESERVED_1[4];
+ __IO uint32_t EEI; /**< Enable Error Interrupt Register, offset: 0x14 */
+ __O uint8_t CEEI; /**< Clear Enable Error Interrupt Register, offset: 0x18 */
+ __O uint8_t SEEI; /**< Set Enable Error Interrupt Register, offset: 0x19 */
+ __O uint8_t CERQ; /**< Clear Enable Request Register, offset: 0x1A */
+ __O uint8_t SERQ; /**< Set Enable Request Register, offset: 0x1B */
+ __O uint8_t CDNE; /**< Clear DONE Status Bit Register, offset: 0x1C */
+ __O uint8_t SSRT; /**< Set START Bit Register, offset: 0x1D */
+ __O uint8_t CERR; /**< Clear Error Register, offset: 0x1E */
+ __O uint8_t CINT; /**< Clear Interrupt Request Register, offset: 0x1F */
+ uint8_t RESERVED_2[4];
+ __IO uint32_t INT; /**< Interrupt Request Register, offset: 0x24 */
+ uint8_t RESERVED_3[4];
+ __IO uint32_t ERR; /**< Error Register, offset: 0x2C */
+ uint8_t RESERVED_4[4];
+ __I uint32_t HRS; /**< Hardware Request Status Register, offset: 0x34 */
+ uint8_t RESERVED_5[12];
+ __IO uint32_t EARS; /**< Enable Asynchronous Request in Stop Register, offset: 0x44 */
+ uint8_t RESERVED_6[184];
+ __IO uint8_t DCHPRI3; /**< Channel n Priority Register, offset: 0x100 */
+ __IO uint8_t DCHPRI2; /**< Channel n Priority Register, offset: 0x101 */
+ __IO uint8_t DCHPRI1; /**< Channel n Priority Register, offset: 0x102 */
+ __IO uint8_t DCHPRI0; /**< Channel n Priority Register, offset: 0x103 */
+ uint8_t RESERVED_7[3836];
+ struct { /* offset: 0x1000, array step: 0x20 */
+ __IO uint32_t SADDR; /**< TCD Source Address, array offset: 0x1000, array step: 0x20 */
+ __IO uint16_t SOFF; /**< TCD Signed Source Address Offset, array offset: 0x1004, array step: 0x20 */
+ __IO uint16_t ATTR; /**< TCD Transfer Attributes, array offset: 0x1006, array step: 0x20 */
+ union { /* offset: 0x1008, array step: 0x20 */
+ __IO uint32_t NBYTES_MLNO; /**< TCD Minor Byte Count (Minor Loop Disabled), array offset: 0x1008, array step: 0x20 */
+ __IO uint32_t NBYTES_MLOFFNO; /**< TCD Signed Minor Loop Offset (Minor Loop Enabled and Offset Disabled), array offset: 0x1008, array step: 0x20 */
+ __IO uint32_t NBYTES_MLOFFYES; /**< TCD Signed Minor Loop Offset (Minor Loop and Offset Enabled), array offset: 0x1008, array step: 0x20 */
+ };
+ __IO uint32_t SLAST; /**< TCD Last Source Address Adjustment, array offset: 0x100C, array step: 0x20 */
+ __IO uint32_t DADDR; /**< TCD Destination Address, array offset: 0x1010, array step: 0x20 */
+ __IO uint16_t DOFF; /**< TCD Signed Destination Address Offset, array offset: 0x1014, array step: 0x20 */
+ union { /* offset: 0x1016, array step: 0x20 */
+ __IO uint16_t CITER_ELINKNO; /**< TCD Current Minor Loop Link, Major Loop Count (Channel Linking Disabled), array offset: 0x1016, array step: 0x20 */
+ __IO uint16_t CITER_ELINKYES; /**< TCD Current Minor Loop Link, Major Loop Count (Channel Linking Enabled), array offset: 0x1016, array step: 0x20 */
+ };
+ __IO uint32_t DLAST_SGA; /**< TCD Last Destination Address Adjustment/Scatter Gather Address, array offset: 0x1018, array step: 0x20 */
+ __IO uint16_t CSR; /**< TCD Control and Status, array offset: 0x101C, array step: 0x20 */
+ union { /* offset: 0x101E, array step: 0x20 */
+ __IO uint16_t BITER_ELINKNO; /**< TCD Beginning Minor Loop Link, Major Loop Count (Channel Linking Disabled), array offset: 0x101E, array step: 0x20 */
+ __IO uint16_t BITER_ELINKYES; /**< TCD Beginning Minor Loop Link, Major Loop Count (Channel Linking Enabled), array offset: 0x101E, array step: 0x20 */
+ };
+ } TCD[4];
+} DMA_Type;
+
+/* ----------------------------------------------------------------------------
+ -- DMA Register Masks
+ ---------------------------------------------------------------------------- */
+
+/*!
+ * @addtogroup DMA_Register_Masks DMA Register Masks
+ * @{
+ */
+
+/*! @name CR - Control Register */
+#define DMA_CR_EDBG_MASK (0x2U)
+#define DMA_CR_EDBG_SHIFT (1U)
+#define DMA_CR_EDBG(x) (((uint32_t)(((uint32_t)(x)) << DMA_CR_EDBG_SHIFT)) & DMA_CR_EDBG_MASK)
+#define DMA_CR_ERCA_MASK (0x4U)
+#define DMA_CR_ERCA_SHIFT (2U)
+#define DMA_CR_ERCA(x) (((uint32_t)(((uint32_t)(x)) << DMA_CR_ERCA_SHIFT)) & DMA_CR_ERCA_MASK)
+#define DMA_CR_HOE_MASK (0x10U)
+#define DMA_CR_HOE_SHIFT (4U)
+#define DMA_CR_HOE(x) (((uint32_t)(((uint32_t)(x)) << DMA_CR_HOE_SHIFT)) & DMA_CR_HOE_MASK)
+#define DMA_CR_HALT_MASK (0x20U)
+#define DMA_CR_HALT_SHIFT (5U)
+#define DMA_CR_HALT(x) (((uint32_t)(((uint32_t)(x)) << DMA_CR_HALT_SHIFT)) & DMA_CR_HALT_MASK)
+#define DMA_CR_CLM_MASK (0x40U)
+#define DMA_CR_CLM_SHIFT (6U)
+#define DMA_CR_CLM(x) (((uint32_t)(((uint32_t)(x)) << DMA_CR_CLM_SHIFT)) & DMA_CR_CLM_MASK)
+#define DMA_CR_EMLM_MASK (0x80U)
+#define DMA_CR_EMLM_SHIFT (7U)
+#define DMA_CR_EMLM(x) (((uint32_t)(((uint32_t)(x)) << DMA_CR_EMLM_SHIFT)) & DMA_CR_EMLM_MASK)
+#define DMA_CR_ECX_MASK (0x10000U)
+#define DMA_CR_ECX_SHIFT (16U)
+#define DMA_CR_ECX(x) (((uint32_t)(((uint32_t)(x)) << DMA_CR_ECX_SHIFT)) & DMA_CR_ECX_MASK)
+#define DMA_CR_CX_MASK (0x20000U)
+#define DMA_CR_CX_SHIFT (17U)
+#define DMA_CR_CX(x) (((uint32_t)(((uint32_t)(x)) << DMA_CR_CX_SHIFT)) & DMA_CR_CX_MASK)
+
+/*! @name ES - Error Status Register */
+#define DMA_ES_DBE_MASK (0x1U)
+#define DMA_ES_DBE_SHIFT (0U)
+#define DMA_ES_DBE(x) (((uint32_t)(((uint32_t)(x)) << DMA_ES_DBE_SHIFT)) & DMA_ES_DBE_MASK)
+#define DMA_ES_SBE_MASK (0x2U)
+#define DMA_ES_SBE_SHIFT (1U)
+#define DMA_ES_SBE(x) (((uint32_t)(((uint32_t)(x)) << DMA_ES_SBE_SHIFT)) & DMA_ES_SBE_MASK)
+#define DMA_ES_SGE_MASK (0x4U)
+#define DMA_ES_SGE_SHIFT (2U)
+#define DMA_ES_SGE(x) (((uint32_t)(((uint32_t)(x)) << DMA_ES_SGE_SHIFT)) & DMA_ES_SGE_MASK)
+#define DMA_ES_NCE_MASK (0x8U)
+#define DMA_ES_NCE_SHIFT (3U)
+#define DMA_ES_NCE(x) (((uint32_t)(((uint32_t)(x)) << DMA_ES_NCE_SHIFT)) & DMA_ES_NCE_MASK)
+#define DMA_ES_DOE_MASK (0x10U)
+#define DMA_ES_DOE_SHIFT (4U)
+#define DMA_ES_DOE(x) (((uint32_t)(((uint32_t)(x)) << DMA_ES_DOE_SHIFT)) & DMA_ES_DOE_MASK)
+#define DMA_ES_DAE_MASK (0x20U)
+#define DMA_ES_DAE_SHIFT (5U)
+#define DMA_ES_DAE(x) (((uint32_t)(((uint32_t)(x)) << DMA_ES_DAE_SHIFT)) & DMA_ES_DAE_MASK)
+#define DMA_ES_SOE_MASK (0x40U)
+#define DMA_ES_SOE_SHIFT (6U)
+#define DMA_ES_SOE(x) (((uint32_t)(((uint32_t)(x)) << DMA_ES_SOE_SHIFT)) & DMA_ES_SOE_MASK)
+#define DMA_ES_SAE_MASK (0x80U)
+#define DMA_ES_SAE_SHIFT (7U)
+#define DMA_ES_SAE(x) (((uint32_t)(((uint32_t)(x)) << DMA_ES_SAE_SHIFT)) & DMA_ES_SAE_MASK)
+#define DMA_ES_ERRCHN_MASK (0x300U)
+#define DMA_ES_ERRCHN_SHIFT (8U)
+#define DMA_ES_ERRCHN(x) (((uint32_t)(((uint32_t)(x)) << DMA_ES_ERRCHN_SHIFT)) & DMA_ES_ERRCHN_MASK)
+#define DMA_ES_CPE_MASK (0x4000U)
+#define DMA_ES_CPE_SHIFT (14U)
+#define DMA_ES_CPE(x) (((uint32_t)(((uint32_t)(x)) << DMA_ES_CPE_SHIFT)) & DMA_ES_CPE_MASK)
+#define DMA_ES_ECX_MASK (0x10000U)
+#define DMA_ES_ECX_SHIFT (16U)
+#define DMA_ES_ECX(x) (((uint32_t)(((uint32_t)(x)) << DMA_ES_ECX_SHIFT)) & DMA_ES_ECX_MASK)
+#define DMA_ES_VLD_MASK (0x80000000U)
+#define DMA_ES_VLD_SHIFT (31U)
+#define DMA_ES_VLD(x) (((uint32_t)(((uint32_t)(x)) << DMA_ES_VLD_SHIFT)) & DMA_ES_VLD_MASK)
+
+/*! @name ERQ - Enable Request Register */
+#define DMA_ERQ_ERQ0_MASK (0x1U)
+#define DMA_ERQ_ERQ0_SHIFT (0U)
+#define DMA_ERQ_ERQ0(x) (((uint32_t)(((uint32_t)(x)) << DMA_ERQ_ERQ0_SHIFT)) & DMA_ERQ_ERQ0_MASK)
+#define DMA_ERQ_ERQ1_MASK (0x2U)
+#define DMA_ERQ_ERQ1_SHIFT (1U)
+#define DMA_ERQ_ERQ1(x) (((uint32_t)(((uint32_t)(x)) << DMA_ERQ_ERQ1_SHIFT)) & DMA_ERQ_ERQ1_MASK)
+#define DMA_ERQ_ERQ2_MASK (0x4U)
+#define DMA_ERQ_ERQ2_SHIFT (2U)
+#define DMA_ERQ_ERQ2(x) (((uint32_t)(((uint32_t)(x)) << DMA_ERQ_ERQ2_SHIFT)) & DMA_ERQ_ERQ2_MASK)
+#define DMA_ERQ_ERQ3_MASK (0x8U)
+#define DMA_ERQ_ERQ3_SHIFT (3U)
+#define DMA_ERQ_ERQ3(x) (((uint32_t)(((uint32_t)(x)) << DMA_ERQ_ERQ3_SHIFT)) & DMA_ERQ_ERQ3_MASK)
+
+/*! @name EEI - Enable Error Interrupt Register */
+#define DMA_EEI_EEI0_MASK (0x1U)
+#define DMA_EEI_EEI0_SHIFT (0U)
+#define DMA_EEI_EEI0(x) (((uint32_t)(((uint32_t)(x)) << DMA_EEI_EEI0_SHIFT)) & DMA_EEI_EEI0_MASK)
+#define DMA_EEI_EEI1_MASK (0x2U)
+#define DMA_EEI_EEI1_SHIFT (1U)
+#define DMA_EEI_EEI1(x) (((uint32_t)(((uint32_t)(x)) << DMA_EEI_EEI1_SHIFT)) & DMA_EEI_EEI1_MASK)
+#define DMA_EEI_EEI2_MASK (0x4U)
+#define DMA_EEI_EEI2_SHIFT (2U)
+#define DMA_EEI_EEI2(x) (((uint32_t)(((uint32_t)(x)) << DMA_EEI_EEI2_SHIFT)) & DMA_EEI_EEI2_MASK)
+#define DMA_EEI_EEI3_MASK (0x8U)
+#define DMA_EEI_EEI3_SHIFT (3U)
+#define DMA_EEI_EEI3(x) (((uint32_t)(((uint32_t)(x)) << DMA_EEI_EEI3_SHIFT)) & DMA_EEI_EEI3_MASK)
+
+/*! @name CEEI - Clear Enable Error Interrupt Register */
+#define DMA_CEEI_CEEI_MASK (0x3U)
+#define DMA_CEEI_CEEI_SHIFT (0U)
+#define DMA_CEEI_CEEI(x) (((uint8_t)(((uint8_t)(x)) << DMA_CEEI_CEEI_SHIFT)) & DMA_CEEI_CEEI_MASK)
+#define DMA_CEEI_CAEE_MASK (0x40U)
+#define DMA_CEEI_CAEE_SHIFT (6U)
+#define DMA_CEEI_CAEE(x) (((uint8_t)(((uint8_t)(x)) << DMA_CEEI_CAEE_SHIFT)) & DMA_CEEI_CAEE_MASK)
+#define DMA_CEEI_NOP_MASK (0x80U)
+#define DMA_CEEI_NOP_SHIFT (7U)
+#define DMA_CEEI_NOP(x) (((uint8_t)(((uint8_t)(x)) << DMA_CEEI_NOP_SHIFT)) & DMA_CEEI_NOP_MASK)
+
+/*! @name SEEI - Set Enable Error Interrupt Register */
+#define DMA_SEEI_SEEI_MASK (0x3U)
+#define DMA_SEEI_SEEI_SHIFT (0U)
+#define DMA_SEEI_SEEI(x) (((uint8_t)(((uint8_t)(x)) << DMA_SEEI_SEEI_SHIFT)) & DMA_SEEI_SEEI_MASK)
+#define DMA_SEEI_SAEE_MASK (0x40U)
+#define DMA_SEEI_SAEE_SHIFT (6U)
+#define DMA_SEEI_SAEE(x) (((uint8_t)(((uint8_t)(x)) << DMA_SEEI_SAEE_SHIFT)) & DMA_SEEI_SAEE_MASK)
+#define DMA_SEEI_NOP_MASK (0x80U)
+#define DMA_SEEI_NOP_SHIFT (7U)
+#define DMA_SEEI_NOP(x) (((uint8_t)(((uint8_t)(x)) << DMA_SEEI_NOP_SHIFT)) & DMA_SEEI_NOP_MASK)
+
+/*! @name CERQ - Clear Enable Request Register */
+#define DMA_CERQ_CERQ_MASK (0x3U)
+#define DMA_CERQ_CERQ_SHIFT (0U)
+#define DMA_CERQ_CERQ(x) (((uint8_t)(((uint8_t)(x)) << DMA_CERQ_CERQ_SHIFT)) & DMA_CERQ_CERQ_MASK)
+#define DMA_CERQ_CAER_MASK (0x40U)
+#define DMA_CERQ_CAER_SHIFT (6U)
+#define DMA_CERQ_CAER(x) (((uint8_t)(((uint8_t)(x)) << DMA_CERQ_CAER_SHIFT)) & DMA_CERQ_CAER_MASK)
+#define DMA_CERQ_NOP_MASK (0x80U)
+#define DMA_CERQ_NOP_SHIFT (7U)
+#define DMA_CERQ_NOP(x) (((uint8_t)(((uint8_t)(x)) << DMA_CERQ_NOP_SHIFT)) & DMA_CERQ_NOP_MASK)
+
+/*! @name SERQ - Set Enable Request Register */
+#define DMA_SERQ_SERQ_MASK (0x3U)
+#define DMA_SERQ_SERQ_SHIFT (0U)
+#define DMA_SERQ_SERQ(x) (((uint8_t)(((uint8_t)(x)) << DMA_SERQ_SERQ_SHIFT)) & DMA_SERQ_SERQ_MASK)
+#define DMA_SERQ_SAER_MASK (0x40U)
+#define DMA_SERQ_SAER_SHIFT (6U)
+#define DMA_SERQ_SAER(x) (((uint8_t)(((uint8_t)(x)) << DMA_SERQ_SAER_SHIFT)) & DMA_SERQ_SAER_MASK)
+#define DMA_SERQ_NOP_MASK (0x80U)
+#define DMA_SERQ_NOP_SHIFT (7U)
+#define DMA_SERQ_NOP(x) (((uint8_t)(((uint8_t)(x)) << DMA_SERQ_NOP_SHIFT)) & DMA_SERQ_NOP_MASK)
+
+/*! @name CDNE - Clear DONE Status Bit Register */
+#define DMA_CDNE_CDNE_MASK (0x3U)
+#define DMA_CDNE_CDNE_SHIFT (0U)
+#define DMA_CDNE_CDNE(x) (((uint8_t)(((uint8_t)(x)) << DMA_CDNE_CDNE_SHIFT)) & DMA_CDNE_CDNE_MASK)
+#define DMA_CDNE_CADN_MASK (0x40U)
+#define DMA_CDNE_CADN_SHIFT (6U)
+#define DMA_CDNE_CADN(x) (((uint8_t)(((uint8_t)(x)) << DMA_CDNE_CADN_SHIFT)) & DMA_CDNE_CADN_MASK)
+#define DMA_CDNE_NOP_MASK (0x80U)
+#define DMA_CDNE_NOP_SHIFT (7U)
+#define DMA_CDNE_NOP(x) (((uint8_t)(((uint8_t)(x)) << DMA_CDNE_NOP_SHIFT)) & DMA_CDNE_NOP_MASK)
+
+/*! @name SSRT - Set START Bit Register */
+#define DMA_SSRT_SSRT_MASK (0x3U)
+#define DMA_SSRT_SSRT_SHIFT (0U)
+#define DMA_SSRT_SSRT(x) (((uint8_t)(((uint8_t)(x)) << DMA_SSRT_SSRT_SHIFT)) & DMA_SSRT_SSRT_MASK)
+#define DMA_SSRT_SAST_MASK (0x40U)
+#define DMA_SSRT_SAST_SHIFT (6U)
+#define DMA_SSRT_SAST(x) (((uint8_t)(((uint8_t)(x)) << DMA_SSRT_SAST_SHIFT)) & DMA_SSRT_SAST_MASK)
+#define DMA_SSRT_NOP_MASK (0x80U)
+#define DMA_SSRT_NOP_SHIFT (7U)
+#define DMA_SSRT_NOP(x) (((uint8_t)(((uint8_t)(x)) << DMA_SSRT_NOP_SHIFT)) & DMA_SSRT_NOP_MASK)
+
+/*! @name CERR - Clear Error Register */
+#define DMA_CERR_CERR_MASK (0x3U)
+#define DMA_CERR_CERR_SHIFT (0U)
+#define DMA_CERR_CERR(x) (((uint8_t)(((uint8_t)(x)) << DMA_CERR_CERR_SHIFT)) & DMA_CERR_CERR_MASK)
+#define DMA_CERR_CAEI_MASK (0x40U)
+#define DMA_CERR_CAEI_SHIFT (6U)
+#define DMA_CERR_CAEI(x) (((uint8_t)(((uint8_t)(x)) << DMA_CERR_CAEI_SHIFT)) & DMA_CERR_CAEI_MASK)
+#define DMA_CERR_NOP_MASK (0x80U)
+#define DMA_CERR_NOP_SHIFT (7U)
+#define DMA_CERR_NOP(x) (((uint8_t)(((uint8_t)(x)) << DMA_CERR_NOP_SHIFT)) & DMA_CERR_NOP_MASK)
+
+/*! @name CINT - Clear Interrupt Request Register */
+#define DMA_CINT_CINT_MASK (0x3U)
+#define DMA_CINT_CINT_SHIFT (0U)
+#define DMA_CINT_CINT(x) (((uint8_t)(((uint8_t)(x)) << DMA_CINT_CINT_SHIFT)) & DMA_CINT_CINT_MASK)
+#define DMA_CINT_CAIR_MASK (0x40U)
+#define DMA_CINT_CAIR_SHIFT (6U)
+#define DMA_CINT_CAIR(x) (((uint8_t)(((uint8_t)(x)) << DMA_CINT_CAIR_SHIFT)) & DMA_CINT_CAIR_MASK)
+#define DMA_CINT_NOP_MASK (0x80U)
+#define DMA_CINT_NOP_SHIFT (7U)
+#define DMA_CINT_NOP(x) (((uint8_t)(((uint8_t)(x)) << DMA_CINT_NOP_SHIFT)) & DMA_CINT_NOP_MASK)
+
+/*! @name INT - Interrupt Request Register */
+#define DMA_INT_INT0_MASK (0x1U)
+#define DMA_INT_INT0_SHIFT (0U)
+#define DMA_INT_INT0(x) (((uint32_t)(((uint32_t)(x)) << DMA_INT_INT0_SHIFT)) & DMA_INT_INT0_MASK)
+#define DMA_INT_INT1_MASK (0x2U)
+#define DMA_INT_INT1_SHIFT (1U)
+#define DMA_INT_INT1(x) (((uint32_t)(((uint32_t)(x)) << DMA_INT_INT1_SHIFT)) & DMA_INT_INT1_MASK)
+#define DMA_INT_INT2_MASK (0x4U)
+#define DMA_INT_INT2_SHIFT (2U)
+#define DMA_INT_INT2(x) (((uint32_t)(((uint32_t)(x)) << DMA_INT_INT2_SHIFT)) & DMA_INT_INT2_MASK)
+#define DMA_INT_INT3_MASK (0x8U)
+#define DMA_INT_INT3_SHIFT (3U)
+#define DMA_INT_INT3(x) (((uint32_t)(((uint32_t)(x)) << DMA_INT_INT3_SHIFT)) & DMA_INT_INT3_MASK)
+
+/*! @name ERR - Error Register */
+#define DMA_ERR_ERR0_MASK (0x1U)
+#define DMA_ERR_ERR0_SHIFT (0U)
+#define DMA_ERR_ERR0(x) (((uint32_t)(((uint32_t)(x)) << DMA_ERR_ERR0_SHIFT)) & DMA_ERR_ERR0_MASK)
+#define DMA_ERR_ERR1_MASK (0x2U)
+#define DMA_ERR_ERR1_SHIFT (1U)
+#define DMA_ERR_ERR1(x) (((uint32_t)(((uint32_t)(x)) << DMA_ERR_ERR1_SHIFT)) & DMA_ERR_ERR1_MASK)
+#define DMA_ERR_ERR2_MASK (0x4U)
+#define DMA_ERR_ERR2_SHIFT (2U)
+#define DMA_ERR_ERR2(x) (((uint32_t)(((uint32_t)(x)) << DMA_ERR_ERR2_SHIFT)) & DMA_ERR_ERR2_MASK)
+#define DMA_ERR_ERR3_MASK (0x8U)
+#define DMA_ERR_ERR3_SHIFT (3U)
+#define DMA_ERR_ERR3(x) (((uint32_t)(((uint32_t)(x)) << DMA_ERR_ERR3_SHIFT)) & DMA_ERR_ERR3_MASK)
+
+/*! @name HRS - Hardware Request Status Register */
+#define DMA_HRS_HRS0_MASK (0x1U)
+#define DMA_HRS_HRS0_SHIFT (0U)
+#define DMA_HRS_HRS0(x) (((uint32_t)(((uint32_t)(x)) << DMA_HRS_HRS0_SHIFT)) & DMA_HRS_HRS0_MASK)
+#define DMA_HRS_HRS1_MASK (0x2U)
+#define DMA_HRS_HRS1_SHIFT (1U)
+#define DMA_HRS_HRS1(x) (((uint32_t)(((uint32_t)(x)) << DMA_HRS_HRS1_SHIFT)) & DMA_HRS_HRS1_MASK)
+#define DMA_HRS_HRS2_MASK (0x4U)
+#define DMA_HRS_HRS2_SHIFT (2U)
+#define DMA_HRS_HRS2(x) (((uint32_t)(((uint32_t)(x)) << DMA_HRS_HRS2_SHIFT)) & DMA_HRS_HRS2_MASK)
+#define DMA_HRS_HRS3_MASK (0x8U)
+#define DMA_HRS_HRS3_SHIFT (3U)
+#define DMA_HRS_HRS3(x) (((uint32_t)(((uint32_t)(x)) << DMA_HRS_HRS3_SHIFT)) & DMA_HRS_HRS3_MASK)
+
+/*! @name EARS - Enable Asynchronous Request in Stop Register */
+#define DMA_EARS_EDREQ_0_MASK (0x1U)
+#define DMA_EARS_EDREQ_0_SHIFT (0U)
+#define DMA_EARS_EDREQ_0(x) (((uint32_t)(((uint32_t)(x)) << DMA_EARS_EDREQ_0_SHIFT)) & DMA_EARS_EDREQ_0_MASK)
+#define DMA_EARS_EDREQ_1_MASK (0x2U)
+#define DMA_EARS_EDREQ_1_SHIFT (1U)
+#define DMA_EARS_EDREQ_1(x) (((uint32_t)(((uint32_t)(x)) << DMA_EARS_EDREQ_1_SHIFT)) & DMA_EARS_EDREQ_1_MASK)
+#define DMA_EARS_EDREQ_2_MASK (0x4U)
+#define DMA_EARS_EDREQ_2_SHIFT (2U)
+#define DMA_EARS_EDREQ_2(x) (((uint32_t)(((uint32_t)(x)) << DMA_EARS_EDREQ_2_SHIFT)) & DMA_EARS_EDREQ_2_MASK)
+#define DMA_EARS_EDREQ_3_MASK (0x8U)
+#define DMA_EARS_EDREQ_3_SHIFT (3U)
+#define DMA_EARS_EDREQ_3(x) (((uint32_t)(((uint32_t)(x)) << DMA_EARS_EDREQ_3_SHIFT)) & DMA_EARS_EDREQ_3_MASK)
+
+/*! @name DCHPRI3 - Channel n Priority Register */
+#define DMA_DCHPRI3_CHPRI_MASK (0x3U)
+#define DMA_DCHPRI3_CHPRI_SHIFT (0U)
+#define DMA_DCHPRI3_CHPRI(x) (((uint8_t)(((uint8_t)(x)) << DMA_DCHPRI3_CHPRI_SHIFT)) & DMA_DCHPRI3_CHPRI_MASK)
+#define DMA_DCHPRI3_DPA_MASK (0x40U)
+#define DMA_DCHPRI3_DPA_SHIFT (6U)
+#define DMA_DCHPRI3_DPA(x) (((uint8_t)(((uint8_t)(x)) << DMA_DCHPRI3_DPA_SHIFT)) & DMA_DCHPRI3_DPA_MASK)
+#define DMA_DCHPRI3_ECP_MASK (0x80U)
+#define DMA_DCHPRI3_ECP_SHIFT (7U)
+#define DMA_DCHPRI3_ECP(x) (((uint8_t)(((uint8_t)(x)) << DMA_DCHPRI3_ECP_SHIFT)) & DMA_DCHPRI3_ECP_MASK)
+
+/*! @name DCHPRI2 - Channel n Priority Register */
+#define DMA_DCHPRI2_CHPRI_MASK (0x3U)
+#define DMA_DCHPRI2_CHPRI_SHIFT (0U)
+#define DMA_DCHPRI2_CHPRI(x) (((uint8_t)(((uint8_t)(x)) << DMA_DCHPRI2_CHPRI_SHIFT)) & DMA_DCHPRI2_CHPRI_MASK)
+#define DMA_DCHPRI2_DPA_MASK (0x40U)
+#define DMA_DCHPRI2_DPA_SHIFT (6U)
+#define DMA_DCHPRI2_DPA(x) (((uint8_t)(((uint8_t)(x)) << DMA_DCHPRI2_DPA_SHIFT)) & DMA_DCHPRI2_DPA_MASK)
+#define DMA_DCHPRI2_ECP_MASK (0x80U)
+#define DMA_DCHPRI2_ECP_SHIFT (7U)
+#define DMA_DCHPRI2_ECP(x) (((uint8_t)(((uint8_t)(x)) << DMA_DCHPRI2_ECP_SHIFT)) & DMA_DCHPRI2_ECP_MASK)
+
+/*! @name DCHPRI1 - Channel n Priority Register */
+#define DMA_DCHPRI1_CHPRI_MASK (0x3U)
+#define DMA_DCHPRI1_CHPRI_SHIFT (0U)
+#define DMA_DCHPRI1_CHPRI(x) (((uint8_t)(((uint8_t)(x)) << DMA_DCHPRI1_CHPRI_SHIFT)) & DMA_DCHPRI1_CHPRI_MASK)
+#define DMA_DCHPRI1_DPA_MASK (0x40U)
+#define DMA_DCHPRI1_DPA_SHIFT (6U)
+#define DMA_DCHPRI1_DPA(x) (((uint8_t)(((uint8_t)(x)) << DMA_DCHPRI1_DPA_SHIFT)) & DMA_DCHPRI1_DPA_MASK)
+#define DMA_DCHPRI1_ECP_MASK (0x80U)
+#define DMA_DCHPRI1_ECP_SHIFT (7U)
+#define DMA_DCHPRI1_ECP(x) (((uint8_t)(((uint8_t)(x)) << DMA_DCHPRI1_ECP_SHIFT)) & DMA_DCHPRI1_ECP_MASK)
+
+/*! @name DCHPRI0 - Channel n Priority Register */
+#define DMA_DCHPRI0_CHPRI_MASK (0x3U)
+#define DMA_DCHPRI0_CHPRI_SHIFT (0U)
+#define DMA_DCHPRI0_CHPRI(x) (((uint8_t)(((uint8_t)(x)) << DMA_DCHPRI0_CHPRI_SHIFT)) & DMA_DCHPRI0_CHPRI_MASK)
+#define DMA_DCHPRI0_DPA_MASK (0x40U)
+#define DMA_DCHPRI0_DPA_SHIFT (6U)
+#define DMA_DCHPRI0_DPA(x) (((uint8_t)(((uint8_t)(x)) << DMA_DCHPRI0_DPA_SHIFT)) & DMA_DCHPRI0_DPA_MASK)
+#define DMA_DCHPRI0_ECP_MASK (0x80U)
+#define DMA_DCHPRI0_ECP_SHIFT (7U)
+#define DMA_DCHPRI0_ECP(x) (((uint8_t)(((uint8_t)(x)) << DMA_DCHPRI0_ECP_SHIFT)) & DMA_DCHPRI0_ECP_MASK)
+
+/*! @name SADDR - TCD Source Address */
+#define DMA_SADDR_SADDR_MASK (0xFFFFFFFFU)
+#define DMA_SADDR_SADDR_SHIFT (0U)
+#define DMA_SADDR_SADDR(x) (((uint32_t)(((uint32_t)(x)) << DMA_SADDR_SADDR_SHIFT)) & DMA_SADDR_SADDR_MASK)
+
+/* The count of DMA_SADDR */
+#define DMA_SADDR_COUNT (4U)
+
+/*! @name SOFF - TCD Signed Source Address Offset */
+#define DMA_SOFF_SOFF_MASK (0xFFFFU)
+#define DMA_SOFF_SOFF_SHIFT (0U)
+#define DMA_SOFF_SOFF(x) (((uint16_t)(((uint16_t)(x)) << DMA_SOFF_SOFF_SHIFT)) & DMA_SOFF_SOFF_MASK)
+
+/* The count of DMA_SOFF */
+#define DMA_SOFF_COUNT (4U)
+
+/*! @name ATTR - TCD Transfer Attributes */
+#define DMA_ATTR_DSIZE_MASK (0x7U)
+#define DMA_ATTR_DSIZE_SHIFT (0U)
+#define DMA_ATTR_DSIZE(x) (((uint16_t)(((uint16_t)(x)) << DMA_ATTR_DSIZE_SHIFT)) & DMA_ATTR_DSIZE_MASK)
+#define DMA_ATTR_DMOD_MASK (0xF8U)
+#define DMA_ATTR_DMOD_SHIFT (3U)
+#define DMA_ATTR_DMOD(x) (((uint16_t)(((uint16_t)(x)) << DMA_ATTR_DMOD_SHIFT)) & DMA_ATTR_DMOD_MASK)
+#define DMA_ATTR_SSIZE_MASK (0x700U)
+#define DMA_ATTR_SSIZE_SHIFT (8U)
+#define DMA_ATTR_SSIZE(x) (((uint16_t)(((uint16_t)(x)) << DMA_ATTR_SSIZE_SHIFT)) & DMA_ATTR_SSIZE_MASK)
+#define DMA_ATTR_SMOD_MASK (0xF800U)
+#define DMA_ATTR_SMOD_SHIFT (11U)
+#define DMA_ATTR_SMOD(x) (((uint16_t)(((uint16_t)(x)) << DMA_ATTR_SMOD_SHIFT)) & DMA_ATTR_SMOD_MASK)
+
+/* The count of DMA_ATTR */
+#define DMA_ATTR_COUNT (4U)
+
+/*! @name NBYTES_MLNO - TCD Minor Byte Count (Minor Loop Disabled) */
+#define DMA_NBYTES_MLNO_NBYTES_MASK (0xFFFFFFFFU)
+#define DMA_NBYTES_MLNO_NBYTES_SHIFT (0U)
+#define DMA_NBYTES_MLNO_NBYTES(x) (((uint32_t)(((uint32_t)(x)) << DMA_NBYTES_MLNO_NBYTES_SHIFT)) & DMA_NBYTES_MLNO_NBYTES_MASK)
+
+/* The count of DMA_NBYTES_MLNO */
+#define DMA_NBYTES_MLNO_COUNT (4U)
+
+/*! @name NBYTES_MLOFFNO - TCD Signed Minor Loop Offset (Minor Loop Enabled and Offset Disabled) */
+#define DMA_NBYTES_MLOFFNO_NBYTES_MASK (0x3FFFFFFFU)
+#define DMA_NBYTES_MLOFFNO_NBYTES_SHIFT (0U)
+#define DMA_NBYTES_MLOFFNO_NBYTES(x) (((uint32_t)(((uint32_t)(x)) << DMA_NBYTES_MLOFFNO_NBYTES_SHIFT)) & DMA_NBYTES_MLOFFNO_NBYTES_MASK)
+#define DMA_NBYTES_MLOFFNO_DMLOE_MASK (0x40000000U)
+#define DMA_NBYTES_MLOFFNO_DMLOE_SHIFT (30U)
+#define DMA_NBYTES_MLOFFNO_DMLOE(x) (((uint32_t)(((uint32_t)(x)) << DMA_NBYTES_MLOFFNO_DMLOE_SHIFT)) & DMA_NBYTES_MLOFFNO_DMLOE_MASK)
+#define DMA_NBYTES_MLOFFNO_SMLOE_MASK (0x80000000U)
+#define DMA_NBYTES_MLOFFNO_SMLOE_SHIFT (31U)
+#define DMA_NBYTES_MLOFFNO_SMLOE(x) (((uint32_t)(((uint32_t)(x)) << DMA_NBYTES_MLOFFNO_SMLOE_SHIFT)) & DMA_NBYTES_MLOFFNO_SMLOE_MASK)
+
+/* The count of DMA_NBYTES_MLOFFNO */
+#define DMA_NBYTES_MLOFFNO_COUNT (4U)
+
+/*! @name NBYTES_MLOFFYES - TCD Signed Minor Loop Offset (Minor Loop and Offset Enabled) */
+#define DMA_NBYTES_MLOFFYES_NBYTES_MASK (0x3FFU)
+#define DMA_NBYTES_MLOFFYES_NBYTES_SHIFT (0U)
+#define DMA_NBYTES_MLOFFYES_NBYTES(x) (((uint32_t)(((uint32_t)(x)) << DMA_NBYTES_MLOFFYES_NBYTES_SHIFT)) & DMA_NBYTES_MLOFFYES_NBYTES_MASK)
+#define DMA_NBYTES_MLOFFYES_MLOFF_MASK (0x3FFFFC00U)
+#define DMA_NBYTES_MLOFFYES_MLOFF_SHIFT (10U)
+#define DMA_NBYTES_MLOFFYES_MLOFF(x) (((uint32_t)(((uint32_t)(x)) << DMA_NBYTES_MLOFFYES_MLOFF_SHIFT)) & DMA_NBYTES_MLOFFYES_MLOFF_MASK)
+#define DMA_NBYTES_MLOFFYES_DMLOE_MASK (0x40000000U)
+#define DMA_NBYTES_MLOFFYES_DMLOE_SHIFT (30U)
+#define DMA_NBYTES_MLOFFYES_DMLOE(x) (((uint32_t)(((uint32_t)(x)) << DMA_NBYTES_MLOFFYES_DMLOE_SHIFT)) & DMA_NBYTES_MLOFFYES_DMLOE_MASK)
+#define DMA_NBYTES_MLOFFYES_SMLOE_MASK (0x80000000U)
+#define DMA_NBYTES_MLOFFYES_SMLOE_SHIFT (31U)
+#define DMA_NBYTES_MLOFFYES_SMLOE(x) (((uint32_t)(((uint32_t)(x)) << DMA_NBYTES_MLOFFYES_SMLOE_SHIFT)) & DMA_NBYTES_MLOFFYES_SMLOE_MASK)
+
+/* The count of DMA_NBYTES_MLOFFYES */
+#define DMA_NBYTES_MLOFFYES_COUNT (4U)
+
+/*! @name SLAST - TCD Last Source Address Adjustment */
+#define DMA_SLAST_SLAST_MASK (0xFFFFFFFFU)
+#define DMA_SLAST_SLAST_SHIFT (0U)
+#define DMA_SLAST_SLAST(x) (((uint32_t)(((uint32_t)(x)) << DMA_SLAST_SLAST_SHIFT)) & DMA_SLAST_SLAST_MASK)
+
+/* The count of DMA_SLAST */
+#define DMA_SLAST_COUNT (4U)
+
+/*! @name DADDR - TCD Destination Address */
+#define DMA_DADDR_DADDR_MASK (0xFFFFFFFFU)
+#define DMA_DADDR_DADDR_SHIFT (0U)
+#define DMA_DADDR_DADDR(x) (((uint32_t)(((uint32_t)(x)) << DMA_DADDR_DADDR_SHIFT)) & DMA_DADDR_DADDR_MASK)
+
+/* The count of DMA_DADDR */
+#define DMA_DADDR_COUNT (4U)
+
+/*! @name DOFF - TCD Signed Destination Address Offset */
+#define DMA_DOFF_DOFF_MASK (0xFFFFU)
+#define DMA_DOFF_DOFF_SHIFT (0U)
+#define DMA_DOFF_DOFF(x) (((uint16_t)(((uint16_t)(x)) << DMA_DOFF_DOFF_SHIFT)) & DMA_DOFF_DOFF_MASK)
+
+/* The count of DMA_DOFF */
+#define DMA_DOFF_COUNT (4U)
+
+/*! @name CITER_ELINKNO - TCD Current Minor Loop Link, Major Loop Count (Channel Linking Disabled) */
+#define DMA_CITER_ELINKNO_CITER_MASK (0x7FFFU)
+#define DMA_CITER_ELINKNO_CITER_SHIFT (0U)
+#define DMA_CITER_ELINKNO_CITER(x) (((uint16_t)(((uint16_t)(x)) << DMA_CITER_ELINKNO_CITER_SHIFT)) & DMA_CITER_ELINKNO_CITER_MASK)
+#define DMA_CITER_ELINKNO_ELINK_MASK (0x8000U)
+#define DMA_CITER_ELINKNO_ELINK_SHIFT (15U)
+#define DMA_CITER_ELINKNO_ELINK(x) (((uint16_t)(((uint16_t)(x)) << DMA_CITER_ELINKNO_ELINK_SHIFT)) & DMA_CITER_ELINKNO_ELINK_MASK)
+
+/* The count of DMA_CITER_ELINKNO */
+#define DMA_CITER_ELINKNO_COUNT (4U)
+
+/*! @name CITER_ELINKYES - TCD Current Minor Loop Link, Major Loop Count (Channel Linking Enabled) */
+#define DMA_CITER_ELINKYES_CITER_MASK (0x1FFU)
+#define DMA_CITER_ELINKYES_CITER_SHIFT (0U)
+#define DMA_CITER_ELINKYES_CITER(x) (((uint16_t)(((uint16_t)(x)) << DMA_CITER_ELINKYES_CITER_SHIFT)) & DMA_CITER_ELINKYES_CITER_MASK)
+#define DMA_CITER_ELINKYES_LINKCH_MASK (0x600U)
+#define DMA_CITER_ELINKYES_LINKCH_SHIFT (9U)
+#define DMA_CITER_ELINKYES_LINKCH(x) (((uint16_t)(((uint16_t)(x)) << DMA_CITER_ELINKYES_LINKCH_SHIFT)) & DMA_CITER_ELINKYES_LINKCH_MASK)
+#define DMA_CITER_ELINKYES_ELINK_MASK (0x8000U)
+#define DMA_CITER_ELINKYES_ELINK_SHIFT (15U)
+#define DMA_CITER_ELINKYES_ELINK(x) (((uint16_t)(((uint16_t)(x)) << DMA_CITER_ELINKYES_ELINK_SHIFT)) & DMA_CITER_ELINKYES_ELINK_MASK)
+
+/* The count of DMA_CITER_ELINKYES */
+#define DMA_CITER_ELINKYES_COUNT (4U)
+
+/*! @name DLAST_SGA - TCD Last Destination Address Adjustment/Scatter Gather Address */
+#define DMA_DLAST_SGA_DLASTSGA_MASK (0xFFFFFFFFU)
+#define DMA_DLAST_SGA_DLASTSGA_SHIFT (0U)
+#define DMA_DLAST_SGA_DLASTSGA(x) (((uint32_t)(((uint32_t)(x)) << DMA_DLAST_SGA_DLASTSGA_SHIFT)) & DMA_DLAST_SGA_DLASTSGA_MASK)
+
+/* The count of DMA_DLAST_SGA */
+#define DMA_DLAST_SGA_COUNT (4U)
+
+/*! @name CSR - TCD Control and Status */
+#define DMA_CSR_START_MASK (0x1U)
+#define DMA_CSR_START_SHIFT (0U)
+#define DMA_CSR_START(x) (((uint16_t)(((uint16_t)(x)) << DMA_CSR_START_SHIFT)) & DMA_CSR_START_MASK)
+#define DMA_CSR_INTMAJOR_MASK (0x2U)
+#define DMA_CSR_INTMAJOR_SHIFT (1U)
+#define DMA_CSR_INTMAJOR(x) (((uint16_t)(((uint16_t)(x)) << DMA_CSR_INTMAJOR_SHIFT)) & DMA_CSR_INTMAJOR_MASK)
+#define DMA_CSR_INTHALF_MASK (0x4U)
+#define DMA_CSR_INTHALF_SHIFT (2U)
+#define DMA_CSR_INTHALF(x) (((uint16_t)(((uint16_t)(x)) << DMA_CSR_INTHALF_SHIFT)) & DMA_CSR_INTHALF_MASK)
+#define DMA_CSR_DREQ_MASK (0x8U)
+#define DMA_CSR_DREQ_SHIFT (3U)
+#define DMA_CSR_DREQ(x) (((uint16_t)(((uint16_t)(x)) << DMA_CSR_DREQ_SHIFT)) & DMA_CSR_DREQ_MASK)
+#define DMA_CSR_ESG_MASK (0x10U)
+#define DMA_CSR_ESG_SHIFT (4U)
+#define DMA_CSR_ESG(x) (((uint16_t)(((uint16_t)(x)) << DMA_CSR_ESG_SHIFT)) & DMA_CSR_ESG_MASK)
+#define DMA_CSR_MAJORELINK_MASK (0x20U)
+#define DMA_CSR_MAJORELINK_SHIFT (5U)
+#define DMA_CSR_MAJORELINK(x) (((uint16_t)(((uint16_t)(x)) << DMA_CSR_MAJORELINK_SHIFT)) & DMA_CSR_MAJORELINK_MASK)
+#define DMA_CSR_ACTIVE_MASK (0x40U)
+#define DMA_CSR_ACTIVE_SHIFT (6U)
+#define DMA_CSR_ACTIVE(x) (((uint16_t)(((uint16_t)(x)) << DMA_CSR_ACTIVE_SHIFT)) & DMA_CSR_ACTIVE_MASK)
+#define DMA_CSR_DONE_MASK (0x80U)
+#define DMA_CSR_DONE_SHIFT (7U)
+#define DMA_CSR_DONE(x) (((uint16_t)(((uint16_t)(x)) << DMA_CSR_DONE_SHIFT)) & DMA_CSR_DONE_MASK)
+#define DMA_CSR_MAJORLINKCH_MASK (0x300U)
+#define DMA_CSR_MAJORLINKCH_SHIFT (8U)
+#define DMA_CSR_MAJORLINKCH(x) (((uint16_t)(((uint16_t)(x)) << DMA_CSR_MAJORLINKCH_SHIFT)) & DMA_CSR_MAJORLINKCH_MASK)
+#define DMA_CSR_BWC_MASK (0xC000U)
+#define DMA_CSR_BWC_SHIFT (14U)
+#define DMA_CSR_BWC(x) (((uint16_t)(((uint16_t)(x)) << DMA_CSR_BWC_SHIFT)) & DMA_CSR_BWC_MASK)
+
+/* The count of DMA_CSR */
+#define DMA_CSR_COUNT (4U)
+
+/*! @name BITER_ELINKNO - TCD Beginning Minor Loop Link, Major Loop Count (Channel Linking Disabled) */
+#define DMA_BITER_ELINKNO_BITER_MASK (0x7FFFU)
+#define DMA_BITER_ELINKNO_BITER_SHIFT (0U)
+#define DMA_BITER_ELINKNO_BITER(x) (((uint16_t)(((uint16_t)(x)) << DMA_BITER_ELINKNO_BITER_SHIFT)) & DMA_BITER_ELINKNO_BITER_MASK)
+#define DMA_BITER_ELINKNO_ELINK_MASK (0x8000U)
+#define DMA_BITER_ELINKNO_ELINK_SHIFT (15U)
+#define DMA_BITER_ELINKNO_ELINK(x) (((uint16_t)(((uint16_t)(x)) << DMA_BITER_ELINKNO_ELINK_SHIFT)) & DMA_BITER_ELINKNO_ELINK_MASK)
+
+/* The count of DMA_BITER_ELINKNO */
+#define DMA_BITER_ELINKNO_COUNT (4U)
+
+/*! @name BITER_ELINKYES - TCD Beginning Minor Loop Link, Major Loop Count (Channel Linking Enabled) */
+#define DMA_BITER_ELINKYES_BITER_MASK (0x1FFU)
+#define DMA_BITER_ELINKYES_BITER_SHIFT (0U)
+#define DMA_BITER_ELINKYES_BITER(x) (((uint16_t)(((uint16_t)(x)) << DMA_BITER_ELINKYES_BITER_SHIFT)) & DMA_BITER_ELINKYES_BITER_MASK)
+#define DMA_BITER_ELINKYES_LINKCH_MASK (0x600U)
+#define DMA_BITER_ELINKYES_LINKCH_SHIFT (9U)
+#define DMA_BITER_ELINKYES_LINKCH(x) (((uint16_t)(((uint16_t)(x)) << DMA_BITER_ELINKYES_LINKCH_SHIFT)) & DMA_BITER_ELINKYES_LINKCH_MASK)
+#define DMA_BITER_ELINKYES_ELINK_MASK (0x8000U)
+#define DMA_BITER_ELINKYES_ELINK_SHIFT (15U)
+#define DMA_BITER_ELINKYES_ELINK(x) (((uint16_t)(((uint16_t)(x)) << DMA_BITER_ELINKYES_ELINK_SHIFT)) & DMA_BITER_ELINKYES_ELINK_MASK)
+
+/* The count of DMA_BITER_ELINKYES */
+#define DMA_BITER_ELINKYES_COUNT (4U)
+
+
+/*!
+ * @}
+ */ /* end of group DMA_Register_Masks */
+
+
+/* DMA - Peripheral instance base addresses */
+/** Peripheral DMA base address */
+#define DMA_BASE (0x40008000u)
+/** Peripheral DMA base pointer */
+#define DMA0 ((DMA_Type *)DMA_BASE)
+/** Array initializer of DMA peripheral base addresses */
+#define DMA_BASE_ADDRS { DMA_BASE }
+/** Array initializer of DMA peripheral base pointers */
+#define DMA_BASE_PTRS { DMA0 }
+/** Interrupt vectors for the DMA peripheral type */
+#define DMA_CHN_IRQS { { DMA0_IRQn, DMA1_IRQn, DMA2_IRQn, DMA3_IRQn } }
+#define DMA_ERROR_IRQS { DMA_Error_IRQn }
+
+/*!
+ * @}
+ */ /* end of group DMA_Peripheral_Access_Layer */
+
+
+/* ----------------------------------------------------------------------------
+ -- DMAMUX Peripheral Access Layer
+ ---------------------------------------------------------------------------- */
+
+/*!
+ * @addtogroup DMAMUX_Peripheral_Access_Layer DMAMUX Peripheral Access Layer
+ * @{
+ */
+
+/** DMAMUX - Register Layout Typedef */
+typedef struct {
+ __IO uint8_t CHCFG[4]; /**< Channel Configuration register, array offset: 0x0, array step: 0x1 */
+} DMAMUX_Type;
+
+/* ----------------------------------------------------------------------------
+ -- DMAMUX Register Masks
+ ---------------------------------------------------------------------------- */
+
+/*!
+ * @addtogroup DMAMUX_Register_Masks DMAMUX Register Masks
+ * @{
+ */
+
+/*! @name CHCFG - Channel Configuration register */
+#define DMAMUX_CHCFG_SOURCE_MASK (0x3FU)
+#define DMAMUX_CHCFG_SOURCE_SHIFT (0U)
+#define DMAMUX_CHCFG_SOURCE(x) (((uint8_t)(((uint8_t)(x)) << DMAMUX_CHCFG_SOURCE_SHIFT)) & DMAMUX_CHCFG_SOURCE_MASK)
+#define DMAMUX_CHCFG_TRIG_MASK (0x40U)
+#define DMAMUX_CHCFG_TRIG_SHIFT (6U)
+#define DMAMUX_CHCFG_TRIG(x) (((uint8_t)(((uint8_t)(x)) << DMAMUX_CHCFG_TRIG_SHIFT)) & DMAMUX_CHCFG_TRIG_MASK)
+#define DMAMUX_CHCFG_ENBL_MASK (0x80U)
+#define DMAMUX_CHCFG_ENBL_SHIFT (7U)
+#define DMAMUX_CHCFG_ENBL(x) (((uint8_t)(((uint8_t)(x)) << DMAMUX_CHCFG_ENBL_SHIFT)) & DMAMUX_CHCFG_ENBL_MASK)
+
+/* The count of DMAMUX_CHCFG */
+#define DMAMUX_CHCFG_COUNT (4U)
+
+
+/*!
+ * @}
+ */ /* end of group DMAMUX_Register_Masks */
+
+
+/* DMAMUX - Peripheral instance base addresses */
+/** Peripheral DMAMUX base address */
+#define DMAMUX_BASE (0x40021000u)
+/** Peripheral DMAMUX base pointer */
+#define DMAMUX ((DMAMUX_Type *)DMAMUX_BASE)
+/** Array initializer of DMAMUX peripheral base addresses */
+#define DMAMUX_BASE_ADDRS { DMAMUX_BASE }
+/** Array initializer of DMAMUX peripheral base pointers */
+#define DMAMUX_BASE_PTRS { DMAMUX }
+
+/*!
+ * @}
+ */ /* end of group DMAMUX_Peripheral_Access_Layer */
+
+
+/* ----------------------------------------------------------------------------
+ -- EWM Peripheral Access Layer
+ ---------------------------------------------------------------------------- */
+
+/*!
+ * @addtogroup EWM_Peripheral_Access_Layer EWM Peripheral Access Layer
+ * @{
+ */
+
+/** EWM - Register Layout Typedef */
+typedef struct {
+ __IO uint8_t CTRL; /**< Control Register, offset: 0x0 */
+ __O uint8_t SERV; /**< Service Register, offset: 0x1 */
+ __IO uint8_t CMPL; /**< Compare Low Register, offset: 0x2 */
+ __IO uint8_t CMPH; /**< Compare High Register, offset: 0x3 */
+ uint8_t RESERVED_0[1];
+ __IO uint8_t CLKPRESCALER; /**< Clock Prescaler Register, offset: 0x5 */
+} EWM_Type;
+
+/* ----------------------------------------------------------------------------
+ -- EWM Register Masks
+ ---------------------------------------------------------------------------- */
+
+/*!
+ * @addtogroup EWM_Register_Masks EWM Register Masks
+ * @{
+ */
+
+/*! @name CTRL - Control Register */
+#define EWM_CTRL_EWMEN_MASK (0x1U)
+#define EWM_CTRL_EWMEN_SHIFT (0U)
+#define EWM_CTRL_EWMEN(x) (((uint8_t)(((uint8_t)(x)) << EWM_CTRL_EWMEN_SHIFT)) & EWM_CTRL_EWMEN_MASK)
+#define EWM_CTRL_ASSIN_MASK (0x2U)
+#define EWM_CTRL_ASSIN_SHIFT (1U)
+#define EWM_CTRL_ASSIN(x) (((uint8_t)(((uint8_t)(x)) << EWM_CTRL_ASSIN_SHIFT)) & EWM_CTRL_ASSIN_MASK)
+#define EWM_CTRL_INEN_MASK (0x4U)
+#define EWM_CTRL_INEN_SHIFT (2U)
+#define EWM_CTRL_INEN(x) (((uint8_t)(((uint8_t)(x)) << EWM_CTRL_INEN_SHIFT)) & EWM_CTRL_INEN_MASK)
+#define EWM_CTRL_INTEN_MASK (0x8U)
+#define EWM_CTRL_INTEN_SHIFT (3U)
+#define EWM_CTRL_INTEN(x) (((uint8_t)(((uint8_t)(x)) << EWM_CTRL_INTEN_SHIFT)) & EWM_CTRL_INTEN_MASK)
+
+/*! @name SERV - Service Register */
+#define EWM_SERV_SERVICE_MASK (0xFFU)
+#define EWM_SERV_SERVICE_SHIFT (0U)
+#define EWM_SERV_SERVICE(x) (((uint8_t)(((uint8_t)(x)) << EWM_SERV_SERVICE_SHIFT)) & EWM_SERV_SERVICE_MASK)
+
+/*! @name CMPL - Compare Low Register */
+#define EWM_CMPL_COMPAREL_MASK (0xFFU)
+#define EWM_CMPL_COMPAREL_SHIFT (0U)
+#define EWM_CMPL_COMPAREL(x) (((uint8_t)(((uint8_t)(x)) << EWM_CMPL_COMPAREL_SHIFT)) & EWM_CMPL_COMPAREL_MASK)
+
+/*! @name CMPH - Compare High Register */
+#define EWM_CMPH_COMPAREH_MASK (0xFFU)
+#define EWM_CMPH_COMPAREH_SHIFT (0U)
+#define EWM_CMPH_COMPAREH(x) (((uint8_t)(((uint8_t)(x)) << EWM_CMPH_COMPAREH_SHIFT)) & EWM_CMPH_COMPAREH_MASK)
+
+/*! @name CLKPRESCALER - Clock Prescaler Register */
+#define EWM_CLKPRESCALER_CLK_DIV_MASK (0xFFU)
+#define EWM_CLKPRESCALER_CLK_DIV_SHIFT (0U)
+#define EWM_CLKPRESCALER_CLK_DIV(x) (((uint8_t)(((uint8_t)(x)) << EWM_CLKPRESCALER_CLK_DIV_SHIFT)) & EWM_CLKPRESCALER_CLK_DIV_MASK)
+
+
+/*!
+ * @}
+ */ /* end of group EWM_Register_Masks */
+
+
+/* EWM - Peripheral instance base addresses */
+/** Peripheral EWM base address */
+#define EWM_BASE (0x40061000u)
+/** Peripheral EWM base pointer */
+#define EWM ((EWM_Type *)EWM_BASE)
+/** Array initializer of EWM peripheral base addresses */
+#define EWM_BASE_ADDRS { EWM_BASE }
+/** Array initializer of EWM peripheral base pointers */
+#define EWM_BASE_PTRS { EWM }
+/** Interrupt vectors for the EWM peripheral type */
+#define EWM_IRQS { WDOG_EWM_IRQn }
+
+/*!
+ * @}
+ */ /* end of group EWM_Peripheral_Access_Layer */
+
+
+/* ----------------------------------------------------------------------------
+ -- FMC Peripheral Access Layer
+ ---------------------------------------------------------------------------- */
+
+/*!
+ * @addtogroup FMC_Peripheral_Access_Layer FMC Peripheral Access Layer
+ * @{
+ */
+
+/** FMC - Register Layout Typedef */
+typedef struct {
+ __IO uint32_t PFAPR; /**< Flash Access Protection Register, offset: 0x0 */
+ __IO uint32_t PFB0CR; /**< Flash Bank 0 Control Register, offset: 0x4 */
+ __IO uint32_t PFB1CR; /**< Flash Bank 1 Control Register, offset: 0x8 */
+ uint8_t RESERVED_0[244];
+ __IO uint32_t TAGVDW0S[8]; /**< Cache Tag Storage, array offset: 0x100, array step: 0x4 */
+ __IO uint32_t TAGVDW1S[8]; /**< Cache Tag Storage, array offset: 0x120, array step: 0x4 */
+ __IO uint32_t TAGVDW2S[8]; /**< Cache Tag Storage, array offset: 0x140, array step: 0x4 */
+ __IO uint32_t TAGVDW3S[8]; /**< Cache Tag Storage, array offset: 0x160, array step: 0x4 */
+ uint8_t RESERVED_1[128];
+ struct { /* offset: 0x200, array step: index*0x40, index2*0x8 */
+ __IO uint32_t DATA_U; /**< Cache Data Storage (upper word), array offset: 0x200, array step: index*0x40, index2*0x8 */
+ __IO uint32_t DATA_L; /**< Cache Data Storage (lower word), array offset: 0x204, array step: index*0x40, index2*0x8 */
+ } SET[4][8];
+} FMC_Type;
+
+/* ----------------------------------------------------------------------------
+ -- FMC Register Masks
+ ---------------------------------------------------------------------------- */
+
+/*!
+ * @addtogroup FMC_Register_Masks FMC Register Masks
+ * @{
+ */
+
+/*! @name PFAPR - Flash Access Protection Register */
+#define FMC_PFAPR_M0AP_MASK (0x3U)
+#define FMC_PFAPR_M0AP_SHIFT (0U)
+#define FMC_PFAPR_M0AP(x) (((uint32_t)(((uint32_t)(x)) << FMC_PFAPR_M0AP_SHIFT)) & FMC_PFAPR_M0AP_MASK)
+#define FMC_PFAPR_M1AP_MASK (0xCU)
+#define FMC_PFAPR_M1AP_SHIFT (2U)
+#define FMC_PFAPR_M1AP(x) (((uint32_t)(((uint32_t)(x)) << FMC_PFAPR_M1AP_SHIFT)) & FMC_PFAPR_M1AP_MASK)
+#define FMC_PFAPR_M2AP_MASK (0x30U)
+#define FMC_PFAPR_M2AP_SHIFT (4U)
+#define FMC_PFAPR_M2AP(x) (((uint32_t)(((uint32_t)(x)) << FMC_PFAPR_M2AP_SHIFT)) & FMC_PFAPR_M2AP_MASK)
+#define FMC_PFAPR_M3AP_MASK (0xC0U)
+#define FMC_PFAPR_M3AP_SHIFT (6U)
+#define FMC_PFAPR_M3AP(x) (((uint32_t)(((uint32_t)(x)) << FMC_PFAPR_M3AP_SHIFT)) & FMC_PFAPR_M3AP_MASK)
+#define FMC_PFAPR_M4AP_MASK (0x300U)
+#define FMC_PFAPR_M4AP_SHIFT (8U)
+#define FMC_PFAPR_M4AP(x) (((uint32_t)(((uint32_t)(x)) << FMC_PFAPR_M4AP_SHIFT)) & FMC_PFAPR_M4AP_MASK)
+#define FMC_PFAPR_M5AP_MASK (0xC00U)
+#define FMC_PFAPR_M5AP_SHIFT (10U)
+#define FMC_PFAPR_M5AP(x) (((uint32_t)(((uint32_t)(x)) << FMC_PFAPR_M5AP_SHIFT)) & FMC_PFAPR_M5AP_MASK)
+#define FMC_PFAPR_M6AP_MASK (0x3000U)
+#define FMC_PFAPR_M6AP_SHIFT (12U)
+#define FMC_PFAPR_M6AP(x) (((uint32_t)(((uint32_t)(x)) << FMC_PFAPR_M6AP_SHIFT)) & FMC_PFAPR_M6AP_MASK)
+#define FMC_PFAPR_M7AP_MASK (0xC000U)
+#define FMC_PFAPR_M7AP_SHIFT (14U)
+#define FMC_PFAPR_M7AP(x) (((uint32_t)(((uint32_t)(x)) << FMC_PFAPR_M7AP_SHIFT)) & FMC_PFAPR_M7AP_MASK)
+#define FMC_PFAPR_M0PFD_MASK (0x10000U)
+#define FMC_PFAPR_M0PFD_SHIFT (16U)
+#define FMC_PFAPR_M0PFD(x) (((uint32_t)(((uint32_t)(x)) << FMC_PFAPR_M0PFD_SHIFT)) & FMC_PFAPR_M0PFD_MASK)
+#define FMC_PFAPR_M1PFD_MASK (0x20000U)
+#define FMC_PFAPR_M1PFD_SHIFT (17U)
+#define FMC_PFAPR_M1PFD(x) (((uint32_t)(((uint32_t)(x)) << FMC_PFAPR_M1PFD_SHIFT)) & FMC_PFAPR_M1PFD_MASK)
+#define FMC_PFAPR_M2PFD_MASK (0x40000U)
+#define FMC_PFAPR_M2PFD_SHIFT (18U)
+#define FMC_PFAPR_M2PFD(x) (((uint32_t)(((uint32_t)(x)) << FMC_PFAPR_M2PFD_SHIFT)) & FMC_PFAPR_M2PFD_MASK)
+#define FMC_PFAPR_M3PFD_MASK (0x80000U)
+#define FMC_PFAPR_M3PFD_SHIFT (19U)
+#define FMC_PFAPR_M3PFD(x) (((uint32_t)(((uint32_t)(x)) << FMC_PFAPR_M3PFD_SHIFT)) & FMC_PFAPR_M3PFD_MASK)
+#define FMC_PFAPR_M4PFD_MASK (0x100000U)
+#define FMC_PFAPR_M4PFD_SHIFT (20U)
+#define FMC_PFAPR_M4PFD(x) (((uint32_t)(((uint32_t)(x)) << FMC_PFAPR_M4PFD_SHIFT)) & FMC_PFAPR_M4PFD_MASK)
+#define FMC_PFAPR_M5PFD_MASK (0x200000U)
+#define FMC_PFAPR_M5PFD_SHIFT (21U)
+#define FMC_PFAPR_M5PFD(x) (((uint32_t)(((uint32_t)(x)) << FMC_PFAPR_M5PFD_SHIFT)) & FMC_PFAPR_M5PFD_MASK)
+#define FMC_PFAPR_M6PFD_MASK (0x400000U)
+#define FMC_PFAPR_M6PFD_SHIFT (22U)
+#define FMC_PFAPR_M6PFD(x) (((uint32_t)(((uint32_t)(x)) << FMC_PFAPR_M6PFD_SHIFT)) & FMC_PFAPR_M6PFD_MASK)
+#define FMC_PFAPR_M7PFD_MASK (0x800000U)
+#define FMC_PFAPR_M7PFD_SHIFT (23U)
+#define FMC_PFAPR_M7PFD(x) (((uint32_t)(((uint32_t)(x)) << FMC_PFAPR_M7PFD_SHIFT)) & FMC_PFAPR_M7PFD_MASK)
+
+/*! @name PFB0CR - Flash Bank 0 Control Register */
+#define FMC_PFB0CR_B0SEBE_MASK (0x1U)
+#define FMC_PFB0CR_B0SEBE_SHIFT (0U)
+#define FMC_PFB0CR_B0SEBE(x) (((uint32_t)(((uint32_t)(x)) << FMC_PFB0CR_B0SEBE_SHIFT)) & FMC_PFB0CR_B0SEBE_MASK)
+#define FMC_PFB0CR_B0IPE_MASK (0x2U)
+#define FMC_PFB0CR_B0IPE_SHIFT (1U)
+#define FMC_PFB0CR_B0IPE(x) (((uint32_t)(((uint32_t)(x)) << FMC_PFB0CR_B0IPE_SHIFT)) & FMC_PFB0CR_B0IPE_MASK)
+#define FMC_PFB0CR_B0DPE_MASK (0x4U)
+#define FMC_PFB0CR_B0DPE_SHIFT (2U)
+#define FMC_PFB0CR_B0DPE(x) (((uint32_t)(((uint32_t)(x)) << FMC_PFB0CR_B0DPE_SHIFT)) & FMC_PFB0CR_B0DPE_MASK)
+#define FMC_PFB0CR_B0ICE_MASK (0x8U)
+#define FMC_PFB0CR_B0ICE_SHIFT (3U)
+#define FMC_PFB0CR_B0ICE(x) (((uint32_t)(((uint32_t)(x)) << FMC_PFB0CR_B0ICE_SHIFT)) & FMC_PFB0CR_B0ICE_MASK)
+#define FMC_PFB0CR_B0DCE_MASK (0x10U)
+#define FMC_PFB0CR_B0DCE_SHIFT (4U)
+#define FMC_PFB0CR_B0DCE(x) (((uint32_t)(((uint32_t)(x)) << FMC_PFB0CR_B0DCE_SHIFT)) & FMC_PFB0CR_B0DCE_MASK)
+#define FMC_PFB0CR_CRC_MASK (0xE0U)
+#define FMC_PFB0CR_CRC_SHIFT (5U)
+#define FMC_PFB0CR_CRC(x) (((uint32_t)(((uint32_t)(x)) << FMC_PFB0CR_CRC_SHIFT)) & FMC_PFB0CR_CRC_MASK)
+#define FMC_PFB0CR_B0MW_MASK (0x60000U)
+#define FMC_PFB0CR_B0MW_SHIFT (17U)
+#define FMC_PFB0CR_B0MW(x) (((uint32_t)(((uint32_t)(x)) << FMC_PFB0CR_B0MW_SHIFT)) & FMC_PFB0CR_B0MW_MASK)
+#define FMC_PFB0CR_S_B_INV_MASK (0x80000U)
+#define FMC_PFB0CR_S_B_INV_SHIFT (19U)
+#define FMC_PFB0CR_S_B_INV(x) (((uint32_t)(((uint32_t)(x)) << FMC_PFB0CR_S_B_INV_SHIFT)) & FMC_PFB0CR_S_B_INV_MASK)
+#define FMC_PFB0CR_CINV_WAY_MASK (0xF00000U)
+#define FMC_PFB0CR_CINV_WAY_SHIFT (20U)
+#define FMC_PFB0CR_CINV_WAY(x) (((uint32_t)(((uint32_t)(x)) << FMC_PFB0CR_CINV_WAY_SHIFT)) & FMC_PFB0CR_CINV_WAY_MASK)
+#define FMC_PFB0CR_CLCK_WAY_MASK (0xF000000U)
+#define FMC_PFB0CR_CLCK_WAY_SHIFT (24U)
+#define FMC_PFB0CR_CLCK_WAY(x) (((uint32_t)(((uint32_t)(x)) << FMC_PFB0CR_CLCK_WAY_SHIFT)) & FMC_PFB0CR_CLCK_WAY_MASK)
+#define FMC_PFB0CR_B0RWSC_MASK (0xF0000000U)
+#define FMC_PFB0CR_B0RWSC_SHIFT (28U)
+#define FMC_PFB0CR_B0RWSC(x) (((uint32_t)(((uint32_t)(x)) << FMC_PFB0CR_B0RWSC_SHIFT)) & FMC_PFB0CR_B0RWSC_MASK)
+
+/*! @name PFB1CR - Flash Bank 1 Control Register */
+#define FMC_PFB1CR_B1SEBE_MASK (0x1U)
+#define FMC_PFB1CR_B1SEBE_SHIFT (0U)
+#define FMC_PFB1CR_B1SEBE(x) (((uint32_t)(((uint32_t)(x)) << FMC_PFB1CR_B1SEBE_SHIFT)) & FMC_PFB1CR_B1SEBE_MASK)
+#define FMC_PFB1CR_B1IPE_MASK (0x2U)
+#define FMC_PFB1CR_B1IPE_SHIFT (1U)
+#define FMC_PFB1CR_B1IPE(x) (((uint32_t)(((uint32_t)(x)) << FMC_PFB1CR_B1IPE_SHIFT)) & FMC_PFB1CR_B1IPE_MASK)
+#define FMC_PFB1CR_B1DPE_MASK (0x4U)
+#define FMC_PFB1CR_B1DPE_SHIFT (2U)
+#define FMC_PFB1CR_B1DPE(x) (((uint32_t)(((uint32_t)(x)) << FMC_PFB1CR_B1DPE_SHIFT)) & FMC_PFB1CR_B1DPE_MASK)
+#define FMC_PFB1CR_B1ICE_MASK (0x8U)
+#define FMC_PFB1CR_B1ICE_SHIFT (3U)
+#define FMC_PFB1CR_B1ICE(x) (((uint32_t)(((uint32_t)(x)) << FMC_PFB1CR_B1ICE_SHIFT)) & FMC_PFB1CR_B1ICE_MASK)
+#define FMC_PFB1CR_B1DCE_MASK (0x10U)
+#define FMC_PFB1CR_B1DCE_SHIFT (4U)
+#define FMC_PFB1CR_B1DCE(x) (((uint32_t)(((uint32_t)(x)) << FMC_PFB1CR_B1DCE_SHIFT)) & FMC_PFB1CR_B1DCE_MASK)
+#define FMC_PFB1CR_B1MW_MASK (0x60000U)
+#define FMC_PFB1CR_B1MW_SHIFT (17U)
+#define FMC_PFB1CR_B1MW(x) (((uint32_t)(((uint32_t)(x)) << FMC_PFB1CR_B1MW_SHIFT)) & FMC_PFB1CR_B1MW_MASK)
+#define FMC_PFB1CR_B1RWSC_MASK (0xF0000000U)
+#define FMC_PFB1CR_B1RWSC_SHIFT (28U)
+#define FMC_PFB1CR_B1RWSC(x) (((uint32_t)(((uint32_t)(x)) << FMC_PFB1CR_B1RWSC_SHIFT)) & FMC_PFB1CR_B1RWSC_MASK)
+
+/*! @name TAGVDW0S - Cache Tag Storage */
+#define FMC_TAGVDW0S_valid_MASK (0x1U)
+#define FMC_TAGVDW0S_valid_SHIFT (0U)
+#define FMC_TAGVDW0S_valid(x) (((uint32_t)(((uint32_t)(x)) << FMC_TAGVDW0S_valid_SHIFT)) & FMC_TAGVDW0S_valid_MASK)
+#define FMC_TAGVDW0S_tag_MASK (0x7FFE0U)
+#define FMC_TAGVDW0S_tag_SHIFT (5U)
+#define FMC_TAGVDW0S_tag(x) (((uint32_t)(((uint32_t)(x)) << FMC_TAGVDW0S_tag_SHIFT)) & FMC_TAGVDW0S_tag_MASK)
+
+/* The count of FMC_TAGVDW0S */
+#define FMC_TAGVDW0S_COUNT (8U)
+
+/*! @name TAGVDW1S - Cache Tag Storage */
+#define FMC_TAGVDW1S_valid_MASK (0x1U)
+#define FMC_TAGVDW1S_valid_SHIFT (0U)
+#define FMC_TAGVDW1S_valid(x) (((uint32_t)(((uint32_t)(x)) << FMC_TAGVDW1S_valid_SHIFT)) & FMC_TAGVDW1S_valid_MASK)
+#define FMC_TAGVDW1S_tag_MASK (0x7FFE0U)
+#define FMC_TAGVDW1S_tag_SHIFT (5U)
+#define FMC_TAGVDW1S_tag(x) (((uint32_t)(((uint32_t)(x)) << FMC_TAGVDW1S_tag_SHIFT)) & FMC_TAGVDW1S_tag_MASK)
+
+/* The count of FMC_TAGVDW1S */
+#define FMC_TAGVDW1S_COUNT (8U)
+
+/*! @name TAGVDW2S - Cache Tag Storage */
+#define FMC_TAGVDW2S_valid_MASK (0x1U)
+#define FMC_TAGVDW2S_valid_SHIFT (0U)
+#define FMC_TAGVDW2S_valid(x) (((uint32_t)(((uint32_t)(x)) << FMC_TAGVDW2S_valid_SHIFT)) & FMC_TAGVDW2S_valid_MASK)
+#define FMC_TAGVDW2S_tag_MASK (0x7FFE0U)
+#define FMC_TAGVDW2S_tag_SHIFT (5U)
+#define FMC_TAGVDW2S_tag(x) (((uint32_t)(((uint32_t)(x)) << FMC_TAGVDW2S_tag_SHIFT)) & FMC_TAGVDW2S_tag_MASK)
+
+/* The count of FMC_TAGVDW2S */
+#define FMC_TAGVDW2S_COUNT (8U)
+
+/*! @name TAGVDW3S - Cache Tag Storage */
+#define FMC_TAGVDW3S_valid_MASK (0x1U)
+#define FMC_TAGVDW3S_valid_SHIFT (0U)
+#define FMC_TAGVDW3S_valid(x) (((uint32_t)(((uint32_t)(x)) << FMC_TAGVDW3S_valid_SHIFT)) & FMC_TAGVDW3S_valid_MASK)
+#define FMC_TAGVDW3S_tag_MASK (0x7FFE0U)
+#define FMC_TAGVDW3S_tag_SHIFT (5U)
+#define FMC_TAGVDW3S_tag(x) (((uint32_t)(((uint32_t)(x)) << FMC_TAGVDW3S_tag_SHIFT)) & FMC_TAGVDW3S_tag_MASK)
+
+/* The count of FMC_TAGVDW3S */
+#define FMC_TAGVDW3S_COUNT (8U)
+
+/*! @name DATA_U - Cache Data Storage (upper word) */
+#define FMC_DATA_U_data_MASK (0xFFFFFFFFU)
+#define FMC_DATA_U_data_SHIFT (0U)
+#define FMC_DATA_U_data(x) (((uint32_t)(((uint32_t)(x)) << FMC_DATA_U_data_SHIFT)) & FMC_DATA_U_data_MASK)
+
+/* The count of FMC_DATA_U */
+#define FMC_DATA_U_COUNT (4U)
+
+/* The count of FMC_DATA_U */
+#define FMC_DATA_U_COUNT2 (8U)
+
+/*! @name DATA_L - Cache Data Storage (lower word) */
+#define FMC_DATA_L_data_MASK (0xFFFFFFFFU)
+#define FMC_DATA_L_data_SHIFT (0U)
+#define FMC_DATA_L_data(x) (((uint32_t)(((uint32_t)(x)) << FMC_DATA_L_data_SHIFT)) & FMC_DATA_L_data_MASK)
+
+/* The count of FMC_DATA_L */
+#define FMC_DATA_L_COUNT (4U)
+
+/* The count of FMC_DATA_L */
+#define FMC_DATA_L_COUNT2 (8U)
+
+
+/*!
+ * @}
+ */ /* end of group FMC_Register_Masks */
+
+
+/* FMC - Peripheral instance base addresses */
+/** Peripheral FMC base address */
+#define FMC_BASE (0x4001F000u)
+/** Peripheral FMC base pointer */
+#define FMC ((FMC_Type *)FMC_BASE)
+/** Array initializer of FMC peripheral base addresses */
+#define FMC_BASE_ADDRS { FMC_BASE }
+/** Array initializer of FMC peripheral base pointers */
+#define FMC_BASE_PTRS { FMC }
+
+/*!
+ * @}
+ */ /* end of group FMC_Peripheral_Access_Layer */
+
+
+/* ----------------------------------------------------------------------------
+ -- FTFA Peripheral Access Layer
+ ---------------------------------------------------------------------------- */
+
+/*!
+ * @addtogroup FTFA_Peripheral_Access_Layer FTFA Peripheral Access Layer
+ * @{
+ */
+
+/** FTFA - Register Layout Typedef */
+typedef struct {
+ __IO uint8_t FSTAT; /**< Flash Status Register, offset: 0x0 */
+ __IO uint8_t FCNFG; /**< Flash Configuration Register, offset: 0x1 */
+ __I uint8_t FSEC; /**< Flash Security Register, offset: 0x2 */
+ __I uint8_t FOPT; /**< Flash Option Register, offset: 0x3 */
+ __IO uint8_t FCCOB3; /**< Flash Common Command Object Registers, offset: 0x4 */
+ __IO uint8_t FCCOB2; /**< Flash Common Command Object Registers, offset: 0x5 */
+ __IO uint8_t FCCOB1; /**< Flash Common Command Object Registers, offset: 0x6 */
+ __IO uint8_t FCCOB0; /**< Flash Common Command Object Registers, offset: 0x7 */
+ __IO uint8_t FCCOB7; /**< Flash Common Command Object Registers, offset: 0x8 */
+ __IO uint8_t FCCOB6; /**< Flash Common Command Object Registers, offset: 0x9 */
+ __IO uint8_t FCCOB5; /**< Flash Common Command Object Registers, offset: 0xA */
+ __IO uint8_t FCCOB4; /**< Flash Common Command Object Registers, offset: 0xB */
+ __IO uint8_t FCCOBB; /**< Flash Common Command Object Registers, offset: 0xC */
+ __IO uint8_t FCCOBA; /**< Flash Common Command Object Registers, offset: 0xD */
+ __IO uint8_t FCCOB9; /**< Flash Common Command Object Registers, offset: 0xE */
+ __IO uint8_t FCCOB8; /**< Flash Common Command Object Registers, offset: 0xF */
+ __IO uint8_t FPROT3; /**< Program Flash Protection Registers, offset: 0x10 */
+ __IO uint8_t FPROT2; /**< Program Flash Protection Registers, offset: 0x11 */
+ __IO uint8_t FPROT1; /**< Program Flash Protection Registers, offset: 0x12 */
+ __IO uint8_t FPROT0; /**< Program Flash Protection Registers, offset: 0x13 */
+ uint8_t RESERVED_0[4];
+ __I uint8_t XACCH3; /**< Execute-only Access Registers, offset: 0x18 */
+ __I uint8_t XACCH2; /**< Execute-only Access Registers, offset: 0x19 */
+ __I uint8_t XACCH1; /**< Execute-only Access Registers, offset: 0x1A */
+ __I uint8_t XACCH0; /**< Execute-only Access Registers, offset: 0x1B */
+ __I uint8_t XACCL3; /**< Execute-only Access Registers, offset: 0x1C */
+ __I uint8_t XACCL2; /**< Execute-only Access Registers, offset: 0x1D */
+ __I uint8_t XACCL1; /**< Execute-only Access Registers, offset: 0x1E */
+ __I uint8_t XACCL0; /**< Execute-only Access Registers, offset: 0x1F */
+ __I uint8_t SACCH3; /**< Supervisor-only Access Registers, offset: 0x20 */
+ __I uint8_t SACCH2; /**< Supervisor-only Access Registers, offset: 0x21 */
+ __I uint8_t SACCH1; /**< Supervisor-only Access Registers, offset: 0x22 */
+ __I uint8_t SACCH0; /**< Supervisor-only Access Registers, offset: 0x23 */
+ __I uint8_t SACCL3; /**< Supervisor-only Access Registers, offset: 0x24 */
+ __I uint8_t SACCL2; /**< Supervisor-only Access Registers, offset: 0x25 */
+ __I uint8_t SACCL1; /**< Supervisor-only Access Registers, offset: 0x26 */
+ __I uint8_t SACCL0; /**< Supervisor-only Access Registers, offset: 0x27 */
+ __I uint8_t FACSS; /**< Flash Access Segment Size Register, offset: 0x28 */
+ uint8_t RESERVED_1[2];
+ __I uint8_t FACSN; /**< Flash Access Segment Number Register, offset: 0x2B */
+} FTFA_Type;
+
+/* ----------------------------------------------------------------------------
+ -- FTFA Register Masks
+ ---------------------------------------------------------------------------- */
+
+/*!
+ * @addtogroup FTFA_Register_Masks FTFA Register Masks
+ * @{
+ */
+
+/*! @name FSTAT - Flash Status Register */
+#define FTFA_FSTAT_MGSTAT0_MASK (0x1U)
+#define FTFA_FSTAT_MGSTAT0_SHIFT (0U)
+#define FTFA_FSTAT_MGSTAT0(x) (((uint8_t)(((uint8_t)(x)) << FTFA_FSTAT_MGSTAT0_SHIFT)) & FTFA_FSTAT_MGSTAT0_MASK)
+#define FTFA_FSTAT_FPVIOL_MASK (0x10U)
+#define FTFA_FSTAT_FPVIOL_SHIFT (4U)
+#define FTFA_FSTAT_FPVIOL(x) (((uint8_t)(((uint8_t)(x)) << FTFA_FSTAT_FPVIOL_SHIFT)) & FTFA_FSTAT_FPVIOL_MASK)
+#define FTFA_FSTAT_ACCERR_MASK (0x20U)
+#define FTFA_FSTAT_ACCERR_SHIFT (5U)
+#define FTFA_FSTAT_ACCERR(x) (((uint8_t)(((uint8_t)(x)) << FTFA_FSTAT_ACCERR_SHIFT)) & FTFA_FSTAT_ACCERR_MASK)
+#define FTFA_FSTAT_RDCOLERR_MASK (0x40U)
+#define FTFA_FSTAT_RDCOLERR_SHIFT (6U)
+#define FTFA_FSTAT_RDCOLERR(x) (((uint8_t)(((uint8_t)(x)) << FTFA_FSTAT_RDCOLERR_SHIFT)) & FTFA_FSTAT_RDCOLERR_MASK)
+#define FTFA_FSTAT_CCIF_MASK (0x80U)
+#define FTFA_FSTAT_CCIF_SHIFT (7U)
+#define FTFA_FSTAT_CCIF(x) (((uint8_t)(((uint8_t)(x)) << FTFA_FSTAT_CCIF_SHIFT)) & FTFA_FSTAT_CCIF_MASK)
+
+/*! @name FCNFG - Flash Configuration Register */
+#define FTFA_FCNFG_ERSSUSP_MASK (0x10U)
+#define FTFA_FCNFG_ERSSUSP_SHIFT (4U)
+#define FTFA_FCNFG_ERSSUSP(x) (((uint8_t)(((uint8_t)(x)) << FTFA_FCNFG_ERSSUSP_SHIFT)) & FTFA_FCNFG_ERSSUSP_MASK)
+#define FTFA_FCNFG_ERSAREQ_MASK (0x20U)
+#define FTFA_FCNFG_ERSAREQ_SHIFT (5U)
+#define FTFA_FCNFG_ERSAREQ(x) (((uint8_t)(((uint8_t)(x)) << FTFA_FCNFG_ERSAREQ_SHIFT)) & FTFA_FCNFG_ERSAREQ_MASK)
+#define FTFA_FCNFG_RDCOLLIE_MASK (0x40U)
+#define FTFA_FCNFG_RDCOLLIE_SHIFT (6U)
+#define FTFA_FCNFG_RDCOLLIE(x) (((uint8_t)(((uint8_t)(x)) << FTFA_FCNFG_RDCOLLIE_SHIFT)) & FTFA_FCNFG_RDCOLLIE_MASK)
+#define FTFA_FCNFG_CCIE_MASK (0x80U)
+#define FTFA_FCNFG_CCIE_SHIFT (7U)
+#define FTFA_FCNFG_CCIE(x) (((uint8_t)(((uint8_t)(x)) << FTFA_FCNFG_CCIE_SHIFT)) & FTFA_FCNFG_CCIE_MASK)
+
+/*! @name FSEC - Flash Security Register */
+#define FTFA_FSEC_SEC_MASK (0x3U)
+#define FTFA_FSEC_SEC_SHIFT (0U)
+#define FTFA_FSEC_SEC(x) (((uint8_t)(((uint8_t)(x)) << FTFA_FSEC_SEC_SHIFT)) & FTFA_FSEC_SEC_MASK)
+#define FTFA_FSEC_FSLACC_MASK (0xCU)
+#define FTFA_FSEC_FSLACC_SHIFT (2U)
+#define FTFA_FSEC_FSLACC(x) (((uint8_t)(((uint8_t)(x)) << FTFA_FSEC_FSLACC_SHIFT)) & FTFA_FSEC_FSLACC_MASK)
+#define FTFA_FSEC_MEEN_MASK (0x30U)
+#define FTFA_FSEC_MEEN_SHIFT (4U)
+#define FTFA_FSEC_MEEN(x) (((uint8_t)(((uint8_t)(x)) << FTFA_FSEC_MEEN_SHIFT)) & FTFA_FSEC_MEEN_MASK)
+#define FTFA_FSEC_KEYEN_MASK (0xC0U)
+#define FTFA_FSEC_KEYEN_SHIFT (6U)
+#define FTFA_FSEC_KEYEN(x) (((uint8_t)(((uint8_t)(x)) << FTFA_FSEC_KEYEN_SHIFT)) & FTFA_FSEC_KEYEN_MASK)
+
+/*! @name FOPT - Flash Option Register */
+#define FTFA_FOPT_OPT_MASK (0xFFU)
+#define FTFA_FOPT_OPT_SHIFT (0U)
+#define FTFA_FOPT_OPT(x) (((uint8_t)(((uint8_t)(x)) << FTFA_FOPT_OPT_SHIFT)) & FTFA_FOPT_OPT_MASK)
+
+/*! @name FCCOB3 - Flash Common Command Object Registers */
+#define FTFA_FCCOB3_CCOBn_MASK (0xFFU)
+#define FTFA_FCCOB3_CCOBn_SHIFT (0U)
+#define FTFA_FCCOB3_CCOBn(x) (((uint8_t)(((uint8_t)(x)) << FTFA_FCCOB3_CCOBn_SHIFT)) & FTFA_FCCOB3_CCOBn_MASK)
+
+/*! @name FCCOB2 - Flash Common Command Object Registers */
+#define FTFA_FCCOB2_CCOBn_MASK (0xFFU)
+#define FTFA_FCCOB2_CCOBn_SHIFT (0U)
+#define FTFA_FCCOB2_CCOBn(x) (((uint8_t)(((uint8_t)(x)) << FTFA_FCCOB2_CCOBn_SHIFT)) & FTFA_FCCOB2_CCOBn_MASK)
+
+/*! @name FCCOB1 - Flash Common Command Object Registers */
+#define FTFA_FCCOB1_CCOBn_MASK (0xFFU)
+#define FTFA_FCCOB1_CCOBn_SHIFT (0U)
+#define FTFA_FCCOB1_CCOBn(x) (((uint8_t)(((uint8_t)(x)) << FTFA_FCCOB1_CCOBn_SHIFT)) & FTFA_FCCOB1_CCOBn_MASK)
+
+/*! @name FCCOB0 - Flash Common Command Object Registers */
+#define FTFA_FCCOB0_CCOBn_MASK (0xFFU)
+#define FTFA_FCCOB0_CCOBn_SHIFT (0U)
+#define FTFA_FCCOB0_CCOBn(x) (((uint8_t)(((uint8_t)(x)) << FTFA_FCCOB0_CCOBn_SHIFT)) & FTFA_FCCOB0_CCOBn_MASK)
+
+/*! @name FCCOB7 - Flash Common Command Object Registers */
+#define FTFA_FCCOB7_CCOBn_MASK (0xFFU)
+#define FTFA_FCCOB7_CCOBn_SHIFT (0U)
+#define FTFA_FCCOB7_CCOBn(x) (((uint8_t)(((uint8_t)(x)) << FTFA_FCCOB7_CCOBn_SHIFT)) & FTFA_FCCOB7_CCOBn_MASK)
+
+/*! @name FCCOB6 - Flash Common Command Object Registers */
+#define FTFA_FCCOB6_CCOBn_MASK (0xFFU)
+#define FTFA_FCCOB6_CCOBn_SHIFT (0U)
+#define FTFA_FCCOB6_CCOBn(x) (((uint8_t)(((uint8_t)(x)) << FTFA_FCCOB6_CCOBn_SHIFT)) & FTFA_FCCOB6_CCOBn_MASK)
+
+/*! @name FCCOB5 - Flash Common Command Object Registers */
+#define FTFA_FCCOB5_CCOBn_MASK (0xFFU)
+#define FTFA_FCCOB5_CCOBn_SHIFT (0U)
+#define FTFA_FCCOB5_CCOBn(x) (((uint8_t)(((uint8_t)(x)) << FTFA_FCCOB5_CCOBn_SHIFT)) & FTFA_FCCOB5_CCOBn_MASK)
+
+/*! @name FCCOB4 - Flash Common Command Object Registers */
+#define FTFA_FCCOB4_CCOBn_MASK (0xFFU)
+#define FTFA_FCCOB4_CCOBn_SHIFT (0U)
+#define FTFA_FCCOB4_CCOBn(x) (((uint8_t)(((uint8_t)(x)) << FTFA_FCCOB4_CCOBn_SHIFT)) & FTFA_FCCOB4_CCOBn_MASK)
+
+/*! @name FCCOBB - Flash Common Command Object Registers */
+#define FTFA_FCCOBB_CCOBn_MASK (0xFFU)
+#define FTFA_FCCOBB_CCOBn_SHIFT (0U)
+#define FTFA_FCCOBB_CCOBn(x) (((uint8_t)(((uint8_t)(x)) << FTFA_FCCOBB_CCOBn_SHIFT)) & FTFA_FCCOBB_CCOBn_MASK)
+
+/*! @name FCCOBA - Flash Common Command Object Registers */
+#define FTFA_FCCOBA_CCOBn_MASK (0xFFU)
+#define FTFA_FCCOBA_CCOBn_SHIFT (0U)
+#define FTFA_FCCOBA_CCOBn(x) (((uint8_t)(((uint8_t)(x)) << FTFA_FCCOBA_CCOBn_SHIFT)) & FTFA_FCCOBA_CCOBn_MASK)
+
+/*! @name FCCOB9 - Flash Common Command Object Registers */
+#define FTFA_FCCOB9_CCOBn_MASK (0xFFU)
+#define FTFA_FCCOB9_CCOBn_SHIFT (0U)
+#define FTFA_FCCOB9_CCOBn(x) (((uint8_t)(((uint8_t)(x)) << FTFA_FCCOB9_CCOBn_SHIFT)) & FTFA_FCCOB9_CCOBn_MASK)
+
+/*! @name FCCOB8 - Flash Common Command Object Registers */
+#define FTFA_FCCOB8_CCOBn_MASK (0xFFU)
+#define FTFA_FCCOB8_CCOBn_SHIFT (0U)
+#define FTFA_FCCOB8_CCOBn(x) (((uint8_t)(((uint8_t)(x)) << FTFA_FCCOB8_CCOBn_SHIFT)) & FTFA_FCCOB8_CCOBn_MASK)
+
+/*! @name FPROT3 - Program Flash Protection Registers */
+#define FTFA_FPROT3_PROT_MASK (0xFFU)
+#define FTFA_FPROT3_PROT_SHIFT (0U)
+#define FTFA_FPROT3_PROT(x) (((uint8_t)(((uint8_t)(x)) << FTFA_FPROT3_PROT_SHIFT)) & FTFA_FPROT3_PROT_MASK)
+
+/*! @name FPROT2 - Program Flash Protection Registers */
+#define FTFA_FPROT2_PROT_MASK (0xFFU)
+#define FTFA_FPROT2_PROT_SHIFT (0U)
+#define FTFA_FPROT2_PROT(x) (((uint8_t)(((uint8_t)(x)) << FTFA_FPROT2_PROT_SHIFT)) & FTFA_FPROT2_PROT_MASK)
+
+/*! @name FPROT1 - Program Flash Protection Registers */
+#define FTFA_FPROT1_PROT_MASK (0xFFU)
+#define FTFA_FPROT1_PROT_SHIFT (0U)
+#define FTFA_FPROT1_PROT(x) (((uint8_t)(((uint8_t)(x)) << FTFA_FPROT1_PROT_SHIFT)) & FTFA_FPROT1_PROT_MASK)
+
+/*! @name FPROT0 - Program Flash Protection Registers */
+#define FTFA_FPROT0_PROT_MASK (0xFFU)
+#define FTFA_FPROT0_PROT_SHIFT (0U)
+#define FTFA_FPROT0_PROT(x) (((uint8_t)(((uint8_t)(x)) << FTFA_FPROT0_PROT_SHIFT)) & FTFA_FPROT0_PROT_MASK)
+
+/*! @name XACCH3 - Execute-only Access Registers */
+#define FTFA_XACCH3_XA_MASK (0xFFU)
+#define FTFA_XACCH3_XA_SHIFT (0U)
+#define FTFA_XACCH3_XA(x) (((uint8_t)(((uint8_t)(x)) << FTFA_XACCH3_XA_SHIFT)) & FTFA_XACCH3_XA_MASK)
+
+/*! @name XACCH2 - Execute-only Access Registers */
+#define FTFA_XACCH2_XA_MASK (0xFFU)
+#define FTFA_XACCH2_XA_SHIFT (0U)
+#define FTFA_XACCH2_XA(x) (((uint8_t)(((uint8_t)(x)) << FTFA_XACCH2_XA_SHIFT)) & FTFA_XACCH2_XA_MASK)
+
+/*! @name XACCH1 - Execute-only Access Registers */
+#define FTFA_XACCH1_XA_MASK (0xFFU)
+#define FTFA_XACCH1_XA_SHIFT (0U)
+#define FTFA_XACCH1_XA(x) (((uint8_t)(((uint8_t)(x)) << FTFA_XACCH1_XA_SHIFT)) & FTFA_XACCH1_XA_MASK)
+
+/*! @name XACCH0 - Execute-only Access Registers */
+#define FTFA_XACCH0_XA_MASK (0xFFU)
+#define FTFA_XACCH0_XA_SHIFT (0U)
+#define FTFA_XACCH0_XA(x) (((uint8_t)(((uint8_t)(x)) << FTFA_XACCH0_XA_SHIFT)) & FTFA_XACCH0_XA_MASK)
+
+/*! @name XACCL3 - Execute-only Access Registers */
+#define FTFA_XACCL3_XA_MASK (0xFFU)
+#define FTFA_XACCL3_XA_SHIFT (0U)
+#define FTFA_XACCL3_XA(x) (((uint8_t)(((uint8_t)(x)) << FTFA_XACCL3_XA_SHIFT)) & FTFA_XACCL3_XA_MASK)
+
+/*! @name XACCL2 - Execute-only Access Registers */
+#define FTFA_XACCL2_XA_MASK (0xFFU)
+#define FTFA_XACCL2_XA_SHIFT (0U)
+#define FTFA_XACCL2_XA(x) (((uint8_t)(((uint8_t)(x)) << FTFA_XACCL2_XA_SHIFT)) & FTFA_XACCL2_XA_MASK)
+
+/*! @name XACCL1 - Execute-only Access Registers */
+#define FTFA_XACCL1_XA_MASK (0xFFU)
+#define FTFA_XACCL1_XA_SHIFT (0U)
+#define FTFA_XACCL1_XA(x) (((uint8_t)(((uint8_t)(x)) << FTFA_XACCL1_XA_SHIFT)) & FTFA_XACCL1_XA_MASK)
+
+/*! @name XACCL0 - Execute-only Access Registers */
+#define FTFA_XACCL0_XA_MASK (0xFFU)
+#define FTFA_XACCL0_XA_SHIFT (0U)
+#define FTFA_XACCL0_XA(x) (((uint8_t)(((uint8_t)(x)) << FTFA_XACCL0_XA_SHIFT)) & FTFA_XACCL0_XA_MASK)
+
+/*! @name SACCH3 - Supervisor-only Access Registers */
+#define FTFA_SACCH3_SA_MASK (0xFFU)
+#define FTFA_SACCH3_SA_SHIFT (0U)
+#define FTFA_SACCH3_SA(x) (((uint8_t)(((uint8_t)(x)) << FTFA_SACCH3_SA_SHIFT)) & FTFA_SACCH3_SA_MASK)
+
+/*! @name SACCH2 - Supervisor-only Access Registers */
+#define FTFA_SACCH2_SA_MASK (0xFFU)
+#define FTFA_SACCH2_SA_SHIFT (0U)
+#define FTFA_SACCH2_SA(x) (((uint8_t)(((uint8_t)(x)) << FTFA_SACCH2_SA_SHIFT)) & FTFA_SACCH2_SA_MASK)
+
+/*! @name SACCH1 - Supervisor-only Access Registers */
+#define FTFA_SACCH1_SA_MASK (0xFFU)
+#define FTFA_SACCH1_SA_SHIFT (0U)
+#define FTFA_SACCH1_SA(x) (((uint8_t)(((uint8_t)(x)) << FTFA_SACCH1_SA_SHIFT)) & FTFA_SACCH1_SA_MASK)
+
+/*! @name SACCH0 - Supervisor-only Access Registers */
+#define FTFA_SACCH0_SA_MASK (0xFFU)
+#define FTFA_SACCH0_SA_SHIFT (0U)
+#define FTFA_SACCH0_SA(x) (((uint8_t)(((uint8_t)(x)) << FTFA_SACCH0_SA_SHIFT)) & FTFA_SACCH0_SA_MASK)
+
+/*! @name SACCL3 - Supervisor-only Access Registers */
+#define FTFA_SACCL3_SA_MASK (0xFFU)
+#define FTFA_SACCL3_SA_SHIFT (0U)
+#define FTFA_SACCL3_SA(x) (((uint8_t)(((uint8_t)(x)) << FTFA_SACCL3_SA_SHIFT)) & FTFA_SACCL3_SA_MASK)
+
+/*! @name SACCL2 - Supervisor-only Access Registers */
+#define FTFA_SACCL2_SA_MASK (0xFFU)
+#define FTFA_SACCL2_SA_SHIFT (0U)
+#define FTFA_SACCL2_SA(x) (((uint8_t)(((uint8_t)(x)) << FTFA_SACCL2_SA_SHIFT)) & FTFA_SACCL2_SA_MASK)
+
+/*! @name SACCL1 - Supervisor-only Access Registers */
+#define FTFA_SACCL1_SA_MASK (0xFFU)
+#define FTFA_SACCL1_SA_SHIFT (0U)
+#define FTFA_SACCL1_SA(x) (((uint8_t)(((uint8_t)(x)) << FTFA_SACCL1_SA_SHIFT)) & FTFA_SACCL1_SA_MASK)
+
+/*! @name SACCL0 - Supervisor-only Access Registers */
+#define FTFA_SACCL0_SA_MASK (0xFFU)
+#define FTFA_SACCL0_SA_SHIFT (0U)
+#define FTFA_SACCL0_SA(x) (((uint8_t)(((uint8_t)(x)) << FTFA_SACCL0_SA_SHIFT)) & FTFA_SACCL0_SA_MASK)
+
+/*! @name FACSS - Flash Access Segment Size Register */
+#define FTFA_FACSS_SGSIZE_MASK (0xFFU)
+#define FTFA_FACSS_SGSIZE_SHIFT (0U)
+#define FTFA_FACSS_SGSIZE(x) (((uint8_t)(((uint8_t)(x)) << FTFA_FACSS_SGSIZE_SHIFT)) & FTFA_FACSS_SGSIZE_MASK)
+
+/*! @name FACSN - Flash Access Segment Number Register */
+#define FTFA_FACSN_NUMSG_MASK (0xFFU)
+#define FTFA_FACSN_NUMSG_SHIFT (0U)
+#define FTFA_FACSN_NUMSG(x) (((uint8_t)(((uint8_t)(x)) << FTFA_FACSN_NUMSG_SHIFT)) & FTFA_FACSN_NUMSG_MASK)
+
+
+/*!
+ * @}
+ */ /* end of group FTFA_Register_Masks */
+
+
+/* FTFA - Peripheral instance base addresses */
+/** Peripheral FTFA base address */
+#define FTFA_BASE (0x40020000u)
+/** Peripheral FTFA base pointer */
+#define FTFA ((FTFA_Type *)FTFA_BASE)
+/** Array initializer of FTFA peripheral base addresses */
+#define FTFA_BASE_ADDRS { FTFA_BASE }
+/** Array initializer of FTFA peripheral base pointers */
+#define FTFA_BASE_PTRS { FTFA }
+/** Interrupt vectors for the FTFA peripheral type */
+#define FTFA_COMMAND_COMPLETE_IRQS { FTF_IRQn }
+#define FTFA_READ_COLLISION_IRQS { Read_Collision_IRQn }
+
+/*!
+ * @}
+ */ /* end of group FTFA_Peripheral_Access_Layer */
+
+
+/* ----------------------------------------------------------------------------
+ -- FTM Peripheral Access Layer
+ ---------------------------------------------------------------------------- */
+
+/*!
+ * @addtogroup FTM_Peripheral_Access_Layer FTM Peripheral Access Layer
+ * @{
+ */
+
+/** FTM - Register Layout Typedef */
+typedef struct {
+ __IO uint32_t SC; /**< Status And Control, offset: 0x0 */
+ __IO uint32_t CNT; /**< Counter, offset: 0x4 */
+ __IO uint32_t MOD; /**< Modulo, offset: 0x8 */
+ struct { /* offset: 0xC, array step: 0x8 */
+ __IO uint32_t CnSC; /**< Channel (n) Status And Control, array offset: 0xC, array step: 0x8 */
+ __IO uint32_t CnV; /**< Channel (n) Value, array offset: 0x10, array step: 0x8 */
+ } CONTROLS[6];
+ uint8_t RESERVED_0[16];
+ __IO uint32_t CNTIN; /**< Counter Initial Value, offset: 0x4C */
+ __IO uint32_t STATUS; /**< Capture And Compare Status, offset: 0x50 */
+ __IO uint32_t MODE; /**< Features Mode Selection, offset: 0x54 */
+ __IO uint32_t SYNC; /**< Synchronization, offset: 0x58 */
+ __IO uint32_t OUTINIT; /**< Initial State For Channels Output, offset: 0x5C */
+ __IO uint32_t OUTMASK; /**< Output Mask, offset: 0x60 */
+ __IO uint32_t COMBINE; /**< Function For Linked Channels, offset: 0x64 */
+ __IO uint32_t DEADTIME; /**< Deadtime Insertion Control, offset: 0x68 */
+ __IO uint32_t EXTTRIG; /**< FTM External Trigger, offset: 0x6C */
+ __IO uint32_t POL; /**< Channels Polarity, offset: 0x70 */
+ __IO uint32_t FMS; /**< Fault Mode Status, offset: 0x74 */
+ __IO uint32_t FILTER; /**< Input Capture Filter Control, offset: 0x78 */
+ __IO uint32_t FLTCTRL; /**< Fault Control, offset: 0x7C */
+ __IO uint32_t QDCTRL; /**< Quadrature Decoder Control And Status, offset: 0x80 */
+ __IO uint32_t CONF; /**< Configuration, offset: 0x84 */
+ __IO uint32_t FLTPOL; /**< FTM Fault Input Polarity, offset: 0x88 */
+ __IO uint32_t SYNCONF; /**< Synchronization Configuration, offset: 0x8C */
+ __IO uint32_t INVCTRL; /**< FTM Inverting Control, offset: 0x90 */
+ __IO uint32_t SWOCTRL; /**< FTM Software Output Control, offset: 0x94 */
+ __IO uint32_t PWMLOAD; /**< FTM PWM Load, offset: 0x98 */
+} FTM_Type;
+
+/* ----------------------------------------------------------------------------
+ -- FTM Register Masks
+ ---------------------------------------------------------------------------- */
+
+/*!
+ * @addtogroup FTM_Register_Masks FTM Register Masks
+ * @{
+ */
+
+/*! @name SC - Status And Control */
+#define FTM_SC_PS_MASK (0x7U)
+#define FTM_SC_PS_SHIFT (0U)
+#define FTM_SC_PS(x) (((uint32_t)(((uint32_t)(x)) << FTM_SC_PS_SHIFT)) & FTM_SC_PS_MASK)
+#define FTM_SC_CLKS_MASK (0x18U)
+#define FTM_SC_CLKS_SHIFT (3U)
+#define FTM_SC_CLKS(x) (((uint32_t)(((uint32_t)(x)) << FTM_SC_CLKS_SHIFT)) & FTM_SC_CLKS_MASK)
+#define FTM_SC_CPWMS_MASK (0x20U)
+#define FTM_SC_CPWMS_SHIFT (5U)
+#define FTM_SC_CPWMS(x) (((uint32_t)(((uint32_t)(x)) << FTM_SC_CPWMS_SHIFT)) & FTM_SC_CPWMS_MASK)
+#define FTM_SC_TOIE_MASK (0x40U)
+#define FTM_SC_TOIE_SHIFT (6U)
+#define FTM_SC_TOIE(x) (((uint32_t)(((uint32_t)(x)) << FTM_SC_TOIE_SHIFT)) & FTM_SC_TOIE_MASK)
+#define FTM_SC_TOF_MASK (0x80U)
+#define FTM_SC_TOF_SHIFT (7U)
+#define FTM_SC_TOF(x) (((uint32_t)(((uint32_t)(x)) << FTM_SC_TOF_SHIFT)) & FTM_SC_TOF_MASK)
+
+/*! @name CNT - Counter */
+#define FTM_CNT_COUNT_MASK (0xFFFFU)
+#define FTM_CNT_COUNT_SHIFT (0U)
+#define FTM_CNT_COUNT(x) (((uint32_t)(((uint32_t)(x)) << FTM_CNT_COUNT_SHIFT)) & FTM_CNT_COUNT_MASK)
+
+/*! @name MOD - Modulo */
+#define FTM_MOD_MOD_MASK (0xFFFFU)
+#define FTM_MOD_MOD_SHIFT (0U)
+#define FTM_MOD_MOD(x) (((uint32_t)(((uint32_t)(x)) << FTM_MOD_MOD_SHIFT)) & FTM_MOD_MOD_MASK)
+
+/*! @name CnSC - Channel (n) Status And Control */
+#define FTM_CnSC_DMA_MASK (0x1U)
+#define FTM_CnSC_DMA_SHIFT (0U)
+#define FTM_CnSC_DMA(x) (((uint32_t)(((uint32_t)(x)) << FTM_CnSC_DMA_SHIFT)) & FTM_CnSC_DMA_MASK)
+#define FTM_CnSC_ICRST_MASK (0x2U)
+#define FTM_CnSC_ICRST_SHIFT (1U)
+#define FTM_CnSC_ICRST(x) (((uint32_t)(((uint32_t)(x)) << FTM_CnSC_ICRST_SHIFT)) & FTM_CnSC_ICRST_MASK)
+#define FTM_CnSC_ELSA_MASK (0x4U)
+#define FTM_CnSC_ELSA_SHIFT (2U)
+#define FTM_CnSC_ELSA(x) (((uint32_t)(((uint32_t)(x)) << FTM_CnSC_ELSA_SHIFT)) & FTM_CnSC_ELSA_MASK)
+#define FTM_CnSC_ELSB_MASK (0x8U)
+#define FTM_CnSC_ELSB_SHIFT (3U)
+#define FTM_CnSC_ELSB(x) (((uint32_t)(((uint32_t)(x)) << FTM_CnSC_ELSB_SHIFT)) & FTM_CnSC_ELSB_MASK)
+#define FTM_CnSC_MSA_MASK (0x10U)
+#define FTM_CnSC_MSA_SHIFT (4U)
+#define FTM_CnSC_MSA(x) (((uint32_t)(((uint32_t)(x)) << FTM_CnSC_MSA_SHIFT)) & FTM_CnSC_MSA_MASK)
+#define FTM_CnSC_MSB_MASK (0x20U)
+#define FTM_CnSC_MSB_SHIFT (5U)
+#define FTM_CnSC_MSB(x) (((uint32_t)(((uint32_t)(x)) << FTM_CnSC_MSB_SHIFT)) & FTM_CnSC_MSB_MASK)
+#define FTM_CnSC_CHIE_MASK (0x40U)
+#define FTM_CnSC_CHIE_SHIFT (6U)
+#define FTM_CnSC_CHIE(x) (((uint32_t)(((uint32_t)(x)) << FTM_CnSC_CHIE_SHIFT)) & FTM_CnSC_CHIE_MASK)
+#define FTM_CnSC_CHF_MASK (0x80U)
+#define FTM_CnSC_CHF_SHIFT (7U)
+#define FTM_CnSC_CHF(x) (((uint32_t)(((uint32_t)(x)) << FTM_CnSC_CHF_SHIFT)) & FTM_CnSC_CHF_MASK)
+
+/* The count of FTM_CnSC */
+#define FTM_CnSC_COUNT (6U)
+
+/*! @name CnV - Channel (n) Value */
+#define FTM_CnV_VAL_MASK (0xFFFFU)
+#define FTM_CnV_VAL_SHIFT (0U)
+#define FTM_CnV_VAL(x) (((uint32_t)(((uint32_t)(x)) << FTM_CnV_VAL_SHIFT)) & FTM_CnV_VAL_MASK)
+
+/* The count of FTM_CnV */
+#define FTM_CnV_COUNT (6U)
+
+/*! @name CNTIN - Counter Initial Value */
+#define FTM_CNTIN_INIT_MASK (0xFFFFU)
+#define FTM_CNTIN_INIT_SHIFT (0U)
+#define FTM_CNTIN_INIT(x) (((uint32_t)(((uint32_t)(x)) << FTM_CNTIN_INIT_SHIFT)) & FTM_CNTIN_INIT_MASK)
+
+/*! @name STATUS - Capture And Compare Status */
+#define FTM_STATUS_CH0F_MASK (0x1U)
+#define FTM_STATUS_CH0F_SHIFT (0U)
+#define FTM_STATUS_CH0F(x) (((uint32_t)(((uint32_t)(x)) << FTM_STATUS_CH0F_SHIFT)) & FTM_STATUS_CH0F_MASK)
+#define FTM_STATUS_CH1F_MASK (0x2U)
+#define FTM_STATUS_CH1F_SHIFT (1U)
+#define FTM_STATUS_CH1F(x) (((uint32_t)(((uint32_t)(x)) << FTM_STATUS_CH1F_SHIFT)) & FTM_STATUS_CH1F_MASK)
+#define FTM_STATUS_CH2F_MASK (0x4U)
+#define FTM_STATUS_CH2F_SHIFT (2U)
+#define FTM_STATUS_CH2F(x) (((uint32_t)(((uint32_t)(x)) << FTM_STATUS_CH2F_SHIFT)) & FTM_STATUS_CH2F_MASK)
+#define FTM_STATUS_CH3F_MASK (0x8U)
+#define FTM_STATUS_CH3F_SHIFT (3U)
+#define FTM_STATUS_CH3F(x) (((uint32_t)(((uint32_t)(x)) << FTM_STATUS_CH3F_SHIFT)) & FTM_STATUS_CH3F_MASK)
+#define FTM_STATUS_CH4F_MASK (0x10U)
+#define FTM_STATUS_CH4F_SHIFT (4U)
+#define FTM_STATUS_CH4F(x) (((uint32_t)(((uint32_t)(x)) << FTM_STATUS_CH4F_SHIFT)) & FTM_STATUS_CH4F_MASK)
+#define FTM_STATUS_CH5F_MASK (0x20U)
+#define FTM_STATUS_CH5F_SHIFT (5U)
+#define FTM_STATUS_CH5F(x) (((uint32_t)(((uint32_t)(x)) << FTM_STATUS_CH5F_SHIFT)) & FTM_STATUS_CH5F_MASK)
+#define FTM_STATUS_CH6F_MASK (0x40U)
+#define FTM_STATUS_CH6F_SHIFT (6U)
+#define FTM_STATUS_CH6F(x) (((uint32_t)(((uint32_t)(x)) << FTM_STATUS_CH6F_SHIFT)) & FTM_STATUS_CH6F_MASK)
+#define FTM_STATUS_CH7F_MASK (0x80U)
+#define FTM_STATUS_CH7F_SHIFT (7U)
+#define FTM_STATUS_CH7F(x) (((uint32_t)(((uint32_t)(x)) << FTM_STATUS_CH7F_SHIFT)) & FTM_STATUS_CH7F_MASK)
+
+/*! @name MODE - Features Mode Selection */
+#define FTM_MODE_FTMEN_MASK (0x1U)
+#define FTM_MODE_FTMEN_SHIFT (0U)
+#define FTM_MODE_FTMEN(x) (((uint32_t)(((uint32_t)(x)) << FTM_MODE_FTMEN_SHIFT)) & FTM_MODE_FTMEN_MASK)
+#define FTM_MODE_INIT_MASK (0x2U)
+#define FTM_MODE_INIT_SHIFT (1U)
+#define FTM_MODE_INIT(x) (((uint32_t)(((uint32_t)(x)) << FTM_MODE_INIT_SHIFT)) & FTM_MODE_INIT_MASK)
+#define FTM_MODE_WPDIS_MASK (0x4U)
+#define FTM_MODE_WPDIS_SHIFT (2U)
+#define FTM_MODE_WPDIS(x) (((uint32_t)(((uint32_t)(x)) << FTM_MODE_WPDIS_SHIFT)) & FTM_MODE_WPDIS_MASK)
+#define FTM_MODE_PWMSYNC_MASK (0x8U)
+#define FTM_MODE_PWMSYNC_SHIFT (3U)
+#define FTM_MODE_PWMSYNC(x) (((uint32_t)(((uint32_t)(x)) << FTM_MODE_PWMSYNC_SHIFT)) & FTM_MODE_PWMSYNC_MASK)
+#define FTM_MODE_CAPTEST_MASK (0x10U)
+#define FTM_MODE_CAPTEST_SHIFT (4U)
+#define FTM_MODE_CAPTEST(x) (((uint32_t)(((uint32_t)(x)) << FTM_MODE_CAPTEST_SHIFT)) & FTM_MODE_CAPTEST_MASK)
+#define FTM_MODE_FAULTM_MASK (0x60U)
+#define FTM_MODE_FAULTM_SHIFT (5U)
+#define FTM_MODE_FAULTM(x) (((uint32_t)(((uint32_t)(x)) << FTM_MODE_FAULTM_SHIFT)) & FTM_MODE_FAULTM_MASK)
+#define FTM_MODE_FAULTIE_MASK (0x80U)
+#define FTM_MODE_FAULTIE_SHIFT (7U)
+#define FTM_MODE_FAULTIE(x) (((uint32_t)(((uint32_t)(x)) << FTM_MODE_FAULTIE_SHIFT)) & FTM_MODE_FAULTIE_MASK)
+
+/*! @name SYNC - Synchronization */
+#define FTM_SYNC_CNTMIN_MASK (0x1U)
+#define FTM_SYNC_CNTMIN_SHIFT (0U)
+#define FTM_SYNC_CNTMIN(x) (((uint32_t)(((uint32_t)(x)) << FTM_SYNC_CNTMIN_SHIFT)) & FTM_SYNC_CNTMIN_MASK)
+#define FTM_SYNC_CNTMAX_MASK (0x2U)
+#define FTM_SYNC_CNTMAX_SHIFT (1U)
+#define FTM_SYNC_CNTMAX(x) (((uint32_t)(((uint32_t)(x)) << FTM_SYNC_CNTMAX_SHIFT)) & FTM_SYNC_CNTMAX_MASK)
+#define FTM_SYNC_REINIT_MASK (0x4U)
+#define FTM_SYNC_REINIT_SHIFT (2U)
+#define FTM_SYNC_REINIT(x) (((uint32_t)(((uint32_t)(x)) << FTM_SYNC_REINIT_SHIFT)) & FTM_SYNC_REINIT_MASK)
+#define FTM_SYNC_SYNCHOM_MASK (0x8U)
+#define FTM_SYNC_SYNCHOM_SHIFT (3U)
+#define FTM_SYNC_SYNCHOM(x) (((uint32_t)(((uint32_t)(x)) << FTM_SYNC_SYNCHOM_SHIFT)) & FTM_SYNC_SYNCHOM_MASK)
+#define FTM_SYNC_TRIG0_MASK (0x10U)
+#define FTM_SYNC_TRIG0_SHIFT (4U)
+#define FTM_SYNC_TRIG0(x) (((uint32_t)(((uint32_t)(x)) << FTM_SYNC_TRIG0_SHIFT)) & FTM_SYNC_TRIG0_MASK)
+#define FTM_SYNC_TRIG1_MASK (0x20U)
+#define FTM_SYNC_TRIG1_SHIFT (5U)
+#define FTM_SYNC_TRIG1(x) (((uint32_t)(((uint32_t)(x)) << FTM_SYNC_TRIG1_SHIFT)) & FTM_SYNC_TRIG1_MASK)
+#define FTM_SYNC_TRIG2_MASK (0x40U)
+#define FTM_SYNC_TRIG2_SHIFT (6U)
+#define FTM_SYNC_TRIG2(x) (((uint32_t)(((uint32_t)(x)) << FTM_SYNC_TRIG2_SHIFT)) & FTM_SYNC_TRIG2_MASK)
+#define FTM_SYNC_SWSYNC_MASK (0x80U)
+#define FTM_SYNC_SWSYNC_SHIFT (7U)
+#define FTM_SYNC_SWSYNC(x) (((uint32_t)(((uint32_t)(x)) << FTM_SYNC_SWSYNC_SHIFT)) & FTM_SYNC_SWSYNC_MASK)
+
+/*! @name OUTINIT - Initial State For Channels Output */
+#define FTM_OUTINIT_CH0OI_MASK (0x1U)
+#define FTM_OUTINIT_CH0OI_SHIFT (0U)
+#define FTM_OUTINIT_CH0OI(x) (((uint32_t)(((uint32_t)(x)) << FTM_OUTINIT_CH0OI_SHIFT)) & FTM_OUTINIT_CH0OI_MASK)
+#define FTM_OUTINIT_CH1OI_MASK (0x2U)
+#define FTM_OUTINIT_CH1OI_SHIFT (1U)
+#define FTM_OUTINIT_CH1OI(x) (((uint32_t)(((uint32_t)(x)) << FTM_OUTINIT_CH1OI_SHIFT)) & FTM_OUTINIT_CH1OI_MASK)
+#define FTM_OUTINIT_CH2OI_MASK (0x4U)
+#define FTM_OUTINIT_CH2OI_SHIFT (2U)
+#define FTM_OUTINIT_CH2OI(x) (((uint32_t)(((uint32_t)(x)) << FTM_OUTINIT_CH2OI_SHIFT)) & FTM_OUTINIT_CH2OI_MASK)
+#define FTM_OUTINIT_CH3OI_MASK (0x8U)
+#define FTM_OUTINIT_CH3OI_SHIFT (3U)
+#define FTM_OUTINIT_CH3OI(x) (((uint32_t)(((uint32_t)(x)) << FTM_OUTINIT_CH3OI_SHIFT)) & FTM_OUTINIT_CH3OI_MASK)
+#define FTM_OUTINIT_CH4OI_MASK (0x10U)
+#define FTM_OUTINIT_CH4OI_SHIFT (4U)
+#define FTM_OUTINIT_CH4OI(x) (((uint32_t)(((uint32_t)(x)) << FTM_OUTINIT_CH4OI_SHIFT)) & FTM_OUTINIT_CH4OI_MASK)
+#define FTM_OUTINIT_CH5OI_MASK (0x20U)
+#define FTM_OUTINIT_CH5OI_SHIFT (5U)
+#define FTM_OUTINIT_CH5OI(x) (((uint32_t)(((uint32_t)(x)) << FTM_OUTINIT_CH5OI_SHIFT)) & FTM_OUTINIT_CH5OI_MASK)
+#define FTM_OUTINIT_CH6OI_MASK (0x40U)
+#define FTM_OUTINIT_CH6OI_SHIFT (6U)
+#define FTM_OUTINIT_CH6OI(x) (((uint32_t)(((uint32_t)(x)) << FTM_OUTINIT_CH6OI_SHIFT)) & FTM_OUTINIT_CH6OI_MASK)
+#define FTM_OUTINIT_CH7OI_MASK (0x80U)
+#define FTM_OUTINIT_CH7OI_SHIFT (7U)
+#define FTM_OUTINIT_CH7OI(x) (((uint32_t)(((uint32_t)(x)) << FTM_OUTINIT_CH7OI_SHIFT)) & FTM_OUTINIT_CH7OI_MASK)
+
+/*! @name OUTMASK - Output Mask */
+#define FTM_OUTMASK_CH0OM_MASK (0x1U)
+#define FTM_OUTMASK_CH0OM_SHIFT (0U)
+#define FTM_OUTMASK_CH0OM(x) (((uint32_t)(((uint32_t)(x)) << FTM_OUTMASK_CH0OM_SHIFT)) & FTM_OUTMASK_CH0OM_MASK)
+#define FTM_OUTMASK_CH1OM_MASK (0x2U)
+#define FTM_OUTMASK_CH1OM_SHIFT (1U)
+#define FTM_OUTMASK_CH1OM(x) (((uint32_t)(((uint32_t)(x)) << FTM_OUTMASK_CH1OM_SHIFT)) & FTM_OUTMASK_CH1OM_MASK)
+#define FTM_OUTMASK_CH2OM_MASK (0x4U)
+#define FTM_OUTMASK_CH2OM_SHIFT (2U)
+#define FTM_OUTMASK_CH2OM(x) (((uint32_t)(((uint32_t)(x)) << FTM_OUTMASK_CH2OM_SHIFT)) & FTM_OUTMASK_CH2OM_MASK)
+#define FTM_OUTMASK_CH3OM_MASK (0x8U)
+#define FTM_OUTMASK_CH3OM_SHIFT (3U)
+#define FTM_OUTMASK_CH3OM(x) (((uint32_t)(((uint32_t)(x)) << FTM_OUTMASK_CH3OM_SHIFT)) & FTM_OUTMASK_CH3OM_MASK)
+#define FTM_OUTMASK_CH4OM_MASK (0x10U)
+#define FTM_OUTMASK_CH4OM_SHIFT (4U)
+#define FTM_OUTMASK_CH4OM(x) (((uint32_t)(((uint32_t)(x)) << FTM_OUTMASK_CH4OM_SHIFT)) & FTM_OUTMASK_CH4OM_MASK)
+#define FTM_OUTMASK_CH5OM_MASK (0x20U)
+#define FTM_OUTMASK_CH5OM_SHIFT (5U)
+#define FTM_OUTMASK_CH5OM(x) (((uint32_t)(((uint32_t)(x)) << FTM_OUTMASK_CH5OM_SHIFT)) & FTM_OUTMASK_CH5OM_MASK)
+#define FTM_OUTMASK_CH6OM_MASK (0x40U)
+#define FTM_OUTMASK_CH6OM_SHIFT (6U)
+#define FTM_OUTMASK_CH6OM(x) (((uint32_t)(((uint32_t)(x)) << FTM_OUTMASK_CH6OM_SHIFT)) & FTM_OUTMASK_CH6OM_MASK)
+#define FTM_OUTMASK_CH7OM_MASK (0x80U)
+#define FTM_OUTMASK_CH7OM_SHIFT (7U)
+#define FTM_OUTMASK_CH7OM(x) (((uint32_t)(((uint32_t)(x)) << FTM_OUTMASK_CH7OM_SHIFT)) & FTM_OUTMASK_CH7OM_MASK)
+
+/*! @name COMBINE - Function For Linked Channels */
+#define FTM_COMBINE_COMBINE0_MASK (0x1U)
+#define FTM_COMBINE_COMBINE0_SHIFT (0U)
+#define FTM_COMBINE_COMBINE0(x) (((uint32_t)(((uint32_t)(x)) << FTM_COMBINE_COMBINE0_SHIFT)) & FTM_COMBINE_COMBINE0_MASK)
+#define FTM_COMBINE_COMP0_MASK (0x2U)
+#define FTM_COMBINE_COMP0_SHIFT (1U)
+#define FTM_COMBINE_COMP0(x) (((uint32_t)(((uint32_t)(x)) << FTM_COMBINE_COMP0_SHIFT)) & FTM_COMBINE_COMP0_MASK)
+#define FTM_COMBINE_DECAPEN0_MASK (0x4U)
+#define FTM_COMBINE_DECAPEN0_SHIFT (2U)
+#define FTM_COMBINE_DECAPEN0(x) (((uint32_t)(((uint32_t)(x)) << FTM_COMBINE_DECAPEN0_SHIFT)) & FTM_COMBINE_DECAPEN0_MASK)
+#define FTM_COMBINE_DECAP0_MASK (0x8U)
+#define FTM_COMBINE_DECAP0_SHIFT (3U)
+#define FTM_COMBINE_DECAP0(x) (((uint32_t)(((uint32_t)(x)) << FTM_COMBINE_DECAP0_SHIFT)) & FTM_COMBINE_DECAP0_MASK)
+#define FTM_COMBINE_DTEN0_MASK (0x10U)
+#define FTM_COMBINE_DTEN0_SHIFT (4U)
+#define FTM_COMBINE_DTEN0(x) (((uint32_t)(((uint32_t)(x)) << FTM_COMBINE_DTEN0_SHIFT)) & FTM_COMBINE_DTEN0_MASK)
+#define FTM_COMBINE_SYNCEN0_MASK (0x20U)
+#define FTM_COMBINE_SYNCEN0_SHIFT (5U)
+#define FTM_COMBINE_SYNCEN0(x) (((uint32_t)(((uint32_t)(x)) << FTM_COMBINE_SYNCEN0_SHIFT)) & FTM_COMBINE_SYNCEN0_MASK)
+#define FTM_COMBINE_FAULTEN0_MASK (0x40U)
+#define FTM_COMBINE_FAULTEN0_SHIFT (6U)
+#define FTM_COMBINE_FAULTEN0(x) (((uint32_t)(((uint32_t)(x)) << FTM_COMBINE_FAULTEN0_SHIFT)) & FTM_COMBINE_FAULTEN0_MASK)
+#define FTM_COMBINE_COMBINE1_MASK (0x100U)
+#define FTM_COMBINE_COMBINE1_SHIFT (8U)
+#define FTM_COMBINE_COMBINE1(x) (((uint32_t)(((uint32_t)(x)) << FTM_COMBINE_COMBINE1_SHIFT)) & FTM_COMBINE_COMBINE1_MASK)
+#define FTM_COMBINE_COMP1_MASK (0x200U)
+#define FTM_COMBINE_COMP1_SHIFT (9U)
+#define FTM_COMBINE_COMP1(x) (((uint32_t)(((uint32_t)(x)) << FTM_COMBINE_COMP1_SHIFT)) & FTM_COMBINE_COMP1_MASK)
+#define FTM_COMBINE_DECAPEN1_MASK (0x400U)
+#define FTM_COMBINE_DECAPEN1_SHIFT (10U)
+#define FTM_COMBINE_DECAPEN1(x) (((uint32_t)(((uint32_t)(x)) << FTM_COMBINE_DECAPEN1_SHIFT)) & FTM_COMBINE_DECAPEN1_MASK)
+#define FTM_COMBINE_DECAP1_MASK (0x800U)
+#define FTM_COMBINE_DECAP1_SHIFT (11U)
+#define FTM_COMBINE_DECAP1(x) (((uint32_t)(((uint32_t)(x)) << FTM_COMBINE_DECAP1_SHIFT)) & FTM_COMBINE_DECAP1_MASK)
+#define FTM_COMBINE_DTEN1_MASK (0x1000U)
+#define FTM_COMBINE_DTEN1_SHIFT (12U)
+#define FTM_COMBINE_DTEN1(x) (((uint32_t)(((uint32_t)(x)) << FTM_COMBINE_DTEN1_SHIFT)) & FTM_COMBINE_DTEN1_MASK)
+#define FTM_COMBINE_SYNCEN1_MASK (0x2000U)
+#define FTM_COMBINE_SYNCEN1_SHIFT (13U)
+#define FTM_COMBINE_SYNCEN1(x) (((uint32_t)(((uint32_t)(x)) << FTM_COMBINE_SYNCEN1_SHIFT)) & FTM_COMBINE_SYNCEN1_MASK)
+#define FTM_COMBINE_FAULTEN1_MASK (0x4000U)
+#define FTM_COMBINE_FAULTEN1_SHIFT (14U)
+#define FTM_COMBINE_FAULTEN1(x) (((uint32_t)(((uint32_t)(x)) << FTM_COMBINE_FAULTEN1_SHIFT)) & FTM_COMBINE_FAULTEN1_MASK)
+#define FTM_COMBINE_COMBINE2_MASK (0x10000U)
+#define FTM_COMBINE_COMBINE2_SHIFT (16U)
+#define FTM_COMBINE_COMBINE2(x) (((uint32_t)(((uint32_t)(x)) << FTM_COMBINE_COMBINE2_SHIFT)) & FTM_COMBINE_COMBINE2_MASK)
+#define FTM_COMBINE_COMP2_MASK (0x20000U)
+#define FTM_COMBINE_COMP2_SHIFT (17U)
+#define FTM_COMBINE_COMP2(x) (((uint32_t)(((uint32_t)(x)) << FTM_COMBINE_COMP2_SHIFT)) & FTM_COMBINE_COMP2_MASK)
+#define FTM_COMBINE_DECAPEN2_MASK (0x40000U)
+#define FTM_COMBINE_DECAPEN2_SHIFT (18U)
+#define FTM_COMBINE_DECAPEN2(x) (((uint32_t)(((uint32_t)(x)) << FTM_COMBINE_DECAPEN2_SHIFT)) & FTM_COMBINE_DECAPEN2_MASK)
+#define FTM_COMBINE_DECAP2_MASK (0x80000U)
+#define FTM_COMBINE_DECAP2_SHIFT (19U)
+#define FTM_COMBINE_DECAP2(x) (((uint32_t)(((uint32_t)(x)) << FTM_COMBINE_DECAP2_SHIFT)) & FTM_COMBINE_DECAP2_MASK)
+#define FTM_COMBINE_DTEN2_MASK (0x100000U)
+#define FTM_COMBINE_DTEN2_SHIFT (20U)
+#define FTM_COMBINE_DTEN2(x) (((uint32_t)(((uint32_t)(x)) << FTM_COMBINE_DTEN2_SHIFT)) & FTM_COMBINE_DTEN2_MASK)
+#define FTM_COMBINE_SYNCEN2_MASK (0x200000U)
+#define FTM_COMBINE_SYNCEN2_SHIFT (21U)
+#define FTM_COMBINE_SYNCEN2(x) (((uint32_t)(((uint32_t)(x)) << FTM_COMBINE_SYNCEN2_SHIFT)) & FTM_COMBINE_SYNCEN2_MASK)
+#define FTM_COMBINE_FAULTEN2_MASK (0x400000U)
+#define FTM_COMBINE_FAULTEN2_SHIFT (22U)
+#define FTM_COMBINE_FAULTEN2(x) (((uint32_t)(((uint32_t)(x)) << FTM_COMBINE_FAULTEN2_SHIFT)) & FTM_COMBINE_FAULTEN2_MASK)
+#define FTM_COMBINE_COMBINE3_MASK (0x1000000U)
+#define FTM_COMBINE_COMBINE3_SHIFT (24U)
+#define FTM_COMBINE_COMBINE3(x) (((uint32_t)(((uint32_t)(x)) << FTM_COMBINE_COMBINE3_SHIFT)) & FTM_COMBINE_COMBINE3_MASK)
+#define FTM_COMBINE_COMP3_MASK (0x2000000U)
+#define FTM_COMBINE_COMP3_SHIFT (25U)
+#define FTM_COMBINE_COMP3(x) (((uint32_t)(((uint32_t)(x)) << FTM_COMBINE_COMP3_SHIFT)) & FTM_COMBINE_COMP3_MASK)
+#define FTM_COMBINE_DECAPEN3_MASK (0x4000000U)
+#define FTM_COMBINE_DECAPEN3_SHIFT (26U)
+#define FTM_COMBINE_DECAPEN3(x) (((uint32_t)(((uint32_t)(x)) << FTM_COMBINE_DECAPEN3_SHIFT)) & FTM_COMBINE_DECAPEN3_MASK)
+#define FTM_COMBINE_DECAP3_MASK (0x8000000U)
+#define FTM_COMBINE_DECAP3_SHIFT (27U)
+#define FTM_COMBINE_DECAP3(x) (((uint32_t)(((uint32_t)(x)) << FTM_COMBINE_DECAP3_SHIFT)) & FTM_COMBINE_DECAP3_MASK)
+#define FTM_COMBINE_DTEN3_MASK (0x10000000U)
+#define FTM_COMBINE_DTEN3_SHIFT (28U)
+#define FTM_COMBINE_DTEN3(x) (((uint32_t)(((uint32_t)(x)) << FTM_COMBINE_DTEN3_SHIFT)) & FTM_COMBINE_DTEN3_MASK)
+#define FTM_COMBINE_SYNCEN3_MASK (0x20000000U)
+#define FTM_COMBINE_SYNCEN3_SHIFT (29U)
+#define FTM_COMBINE_SYNCEN3(x) (((uint32_t)(((uint32_t)(x)) << FTM_COMBINE_SYNCEN3_SHIFT)) & FTM_COMBINE_SYNCEN3_MASK)
+#define FTM_COMBINE_FAULTEN3_MASK (0x40000000U)
+#define FTM_COMBINE_FAULTEN3_SHIFT (30U)
+#define FTM_COMBINE_FAULTEN3(x) (((uint32_t)(((uint32_t)(x)) << FTM_COMBINE_FAULTEN3_SHIFT)) & FTM_COMBINE_FAULTEN3_MASK)
+
+/*! @name DEADTIME - Deadtime Insertion Control */
+#define FTM_DEADTIME_DTVAL_MASK (0x3FU)
+#define FTM_DEADTIME_DTVAL_SHIFT (0U)
+#define FTM_DEADTIME_DTVAL(x) (((uint32_t)(((uint32_t)(x)) << FTM_DEADTIME_DTVAL_SHIFT)) & FTM_DEADTIME_DTVAL_MASK)
+#define FTM_DEADTIME_DTPS_MASK (0xC0U)
+#define FTM_DEADTIME_DTPS_SHIFT (6U)
+#define FTM_DEADTIME_DTPS(x) (((uint32_t)(((uint32_t)(x)) << FTM_DEADTIME_DTPS_SHIFT)) & FTM_DEADTIME_DTPS_MASK)
+
+/*! @name EXTTRIG - FTM External Trigger */
+#define FTM_EXTTRIG_CH2TRIG_MASK (0x1U)
+#define FTM_EXTTRIG_CH2TRIG_SHIFT (0U)
+#define FTM_EXTTRIG_CH2TRIG(x) (((uint32_t)(((uint32_t)(x)) << FTM_EXTTRIG_CH2TRIG_SHIFT)) & FTM_EXTTRIG_CH2TRIG_MASK)
+#define FTM_EXTTRIG_CH3TRIG_MASK (0x2U)
+#define FTM_EXTTRIG_CH3TRIG_SHIFT (1U)
+#define FTM_EXTTRIG_CH3TRIG(x) (((uint32_t)(((uint32_t)(x)) << FTM_EXTTRIG_CH3TRIG_SHIFT)) & FTM_EXTTRIG_CH3TRIG_MASK)
+#define FTM_EXTTRIG_CH4TRIG_MASK (0x4U)
+#define FTM_EXTTRIG_CH4TRIG_SHIFT (2U)
+#define FTM_EXTTRIG_CH4TRIG(x) (((uint32_t)(((uint32_t)(x)) << FTM_EXTTRIG_CH4TRIG_SHIFT)) & FTM_EXTTRIG_CH4TRIG_MASK)
+#define FTM_EXTTRIG_CH5TRIG_MASK (0x8U)
+#define FTM_EXTTRIG_CH5TRIG_SHIFT (3U)
+#define FTM_EXTTRIG_CH5TRIG(x) (((uint32_t)(((uint32_t)(x)) << FTM_EXTTRIG_CH5TRIG_SHIFT)) & FTM_EXTTRIG_CH5TRIG_MASK)
+#define FTM_EXTTRIG_CH0TRIG_MASK (0x10U)
+#define FTM_EXTTRIG_CH0TRIG_SHIFT (4U)
+#define FTM_EXTTRIG_CH0TRIG(x) (((uint32_t)(((uint32_t)(x)) << FTM_EXTTRIG_CH0TRIG_SHIFT)) & FTM_EXTTRIG_CH0TRIG_MASK)
+#define FTM_EXTTRIG_CH1TRIG_MASK (0x20U)
+#define FTM_EXTTRIG_CH1TRIG_SHIFT (5U)
+#define FTM_EXTTRIG_CH1TRIG(x) (((uint32_t)(((uint32_t)(x)) << FTM_EXTTRIG_CH1TRIG_SHIFT)) & FTM_EXTTRIG_CH1TRIG_MASK)
+#define FTM_EXTTRIG_INITTRIGEN_MASK (0x40U)
+#define FTM_EXTTRIG_INITTRIGEN_SHIFT (6U)
+#define FTM_EXTTRIG_INITTRIGEN(x) (((uint32_t)(((uint32_t)(x)) << FTM_EXTTRIG_INITTRIGEN_SHIFT)) & FTM_EXTTRIG_INITTRIGEN_MASK)
+#define FTM_EXTTRIG_TRIGF_MASK (0x80U)
+#define FTM_EXTTRIG_TRIGF_SHIFT (7U)
+#define FTM_EXTTRIG_TRIGF(x) (((uint32_t)(((uint32_t)(x)) << FTM_EXTTRIG_TRIGF_SHIFT)) & FTM_EXTTRIG_TRIGF_MASK)
+
+/*! @name POL - Channels Polarity */
+#define FTM_POL_POL0_MASK (0x1U)
+#define FTM_POL_POL0_SHIFT (0U)
+#define FTM_POL_POL0(x) (((uint32_t)(((uint32_t)(x)) << FTM_POL_POL0_SHIFT)) & FTM_POL_POL0_MASK)
+#define FTM_POL_POL1_MASK (0x2U)
+#define FTM_POL_POL1_SHIFT (1U)
+#define FTM_POL_POL1(x) (((uint32_t)(((uint32_t)(x)) << FTM_POL_POL1_SHIFT)) & FTM_POL_POL1_MASK)
+#define FTM_POL_POL2_MASK (0x4U)
+#define FTM_POL_POL2_SHIFT (2U)
+#define FTM_POL_POL2(x) (((uint32_t)(((uint32_t)(x)) << FTM_POL_POL2_SHIFT)) & FTM_POL_POL2_MASK)
+#define FTM_POL_POL3_MASK (0x8U)
+#define FTM_POL_POL3_SHIFT (3U)
+#define FTM_POL_POL3(x) (((uint32_t)(((uint32_t)(x)) << FTM_POL_POL3_SHIFT)) & FTM_POL_POL3_MASK)
+#define FTM_POL_POL4_MASK (0x10U)
+#define FTM_POL_POL4_SHIFT (4U)
+#define FTM_POL_POL4(x) (((uint32_t)(((uint32_t)(x)) << FTM_POL_POL4_SHIFT)) & FTM_POL_POL4_MASK)
+#define FTM_POL_POL5_MASK (0x20U)
+#define FTM_POL_POL5_SHIFT (5U)
+#define FTM_POL_POL5(x) (((uint32_t)(((uint32_t)(x)) << FTM_POL_POL5_SHIFT)) & FTM_POL_POL5_MASK)
+#define FTM_POL_POL6_MASK (0x40U)
+#define FTM_POL_POL6_SHIFT (6U)
+#define FTM_POL_POL6(x) (((uint32_t)(((uint32_t)(x)) << FTM_POL_POL6_SHIFT)) & FTM_POL_POL6_MASK)
+#define FTM_POL_POL7_MASK (0x80U)
+#define FTM_POL_POL7_SHIFT (7U)
+#define FTM_POL_POL7(x) (((uint32_t)(((uint32_t)(x)) << FTM_POL_POL7_SHIFT)) & FTM_POL_POL7_MASK)
+
+/*! @name FMS - Fault Mode Status */
+#define FTM_FMS_FAULTF0_MASK (0x1U)
+#define FTM_FMS_FAULTF0_SHIFT (0U)
+#define FTM_FMS_FAULTF0(x) (((uint32_t)(((uint32_t)(x)) << FTM_FMS_FAULTF0_SHIFT)) & FTM_FMS_FAULTF0_MASK)
+#define FTM_FMS_FAULTF1_MASK (0x2U)
+#define FTM_FMS_FAULTF1_SHIFT (1U)
+#define FTM_FMS_FAULTF1(x) (((uint32_t)(((uint32_t)(x)) << FTM_FMS_FAULTF1_SHIFT)) & FTM_FMS_FAULTF1_MASK)
+#define FTM_FMS_FAULTF2_MASK (0x4U)
+#define FTM_FMS_FAULTF2_SHIFT (2U)
+#define FTM_FMS_FAULTF2(x) (((uint32_t)(((uint32_t)(x)) << FTM_FMS_FAULTF2_SHIFT)) & FTM_FMS_FAULTF2_MASK)
+#define FTM_FMS_FAULTF3_MASK (0x8U)
+#define FTM_FMS_FAULTF3_SHIFT (3U)
+#define FTM_FMS_FAULTF3(x) (((uint32_t)(((uint32_t)(x)) << FTM_FMS_FAULTF3_SHIFT)) & FTM_FMS_FAULTF3_MASK)
+#define FTM_FMS_FAULTIN_MASK (0x20U)
+#define FTM_FMS_FAULTIN_SHIFT (5U)
+#define FTM_FMS_FAULTIN(x) (((uint32_t)(((uint32_t)(x)) << FTM_FMS_FAULTIN_SHIFT)) & FTM_FMS_FAULTIN_MASK)
+#define FTM_FMS_WPEN_MASK (0x40U)
+#define FTM_FMS_WPEN_SHIFT (6U)
+#define FTM_FMS_WPEN(x) (((uint32_t)(((uint32_t)(x)) << FTM_FMS_WPEN_SHIFT)) & FTM_FMS_WPEN_MASK)
+#define FTM_FMS_FAULTF_MASK (0x80U)
+#define FTM_FMS_FAULTF_SHIFT (7U)
+#define FTM_FMS_FAULTF(x) (((uint32_t)(((uint32_t)(x)) << FTM_FMS_FAULTF_SHIFT)) & FTM_FMS_FAULTF_MASK)
+
+/*! @name FILTER - Input Capture Filter Control */
+#define FTM_FILTER_CH0FVAL_MASK (0xFU)
+#define FTM_FILTER_CH0FVAL_SHIFT (0U)
+#define FTM_FILTER_CH0FVAL(x) (((uint32_t)(((uint32_t)(x)) << FTM_FILTER_CH0FVAL_SHIFT)) & FTM_FILTER_CH0FVAL_MASK)
+#define FTM_FILTER_CH1FVAL_MASK (0xF0U)
+#define FTM_FILTER_CH1FVAL_SHIFT (4U)
+#define FTM_FILTER_CH1FVAL(x) (((uint32_t)(((uint32_t)(x)) << FTM_FILTER_CH1FVAL_SHIFT)) & FTM_FILTER_CH1FVAL_MASK)
+#define FTM_FILTER_CH2FVAL_MASK (0xF00U)
+#define FTM_FILTER_CH2FVAL_SHIFT (8U)
+#define FTM_FILTER_CH2FVAL(x) (((uint32_t)(((uint32_t)(x)) << FTM_FILTER_CH2FVAL_SHIFT)) & FTM_FILTER_CH2FVAL_MASK)
+#define FTM_FILTER_CH3FVAL_MASK (0xF000U)
+#define FTM_FILTER_CH3FVAL_SHIFT (12U)
+#define FTM_FILTER_CH3FVAL(x) (((uint32_t)(((uint32_t)(x)) << FTM_FILTER_CH3FVAL_SHIFT)) & FTM_FILTER_CH3FVAL_MASK)
+
+/*! @name FLTCTRL - Fault Control */
+#define FTM_FLTCTRL_FAULT0EN_MASK (0x1U)
+#define FTM_FLTCTRL_FAULT0EN_SHIFT (0U)
+#define FTM_FLTCTRL_FAULT0EN(x) (((uint32_t)(((uint32_t)(x)) << FTM_FLTCTRL_FAULT0EN_SHIFT)) & FTM_FLTCTRL_FAULT0EN_MASK)
+#define FTM_FLTCTRL_FAULT1EN_MASK (0x2U)
+#define FTM_FLTCTRL_FAULT1EN_SHIFT (1U)
+#define FTM_FLTCTRL_FAULT1EN(x) (((uint32_t)(((uint32_t)(x)) << FTM_FLTCTRL_FAULT1EN_SHIFT)) & FTM_FLTCTRL_FAULT1EN_MASK)
+#define FTM_FLTCTRL_FAULT2EN_MASK (0x4U)
+#define FTM_FLTCTRL_FAULT2EN_SHIFT (2U)
+#define FTM_FLTCTRL_FAULT2EN(x) (((uint32_t)(((uint32_t)(x)) << FTM_FLTCTRL_FAULT2EN_SHIFT)) & FTM_FLTCTRL_FAULT2EN_MASK)
+#define FTM_FLTCTRL_FAULT3EN_MASK (0x8U)
+#define FTM_FLTCTRL_FAULT3EN_SHIFT (3U)
+#define FTM_FLTCTRL_FAULT3EN(x) (((uint32_t)(((uint32_t)(x)) << FTM_FLTCTRL_FAULT3EN_SHIFT)) & FTM_FLTCTRL_FAULT3EN_MASK)
+#define FTM_FLTCTRL_FFLTR0EN_MASK (0x10U)
+#define FTM_FLTCTRL_FFLTR0EN_SHIFT (4U)
+#define FTM_FLTCTRL_FFLTR0EN(x) (((uint32_t)(((uint32_t)(x)) << FTM_FLTCTRL_FFLTR0EN_SHIFT)) & FTM_FLTCTRL_FFLTR0EN_MASK)
+#define FTM_FLTCTRL_FFLTR1EN_MASK (0x20U)
+#define FTM_FLTCTRL_FFLTR1EN_SHIFT (5U)
+#define FTM_FLTCTRL_FFLTR1EN(x) (((uint32_t)(((uint32_t)(x)) << FTM_FLTCTRL_FFLTR1EN_SHIFT)) & FTM_FLTCTRL_FFLTR1EN_MASK)
+#define FTM_FLTCTRL_FFLTR2EN_MASK (0x40U)
+#define FTM_FLTCTRL_FFLTR2EN_SHIFT (6U)
+#define FTM_FLTCTRL_FFLTR2EN(x) (((uint32_t)(((uint32_t)(x)) << FTM_FLTCTRL_FFLTR2EN_SHIFT)) & FTM_FLTCTRL_FFLTR2EN_MASK)
+#define FTM_FLTCTRL_FFLTR3EN_MASK (0x80U)
+#define FTM_FLTCTRL_FFLTR3EN_SHIFT (7U)
+#define FTM_FLTCTRL_FFLTR3EN(x) (((uint32_t)(((uint32_t)(x)) << FTM_FLTCTRL_FFLTR3EN_SHIFT)) & FTM_FLTCTRL_FFLTR3EN_MASK)
+#define FTM_FLTCTRL_FFVAL_MASK (0xF00U)
+#define FTM_FLTCTRL_FFVAL_SHIFT (8U)
+#define FTM_FLTCTRL_FFVAL(x) (((uint32_t)(((uint32_t)(x)) << FTM_FLTCTRL_FFVAL_SHIFT)) & FTM_FLTCTRL_FFVAL_MASK)
+
+/*! @name QDCTRL - Quadrature Decoder Control And Status */
+#define FTM_QDCTRL_QUADEN_MASK (0x1U)
+#define FTM_QDCTRL_QUADEN_SHIFT (0U)
+#define FTM_QDCTRL_QUADEN(x) (((uint32_t)(((uint32_t)(x)) << FTM_QDCTRL_QUADEN_SHIFT)) & FTM_QDCTRL_QUADEN_MASK)
+#define FTM_QDCTRL_TOFDIR_MASK (0x2U)
+#define FTM_QDCTRL_TOFDIR_SHIFT (1U)
+#define FTM_QDCTRL_TOFDIR(x) (((uint32_t)(((uint32_t)(x)) << FTM_QDCTRL_TOFDIR_SHIFT)) & FTM_QDCTRL_TOFDIR_MASK)
+#define FTM_QDCTRL_QUADIR_MASK (0x4U)
+#define FTM_QDCTRL_QUADIR_SHIFT (2U)
+#define FTM_QDCTRL_QUADIR(x) (((uint32_t)(((uint32_t)(x)) << FTM_QDCTRL_QUADIR_SHIFT)) & FTM_QDCTRL_QUADIR_MASK)
+#define FTM_QDCTRL_QUADMODE_MASK (0x8U)
+#define FTM_QDCTRL_QUADMODE_SHIFT (3U)
+#define FTM_QDCTRL_QUADMODE(x) (((uint32_t)(((uint32_t)(x)) << FTM_QDCTRL_QUADMODE_SHIFT)) & FTM_QDCTRL_QUADMODE_MASK)
+#define FTM_QDCTRL_PHBPOL_MASK (0x10U)
+#define FTM_QDCTRL_PHBPOL_SHIFT (4U)
+#define FTM_QDCTRL_PHBPOL(x) (((uint32_t)(((uint32_t)(x)) << FTM_QDCTRL_PHBPOL_SHIFT)) & FTM_QDCTRL_PHBPOL_MASK)
+#define FTM_QDCTRL_PHAPOL_MASK (0x20U)
+#define FTM_QDCTRL_PHAPOL_SHIFT (5U)
+#define FTM_QDCTRL_PHAPOL(x) (((uint32_t)(((uint32_t)(x)) << FTM_QDCTRL_PHAPOL_SHIFT)) & FTM_QDCTRL_PHAPOL_MASK)
+#define FTM_QDCTRL_PHBFLTREN_MASK (0x40U)
+#define FTM_QDCTRL_PHBFLTREN_SHIFT (6U)
+#define FTM_QDCTRL_PHBFLTREN(x) (((uint32_t)(((uint32_t)(x)) << FTM_QDCTRL_PHBFLTREN_SHIFT)) & FTM_QDCTRL_PHBFLTREN_MASK)
+#define FTM_QDCTRL_PHAFLTREN_MASK (0x80U)
+#define FTM_QDCTRL_PHAFLTREN_SHIFT (7U)
+#define FTM_QDCTRL_PHAFLTREN(x) (((uint32_t)(((uint32_t)(x)) << FTM_QDCTRL_PHAFLTREN_SHIFT)) & FTM_QDCTRL_PHAFLTREN_MASK)
+
+/*! @name CONF - Configuration */
+#define FTM_CONF_NUMTOF_MASK (0x1FU)
+#define FTM_CONF_NUMTOF_SHIFT (0U)
+#define FTM_CONF_NUMTOF(x) (((uint32_t)(((uint32_t)(x)) << FTM_CONF_NUMTOF_SHIFT)) & FTM_CONF_NUMTOF_MASK)
+#define FTM_CONF_BDMMODE_MASK (0xC0U)
+#define FTM_CONF_BDMMODE_SHIFT (6U)
+#define FTM_CONF_BDMMODE(x) (((uint32_t)(((uint32_t)(x)) << FTM_CONF_BDMMODE_SHIFT)) & FTM_CONF_BDMMODE_MASK)
+#define FTM_CONF_GTBEEN_MASK (0x200U)
+#define FTM_CONF_GTBEEN_SHIFT (9U)
+#define FTM_CONF_GTBEEN(x) (((uint32_t)(((uint32_t)(x)) << FTM_CONF_GTBEEN_SHIFT)) & FTM_CONF_GTBEEN_MASK)
+#define FTM_CONF_GTBEOUT_MASK (0x400U)
+#define FTM_CONF_GTBEOUT_SHIFT (10U)
+#define FTM_CONF_GTBEOUT(x) (((uint32_t)(((uint32_t)(x)) << FTM_CONF_GTBEOUT_SHIFT)) & FTM_CONF_GTBEOUT_MASK)
+
+/*! @name FLTPOL - FTM Fault Input Polarity */
+#define FTM_FLTPOL_FLT0POL_MASK (0x1U)
+#define FTM_FLTPOL_FLT0POL_SHIFT (0U)
+#define FTM_FLTPOL_FLT0POL(x) (((uint32_t)(((uint32_t)(x)) << FTM_FLTPOL_FLT0POL_SHIFT)) & FTM_FLTPOL_FLT0POL_MASK)
+#define FTM_FLTPOL_FLT1POL_MASK (0x2U)
+#define FTM_FLTPOL_FLT1POL_SHIFT (1U)
+#define FTM_FLTPOL_FLT1POL(x) (((uint32_t)(((uint32_t)(x)) << FTM_FLTPOL_FLT1POL_SHIFT)) & FTM_FLTPOL_FLT1POL_MASK)
+#define FTM_FLTPOL_FLT2POL_MASK (0x4U)
+#define FTM_FLTPOL_FLT2POL_SHIFT (2U)
+#define FTM_FLTPOL_FLT2POL(x) (((uint32_t)(((uint32_t)(x)) << FTM_FLTPOL_FLT2POL_SHIFT)) & FTM_FLTPOL_FLT2POL_MASK)
+#define FTM_FLTPOL_FLT3POL_MASK (0x8U)
+#define FTM_FLTPOL_FLT3POL_SHIFT (3U)
+#define FTM_FLTPOL_FLT3POL(x) (((uint32_t)(((uint32_t)(x)) << FTM_FLTPOL_FLT3POL_SHIFT)) & FTM_FLTPOL_FLT3POL_MASK)
+
+/*! @name SYNCONF - Synchronization Configuration */
+#define FTM_SYNCONF_HWTRIGMODE_MASK (0x1U)
+#define FTM_SYNCONF_HWTRIGMODE_SHIFT (0U)
+#define FTM_SYNCONF_HWTRIGMODE(x) (((uint32_t)(((uint32_t)(x)) << FTM_SYNCONF_HWTRIGMODE_SHIFT)) & FTM_SYNCONF_HWTRIGMODE_MASK)
+#define FTM_SYNCONF_CNTINC_MASK (0x4U)
+#define FTM_SYNCONF_CNTINC_SHIFT (2U)
+#define FTM_SYNCONF_CNTINC(x) (((uint32_t)(((uint32_t)(x)) << FTM_SYNCONF_CNTINC_SHIFT)) & FTM_SYNCONF_CNTINC_MASK)
+#define FTM_SYNCONF_INVC_MASK (0x10U)
+#define FTM_SYNCONF_INVC_SHIFT (4U)
+#define FTM_SYNCONF_INVC(x) (((uint32_t)(((uint32_t)(x)) << FTM_SYNCONF_INVC_SHIFT)) & FTM_SYNCONF_INVC_MASK)
+#define FTM_SYNCONF_SWOC_MASK (0x20U)
+#define FTM_SYNCONF_SWOC_SHIFT (5U)
+#define FTM_SYNCONF_SWOC(x) (((uint32_t)(((uint32_t)(x)) << FTM_SYNCONF_SWOC_SHIFT)) & FTM_SYNCONF_SWOC_MASK)
+#define FTM_SYNCONF_SYNCMODE_MASK (0x80U)
+#define FTM_SYNCONF_SYNCMODE_SHIFT (7U)
+#define FTM_SYNCONF_SYNCMODE(x) (((uint32_t)(((uint32_t)(x)) << FTM_SYNCONF_SYNCMODE_SHIFT)) & FTM_SYNCONF_SYNCMODE_MASK)
+#define FTM_SYNCONF_SWRSTCNT_MASK (0x100U)
+#define FTM_SYNCONF_SWRSTCNT_SHIFT (8U)
+#define FTM_SYNCONF_SWRSTCNT(x) (((uint32_t)(((uint32_t)(x)) << FTM_SYNCONF_SWRSTCNT_SHIFT)) & FTM_SYNCONF_SWRSTCNT_MASK)
+#define FTM_SYNCONF_SWWRBUF_MASK (0x200U)
+#define FTM_SYNCONF_SWWRBUF_SHIFT (9U)
+#define FTM_SYNCONF_SWWRBUF(x) (((uint32_t)(((uint32_t)(x)) << FTM_SYNCONF_SWWRBUF_SHIFT)) & FTM_SYNCONF_SWWRBUF_MASK)
+#define FTM_SYNCONF_SWOM_MASK (0x400U)
+#define FTM_SYNCONF_SWOM_SHIFT (10U)
+#define FTM_SYNCONF_SWOM(x) (((uint32_t)(((uint32_t)(x)) << FTM_SYNCONF_SWOM_SHIFT)) & FTM_SYNCONF_SWOM_MASK)
+#define FTM_SYNCONF_SWINVC_MASK (0x800U)
+#define FTM_SYNCONF_SWINVC_SHIFT (11U)
+#define FTM_SYNCONF_SWINVC(x) (((uint32_t)(((uint32_t)(x)) << FTM_SYNCONF_SWINVC_SHIFT)) & FTM_SYNCONF_SWINVC_MASK)
+#define FTM_SYNCONF_SWSOC_MASK (0x1000U)
+#define FTM_SYNCONF_SWSOC_SHIFT (12U)
+#define FTM_SYNCONF_SWSOC(x) (((uint32_t)(((uint32_t)(x)) << FTM_SYNCONF_SWSOC_SHIFT)) & FTM_SYNCONF_SWSOC_MASK)
+#define FTM_SYNCONF_HWRSTCNT_MASK (0x10000U)
+#define FTM_SYNCONF_HWRSTCNT_SHIFT (16U)
+#define FTM_SYNCONF_HWRSTCNT(x) (((uint32_t)(((uint32_t)(x)) << FTM_SYNCONF_HWRSTCNT_SHIFT)) & FTM_SYNCONF_HWRSTCNT_MASK)
+#define FTM_SYNCONF_HWWRBUF_MASK (0x20000U)
+#define FTM_SYNCONF_HWWRBUF_SHIFT (17U)
+#define FTM_SYNCONF_HWWRBUF(x) (((uint32_t)(((uint32_t)(x)) << FTM_SYNCONF_HWWRBUF_SHIFT)) & FTM_SYNCONF_HWWRBUF_MASK)
+#define FTM_SYNCONF_HWOM_MASK (0x40000U)
+#define FTM_SYNCONF_HWOM_SHIFT (18U)
+#define FTM_SYNCONF_HWOM(x) (((uint32_t)(((uint32_t)(x)) << FTM_SYNCONF_HWOM_SHIFT)) & FTM_SYNCONF_HWOM_MASK)
+#define FTM_SYNCONF_HWINVC_MASK (0x80000U)
+#define FTM_SYNCONF_HWINVC_SHIFT (19U)
+#define FTM_SYNCONF_HWINVC(x) (((uint32_t)(((uint32_t)(x)) << FTM_SYNCONF_HWINVC_SHIFT)) & FTM_SYNCONF_HWINVC_MASK)
+#define FTM_SYNCONF_HWSOC_MASK (0x100000U)
+#define FTM_SYNCONF_HWSOC_SHIFT (20U)
+#define FTM_SYNCONF_HWSOC(x) (((uint32_t)(((uint32_t)(x)) << FTM_SYNCONF_HWSOC_SHIFT)) & FTM_SYNCONF_HWSOC_MASK)
+
+/*! @name INVCTRL - FTM Inverting Control */
+#define FTM_INVCTRL_INV0EN_MASK (0x1U)
+#define FTM_INVCTRL_INV0EN_SHIFT (0U)
+#define FTM_INVCTRL_INV0EN(x) (((uint32_t)(((uint32_t)(x)) << FTM_INVCTRL_INV0EN_SHIFT)) & FTM_INVCTRL_INV0EN_MASK)
+#define FTM_INVCTRL_INV1EN_MASK (0x2U)
+#define FTM_INVCTRL_INV1EN_SHIFT (1U)
+#define FTM_INVCTRL_INV1EN(x) (((uint32_t)(((uint32_t)(x)) << FTM_INVCTRL_INV1EN_SHIFT)) & FTM_INVCTRL_INV1EN_MASK)
+#define FTM_INVCTRL_INV2EN_MASK (0x4U)
+#define FTM_INVCTRL_INV2EN_SHIFT (2U)
+#define FTM_INVCTRL_INV2EN(x) (((uint32_t)(((uint32_t)(x)) << FTM_INVCTRL_INV2EN_SHIFT)) & FTM_INVCTRL_INV2EN_MASK)
+#define FTM_INVCTRL_INV3EN_MASK (0x8U)
+#define FTM_INVCTRL_INV3EN_SHIFT (3U)
+#define FTM_INVCTRL_INV3EN(x) (((uint32_t)(((uint32_t)(x)) << FTM_INVCTRL_INV3EN_SHIFT)) & FTM_INVCTRL_INV3EN_MASK)
+
+/*! @name SWOCTRL - FTM Software Output Control */
+#define FTM_SWOCTRL_CH0OC_MASK (0x1U)
+#define FTM_SWOCTRL_CH0OC_SHIFT (0U)
+#define FTM_SWOCTRL_CH0OC(x) (((uint32_t)(((uint32_t)(x)) << FTM_SWOCTRL_CH0OC_SHIFT)) & FTM_SWOCTRL_CH0OC_MASK)
+#define FTM_SWOCTRL_CH1OC_MASK (0x2U)
+#define FTM_SWOCTRL_CH1OC_SHIFT (1U)
+#define FTM_SWOCTRL_CH1OC(x) (((uint32_t)(((uint32_t)(x)) << FTM_SWOCTRL_CH1OC_SHIFT)) & FTM_SWOCTRL_CH1OC_MASK)
+#define FTM_SWOCTRL_CH2OC_MASK (0x4U)
+#define FTM_SWOCTRL_CH2OC_SHIFT (2U)
+#define FTM_SWOCTRL_CH2OC(x) (((uint32_t)(((uint32_t)(x)) << FTM_SWOCTRL_CH2OC_SHIFT)) & FTM_SWOCTRL_CH2OC_MASK)
+#define FTM_SWOCTRL_CH3OC_MASK (0x8U)
+#define FTM_SWOCTRL_CH3OC_SHIFT (3U)
+#define FTM_SWOCTRL_CH3OC(x) (((uint32_t)(((uint32_t)(x)) << FTM_SWOCTRL_CH3OC_SHIFT)) & FTM_SWOCTRL_CH3OC_MASK)
+#define FTM_SWOCTRL_CH4OC_MASK (0x10U)
+#define FTM_SWOCTRL_CH4OC_SHIFT (4U)
+#define FTM_SWOCTRL_CH4OC(x) (((uint32_t)(((uint32_t)(x)) << FTM_SWOCTRL_CH4OC_SHIFT)) & FTM_SWOCTRL_CH4OC_MASK)
+#define FTM_SWOCTRL_CH5OC_MASK (0x20U)
+#define FTM_SWOCTRL_CH5OC_SHIFT (5U)
+#define FTM_SWOCTRL_CH5OC(x) (((uint32_t)(((uint32_t)(x)) << FTM_SWOCTRL_CH5OC_SHIFT)) & FTM_SWOCTRL_CH5OC_MASK)
+#define FTM_SWOCTRL_CH6OC_MASK (0x40U)
+#define FTM_SWOCTRL_CH6OC_SHIFT (6U)
+#define FTM_SWOCTRL_CH6OC(x) (((uint32_t)(((uint32_t)(x)) << FTM_SWOCTRL_CH6OC_SHIFT)) & FTM_SWOCTRL_CH6OC_MASK)
+#define FTM_SWOCTRL_CH7OC_MASK (0x80U)
+#define FTM_SWOCTRL_CH7OC_SHIFT (7U)
+#define FTM_SWOCTRL_CH7OC(x) (((uint32_t)(((uint32_t)(x)) << FTM_SWOCTRL_CH7OC_SHIFT)) & FTM_SWOCTRL_CH7OC_MASK)
+#define FTM_SWOCTRL_CH0OCV_MASK (0x100U)
+#define FTM_SWOCTRL_CH0OCV_SHIFT (8U)
+#define FTM_SWOCTRL_CH0OCV(x) (((uint32_t)(((uint32_t)(x)) << FTM_SWOCTRL_CH0OCV_SHIFT)) & FTM_SWOCTRL_CH0OCV_MASK)
+#define FTM_SWOCTRL_CH1OCV_MASK (0x200U)
+#define FTM_SWOCTRL_CH1OCV_SHIFT (9U)
+#define FTM_SWOCTRL_CH1OCV(x) (((uint32_t)(((uint32_t)(x)) << FTM_SWOCTRL_CH1OCV_SHIFT)) & FTM_SWOCTRL_CH1OCV_MASK)
+#define FTM_SWOCTRL_CH2OCV_MASK (0x400U)
+#define FTM_SWOCTRL_CH2OCV_SHIFT (10U)
+#define FTM_SWOCTRL_CH2OCV(x) (((uint32_t)(((uint32_t)(x)) << FTM_SWOCTRL_CH2OCV_SHIFT)) & FTM_SWOCTRL_CH2OCV_MASK)
+#define FTM_SWOCTRL_CH3OCV_MASK (0x800U)
+#define FTM_SWOCTRL_CH3OCV_SHIFT (11U)
+#define FTM_SWOCTRL_CH3OCV(x) (((uint32_t)(((uint32_t)(x)) << FTM_SWOCTRL_CH3OCV_SHIFT)) & FTM_SWOCTRL_CH3OCV_MASK)
+#define FTM_SWOCTRL_CH4OCV_MASK (0x1000U)
+#define FTM_SWOCTRL_CH4OCV_SHIFT (12U)
+#define FTM_SWOCTRL_CH4OCV(x) (((uint32_t)(((uint32_t)(x)) << FTM_SWOCTRL_CH4OCV_SHIFT)) & FTM_SWOCTRL_CH4OCV_MASK)
+#define FTM_SWOCTRL_CH5OCV_MASK (0x2000U)
+#define FTM_SWOCTRL_CH5OCV_SHIFT (13U)
+#define FTM_SWOCTRL_CH5OCV(x) (((uint32_t)(((uint32_t)(x)) << FTM_SWOCTRL_CH5OCV_SHIFT)) & FTM_SWOCTRL_CH5OCV_MASK)
+#define FTM_SWOCTRL_CH6OCV_MASK (0x4000U)
+#define FTM_SWOCTRL_CH6OCV_SHIFT (14U)
+#define FTM_SWOCTRL_CH6OCV(x) (((uint32_t)(((uint32_t)(x)) << FTM_SWOCTRL_CH6OCV_SHIFT)) & FTM_SWOCTRL_CH6OCV_MASK)
+#define FTM_SWOCTRL_CH7OCV_MASK (0x8000U)
+#define FTM_SWOCTRL_CH7OCV_SHIFT (15U)
+#define FTM_SWOCTRL_CH7OCV(x) (((uint32_t)(((uint32_t)(x)) << FTM_SWOCTRL_CH7OCV_SHIFT)) & FTM_SWOCTRL_CH7OCV_MASK)
+
+/*! @name PWMLOAD - FTM PWM Load */
+#define FTM_PWMLOAD_CH0SEL_MASK (0x1U)
+#define FTM_PWMLOAD_CH0SEL_SHIFT (0U)
+#define FTM_PWMLOAD_CH0SEL(x) (((uint32_t)(((uint32_t)(x)) << FTM_PWMLOAD_CH0SEL_SHIFT)) & FTM_PWMLOAD_CH0SEL_MASK)
+#define FTM_PWMLOAD_CH1SEL_MASK (0x2U)
+#define FTM_PWMLOAD_CH1SEL_SHIFT (1U)
+#define FTM_PWMLOAD_CH1SEL(x) (((uint32_t)(((uint32_t)(x)) << FTM_PWMLOAD_CH1SEL_SHIFT)) & FTM_PWMLOAD_CH1SEL_MASK)
+#define FTM_PWMLOAD_CH2SEL_MASK (0x4U)
+#define FTM_PWMLOAD_CH2SEL_SHIFT (2U)
+#define FTM_PWMLOAD_CH2SEL(x) (((uint32_t)(((uint32_t)(x)) << FTM_PWMLOAD_CH2SEL_SHIFT)) & FTM_PWMLOAD_CH2SEL_MASK)
+#define FTM_PWMLOAD_CH3SEL_MASK (0x8U)
+#define FTM_PWMLOAD_CH3SEL_SHIFT (3U)
+#define FTM_PWMLOAD_CH3SEL(x) (((uint32_t)(((uint32_t)(x)) << FTM_PWMLOAD_CH3SEL_SHIFT)) & FTM_PWMLOAD_CH3SEL_MASK)
+#define FTM_PWMLOAD_CH4SEL_MASK (0x10U)
+#define FTM_PWMLOAD_CH4SEL_SHIFT (4U)
+#define FTM_PWMLOAD_CH4SEL(x) (((uint32_t)(((uint32_t)(x)) << FTM_PWMLOAD_CH4SEL_SHIFT)) & FTM_PWMLOAD_CH4SEL_MASK)
+#define FTM_PWMLOAD_CH5SEL_MASK (0x20U)
+#define FTM_PWMLOAD_CH5SEL_SHIFT (5U)
+#define FTM_PWMLOAD_CH5SEL(x) (((uint32_t)(((uint32_t)(x)) << FTM_PWMLOAD_CH5SEL_SHIFT)) & FTM_PWMLOAD_CH5SEL_MASK)
+#define FTM_PWMLOAD_CH6SEL_MASK (0x40U)
+#define FTM_PWMLOAD_CH6SEL_SHIFT (6U)
+#define FTM_PWMLOAD_CH6SEL(x) (((uint32_t)(((uint32_t)(x)) << FTM_PWMLOAD_CH6SEL_SHIFT)) & FTM_PWMLOAD_CH6SEL_MASK)
+#define FTM_PWMLOAD_CH7SEL_MASK (0x80U)
+#define FTM_PWMLOAD_CH7SEL_SHIFT (7U)
+#define FTM_PWMLOAD_CH7SEL(x) (((uint32_t)(((uint32_t)(x)) << FTM_PWMLOAD_CH7SEL_SHIFT)) & FTM_PWMLOAD_CH7SEL_MASK)
+#define FTM_PWMLOAD_LDOK_MASK (0x200U)
+#define FTM_PWMLOAD_LDOK_SHIFT (9U)
+#define FTM_PWMLOAD_LDOK(x) (((uint32_t)(((uint32_t)(x)) << FTM_PWMLOAD_LDOK_SHIFT)) & FTM_PWMLOAD_LDOK_MASK)
+
+
+/*!
+ * @}
+ */ /* end of group FTM_Register_Masks */
+
+
+/* FTM - Peripheral instance base addresses */
+/** Peripheral FTM0 base address */
+#define FTM0_BASE (0x40038000u)
+/** Peripheral FTM0 base pointer */
+#define FTM0 ((FTM_Type *)FTM0_BASE)
+/** Peripheral FTM1 base address */
+#define FTM1_BASE (0x40039000u)
+/** Peripheral FTM1 base pointer */
+#define FTM1 ((FTM_Type *)FTM1_BASE)
+/** Peripheral FTM2 base address */
+#define FTM2_BASE (0x4003A000u)
+/** Peripheral FTM2 base pointer */
+#define FTM2 ((FTM_Type *)FTM2_BASE)
+/** Array initializer of FTM peripheral base addresses */
+#define FTM_BASE_ADDRS { FTM0_BASE, FTM1_BASE, FTM2_BASE }
+/** Array initializer of FTM peripheral base pointers */
+#define FTM_BASE_PTRS { FTM0, FTM1, FTM2 }
+/** Interrupt vectors for the FTM peripheral type */
+#define FTM_IRQS { FTM0_IRQn, FTM1_IRQn, FTM2_IRQn }
+
+/*!
+ * @}
+ */ /* end of group FTM_Peripheral_Access_Layer */
+
+
+/* ----------------------------------------------------------------------------
+ -- GPIO Peripheral Access Layer
+ ---------------------------------------------------------------------------- */
+
+/*!
+ * @addtogroup GPIO_Peripheral_Access_Layer GPIO Peripheral Access Layer
+ * @{
+ */
+
+/** GPIO - Register Layout Typedef */
+typedef struct {
+ __IO uint32_t PDOR; /**< Port Data Output Register, offset: 0x0 */
+ __O uint32_t PSOR; /**< Port Set Output Register, offset: 0x4 */
+ __O uint32_t PCOR; /**< Port Clear Output Register, offset: 0x8 */
+ __O uint32_t PTOR; /**< Port Toggle Output Register, offset: 0xC */
+ __I uint32_t PDIR; /**< Port Data Input Register, offset: 0x10 */
+ __IO uint32_t PDDR; /**< Port Data Direction Register, offset: 0x14 */
+} GPIO_Type;
+
+/* ----------------------------------------------------------------------------
+ -- GPIO Register Masks
+ ---------------------------------------------------------------------------- */
+
+/*!
+ * @addtogroup GPIO_Register_Masks GPIO Register Masks
+ * @{
+ */
+
+/*! @name PDOR - Port Data Output Register */
+#define GPIO_PDOR_PDO_MASK (0xFFFFFFFFU)
+#define GPIO_PDOR_PDO_SHIFT (0U)
+#define GPIO_PDOR_PDO(x) (((uint32_t)(((uint32_t)(x)) << GPIO_PDOR_PDO_SHIFT)) & GPIO_PDOR_PDO_MASK)
+
+/*! @name PSOR - Port Set Output Register */
+#define GPIO_PSOR_PTSO_MASK (0xFFFFFFFFU)
+#define GPIO_PSOR_PTSO_SHIFT (0U)
+#define GPIO_PSOR_PTSO(x) (((uint32_t)(((uint32_t)(x)) << GPIO_PSOR_PTSO_SHIFT)) & GPIO_PSOR_PTSO_MASK)
+
+/*! @name PCOR - Port Clear Output Register */
+#define GPIO_PCOR_PTCO_MASK (0xFFFFFFFFU)
+#define GPIO_PCOR_PTCO_SHIFT (0U)
+#define GPIO_PCOR_PTCO(x) (((uint32_t)(((uint32_t)(x)) << GPIO_PCOR_PTCO_SHIFT)) & GPIO_PCOR_PTCO_MASK)
+
+/*! @name PTOR - Port Toggle Output Register */
+#define GPIO_PTOR_PTTO_MASK (0xFFFFFFFFU)
+#define GPIO_PTOR_PTTO_SHIFT (0U)
+#define GPIO_PTOR_PTTO(x) (((uint32_t)(((uint32_t)(x)) << GPIO_PTOR_PTTO_SHIFT)) & GPIO_PTOR_PTTO_MASK)
+
+/*! @name PDIR - Port Data Input Register */
+#define GPIO_PDIR_PDI_MASK (0xFFFFFFFFU)
+#define GPIO_PDIR_PDI_SHIFT (0U)
+#define GPIO_PDIR_PDI(x) (((uint32_t)(((uint32_t)(x)) << GPIO_PDIR_PDI_SHIFT)) & GPIO_PDIR_PDI_MASK)
+
+/*! @name PDDR - Port Data Direction Register */
+#define GPIO_PDDR_PDD_MASK (0xFFFFFFFFU)
+#define GPIO_PDDR_PDD_SHIFT (0U)
+#define GPIO_PDDR_PDD(x) (((uint32_t)(((uint32_t)(x)) << GPIO_PDDR_PDD_SHIFT)) & GPIO_PDDR_PDD_MASK)
+
+
+/*!
+ * @}
+ */ /* end of group GPIO_Register_Masks */
+
+
+/* GPIO - Peripheral instance base addresses */
+/** Peripheral GPIOA base address */
+#define GPIOA_BASE (0x400FF000u)
+/** Peripheral GPIOA base pointer */
+#define GPIOA ((GPIO_Type *)GPIOA_BASE)
+/** Peripheral GPIOB base address */
+#define GPIOB_BASE (0x400FF040u)
+/** Peripheral GPIOB base pointer */
+#define GPIOB ((GPIO_Type *)GPIOB_BASE)
+/** Peripheral GPIOC base address */
+#define GPIOC_BASE (0x400FF080u)
+/** Peripheral GPIOC base pointer */
+#define GPIOC ((GPIO_Type *)GPIOC_BASE)
+/** Peripheral GPIOD base address */
+#define GPIOD_BASE (0x400FF0C0u)
+/** Peripheral GPIOD base pointer */
+#define GPIOD ((GPIO_Type *)GPIOD_BASE)
+/** Peripheral GPIOE base address */
+#define GPIOE_BASE (0x400FF100u)
+/** Peripheral GPIOE base pointer */
+#define GPIOE ((GPIO_Type *)GPIOE_BASE)
+/** Array initializer of GPIO peripheral base addresses */
+#define GPIO_BASE_ADDRS { GPIOA_BASE, GPIOB_BASE, GPIOC_BASE, GPIOD_BASE, GPIOE_BASE }
+/** Array initializer of GPIO peripheral base pointers */
+#define GPIO_BASE_PTRS { GPIOA, GPIOB, GPIOC, GPIOD, GPIOE }
+
+/*!
+ * @}
+ */ /* end of group GPIO_Peripheral_Access_Layer */
+
+
+/* ----------------------------------------------------------------------------
+ -- I2C Peripheral Access Layer
+ ---------------------------------------------------------------------------- */
+
+/*!
+ * @addtogroup I2C_Peripheral_Access_Layer I2C Peripheral Access Layer
+ * @{
+ */
+
+/** I2C - Register Layout Typedef */
+typedef struct {
+ __IO uint8_t A1; /**< I2C Address Register 1, offset: 0x0 */
+ __IO uint8_t F; /**< I2C Frequency Divider register, offset: 0x1 */
+ __IO uint8_t C1; /**< I2C Control Register 1, offset: 0x2 */
+ __IO uint8_t S; /**< I2C Status register, offset: 0x3 */
+ __IO uint8_t D; /**< I2C Data I/O register, offset: 0x4 */
+ __IO uint8_t C2; /**< I2C Control Register 2, offset: 0x5 */
+ __IO uint8_t FLT; /**< I2C Programmable Input Glitch Filter register, offset: 0x6 */
+ __IO uint8_t RA; /**< I2C Range Address register, offset: 0x7 */
+ __IO uint8_t SMB; /**< I2C SMBus Control and Status register, offset: 0x8 */
+ __IO uint8_t A2; /**< I2C Address Register 2, offset: 0x9 */
+ __IO uint8_t SLTH; /**< I2C SCL Low Timeout Register High, offset: 0xA */
+ __IO uint8_t SLTL; /**< I2C SCL Low Timeout Register Low, offset: 0xB */
+} I2C_Type;
+
+/* ----------------------------------------------------------------------------
+ -- I2C Register Masks
+ ---------------------------------------------------------------------------- */
+
+/*!
+ * @addtogroup I2C_Register_Masks I2C Register Masks
+ * @{
+ */
+
+/*! @name A1 - I2C Address Register 1 */
+#define I2C_A1_AD_MASK (0xFEU)
+#define I2C_A1_AD_SHIFT (1U)
+#define I2C_A1_AD(x) (((uint8_t)(((uint8_t)(x)) << I2C_A1_AD_SHIFT)) & I2C_A1_AD_MASK)
+
+/*! @name F - I2C Frequency Divider register */
+#define I2C_F_ICR_MASK (0x3FU)
+#define I2C_F_ICR_SHIFT (0U)
+#define I2C_F_ICR(x) (((uint8_t)(((uint8_t)(x)) << I2C_F_ICR_SHIFT)) & I2C_F_ICR_MASK)
+#define I2C_F_MULT_MASK (0xC0U)
+#define I2C_F_MULT_SHIFT (6U)
+#define I2C_F_MULT(x) (((uint8_t)(((uint8_t)(x)) << I2C_F_MULT_SHIFT)) & I2C_F_MULT_MASK)
+
+/*! @name C1 - I2C Control Register 1 */
+#define I2C_C1_DMAEN_MASK (0x1U)
+#define I2C_C1_DMAEN_SHIFT (0U)
+#define I2C_C1_DMAEN(x) (((uint8_t)(((uint8_t)(x)) << I2C_C1_DMAEN_SHIFT)) & I2C_C1_DMAEN_MASK)
+#define I2C_C1_WUEN_MASK (0x2U)
+#define I2C_C1_WUEN_SHIFT (1U)
+#define I2C_C1_WUEN(x) (((uint8_t)(((uint8_t)(x)) << I2C_C1_WUEN_SHIFT)) & I2C_C1_WUEN_MASK)
+#define I2C_C1_RSTA_MASK (0x4U)
+#define I2C_C1_RSTA_SHIFT (2U)
+#define I2C_C1_RSTA(x) (((uint8_t)(((uint8_t)(x)) << I2C_C1_RSTA_SHIFT)) & I2C_C1_RSTA_MASK)
+#define I2C_C1_TXAK_MASK (0x8U)
+#define I2C_C1_TXAK_SHIFT (3U)
+#define I2C_C1_TXAK(x) (((uint8_t)(((uint8_t)(x)) << I2C_C1_TXAK_SHIFT)) & I2C_C1_TXAK_MASK)
+#define I2C_C1_TX_MASK (0x10U)
+#define I2C_C1_TX_SHIFT (4U)
+#define I2C_C1_TX(x) (((uint8_t)(((uint8_t)(x)) << I2C_C1_TX_SHIFT)) & I2C_C1_TX_MASK)
+#define I2C_C1_MST_MASK (0x20U)
+#define I2C_C1_MST_SHIFT (5U)
+#define I2C_C1_MST(x) (((uint8_t)(((uint8_t)(x)) << I2C_C1_MST_SHIFT)) & I2C_C1_MST_MASK)
+#define I2C_C1_IICIE_MASK (0x40U)
+#define I2C_C1_IICIE_SHIFT (6U)
+#define I2C_C1_IICIE(x) (((uint8_t)(((uint8_t)(x)) << I2C_C1_IICIE_SHIFT)) & I2C_C1_IICIE_MASK)
+#define I2C_C1_IICEN_MASK (0x80U)
+#define I2C_C1_IICEN_SHIFT (7U)
+#define I2C_C1_IICEN(x) (((uint8_t)(((uint8_t)(x)) << I2C_C1_IICEN_SHIFT)) & I2C_C1_IICEN_MASK)
+
+/*! @name S - I2C Status register */
+#define I2C_S_RXAK_MASK (0x1U)
+#define I2C_S_RXAK_SHIFT (0U)
+#define I2C_S_RXAK(x) (((uint8_t)(((uint8_t)(x)) << I2C_S_RXAK_SHIFT)) & I2C_S_RXAK_MASK)
+#define I2C_S_IICIF_MASK (0x2U)
+#define I2C_S_IICIF_SHIFT (1U)
+#define I2C_S_IICIF(x) (((uint8_t)(((uint8_t)(x)) << I2C_S_IICIF_SHIFT)) & I2C_S_IICIF_MASK)
+#define I2C_S_SRW_MASK (0x4U)
+#define I2C_S_SRW_SHIFT (2U)
+#define I2C_S_SRW(x) (((uint8_t)(((uint8_t)(x)) << I2C_S_SRW_SHIFT)) & I2C_S_SRW_MASK)
+#define I2C_S_RAM_MASK (0x8U)
+#define I2C_S_RAM_SHIFT (3U)
+#define I2C_S_RAM(x) (((uint8_t)(((uint8_t)(x)) << I2C_S_RAM_SHIFT)) & I2C_S_RAM_MASK)
+#define I2C_S_ARBL_MASK (0x10U)
+#define I2C_S_ARBL_SHIFT (4U)
+#define I2C_S_ARBL(x) (((uint8_t)(((uint8_t)(x)) << I2C_S_ARBL_SHIFT)) & I2C_S_ARBL_MASK)
+#define I2C_S_BUSY_MASK (0x20U)
+#define I2C_S_BUSY_SHIFT (5U)
+#define I2C_S_BUSY(x) (((uint8_t)(((uint8_t)(x)) << I2C_S_BUSY_SHIFT)) & I2C_S_BUSY_MASK)
+#define I2C_S_IAAS_MASK (0x40U)
+#define I2C_S_IAAS_SHIFT (6U)
+#define I2C_S_IAAS(x) (((uint8_t)(((uint8_t)(x)) << I2C_S_IAAS_SHIFT)) & I2C_S_IAAS_MASK)
+#define I2C_S_TCF_MASK (0x80U)
+#define I2C_S_TCF_SHIFT (7U)
+#define I2C_S_TCF(x) (((uint8_t)(((uint8_t)(x)) << I2C_S_TCF_SHIFT)) & I2C_S_TCF_MASK)
+
+/*! @name D - I2C Data I/O register */
+#define I2C_D_DATA_MASK (0xFFU)
+#define I2C_D_DATA_SHIFT (0U)
+#define I2C_D_DATA(x) (((uint8_t)(((uint8_t)(x)) << I2C_D_DATA_SHIFT)) & I2C_D_DATA_MASK)
+
+/*! @name C2 - I2C Control Register 2 */
+#define I2C_C2_AD_MASK (0x7U)
+#define I2C_C2_AD_SHIFT (0U)
+#define I2C_C2_AD(x) (((uint8_t)(((uint8_t)(x)) << I2C_C2_AD_SHIFT)) & I2C_C2_AD_MASK)
+#define I2C_C2_RMEN_MASK (0x8U)
+#define I2C_C2_RMEN_SHIFT (3U)
+#define I2C_C2_RMEN(x) (((uint8_t)(((uint8_t)(x)) << I2C_C2_RMEN_SHIFT)) & I2C_C2_RMEN_MASK)
+#define I2C_C2_SBRC_MASK (0x10U)
+#define I2C_C2_SBRC_SHIFT (4U)
+#define I2C_C2_SBRC(x) (((uint8_t)(((uint8_t)(x)) << I2C_C2_SBRC_SHIFT)) & I2C_C2_SBRC_MASK)
+#define I2C_C2_HDRS_MASK (0x20U)
+#define I2C_C2_HDRS_SHIFT (5U)
+#define I2C_C2_HDRS(x) (((uint8_t)(((uint8_t)(x)) << I2C_C2_HDRS_SHIFT)) & I2C_C2_HDRS_MASK)
+#define I2C_C2_ADEXT_MASK (0x40U)
+#define I2C_C2_ADEXT_SHIFT (6U)
+#define I2C_C2_ADEXT(x) (((uint8_t)(((uint8_t)(x)) << I2C_C2_ADEXT_SHIFT)) & I2C_C2_ADEXT_MASK)
+#define I2C_C2_GCAEN_MASK (0x80U)
+#define I2C_C2_GCAEN_SHIFT (7U)
+#define I2C_C2_GCAEN(x) (((uint8_t)(((uint8_t)(x)) << I2C_C2_GCAEN_SHIFT)) & I2C_C2_GCAEN_MASK)
+
+/*! @name FLT - I2C Programmable Input Glitch Filter register */
+#define I2C_FLT_FLT_MASK (0xFU)
+#define I2C_FLT_FLT_SHIFT (0U)
+#define I2C_FLT_FLT(x) (((uint8_t)(((uint8_t)(x)) << I2C_FLT_FLT_SHIFT)) & I2C_FLT_FLT_MASK)
+#define I2C_FLT_STARTF_MASK (0x10U)
+#define I2C_FLT_STARTF_SHIFT (4U)
+#define I2C_FLT_STARTF(x) (((uint8_t)(((uint8_t)(x)) << I2C_FLT_STARTF_SHIFT)) & I2C_FLT_STARTF_MASK)
+#define I2C_FLT_SSIE_MASK (0x20U)
+#define I2C_FLT_SSIE_SHIFT (5U)
+#define I2C_FLT_SSIE(x) (((uint8_t)(((uint8_t)(x)) << I2C_FLT_SSIE_SHIFT)) & I2C_FLT_SSIE_MASK)
+#define I2C_FLT_STOPF_MASK (0x40U)
+#define I2C_FLT_STOPF_SHIFT (6U)
+#define I2C_FLT_STOPF(x) (((uint8_t)(((uint8_t)(x)) << I2C_FLT_STOPF_SHIFT)) & I2C_FLT_STOPF_MASK)
+#define I2C_FLT_SHEN_MASK (0x80U)
+#define I2C_FLT_SHEN_SHIFT (7U)
+#define I2C_FLT_SHEN(x) (((uint8_t)(((uint8_t)(x)) << I2C_FLT_SHEN_SHIFT)) & I2C_FLT_SHEN_MASK)
+
+/*! @name RA - I2C Range Address register */
+#define I2C_RA_RAD_MASK (0xFEU)
+#define I2C_RA_RAD_SHIFT (1U)
+#define I2C_RA_RAD(x) (((uint8_t)(((uint8_t)(x)) << I2C_RA_RAD_SHIFT)) & I2C_RA_RAD_MASK)
+
+/*! @name SMB - I2C SMBus Control and Status register */
+#define I2C_SMB_SHTF2IE_MASK (0x1U)
+#define I2C_SMB_SHTF2IE_SHIFT (0U)
+#define I2C_SMB_SHTF2IE(x) (((uint8_t)(((uint8_t)(x)) << I2C_SMB_SHTF2IE_SHIFT)) & I2C_SMB_SHTF2IE_MASK)
+#define I2C_SMB_SHTF2_MASK (0x2U)
+#define I2C_SMB_SHTF2_SHIFT (1U)
+#define I2C_SMB_SHTF2(x) (((uint8_t)(((uint8_t)(x)) << I2C_SMB_SHTF2_SHIFT)) & I2C_SMB_SHTF2_MASK)
+#define I2C_SMB_SHTF1_MASK (0x4U)
+#define I2C_SMB_SHTF1_SHIFT (2U)
+#define I2C_SMB_SHTF1(x) (((uint8_t)(((uint8_t)(x)) << I2C_SMB_SHTF1_SHIFT)) & I2C_SMB_SHTF1_MASK)
+#define I2C_SMB_SLTF_MASK (0x8U)
+#define I2C_SMB_SLTF_SHIFT (3U)
+#define I2C_SMB_SLTF(x) (((uint8_t)(((uint8_t)(x)) << I2C_SMB_SLTF_SHIFT)) & I2C_SMB_SLTF_MASK)
+#define I2C_SMB_TCKSEL_MASK (0x10U)
+#define I2C_SMB_TCKSEL_SHIFT (4U)
+#define I2C_SMB_TCKSEL(x) (((uint8_t)(((uint8_t)(x)) << I2C_SMB_TCKSEL_SHIFT)) & I2C_SMB_TCKSEL_MASK)
+#define I2C_SMB_SIICAEN_MASK (0x20U)
+#define I2C_SMB_SIICAEN_SHIFT (5U)
+#define I2C_SMB_SIICAEN(x) (((uint8_t)(((uint8_t)(x)) << I2C_SMB_SIICAEN_SHIFT)) & I2C_SMB_SIICAEN_MASK)
+#define I2C_SMB_ALERTEN_MASK (0x40U)
+#define I2C_SMB_ALERTEN_SHIFT (6U)
+#define I2C_SMB_ALERTEN(x) (((uint8_t)(((uint8_t)(x)) << I2C_SMB_ALERTEN_SHIFT)) & I2C_SMB_ALERTEN_MASK)
+#define I2C_SMB_FACK_MASK (0x80U)
+#define I2C_SMB_FACK_SHIFT (7U)
+#define I2C_SMB_FACK(x) (((uint8_t)(((uint8_t)(x)) << I2C_SMB_FACK_SHIFT)) & I2C_SMB_FACK_MASK)
+
+/*! @name A2 - I2C Address Register 2 */
+#define I2C_A2_SAD_MASK (0xFEU)
+#define I2C_A2_SAD_SHIFT (1U)
+#define I2C_A2_SAD(x) (((uint8_t)(((uint8_t)(x)) << I2C_A2_SAD_SHIFT)) & I2C_A2_SAD_MASK)
+
+/*! @name SLTH - I2C SCL Low Timeout Register High */
+#define I2C_SLTH_SSLT_MASK (0xFFU)
+#define I2C_SLTH_SSLT_SHIFT (0U)
+#define I2C_SLTH_SSLT(x) (((uint8_t)(((uint8_t)(x)) << I2C_SLTH_SSLT_SHIFT)) & I2C_SLTH_SSLT_MASK)
+
+/*! @name SLTL - I2C SCL Low Timeout Register Low */
+#define I2C_SLTL_SSLT_MASK (0xFFU)
+#define I2C_SLTL_SSLT_SHIFT (0U)
+#define I2C_SLTL_SSLT(x) (((uint8_t)(((uint8_t)(x)) << I2C_SLTL_SSLT_SHIFT)) & I2C_SLTL_SSLT_MASK)
+
+
+/*!
+ * @}
+ */ /* end of group I2C_Register_Masks */
+
+
+/* I2C - Peripheral instance base addresses */
+/** Peripheral I2C0 base address */
+#define I2C0_BASE (0x40066000u)
+/** Peripheral I2C0 base pointer */
+#define I2C0 ((I2C_Type *)I2C0_BASE)
+/** Array initializer of I2C peripheral base addresses */
+#define I2C_BASE_ADDRS { I2C0_BASE }
+/** Array initializer of I2C peripheral base pointers */
+#define I2C_BASE_PTRS { I2C0 }
+/** Interrupt vectors for the I2C peripheral type */
+#define I2C_IRQS { I2C0_IRQn }
+
+/*!
+ * @}
+ */ /* end of group I2C_Peripheral_Access_Layer */
+
+
+/* ----------------------------------------------------------------------------
+ -- LLWU Peripheral Access Layer
+ ---------------------------------------------------------------------------- */
+
+/*!
+ * @addtogroup LLWU_Peripheral_Access_Layer LLWU Peripheral Access Layer
+ * @{
+ */
+
+/** LLWU - Register Layout Typedef */
+typedef struct {
+ __IO uint8_t PE1; /**< LLWU Pin Enable 1 register, offset: 0x0 */
+ __IO uint8_t PE2; /**< LLWU Pin Enable 2 register, offset: 0x1 */
+ __IO uint8_t PE3; /**< LLWU Pin Enable 3 register, offset: 0x2 */
+ __IO uint8_t PE4; /**< LLWU Pin Enable 4 register, offset: 0x3 */
+ __IO uint8_t ME; /**< LLWU Module Enable register, offset: 0x4 */
+ __IO uint8_t F1; /**< LLWU Flag 1 register, offset: 0x5 */
+ __IO uint8_t F2; /**< LLWU Flag 2 register, offset: 0x6 */
+ __I uint8_t F3; /**< LLWU Flag 3 register, offset: 0x7 */
+ __IO uint8_t FILT1; /**< LLWU Pin Filter 1 register, offset: 0x8 */
+ __IO uint8_t FILT2; /**< LLWU Pin Filter 2 register, offset: 0x9 */
+} LLWU_Type;
+
+/* ----------------------------------------------------------------------------
+ -- LLWU Register Masks
+ ---------------------------------------------------------------------------- */
+
+/*!
+ * @addtogroup LLWU_Register_Masks LLWU Register Masks
+ * @{
+ */
+
+/*! @name PE1 - LLWU Pin Enable 1 register */
+#define LLWU_PE1_WUPE0_MASK (0x3U)
+#define LLWU_PE1_WUPE0_SHIFT (0U)
+#define LLWU_PE1_WUPE0(x) (((uint8_t)(((uint8_t)(x)) << LLWU_PE1_WUPE0_SHIFT)) & LLWU_PE1_WUPE0_MASK)
+#define LLWU_PE1_WUPE1_MASK (0xCU)
+#define LLWU_PE1_WUPE1_SHIFT (2U)
+#define LLWU_PE1_WUPE1(x) (((uint8_t)(((uint8_t)(x)) << LLWU_PE1_WUPE1_SHIFT)) & LLWU_PE1_WUPE1_MASK)
+#define LLWU_PE1_WUPE2_MASK (0x30U)
+#define LLWU_PE1_WUPE2_SHIFT (4U)
+#define LLWU_PE1_WUPE2(x) (((uint8_t)(((uint8_t)(x)) << LLWU_PE1_WUPE2_SHIFT)) & LLWU_PE1_WUPE2_MASK)
+#define LLWU_PE1_WUPE3_MASK (0xC0U)
+#define LLWU_PE1_WUPE3_SHIFT (6U)
+#define LLWU_PE1_WUPE3(x) (((uint8_t)(((uint8_t)(x)) << LLWU_PE1_WUPE3_SHIFT)) & LLWU_PE1_WUPE3_MASK)
+
+/*! @name PE2 - LLWU Pin Enable 2 register */
+#define LLWU_PE2_WUPE4_MASK (0x3U)
+#define LLWU_PE2_WUPE4_SHIFT (0U)
+#define LLWU_PE2_WUPE4(x) (((uint8_t)(((uint8_t)(x)) << LLWU_PE2_WUPE4_SHIFT)) & LLWU_PE2_WUPE4_MASK)
+#define LLWU_PE2_WUPE5_MASK (0xCU)
+#define LLWU_PE2_WUPE5_SHIFT (2U)
+#define LLWU_PE2_WUPE5(x) (((uint8_t)(((uint8_t)(x)) << LLWU_PE2_WUPE5_SHIFT)) & LLWU_PE2_WUPE5_MASK)
+#define LLWU_PE2_WUPE6_MASK (0x30U)
+#define LLWU_PE2_WUPE6_SHIFT (4U)
+#define LLWU_PE2_WUPE6(x) (((uint8_t)(((uint8_t)(x)) << LLWU_PE2_WUPE6_SHIFT)) & LLWU_PE2_WUPE6_MASK)
+#define LLWU_PE2_WUPE7_MASK (0xC0U)
+#define LLWU_PE2_WUPE7_SHIFT (6U)
+#define LLWU_PE2_WUPE7(x) (((uint8_t)(((uint8_t)(x)) << LLWU_PE2_WUPE7_SHIFT)) & LLWU_PE2_WUPE7_MASK)
+
+/*! @name PE3 - LLWU Pin Enable 3 register */
+#define LLWU_PE3_WUPE8_MASK (0x3U)
+#define LLWU_PE3_WUPE8_SHIFT (0U)
+#define LLWU_PE3_WUPE8(x) (((uint8_t)(((uint8_t)(x)) << LLWU_PE3_WUPE8_SHIFT)) & LLWU_PE3_WUPE8_MASK)
+#define LLWU_PE3_WUPE9_MASK (0xCU)
+#define LLWU_PE3_WUPE9_SHIFT (2U)
+#define LLWU_PE3_WUPE9(x) (((uint8_t)(((uint8_t)(x)) << LLWU_PE3_WUPE9_SHIFT)) & LLWU_PE3_WUPE9_MASK)
+#define LLWU_PE3_WUPE10_MASK (0x30U)
+#define LLWU_PE3_WUPE10_SHIFT (4U)
+#define LLWU_PE3_WUPE10(x) (((uint8_t)(((uint8_t)(x)) << LLWU_PE3_WUPE10_SHIFT)) & LLWU_PE3_WUPE10_MASK)
+#define LLWU_PE3_WUPE11_MASK (0xC0U)
+#define LLWU_PE3_WUPE11_SHIFT (6U)
+#define LLWU_PE3_WUPE11(x) (((uint8_t)(((uint8_t)(x)) << LLWU_PE3_WUPE11_SHIFT)) & LLWU_PE3_WUPE11_MASK)
+
+/*! @name PE4 - LLWU Pin Enable 4 register */
+#define LLWU_PE4_WUPE12_MASK (0x3U)
+#define LLWU_PE4_WUPE12_SHIFT (0U)
+#define LLWU_PE4_WUPE12(x) (((uint8_t)(((uint8_t)(x)) << LLWU_PE4_WUPE12_SHIFT)) & LLWU_PE4_WUPE12_MASK)
+#define LLWU_PE4_WUPE13_MASK (0xCU)
+#define LLWU_PE4_WUPE13_SHIFT (2U)
+#define LLWU_PE4_WUPE13(x) (((uint8_t)(((uint8_t)(x)) << LLWU_PE4_WUPE13_SHIFT)) & LLWU_PE4_WUPE13_MASK)
+#define LLWU_PE4_WUPE14_MASK (0x30U)
+#define LLWU_PE4_WUPE14_SHIFT (4U)
+#define LLWU_PE4_WUPE14(x) (((uint8_t)(((uint8_t)(x)) << LLWU_PE4_WUPE14_SHIFT)) & LLWU_PE4_WUPE14_MASK)
+#define LLWU_PE4_WUPE15_MASK (0xC0U)
+#define LLWU_PE4_WUPE15_SHIFT (6U)
+#define LLWU_PE4_WUPE15(x) (((uint8_t)(((uint8_t)(x)) << LLWU_PE4_WUPE15_SHIFT)) & LLWU_PE4_WUPE15_MASK)
+
+/*! @name ME - LLWU Module Enable register */
+#define LLWU_ME_WUME0_MASK (0x1U)
+#define LLWU_ME_WUME0_SHIFT (0U)
+#define LLWU_ME_WUME0(x) (((uint8_t)(((uint8_t)(x)) << LLWU_ME_WUME0_SHIFT)) & LLWU_ME_WUME0_MASK)
+#define LLWU_ME_WUME1_MASK (0x2U)
+#define LLWU_ME_WUME1_SHIFT (1U)
+#define LLWU_ME_WUME1(x) (((uint8_t)(((uint8_t)(x)) << LLWU_ME_WUME1_SHIFT)) & LLWU_ME_WUME1_MASK)
+#define LLWU_ME_WUME2_MASK (0x4U)
+#define LLWU_ME_WUME2_SHIFT (2U)
+#define LLWU_ME_WUME2(x) (((uint8_t)(((uint8_t)(x)) << LLWU_ME_WUME2_SHIFT)) & LLWU_ME_WUME2_MASK)
+#define LLWU_ME_WUME3_MASK (0x8U)
+#define LLWU_ME_WUME3_SHIFT (3U)
+#define LLWU_ME_WUME3(x) (((uint8_t)(((uint8_t)(x)) << LLWU_ME_WUME3_SHIFT)) & LLWU_ME_WUME3_MASK)
+#define LLWU_ME_WUME4_MASK (0x10U)
+#define LLWU_ME_WUME4_SHIFT (4U)
+#define LLWU_ME_WUME4(x) (((uint8_t)(((uint8_t)(x)) << LLWU_ME_WUME4_SHIFT)) & LLWU_ME_WUME4_MASK)
+#define LLWU_ME_WUME5_MASK (0x20U)
+#define LLWU_ME_WUME5_SHIFT (5U)
+#define LLWU_ME_WUME5(x) (((uint8_t)(((uint8_t)(x)) << LLWU_ME_WUME5_SHIFT)) & LLWU_ME_WUME5_MASK)
+#define LLWU_ME_WUME6_MASK (0x40U)
+#define LLWU_ME_WUME6_SHIFT (6U)
+#define LLWU_ME_WUME6(x) (((uint8_t)(((uint8_t)(x)) << LLWU_ME_WUME6_SHIFT)) & LLWU_ME_WUME6_MASK)
+#define LLWU_ME_WUME7_MASK (0x80U)
+#define LLWU_ME_WUME7_SHIFT (7U)
+#define LLWU_ME_WUME7(x) (((uint8_t)(((uint8_t)(x)) << LLWU_ME_WUME7_SHIFT)) & LLWU_ME_WUME7_MASK)
+
+/*! @name F1 - LLWU Flag 1 register */
+#define LLWU_F1_WUF0_MASK (0x1U)
+#define LLWU_F1_WUF0_SHIFT (0U)
+#define LLWU_F1_WUF0(x) (((uint8_t)(((uint8_t)(x)) << LLWU_F1_WUF0_SHIFT)) & LLWU_F1_WUF0_MASK)
+#define LLWU_F1_WUF1_MASK (0x2U)
+#define LLWU_F1_WUF1_SHIFT (1U)
+#define LLWU_F1_WUF1(x) (((uint8_t)(((uint8_t)(x)) << LLWU_F1_WUF1_SHIFT)) & LLWU_F1_WUF1_MASK)
+#define LLWU_F1_WUF2_MASK (0x4U)
+#define LLWU_F1_WUF2_SHIFT (2U)
+#define LLWU_F1_WUF2(x) (((uint8_t)(((uint8_t)(x)) << LLWU_F1_WUF2_SHIFT)) & LLWU_F1_WUF2_MASK)
+#define LLWU_F1_WUF3_MASK (0x8U)
+#define LLWU_F1_WUF3_SHIFT (3U)
+#define LLWU_F1_WUF3(x) (((uint8_t)(((uint8_t)(x)) << LLWU_F1_WUF3_SHIFT)) & LLWU_F1_WUF3_MASK)
+#define LLWU_F1_WUF4_MASK (0x10U)
+#define LLWU_F1_WUF4_SHIFT (4U)
+#define LLWU_F1_WUF4(x) (((uint8_t)(((uint8_t)(x)) << LLWU_F1_WUF4_SHIFT)) & LLWU_F1_WUF4_MASK)
+#define LLWU_F1_WUF5_MASK (0x20U)
+#define LLWU_F1_WUF5_SHIFT (5U)
+#define LLWU_F1_WUF5(x) (((uint8_t)(((uint8_t)(x)) << LLWU_F1_WUF5_SHIFT)) & LLWU_F1_WUF5_MASK)
+#define LLWU_F1_WUF6_MASK (0x40U)
+#define LLWU_F1_WUF6_SHIFT (6U)
+#define LLWU_F1_WUF6(x) (((uint8_t)(((uint8_t)(x)) << LLWU_F1_WUF6_SHIFT)) & LLWU_F1_WUF6_MASK)
+#define LLWU_F1_WUF7_MASK (0x80U)
+#define LLWU_F1_WUF7_SHIFT (7U)
+#define LLWU_F1_WUF7(x) (((uint8_t)(((uint8_t)(x)) << LLWU_F1_WUF7_SHIFT)) & LLWU_F1_WUF7_MASK)
+
+/*! @name F2 - LLWU Flag 2 register */
+#define LLWU_F2_WUF8_MASK (0x1U)
+#define LLWU_F2_WUF8_SHIFT (0U)
+#define LLWU_F2_WUF8(x) (((uint8_t)(((uint8_t)(x)) << LLWU_F2_WUF8_SHIFT)) & LLWU_F2_WUF8_MASK)
+#define LLWU_F2_WUF9_MASK (0x2U)
+#define LLWU_F2_WUF9_SHIFT (1U)
+#define LLWU_F2_WUF9(x) (((uint8_t)(((uint8_t)(x)) << LLWU_F2_WUF9_SHIFT)) & LLWU_F2_WUF9_MASK)
+#define LLWU_F2_WUF10_MASK (0x4U)
+#define LLWU_F2_WUF10_SHIFT (2U)
+#define LLWU_F2_WUF10(x) (((uint8_t)(((uint8_t)(x)) << LLWU_F2_WUF10_SHIFT)) & LLWU_F2_WUF10_MASK)
+#define LLWU_F2_WUF11_MASK (0x8U)
+#define LLWU_F2_WUF11_SHIFT (3U)
+#define LLWU_F2_WUF11(x) (((uint8_t)(((uint8_t)(x)) << LLWU_F2_WUF11_SHIFT)) & LLWU_F2_WUF11_MASK)
+#define LLWU_F2_WUF12_MASK (0x10U)
+#define LLWU_F2_WUF12_SHIFT (4U)
+#define LLWU_F2_WUF12(x) (((uint8_t)(((uint8_t)(x)) << LLWU_F2_WUF12_SHIFT)) & LLWU_F2_WUF12_MASK)
+#define LLWU_F2_WUF13_MASK (0x20U)
+#define LLWU_F2_WUF13_SHIFT (5U)
+#define LLWU_F2_WUF13(x) (((uint8_t)(((uint8_t)(x)) << LLWU_F2_WUF13_SHIFT)) & LLWU_F2_WUF13_MASK)
+#define LLWU_F2_WUF14_MASK (0x40U)
+#define LLWU_F2_WUF14_SHIFT (6U)
+#define LLWU_F2_WUF14(x) (((uint8_t)(((uint8_t)(x)) << LLWU_F2_WUF14_SHIFT)) & LLWU_F2_WUF14_MASK)
+#define LLWU_F2_WUF15_MASK (0x80U)
+#define LLWU_F2_WUF15_SHIFT (7U)
+#define LLWU_F2_WUF15(x) (((uint8_t)(((uint8_t)(x)) << LLWU_F2_WUF15_SHIFT)) & LLWU_F2_WUF15_MASK)
+
+/*! @name F3 - LLWU Flag 3 register */
+#define LLWU_F3_MWUF0_MASK (0x1U)
+#define LLWU_F3_MWUF0_SHIFT (0U)
+#define LLWU_F3_MWUF0(x) (((uint8_t)(((uint8_t)(x)) << LLWU_F3_MWUF0_SHIFT)) & LLWU_F3_MWUF0_MASK)
+#define LLWU_F3_MWUF1_MASK (0x2U)
+#define LLWU_F3_MWUF1_SHIFT (1U)
+#define LLWU_F3_MWUF1(x) (((uint8_t)(((uint8_t)(x)) << LLWU_F3_MWUF1_SHIFT)) & LLWU_F3_MWUF1_MASK)
+#define LLWU_F3_MWUF2_MASK (0x4U)
+#define LLWU_F3_MWUF2_SHIFT (2U)
+#define LLWU_F3_MWUF2(x) (((uint8_t)(((uint8_t)(x)) << LLWU_F3_MWUF2_SHIFT)) & LLWU_F3_MWUF2_MASK)
+#define LLWU_F3_MWUF3_MASK (0x8U)
+#define LLWU_F3_MWUF3_SHIFT (3U)
+#define LLWU_F3_MWUF3(x) (((uint8_t)(((uint8_t)(x)) << LLWU_F3_MWUF3_SHIFT)) & LLWU_F3_MWUF3_MASK)
+#define LLWU_F3_MWUF4_MASK (0x10U)
+#define LLWU_F3_MWUF4_SHIFT (4U)
+#define LLWU_F3_MWUF4(x) (((uint8_t)(((uint8_t)(x)) << LLWU_F3_MWUF4_SHIFT)) & LLWU_F3_MWUF4_MASK)
+#define LLWU_F3_MWUF5_MASK (0x20U)
+#define LLWU_F3_MWUF5_SHIFT (5U)
+#define LLWU_F3_MWUF5(x) (((uint8_t)(((uint8_t)(x)) << LLWU_F3_MWUF5_SHIFT)) & LLWU_F3_MWUF5_MASK)
+#define LLWU_F3_MWUF6_MASK (0x40U)
+#define LLWU_F3_MWUF6_SHIFT (6U)
+#define LLWU_F3_MWUF6(x) (((uint8_t)(((uint8_t)(x)) << LLWU_F3_MWUF6_SHIFT)) & LLWU_F3_MWUF6_MASK)
+#define LLWU_F3_MWUF7_MASK (0x80U)
+#define LLWU_F3_MWUF7_SHIFT (7U)
+#define LLWU_F3_MWUF7(x) (((uint8_t)(((uint8_t)(x)) << LLWU_F3_MWUF7_SHIFT)) & LLWU_F3_MWUF7_MASK)
+
+/*! @name FILT1 - LLWU Pin Filter 1 register */
+#define LLWU_FILT1_FILTSEL_MASK (0xFU)
+#define LLWU_FILT1_FILTSEL_SHIFT (0U)
+#define LLWU_FILT1_FILTSEL(x) (((uint8_t)(((uint8_t)(x)) << LLWU_FILT1_FILTSEL_SHIFT)) & LLWU_FILT1_FILTSEL_MASK)
+#define LLWU_FILT1_FILTE_MASK (0x60U)
+#define LLWU_FILT1_FILTE_SHIFT (5U)
+#define LLWU_FILT1_FILTE(x) (((uint8_t)(((uint8_t)(x)) << LLWU_FILT1_FILTE_SHIFT)) & LLWU_FILT1_FILTE_MASK)
+#define LLWU_FILT1_FILTF_MASK (0x80U)
+#define LLWU_FILT1_FILTF_SHIFT (7U)
+#define LLWU_FILT1_FILTF(x) (((uint8_t)(((uint8_t)(x)) << LLWU_FILT1_FILTF_SHIFT)) & LLWU_FILT1_FILTF_MASK)
+
+/*! @name FILT2 - LLWU Pin Filter 2 register */
+#define LLWU_FILT2_FILTSEL_MASK (0xFU)
+#define LLWU_FILT2_FILTSEL_SHIFT (0U)
+#define LLWU_FILT2_FILTSEL(x) (((uint8_t)(((uint8_t)(x)) << LLWU_FILT2_FILTSEL_SHIFT)) & LLWU_FILT2_FILTSEL_MASK)
+#define LLWU_FILT2_FILTE_MASK (0x60U)
+#define LLWU_FILT2_FILTE_SHIFT (5U)
+#define LLWU_FILT2_FILTE(x) (((uint8_t)(((uint8_t)(x)) << LLWU_FILT2_FILTE_SHIFT)) & LLWU_FILT2_FILTE_MASK)
+#define LLWU_FILT2_FILTF_MASK (0x80U)
+#define LLWU_FILT2_FILTF_SHIFT (7U)
+#define LLWU_FILT2_FILTF(x) (((uint8_t)(((uint8_t)(x)) << LLWU_FILT2_FILTF_SHIFT)) & LLWU_FILT2_FILTF_MASK)
+
+
+/*!
+ * @}
+ */ /* end of group LLWU_Register_Masks */
+
+
+/* LLWU - Peripheral instance base addresses */
+/** Peripheral LLWU base address */
+#define LLWU_BASE (0x4007C000u)
+/** Peripheral LLWU base pointer */
+#define LLWU ((LLWU_Type *)LLWU_BASE)
+/** Array initializer of LLWU peripheral base addresses */
+#define LLWU_BASE_ADDRS { LLWU_BASE }
+/** Array initializer of LLWU peripheral base pointers */
+#define LLWU_BASE_PTRS { LLWU }
+/** Interrupt vectors for the LLWU peripheral type */
+#define LLWU_IRQS { LLWU_IRQn }
+
+/*!
+ * @}
+ */ /* end of group LLWU_Peripheral_Access_Layer */
+
+
+/* ----------------------------------------------------------------------------
+ -- LPTMR Peripheral Access Layer
+ ---------------------------------------------------------------------------- */
+
+/*!
+ * @addtogroup LPTMR_Peripheral_Access_Layer LPTMR Peripheral Access Layer
+ * @{
+ */
+
+/** LPTMR - Register Layout Typedef */
+typedef struct {
+ __IO uint32_t CSR; /**< Low Power Timer Control Status Register, offset: 0x0 */
+ __IO uint32_t PSR; /**< Low Power Timer Prescale Register, offset: 0x4 */
+ __IO uint32_t CMR; /**< Low Power Timer Compare Register, offset: 0x8 */
+ __IO uint32_t CNR; /**< Low Power Timer Counter Register, offset: 0xC */
+} LPTMR_Type;
+
+/* ----------------------------------------------------------------------------
+ -- LPTMR Register Masks
+ ---------------------------------------------------------------------------- */
+
+/*!
+ * @addtogroup LPTMR_Register_Masks LPTMR Register Masks
+ * @{
+ */
+
+/*! @name CSR - Low Power Timer Control Status Register */
+#define LPTMR_CSR_TEN_MASK (0x1U)
+#define LPTMR_CSR_TEN_SHIFT (0U)
+#define LPTMR_CSR_TEN(x) (((uint32_t)(((uint32_t)(x)) << LPTMR_CSR_TEN_SHIFT)) & LPTMR_CSR_TEN_MASK)
+#define LPTMR_CSR_TMS_MASK (0x2U)
+#define LPTMR_CSR_TMS_SHIFT (1U)
+#define LPTMR_CSR_TMS(x) (((uint32_t)(((uint32_t)(x)) << LPTMR_CSR_TMS_SHIFT)) & LPTMR_CSR_TMS_MASK)
+#define LPTMR_CSR_TFC_MASK (0x4U)
+#define LPTMR_CSR_TFC_SHIFT (2U)
+#define LPTMR_CSR_TFC(x) (((uint32_t)(((uint32_t)(x)) << LPTMR_CSR_TFC_SHIFT)) & LPTMR_CSR_TFC_MASK)
+#define LPTMR_CSR_TPP_MASK (0x8U)
+#define LPTMR_CSR_TPP_SHIFT (3U)
+#define LPTMR_CSR_TPP(x) (((uint32_t)(((uint32_t)(x)) << LPTMR_CSR_TPP_SHIFT)) & LPTMR_CSR_TPP_MASK)
+#define LPTMR_CSR_TPS_MASK (0x30U)
+#define LPTMR_CSR_TPS_SHIFT (4U)
+#define LPTMR_CSR_TPS(x) (((uint32_t)(((uint32_t)(x)) << LPTMR_CSR_TPS_SHIFT)) & LPTMR_CSR_TPS_MASK)
+#define LPTMR_CSR_TIE_MASK (0x40U)
+#define LPTMR_CSR_TIE_SHIFT (6U)
+#define LPTMR_CSR_TIE(x) (((uint32_t)(((uint32_t)(x)) << LPTMR_CSR_TIE_SHIFT)) & LPTMR_CSR_TIE_MASK)
+#define LPTMR_CSR_TCF_MASK (0x80U)
+#define LPTMR_CSR_TCF_SHIFT (7U)
+#define LPTMR_CSR_TCF(x) (((uint32_t)(((uint32_t)(x)) << LPTMR_CSR_TCF_SHIFT)) & LPTMR_CSR_TCF_MASK)
+
+/*! @name PSR - Low Power Timer Prescale Register */
+#define LPTMR_PSR_PCS_MASK (0x3U)
+#define LPTMR_PSR_PCS_SHIFT (0U)
+#define LPTMR_PSR_PCS(x) (((uint32_t)(((uint32_t)(x)) << LPTMR_PSR_PCS_SHIFT)) & LPTMR_PSR_PCS_MASK)
+#define LPTMR_PSR_PBYP_MASK (0x4U)
+#define LPTMR_PSR_PBYP_SHIFT (2U)
+#define LPTMR_PSR_PBYP(x) (((uint32_t)(((uint32_t)(x)) << LPTMR_PSR_PBYP_SHIFT)) & LPTMR_PSR_PBYP_MASK)
+#define LPTMR_PSR_PRESCALE_MASK (0x78U)
+#define LPTMR_PSR_PRESCALE_SHIFT (3U)
+#define LPTMR_PSR_PRESCALE(x) (((uint32_t)(((uint32_t)(x)) << LPTMR_PSR_PRESCALE_SHIFT)) & LPTMR_PSR_PRESCALE_MASK)
+
+/*! @name CMR - Low Power Timer Compare Register */
+#define LPTMR_CMR_COMPARE_MASK (0xFFFFU)
+#define LPTMR_CMR_COMPARE_SHIFT (0U)
+#define LPTMR_CMR_COMPARE(x) (((uint32_t)(((uint32_t)(x)) << LPTMR_CMR_COMPARE_SHIFT)) & LPTMR_CMR_COMPARE_MASK)
+
+/*! @name CNR - Low Power Timer Counter Register */
+#define LPTMR_CNR_COUNTER_MASK (0xFFFFU)
+#define LPTMR_CNR_COUNTER_SHIFT (0U)
+#define LPTMR_CNR_COUNTER(x) (((uint32_t)(((uint32_t)(x)) << LPTMR_CNR_COUNTER_SHIFT)) & LPTMR_CNR_COUNTER_MASK)
+
+
+/*!
+ * @}
+ */ /* end of group LPTMR_Register_Masks */
+
+
+/* LPTMR - Peripheral instance base addresses */
+/** Peripheral LPTMR0 base address */
+#define LPTMR0_BASE (0x40040000u)
+/** Peripheral LPTMR0 base pointer */
+#define LPTMR0 ((LPTMR_Type *)LPTMR0_BASE)
+/** Array initializer of LPTMR peripheral base addresses */
+#define LPTMR_BASE_ADDRS { LPTMR0_BASE }
+/** Array initializer of LPTMR peripheral base pointers */
+#define LPTMR_BASE_PTRS { LPTMR0 }
+/** Interrupt vectors for the LPTMR peripheral type */
+#define LPTMR_IRQS { LPTMR0_IRQn }
+
+/*!
+ * @}
+ */ /* end of group LPTMR_Peripheral_Access_Layer */
+
+
+/* ----------------------------------------------------------------------------
+ -- MCG Peripheral Access Layer
+ ---------------------------------------------------------------------------- */
+
+/*!
+ * @addtogroup MCG_Peripheral_Access_Layer MCG Peripheral Access Layer
+ * @{
+ */
+
+/** MCG - Register Layout Typedef */
+typedef struct {
+ __IO uint8_t C1; /**< MCG Control 1 Register, offset: 0x0 */
+ __IO uint8_t C2; /**< MCG Control 2 Register, offset: 0x1 */
+ __IO uint8_t C3; /**< MCG Control 3 Register, offset: 0x2 */
+ __IO uint8_t C4; /**< MCG Control 4 Register, offset: 0x3 */
+ uint8_t C5; /**< MCG Control 5 Register, offset: 0x4 */
+ __IO uint8_t C6; /**< MCG Control 6 Register, offset: 0x5 */
+ __I uint8_t S; /**< MCG Status Register, offset: 0x6 */
+ uint8_t RESERVED_0[1];
+ __IO uint8_t SC; /**< MCG Status and Control Register, offset: 0x8 */
+ uint8_t RESERVED_1[1];
+ __IO uint8_t ATCVH; /**< MCG Auto Trim Compare Value High Register, offset: 0xA */
+ __IO uint8_t ATCVL; /**< MCG Auto Trim Compare Value Low Register, offset: 0xB */
+ __IO uint8_t C7; /**< MCG Control 7 Register, offset: 0xC */
+ __IO uint8_t C8; /**< MCG Control 8 Register, offset: 0xD */
+} MCG_Type;
+
+/* ----------------------------------------------------------------------------
+ -- MCG Register Masks
+ ---------------------------------------------------------------------------- */
+
+/*!
+ * @addtogroup MCG_Register_Masks MCG Register Masks
+ * @{
+ */
+
+/*! @name C1 - MCG Control 1 Register */
+#define MCG_C1_IREFSTEN_MASK (0x1U)
+#define MCG_C1_IREFSTEN_SHIFT (0U)
+#define MCG_C1_IREFSTEN(x) (((uint8_t)(((uint8_t)(x)) << MCG_C1_IREFSTEN_SHIFT)) & MCG_C1_IREFSTEN_MASK)
+#define MCG_C1_IRCLKEN_MASK (0x2U)
+#define MCG_C1_IRCLKEN_SHIFT (1U)
+#define MCG_C1_IRCLKEN(x) (((uint8_t)(((uint8_t)(x)) << MCG_C1_IRCLKEN_SHIFT)) & MCG_C1_IRCLKEN_MASK)
+#define MCG_C1_IREFS_MASK (0x4U)
+#define MCG_C1_IREFS_SHIFT (2U)
+#define MCG_C1_IREFS(x) (((uint8_t)(((uint8_t)(x)) << MCG_C1_IREFS_SHIFT)) & MCG_C1_IREFS_MASK)
+#define MCG_C1_FRDIV_MASK (0x38U)
+#define MCG_C1_FRDIV_SHIFT (3U)
+#define MCG_C1_FRDIV(x) (((uint8_t)(((uint8_t)(x)) << MCG_C1_FRDIV_SHIFT)) & MCG_C1_FRDIV_MASK)
+#define MCG_C1_CLKS_MASK (0xC0U)
+#define MCG_C1_CLKS_SHIFT (6U)
+#define MCG_C1_CLKS(x) (((uint8_t)(((uint8_t)(x)) << MCG_C1_CLKS_SHIFT)) & MCG_C1_CLKS_MASK)
+
+/*! @name C2 - MCG Control 2 Register */
+#define MCG_C2_IRCS_MASK (0x1U)
+#define MCG_C2_IRCS_SHIFT (0U)
+#define MCG_C2_IRCS(x) (((uint8_t)(((uint8_t)(x)) << MCG_C2_IRCS_SHIFT)) & MCG_C2_IRCS_MASK)
+#define MCG_C2_LP_MASK (0x2U)
+#define MCG_C2_LP_SHIFT (1U)
+#define MCG_C2_LP(x) (((uint8_t)(((uint8_t)(x)) << MCG_C2_LP_SHIFT)) & MCG_C2_LP_MASK)
+#define MCG_C2_EREFS_MASK (0x4U)
+#define MCG_C2_EREFS_SHIFT (2U)
+#define MCG_C2_EREFS(x) (((uint8_t)(((uint8_t)(x)) << MCG_C2_EREFS_SHIFT)) & MCG_C2_EREFS_MASK)
+#define MCG_C2_HGO_MASK (0x8U)
+#define MCG_C2_HGO_SHIFT (3U)
+#define MCG_C2_HGO(x) (((uint8_t)(((uint8_t)(x)) << MCG_C2_HGO_SHIFT)) & MCG_C2_HGO_MASK)
+#define MCG_C2_RANGE_MASK (0x30U)
+#define MCG_C2_RANGE_SHIFT (4U)
+#define MCG_C2_RANGE(x) (((uint8_t)(((uint8_t)(x)) << MCG_C2_RANGE_SHIFT)) & MCG_C2_RANGE_MASK)
+#define MCG_C2_FCFTRIM_MASK (0x40U)
+#define MCG_C2_FCFTRIM_SHIFT (6U)
+#define MCG_C2_FCFTRIM(x) (((uint8_t)(((uint8_t)(x)) << MCG_C2_FCFTRIM_SHIFT)) & MCG_C2_FCFTRIM_MASK)
+#define MCG_C2_LOCRE0_MASK (0x80U)
+#define MCG_C2_LOCRE0_SHIFT (7U)
+#define MCG_C2_LOCRE0(x) (((uint8_t)(((uint8_t)(x)) << MCG_C2_LOCRE0_SHIFT)) & MCG_C2_LOCRE0_MASK)
+
+/*! @name C3 - MCG Control 3 Register */
+#define MCG_C3_SCTRIM_MASK (0xFFU)
+#define MCG_C3_SCTRIM_SHIFT (0U)
+#define MCG_C3_SCTRIM(x) (((uint8_t)(((uint8_t)(x)) << MCG_C3_SCTRIM_SHIFT)) & MCG_C3_SCTRIM_MASK)
+
+/*! @name C4 - MCG Control 4 Register */
+#define MCG_C4_SCFTRIM_MASK (0x1U)
+#define MCG_C4_SCFTRIM_SHIFT (0U)
+#define MCG_C4_SCFTRIM(x) (((uint8_t)(((uint8_t)(x)) << MCG_C4_SCFTRIM_SHIFT)) & MCG_C4_SCFTRIM_MASK)
+#define MCG_C4_FCTRIM_MASK (0x1EU)
+#define MCG_C4_FCTRIM_SHIFT (1U)
+#define MCG_C4_FCTRIM(x) (((uint8_t)(((uint8_t)(x)) << MCG_C4_FCTRIM_SHIFT)) & MCG_C4_FCTRIM_MASK)
+#define MCG_C4_DRST_DRS_MASK (0x60U)
+#define MCG_C4_DRST_DRS_SHIFT (5U)
+#define MCG_C4_DRST_DRS(x) (((uint8_t)(((uint8_t)(x)) << MCG_C4_DRST_DRS_SHIFT)) & MCG_C4_DRST_DRS_MASK)
+#define MCG_C4_DMX32_MASK (0x80U)
+#define MCG_C4_DMX32_SHIFT (7U)
+#define MCG_C4_DMX32(x) (((uint8_t)(((uint8_t)(x)) << MCG_C4_DMX32_SHIFT)) & MCG_C4_DMX32_MASK)
+
+/*! @name C6 - MCG Control 6 Register */
+#define MCG_C6_CME_MASK (0x20U)
+#define MCG_C6_CME_SHIFT (5U)
+#define MCG_C6_CME(x) (((uint8_t)(((uint8_t)(x)) << MCG_C6_CME_SHIFT)) & MCG_C6_CME_MASK)
+
+/*! @name S - MCG Status Register */
+#define MCG_S_IRCST_MASK (0x1U)
+#define MCG_S_IRCST_SHIFT (0U)
+#define MCG_S_IRCST(x) (((uint8_t)(((uint8_t)(x)) << MCG_S_IRCST_SHIFT)) & MCG_S_IRCST_MASK)
+#define MCG_S_OSCINIT0_MASK (0x2U)
+#define MCG_S_OSCINIT0_SHIFT (1U)
+#define MCG_S_OSCINIT0(x) (((uint8_t)(((uint8_t)(x)) << MCG_S_OSCINIT0_SHIFT)) & MCG_S_OSCINIT0_MASK)
+#define MCG_S_CLKST_MASK (0xCU)
+#define MCG_S_CLKST_SHIFT (2U)
+#define MCG_S_CLKST(x) (((uint8_t)(((uint8_t)(x)) << MCG_S_CLKST_SHIFT)) & MCG_S_CLKST_MASK)
+#define MCG_S_IREFST_MASK (0x10U)
+#define MCG_S_IREFST_SHIFT (4U)
+#define MCG_S_IREFST(x) (((uint8_t)(((uint8_t)(x)) << MCG_S_IREFST_SHIFT)) & MCG_S_IREFST_MASK)
+
+/*! @name SC - MCG Status and Control Register */
+#define MCG_SC_LOCS0_MASK (0x1U)
+#define MCG_SC_LOCS0_SHIFT (0U)
+#define MCG_SC_LOCS0(x) (((uint8_t)(((uint8_t)(x)) << MCG_SC_LOCS0_SHIFT)) & MCG_SC_LOCS0_MASK)
+#define MCG_SC_FCRDIV_MASK (0xEU)
+#define MCG_SC_FCRDIV_SHIFT (1U)
+#define MCG_SC_FCRDIV(x) (((uint8_t)(((uint8_t)(x)) << MCG_SC_FCRDIV_SHIFT)) & MCG_SC_FCRDIV_MASK)
+#define MCG_SC_FLTPRSRV_MASK (0x10U)
+#define MCG_SC_FLTPRSRV_SHIFT (4U)
+#define MCG_SC_FLTPRSRV(x) (((uint8_t)(((uint8_t)(x)) << MCG_SC_FLTPRSRV_SHIFT)) & MCG_SC_FLTPRSRV_MASK)
+#define MCG_SC_ATMF_MASK (0x20U)
+#define MCG_SC_ATMF_SHIFT (5U)
+#define MCG_SC_ATMF(x) (((uint8_t)(((uint8_t)(x)) << MCG_SC_ATMF_SHIFT)) & MCG_SC_ATMF_MASK)
+#define MCG_SC_ATMS_MASK (0x40U)
+#define MCG_SC_ATMS_SHIFT (6U)
+#define MCG_SC_ATMS(x) (((uint8_t)(((uint8_t)(x)) << MCG_SC_ATMS_SHIFT)) & MCG_SC_ATMS_MASK)
+#define MCG_SC_ATME_MASK (0x80U)
+#define MCG_SC_ATME_SHIFT (7U)
+#define MCG_SC_ATME(x) (((uint8_t)(((uint8_t)(x)) << MCG_SC_ATME_SHIFT)) & MCG_SC_ATME_MASK)
+
+/*! @name ATCVH - MCG Auto Trim Compare Value High Register */
+#define MCG_ATCVH_ATCVH_MASK (0xFFU)
+#define MCG_ATCVH_ATCVH_SHIFT (0U)
+#define MCG_ATCVH_ATCVH(x) (((uint8_t)(((uint8_t)(x)) << MCG_ATCVH_ATCVH_SHIFT)) & MCG_ATCVH_ATCVH_MASK)
+
+/*! @name ATCVL - MCG Auto Trim Compare Value Low Register */
+#define MCG_ATCVL_ATCVL_MASK (0xFFU)
+#define MCG_ATCVL_ATCVL_SHIFT (0U)
+#define MCG_ATCVL_ATCVL(x) (((uint8_t)(((uint8_t)(x)) << MCG_ATCVL_ATCVL_SHIFT)) & MCG_ATCVL_ATCVL_MASK)
+
+/*! @name C7 - MCG Control 7 Register */
+#define MCG_C7_OSCSEL_MASK (0x3U)
+#define MCG_C7_OSCSEL_SHIFT (0U)
+#define MCG_C7_OSCSEL(x) (((uint8_t)(((uint8_t)(x)) << MCG_C7_OSCSEL_SHIFT)) & MCG_C7_OSCSEL_MASK)
+
+/*! @name C8 - MCG Control 8 Register */
+#define MCG_C8_LOCS1_MASK (0x1U)
+#define MCG_C8_LOCS1_SHIFT (0U)
+#define MCG_C8_LOCS1(x) (((uint8_t)(((uint8_t)(x)) << MCG_C8_LOCS1_SHIFT)) & MCG_C8_LOCS1_MASK)
+#define MCG_C8_CME1_MASK (0x20U)
+#define MCG_C8_CME1_SHIFT (5U)
+#define MCG_C8_CME1(x) (((uint8_t)(((uint8_t)(x)) << MCG_C8_CME1_SHIFT)) & MCG_C8_CME1_MASK)
+#define MCG_C8_LOCRE1_MASK (0x80U)
+#define MCG_C8_LOCRE1_SHIFT (7U)
+#define MCG_C8_LOCRE1(x) (((uint8_t)(((uint8_t)(x)) << MCG_C8_LOCRE1_SHIFT)) & MCG_C8_LOCRE1_MASK)
+
+
+/*!
+ * @}
+ */ /* end of group MCG_Register_Masks */
+
+
+/* MCG - Peripheral instance base addresses */
+/** Peripheral MCG base address */
+#define MCG_BASE (0x40064000u)
+/** Peripheral MCG base pointer */
+#define MCG ((MCG_Type *)MCG_BASE)
+/** Array initializer of MCG peripheral base addresses */
+#define MCG_BASE_ADDRS { MCG_BASE }
+/** Array initializer of MCG peripheral base pointers */
+#define MCG_BASE_PTRS { MCG }
+
+/*!
+ * @}
+ */ /* end of group MCG_Peripheral_Access_Layer */
+
+
+/* ----------------------------------------------------------------------------
+ -- MCM Peripheral Access Layer
+ ---------------------------------------------------------------------------- */
+
+/*!
+ * @addtogroup MCM_Peripheral_Access_Layer MCM Peripheral Access Layer
+ * @{
+ */
+
+/** MCM - Register Layout Typedef */
+typedef struct {
+ uint8_t RESERVED_0[8];
+ __I uint16_t PLASC; /**< Crossbar Switch (AXBS) Slave Configuration, offset: 0x8 */
+ __I uint16_t PLAMC; /**< Crossbar Switch (AXBS) Master Configuration, offset: 0xA */
+ __IO uint32_t PLACR; /**< Crossbar Switch (AXBS) Control Register, offset: 0xC */
+ __IO uint32_t ISCR; /**< Interrupt Status and Control Register, offset: 0x10 */
+ uint8_t RESERVED_1[44];
+ __IO uint32_t CPO; /**< Compute Operation Control Register, offset: 0x40 */
+} MCM_Type;
+
+/* ----------------------------------------------------------------------------
+ -- MCM Register Masks
+ ---------------------------------------------------------------------------- */
+
+/*!
+ * @addtogroup MCM_Register_Masks MCM Register Masks
+ * @{
+ */
+
+/*! @name PLASC - Crossbar Switch (AXBS) Slave Configuration */
+#define MCM_PLASC_ASC_MASK (0xFFU)
+#define MCM_PLASC_ASC_SHIFT (0U)
+#define MCM_PLASC_ASC(x) (((uint16_t)(((uint16_t)(x)) << MCM_PLASC_ASC_SHIFT)) & MCM_PLASC_ASC_MASK)
+
+/*! @name PLAMC - Crossbar Switch (AXBS) Master Configuration */
+#define MCM_PLAMC_AMC_MASK (0xFFU)
+#define MCM_PLAMC_AMC_SHIFT (0U)
+#define MCM_PLAMC_AMC(x) (((uint16_t)(((uint16_t)(x)) << MCM_PLAMC_AMC_SHIFT)) & MCM_PLAMC_AMC_MASK)
+
+/*! @name PLACR - Crossbar Switch (AXBS) Control Register */
+#define MCM_PLACR_ARB_MASK (0x200U)
+#define MCM_PLACR_ARB_SHIFT (9U)
+#define MCM_PLACR_ARB(x) (((uint32_t)(((uint32_t)(x)) << MCM_PLACR_ARB_SHIFT)) & MCM_PLACR_ARB_MASK)
+
+/*! @name ISCR - Interrupt Status and Control Register */
+#define MCM_ISCR_FIOC_MASK (0x100U)
+#define MCM_ISCR_FIOC_SHIFT (8U)
+#define MCM_ISCR_FIOC(x) (((uint32_t)(((uint32_t)(x)) << MCM_ISCR_FIOC_SHIFT)) & MCM_ISCR_FIOC_MASK)
+#define MCM_ISCR_FDZC_MASK (0x200U)
+#define MCM_ISCR_FDZC_SHIFT (9U)
+#define MCM_ISCR_FDZC(x) (((uint32_t)(((uint32_t)(x)) << MCM_ISCR_FDZC_SHIFT)) & MCM_ISCR_FDZC_MASK)
+#define MCM_ISCR_FOFC_MASK (0x400U)
+#define MCM_ISCR_FOFC_SHIFT (10U)
+#define MCM_ISCR_FOFC(x) (((uint32_t)(((uint32_t)(x)) << MCM_ISCR_FOFC_SHIFT)) & MCM_ISCR_FOFC_MASK)
+#define MCM_ISCR_FUFC_MASK (0x800U)
+#define MCM_ISCR_FUFC_SHIFT (11U)
+#define MCM_ISCR_FUFC(x) (((uint32_t)(((uint32_t)(x)) << MCM_ISCR_FUFC_SHIFT)) & MCM_ISCR_FUFC_MASK)
+#define MCM_ISCR_FIXC_MASK (0x1000U)
+#define MCM_ISCR_FIXC_SHIFT (12U)
+#define MCM_ISCR_FIXC(x) (((uint32_t)(((uint32_t)(x)) << MCM_ISCR_FIXC_SHIFT)) & MCM_ISCR_FIXC_MASK)
+#define MCM_ISCR_FIDC_MASK (0x8000U)
+#define MCM_ISCR_FIDC_SHIFT (15U)
+#define MCM_ISCR_FIDC(x) (((uint32_t)(((uint32_t)(x)) << MCM_ISCR_FIDC_SHIFT)) & MCM_ISCR_FIDC_MASK)
+#define MCM_ISCR_FIOCE_MASK (0x1000000U)
+#define MCM_ISCR_FIOCE_SHIFT (24U)
+#define MCM_ISCR_FIOCE(x) (((uint32_t)(((uint32_t)(x)) << MCM_ISCR_FIOCE_SHIFT)) & MCM_ISCR_FIOCE_MASK)
+#define MCM_ISCR_FDZCE_MASK (0x2000000U)
+#define MCM_ISCR_FDZCE_SHIFT (25U)
+#define MCM_ISCR_FDZCE(x) (((uint32_t)(((uint32_t)(x)) << MCM_ISCR_FDZCE_SHIFT)) & MCM_ISCR_FDZCE_MASK)
+#define MCM_ISCR_FOFCE_MASK (0x4000000U)
+#define MCM_ISCR_FOFCE_SHIFT (26U)
+#define MCM_ISCR_FOFCE(x) (((uint32_t)(((uint32_t)(x)) << MCM_ISCR_FOFCE_SHIFT)) & MCM_ISCR_FOFCE_MASK)
+#define MCM_ISCR_FUFCE_MASK (0x8000000U)
+#define MCM_ISCR_FUFCE_SHIFT (27U)
+#define MCM_ISCR_FUFCE(x) (((uint32_t)(((uint32_t)(x)) << MCM_ISCR_FUFCE_SHIFT)) & MCM_ISCR_FUFCE_MASK)
+#define MCM_ISCR_FIXCE_MASK (0x10000000U)
+#define MCM_ISCR_FIXCE_SHIFT (28U)
+#define MCM_ISCR_FIXCE(x) (((uint32_t)(((uint32_t)(x)) << MCM_ISCR_FIXCE_SHIFT)) & MCM_ISCR_FIXCE_MASK)
+#define MCM_ISCR_FIDCE_MASK (0x80000000U)
+#define MCM_ISCR_FIDCE_SHIFT (31U)
+#define MCM_ISCR_FIDCE(x) (((uint32_t)(((uint32_t)(x)) << MCM_ISCR_FIDCE_SHIFT)) & MCM_ISCR_FIDCE_MASK)
+
+/*! @name CPO - Compute Operation Control Register */
+#define MCM_CPO_CPOREQ_MASK (0x1U)
+#define MCM_CPO_CPOREQ_SHIFT (0U)
+#define MCM_CPO_CPOREQ(x) (((uint32_t)(((uint32_t)(x)) << MCM_CPO_CPOREQ_SHIFT)) & MCM_CPO_CPOREQ_MASK)
+#define MCM_CPO_CPOACK_MASK (0x2U)
+#define MCM_CPO_CPOACK_SHIFT (1U)
+#define MCM_CPO_CPOACK(x) (((uint32_t)(((uint32_t)(x)) << MCM_CPO_CPOACK_SHIFT)) & MCM_CPO_CPOACK_MASK)
+#define MCM_CPO_CPOWOI_MASK (0x4U)
+#define MCM_CPO_CPOWOI_SHIFT (2U)
+#define MCM_CPO_CPOWOI(x) (((uint32_t)(((uint32_t)(x)) << MCM_CPO_CPOWOI_SHIFT)) & MCM_CPO_CPOWOI_MASK)
+
+
+/*!
+ * @}
+ */ /* end of group MCM_Register_Masks */
+
+
+/* MCM - Peripheral instance base addresses */
+/** Peripheral MCM base address */
+#define MCM_BASE (0xE0080000u)
+/** Peripheral MCM base pointer */
+#define MCM ((MCM_Type *)MCM_BASE)
+/** Array initializer of MCM peripheral base addresses */
+#define MCM_BASE_ADDRS { MCM_BASE }
+/** Array initializer of MCM peripheral base pointers */
+#define MCM_BASE_PTRS { MCM }
+/** Interrupt vectors for the MCM peripheral type */
+#define MCM_IRQS { MCM_IRQn }
+
+/*!
+ * @}
+ */ /* end of group MCM_Peripheral_Access_Layer */
+
+
+/* ----------------------------------------------------------------------------
+ -- NV Peripheral Access Layer
+ ---------------------------------------------------------------------------- */
+
+/*!
+ * @addtogroup NV_Peripheral_Access_Layer NV Peripheral Access Layer
+ * @{
+ */
+
+/** NV - Register Layout Typedef */
+typedef struct {
+ __I uint8_t BACKKEY3; /**< Backdoor Comparison Key 3., offset: 0x0 */
+ __I uint8_t BACKKEY2; /**< Backdoor Comparison Key 2., offset: 0x1 */
+ __I uint8_t BACKKEY1; /**< Backdoor Comparison Key 1., offset: 0x2 */
+ __I uint8_t BACKKEY0; /**< Backdoor Comparison Key 0., offset: 0x3 */
+ __I uint8_t BACKKEY7; /**< Backdoor Comparison Key 7., offset: 0x4 */
+ __I uint8_t BACKKEY6; /**< Backdoor Comparison Key 6., offset: 0x5 */
+ __I uint8_t BACKKEY5; /**< Backdoor Comparison Key 5., offset: 0x6 */
+ __I uint8_t BACKKEY4; /**< Backdoor Comparison Key 4., offset: 0x7 */
+ __I uint8_t FPROT3; /**< Non-volatile P-Flash Protection 1 - Low Register, offset: 0x8 */
+ __I uint8_t FPROT2; /**< Non-volatile P-Flash Protection 1 - High Register, offset: 0x9 */
+ __I uint8_t FPROT1; /**< Non-volatile P-Flash Protection 0 - Low Register, offset: 0xA */
+ __I uint8_t FPROT0; /**< Non-volatile P-Flash Protection 0 - High Register, offset: 0xB */
+ __I uint8_t FSEC; /**< Non-volatile Flash Security Register, offset: 0xC */
+ __I uint8_t FOPT; /**< Non-volatile Flash Option Register, offset: 0xD */
+} NV_Type;
+
+/* ----------------------------------------------------------------------------
+ -- NV Register Masks
+ ---------------------------------------------------------------------------- */
+
+/*!
+ * @addtogroup NV_Register_Masks NV Register Masks
+ * @{
+ */
+
+/*! @name BACKKEY3 - Backdoor Comparison Key 3. */
+#define NV_BACKKEY3_KEY_MASK (0xFFU)
+#define NV_BACKKEY3_KEY_SHIFT (0U)
+#define NV_BACKKEY3_KEY(x) (((uint8_t)(((uint8_t)(x)) << NV_BACKKEY3_KEY_SHIFT)) & NV_BACKKEY3_KEY_MASK)
+
+/*! @name BACKKEY2 - Backdoor Comparison Key 2. */
+#define NV_BACKKEY2_KEY_MASK (0xFFU)
+#define NV_BACKKEY2_KEY_SHIFT (0U)
+#define NV_BACKKEY2_KEY(x) (((uint8_t)(((uint8_t)(x)) << NV_BACKKEY2_KEY_SHIFT)) & NV_BACKKEY2_KEY_MASK)
+
+/*! @name BACKKEY1 - Backdoor Comparison Key 1. */
+#define NV_BACKKEY1_KEY_MASK (0xFFU)
+#define NV_BACKKEY1_KEY_SHIFT (0U)
+#define NV_BACKKEY1_KEY(x) (((uint8_t)(((uint8_t)(x)) << NV_BACKKEY1_KEY_SHIFT)) & NV_BACKKEY1_KEY_MASK)
+
+/*! @name BACKKEY0 - Backdoor Comparison Key 0. */
+#define NV_BACKKEY0_KEY_MASK (0xFFU)
+#define NV_BACKKEY0_KEY_SHIFT (0U)
+#define NV_BACKKEY0_KEY(x) (((uint8_t)(((uint8_t)(x)) << NV_BACKKEY0_KEY_SHIFT)) & NV_BACKKEY0_KEY_MASK)
+
+/*! @name BACKKEY7 - Backdoor Comparison Key 7. */
+#define NV_BACKKEY7_KEY_MASK (0xFFU)
+#define NV_BACKKEY7_KEY_SHIFT (0U)
+#define NV_BACKKEY7_KEY(x) (((uint8_t)(((uint8_t)(x)) << NV_BACKKEY7_KEY_SHIFT)) & NV_BACKKEY7_KEY_MASK)
+
+/*! @name BACKKEY6 - Backdoor Comparison Key 6. */
+#define NV_BACKKEY6_KEY_MASK (0xFFU)
+#define NV_BACKKEY6_KEY_SHIFT (0U)
+#define NV_BACKKEY6_KEY(x) (((uint8_t)(((uint8_t)(x)) << NV_BACKKEY6_KEY_SHIFT)) & NV_BACKKEY6_KEY_MASK)
+
+/*! @name BACKKEY5 - Backdoor Comparison Key 5. */
+#define NV_BACKKEY5_KEY_MASK (0xFFU)
+#define NV_BACKKEY5_KEY_SHIFT (0U)
+#define NV_BACKKEY5_KEY(x) (((uint8_t)(((uint8_t)(x)) << NV_BACKKEY5_KEY_SHIFT)) & NV_BACKKEY5_KEY_MASK)
+
+/*! @name BACKKEY4 - Backdoor Comparison Key 4. */
+#define NV_BACKKEY4_KEY_MASK (0xFFU)
+#define NV_BACKKEY4_KEY_SHIFT (0U)
+#define NV_BACKKEY4_KEY(x) (((uint8_t)(((uint8_t)(x)) << NV_BACKKEY4_KEY_SHIFT)) & NV_BACKKEY4_KEY_MASK)
+
+/*! @name FPROT3 - Non-volatile P-Flash Protection 1 - Low Register */
+#define NV_FPROT3_PROT_MASK (0xFFU)
+#define NV_FPROT3_PROT_SHIFT (0U)
+#define NV_FPROT3_PROT(x) (((uint8_t)(((uint8_t)(x)) << NV_FPROT3_PROT_SHIFT)) & NV_FPROT3_PROT_MASK)
+
+/*! @name FPROT2 - Non-volatile P-Flash Protection 1 - High Register */
+#define NV_FPROT2_PROT_MASK (0xFFU)
+#define NV_FPROT2_PROT_SHIFT (0U)
+#define NV_FPROT2_PROT(x) (((uint8_t)(((uint8_t)(x)) << NV_FPROT2_PROT_SHIFT)) & NV_FPROT2_PROT_MASK)
+
+/*! @name FPROT1 - Non-volatile P-Flash Protection 0 - Low Register */
+#define NV_FPROT1_PROT_MASK (0xFFU)
+#define NV_FPROT1_PROT_SHIFT (0U)
+#define NV_FPROT1_PROT(x) (((uint8_t)(((uint8_t)(x)) << NV_FPROT1_PROT_SHIFT)) & NV_FPROT1_PROT_MASK)
+
+/*! @name FPROT0 - Non-volatile P-Flash Protection 0 - High Register */
+#define NV_FPROT0_PROT_MASK (0xFFU)
+#define NV_FPROT0_PROT_SHIFT (0U)
+#define NV_FPROT0_PROT(x) (((uint8_t)(((uint8_t)(x)) << NV_FPROT0_PROT_SHIFT)) & NV_FPROT0_PROT_MASK)
+
+/*! @name FSEC - Non-volatile Flash Security Register */
+#define NV_FSEC_SEC_MASK (0x3U)
+#define NV_FSEC_SEC_SHIFT (0U)
+#define NV_FSEC_SEC(x) (((uint8_t)(((uint8_t)(x)) << NV_FSEC_SEC_SHIFT)) & NV_FSEC_SEC_MASK)
+#define NV_FSEC_FSLACC_MASK (0xCU)
+#define NV_FSEC_FSLACC_SHIFT (2U)
+#define NV_FSEC_FSLACC(x) (((uint8_t)(((uint8_t)(x)) << NV_FSEC_FSLACC_SHIFT)) & NV_FSEC_FSLACC_MASK)
+#define NV_FSEC_MEEN_MASK (0x30U)
+#define NV_FSEC_MEEN_SHIFT (4U)
+#define NV_FSEC_MEEN(x) (((uint8_t)(((uint8_t)(x)) << NV_FSEC_MEEN_SHIFT)) & NV_FSEC_MEEN_MASK)
+#define NV_FSEC_KEYEN_MASK (0xC0U)
+#define NV_FSEC_KEYEN_SHIFT (6U)
+#define NV_FSEC_KEYEN(x) (((uint8_t)(((uint8_t)(x)) << NV_FSEC_KEYEN_SHIFT)) & NV_FSEC_KEYEN_MASK)
+
+/*! @name FOPT - Non-volatile Flash Option Register */
+#define NV_FOPT_LPBOOT_MASK (0x1U)
+#define NV_FOPT_LPBOOT_SHIFT (0U)
+#define NV_FOPT_LPBOOT(x) (((uint8_t)(((uint8_t)(x)) << NV_FOPT_LPBOOT_SHIFT)) & NV_FOPT_LPBOOT_MASK)
+#define NV_FOPT_EZPORT_DIS_MASK (0x2U)
+#define NV_FOPT_EZPORT_DIS_SHIFT (1U)
+#define NV_FOPT_EZPORT_DIS(x) (((uint8_t)(((uint8_t)(x)) << NV_FOPT_EZPORT_DIS_SHIFT)) & NV_FOPT_EZPORT_DIS_MASK)
+#define NV_FOPT_NMI_DIS_MASK (0x4U)
+#define NV_FOPT_NMI_DIS_SHIFT (2U)
+#define NV_FOPT_NMI_DIS(x) (((uint8_t)(((uint8_t)(x)) << NV_FOPT_NMI_DIS_SHIFT)) & NV_FOPT_NMI_DIS_MASK)
+#define NV_FOPT_FAST_INIT_MASK (0x20U)
+#define NV_FOPT_FAST_INIT_SHIFT (5U)
+#define NV_FOPT_FAST_INIT(x) (((uint8_t)(((uint8_t)(x)) << NV_FOPT_FAST_INIT_SHIFT)) & NV_FOPT_FAST_INIT_MASK)
+
+
+/*!
+ * @}
+ */ /* end of group NV_Register_Masks */
+
+
+/* NV - Peripheral instance base addresses */
+/** Peripheral FTFA_FlashConfig base address */
+#define FTFA_FlashConfig_BASE (0x400u)
+/** Peripheral FTFA_FlashConfig base pointer */
+#define FTFA_FlashConfig ((NV_Type *)FTFA_FlashConfig_BASE)
+/** Array initializer of NV peripheral base addresses */
+#define NV_BASE_ADDRS { FTFA_FlashConfig_BASE }
+/** Array initializer of NV peripheral base pointers */
+#define NV_BASE_PTRS { FTFA_FlashConfig }
+
+/*!
+ * @}
+ */ /* end of group NV_Peripheral_Access_Layer */
+
+
+/* ----------------------------------------------------------------------------
+ -- OSC Peripheral Access Layer
+ ---------------------------------------------------------------------------- */
+
+/*!
+ * @addtogroup OSC_Peripheral_Access_Layer OSC Peripheral Access Layer
+ * @{
+ */
+
+/** OSC - Register Layout Typedef */
+typedef struct {
+ __IO uint8_t CR; /**< OSC Control Register, offset: 0x0 */
+ uint8_t RESERVED_0[1];
+ __IO uint8_t DIV; /**< OSC_DIV, offset: 0x2 */
+} OSC_Type;
+
+/* ----------------------------------------------------------------------------
+ -- OSC Register Masks
+ ---------------------------------------------------------------------------- */
+
+/*!
+ * @addtogroup OSC_Register_Masks OSC Register Masks
+ * @{
+ */
+
+/*! @name CR - OSC Control Register */
+#define OSC_CR_SC16P_MASK (0x1U)
+#define OSC_CR_SC16P_SHIFT (0U)
+#define OSC_CR_SC16P(x) (((uint8_t)(((uint8_t)(x)) << OSC_CR_SC16P_SHIFT)) & OSC_CR_SC16P_MASK)
+#define OSC_CR_SC8P_MASK (0x2U)
+#define OSC_CR_SC8P_SHIFT (1U)
+#define OSC_CR_SC8P(x) (((uint8_t)(((uint8_t)(x)) << OSC_CR_SC8P_SHIFT)) & OSC_CR_SC8P_MASK)
+#define OSC_CR_SC4P_MASK (0x4U)
+#define OSC_CR_SC4P_SHIFT (2U)
+#define OSC_CR_SC4P(x) (((uint8_t)(((uint8_t)(x)) << OSC_CR_SC4P_SHIFT)) & OSC_CR_SC4P_MASK)
+#define OSC_CR_SC2P_MASK (0x8U)
+#define OSC_CR_SC2P_SHIFT (3U)
+#define OSC_CR_SC2P(x) (((uint8_t)(((uint8_t)(x)) << OSC_CR_SC2P_SHIFT)) & OSC_CR_SC2P_MASK)
+#define OSC_CR_EREFSTEN_MASK (0x20U)
+#define OSC_CR_EREFSTEN_SHIFT (5U)
+#define OSC_CR_EREFSTEN(x) (((uint8_t)(((uint8_t)(x)) << OSC_CR_EREFSTEN_SHIFT)) & OSC_CR_EREFSTEN_MASK)
+#define OSC_CR_ERCLKEN_MASK (0x80U)
+#define OSC_CR_ERCLKEN_SHIFT (7U)
+#define OSC_CR_ERCLKEN(x) (((uint8_t)(((uint8_t)(x)) << OSC_CR_ERCLKEN_SHIFT)) & OSC_CR_ERCLKEN_MASK)
+
+/*! @name DIV - OSC_DIV */
+#define OSC_DIV_ERPS_MASK (0xC0U)
+#define OSC_DIV_ERPS_SHIFT (6U)
+#define OSC_DIV_ERPS(x) (((uint8_t)(((uint8_t)(x)) << OSC_DIV_ERPS_SHIFT)) & OSC_DIV_ERPS_MASK)
+
+
+/*!
+ * @}
+ */ /* end of group OSC_Register_Masks */
+
+
+/* OSC - Peripheral instance base addresses */
+/** Peripheral OSC base address */
+#define OSC_BASE (0x40065000u)
+/** Peripheral OSC base pointer */
+#define OSC ((OSC_Type *)OSC_BASE)
+/** Array initializer of OSC peripheral base addresses */
+#define OSC_BASE_ADDRS { OSC_BASE }
+/** Array initializer of OSC peripheral base pointers */
+#define OSC_BASE_PTRS { OSC }
+
+/*!
+ * @}
+ */ /* end of group OSC_Peripheral_Access_Layer */
+
+
+/* ----------------------------------------------------------------------------
+ -- PDB Peripheral Access Layer
+ ---------------------------------------------------------------------------- */
+
+/*!
+ * @addtogroup PDB_Peripheral_Access_Layer PDB Peripheral Access Layer
+ * @{
+ */
+
+/** PDB - Register Layout Typedef */
+typedef struct {
+ __IO uint32_t SC; /**< Status and Control register, offset: 0x0 */
+ __IO uint32_t MOD; /**< Modulus register, offset: 0x4 */
+ __I uint32_t CNT; /**< Counter register, offset: 0x8 */
+ __IO uint32_t IDLY; /**< Interrupt Delay register, offset: 0xC */
+ struct { /* offset: 0x10, array step: 0x28 */
+ __IO uint32_t C1; /**< Channel n Control register 1, array offset: 0x10, array step: 0x28 */
+ __IO uint32_t S; /**< Channel n Status register, array offset: 0x14, array step: 0x28 */
+ __IO uint32_t DLY[2]; /**< Channel n Delay 0 register..Channel n Delay 1 register, array offset: 0x18, array step: index*0x28, index2*0x4 */
+ uint8_t RESERVED_0[24];
+ } CH[2];
+ uint8_t RESERVED_0[240];
+ struct { /* offset: 0x150, array step: 0x8 */
+ __IO uint32_t INTC; /**< DAC Interval Trigger n Control register, array offset: 0x150, array step: 0x8 */
+ __IO uint32_t INT; /**< DAC Interval n register, array offset: 0x154, array step: 0x8 */
+ } DAC[1];
+ uint8_t RESERVED_1[56];
+ __IO uint32_t POEN; /**< Pulse-Out n Enable register, offset: 0x190 */
+ __IO uint32_t PODLY[2]; /**< Pulse-Out n Delay register, array offset: 0x194, array step: 0x4 */
+} PDB_Type;
+
+/* ----------------------------------------------------------------------------
+ -- PDB Register Masks
+ ---------------------------------------------------------------------------- */
+
+/*!
+ * @addtogroup PDB_Register_Masks PDB Register Masks
+ * @{
+ */
+
+/*! @name SC - Status and Control register */
+#define PDB_SC_LDOK_MASK (0x1U)
+#define PDB_SC_LDOK_SHIFT (0U)
+#define PDB_SC_LDOK(x) (((uint32_t)(((uint32_t)(x)) << PDB_SC_LDOK_SHIFT)) & PDB_SC_LDOK_MASK)
+#define PDB_SC_CONT_MASK (0x2U)
+#define PDB_SC_CONT_SHIFT (1U)
+#define PDB_SC_CONT(x) (((uint32_t)(((uint32_t)(x)) << PDB_SC_CONT_SHIFT)) & PDB_SC_CONT_MASK)
+#define PDB_SC_MULT_MASK (0xCU)
+#define PDB_SC_MULT_SHIFT (2U)
+#define PDB_SC_MULT(x) (((uint32_t)(((uint32_t)(x)) << PDB_SC_MULT_SHIFT)) & PDB_SC_MULT_MASK)
+#define PDB_SC_PDBIE_MASK (0x20U)
+#define PDB_SC_PDBIE_SHIFT (5U)
+#define PDB_SC_PDBIE(x) (((uint32_t)(((uint32_t)(x)) << PDB_SC_PDBIE_SHIFT)) & PDB_SC_PDBIE_MASK)
+#define PDB_SC_PDBIF_MASK (0x40U)
+#define PDB_SC_PDBIF_SHIFT (6U)
+#define PDB_SC_PDBIF(x) (((uint32_t)(((uint32_t)(x)) << PDB_SC_PDBIF_SHIFT)) & PDB_SC_PDBIF_MASK)
+#define PDB_SC_PDBEN_MASK (0x80U)
+#define PDB_SC_PDBEN_SHIFT (7U)
+#define PDB_SC_PDBEN(x) (((uint32_t)(((uint32_t)(x)) << PDB_SC_PDBEN_SHIFT)) & PDB_SC_PDBEN_MASK)
+#define PDB_SC_TRGSEL_MASK (0xF00U)
+#define PDB_SC_TRGSEL_SHIFT (8U)
+#define PDB_SC_TRGSEL(x) (((uint32_t)(((uint32_t)(x)) << PDB_SC_TRGSEL_SHIFT)) & PDB_SC_TRGSEL_MASK)
+#define PDB_SC_PRESCALER_MASK (0x7000U)
+#define PDB_SC_PRESCALER_SHIFT (12U)
+#define PDB_SC_PRESCALER(x) (((uint32_t)(((uint32_t)(x)) << PDB_SC_PRESCALER_SHIFT)) & PDB_SC_PRESCALER_MASK)
+#define PDB_SC_DMAEN_MASK (0x8000U)
+#define PDB_SC_DMAEN_SHIFT (15U)
+#define PDB_SC_DMAEN(x) (((uint32_t)(((uint32_t)(x)) << PDB_SC_DMAEN_SHIFT)) & PDB_SC_DMAEN_MASK)
+#define PDB_SC_SWTRIG_MASK (0x10000U)
+#define PDB_SC_SWTRIG_SHIFT (16U)
+#define PDB_SC_SWTRIG(x) (((uint32_t)(((uint32_t)(x)) << PDB_SC_SWTRIG_SHIFT)) & PDB_SC_SWTRIG_MASK)
+#define PDB_SC_PDBEIE_MASK (0x20000U)
+#define PDB_SC_PDBEIE_SHIFT (17U)
+#define PDB_SC_PDBEIE(x) (((uint32_t)(((uint32_t)(x)) << PDB_SC_PDBEIE_SHIFT)) & PDB_SC_PDBEIE_MASK)
+#define PDB_SC_LDMOD_MASK (0xC0000U)
+#define PDB_SC_LDMOD_SHIFT (18U)
+#define PDB_SC_LDMOD(x) (((uint32_t)(((uint32_t)(x)) << PDB_SC_LDMOD_SHIFT)) & PDB_SC_LDMOD_MASK)
+
+/*! @name MOD - Modulus register */
+#define PDB_MOD_MOD_MASK (0xFFFFU)
+#define PDB_MOD_MOD_SHIFT (0U)
+#define PDB_MOD_MOD(x) (((uint32_t)(((uint32_t)(x)) << PDB_MOD_MOD_SHIFT)) & PDB_MOD_MOD_MASK)
+
+/*! @name CNT - Counter register */
+#define PDB_CNT_CNT_MASK (0xFFFFU)
+#define PDB_CNT_CNT_SHIFT (0U)
+#define PDB_CNT_CNT(x) (((uint32_t)(((uint32_t)(x)) << PDB_CNT_CNT_SHIFT)) & PDB_CNT_CNT_MASK)
+
+/*! @name IDLY - Interrupt Delay register */
+#define PDB_IDLY_IDLY_MASK (0xFFFFU)
+#define PDB_IDLY_IDLY_SHIFT (0U)
+#define PDB_IDLY_IDLY(x) (((uint32_t)(((uint32_t)(x)) << PDB_IDLY_IDLY_SHIFT)) & PDB_IDLY_IDLY_MASK)
+
+/*! @name C1 - Channel n Control register 1 */
+#define PDB_C1_EN_MASK (0xFFU)
+#define PDB_C1_EN_SHIFT (0U)
+#define PDB_C1_EN(x) (((uint32_t)(((uint32_t)(x)) << PDB_C1_EN_SHIFT)) & PDB_C1_EN_MASK)
+#define PDB_C1_TOS_MASK (0xFF00U)
+#define PDB_C1_TOS_SHIFT (8U)
+#define PDB_C1_TOS(x) (((uint32_t)(((uint32_t)(x)) << PDB_C1_TOS_SHIFT)) & PDB_C1_TOS_MASK)
+#define PDB_C1_BB_MASK (0xFF0000U)
+#define PDB_C1_BB_SHIFT (16U)
+#define PDB_C1_BB(x) (((uint32_t)(((uint32_t)(x)) << PDB_C1_BB_SHIFT)) & PDB_C1_BB_MASK)
+
+/* The count of PDB_C1 */
+#define PDB_C1_COUNT (2U)
+
+/*! @name S - Channel n Status register */
+#define PDB_S_ERR_MASK (0xFFU)
+#define PDB_S_ERR_SHIFT (0U)
+#define PDB_S_ERR(x) (((uint32_t)(((uint32_t)(x)) << PDB_S_ERR_SHIFT)) & PDB_S_ERR_MASK)
+#define PDB_S_CF_MASK (0xFF0000U)
+#define PDB_S_CF_SHIFT (16U)
+#define PDB_S_CF(x) (((uint32_t)(((uint32_t)(x)) << PDB_S_CF_SHIFT)) & PDB_S_CF_MASK)
+
+/* The count of PDB_S */
+#define PDB_S_COUNT (2U)
+
+/*! @name DLY - Channel n Delay 0 register..Channel n Delay 1 register */
+#define PDB_DLY_DLY_MASK (0xFFFFU)
+#define PDB_DLY_DLY_SHIFT (0U)
+#define PDB_DLY_DLY(x) (((uint32_t)(((uint32_t)(x)) << PDB_DLY_DLY_SHIFT)) & PDB_DLY_DLY_MASK)
+
+/* The count of PDB_DLY */
+#define PDB_DLY_COUNT (2U)
+
+/* The count of PDB_DLY */
+#define PDB_DLY_COUNT2 (2U)
+
+/*! @name INTC - DAC Interval Trigger n Control register */
+#define PDB_INTC_TOE_MASK (0x1U)
+#define PDB_INTC_TOE_SHIFT (0U)
+#define PDB_INTC_TOE(x) (((uint32_t)(((uint32_t)(x)) << PDB_INTC_TOE_SHIFT)) & PDB_INTC_TOE_MASK)
+#define PDB_INTC_EXT_MASK (0x2U)
+#define PDB_INTC_EXT_SHIFT (1U)
+#define PDB_INTC_EXT(x) (((uint32_t)(((uint32_t)(x)) << PDB_INTC_EXT_SHIFT)) & PDB_INTC_EXT_MASK)
+
+/* The count of PDB_INTC */
+#define PDB_INTC_COUNT (1U)
+
+/*! @name INT - DAC Interval n register */
+#define PDB_INT_INT_MASK (0xFFFFU)
+#define PDB_INT_INT_SHIFT (0U)
+#define PDB_INT_INT(x) (((uint32_t)(((uint32_t)(x)) << PDB_INT_INT_SHIFT)) & PDB_INT_INT_MASK)
+
+/* The count of PDB_INT */
+#define PDB_INT_COUNT (1U)
+
+/*! @name POEN - Pulse-Out n Enable register */
+#define PDB_POEN_POEN_MASK (0xFFU)
+#define PDB_POEN_POEN_SHIFT (0U)
+#define PDB_POEN_POEN(x) (((uint32_t)(((uint32_t)(x)) << PDB_POEN_POEN_SHIFT)) & PDB_POEN_POEN_MASK)
+
+/*! @name PODLY - Pulse-Out n Delay register */
+#define PDB_PODLY_DLY2_MASK (0xFFFFU)
+#define PDB_PODLY_DLY2_SHIFT (0U)
+#define PDB_PODLY_DLY2(x) (((uint32_t)(((uint32_t)(x)) << PDB_PODLY_DLY2_SHIFT)) & PDB_PODLY_DLY2_MASK)
+#define PDB_PODLY_DLY1_MASK (0xFFFF0000U)
+#define PDB_PODLY_DLY1_SHIFT (16U)
+#define PDB_PODLY_DLY1(x) (((uint32_t)(((uint32_t)(x)) << PDB_PODLY_DLY1_SHIFT)) & PDB_PODLY_DLY1_MASK)
+
+/* The count of PDB_PODLY */
+#define PDB_PODLY_COUNT (2U)
+
+
+/*!
+ * @}
+ */ /* end of group PDB_Register_Masks */
+
+
+/* PDB - Peripheral instance base addresses */
+/** Peripheral PDB0 base address */
+#define PDB0_BASE (0x40036000u)
+/** Peripheral PDB0 base pointer */
+#define PDB0 ((PDB_Type *)PDB0_BASE)
+/** Array initializer of PDB peripheral base addresses */
+#define PDB_BASE_ADDRS { PDB0_BASE }
+/** Array initializer of PDB peripheral base pointers */
+#define PDB_BASE_PTRS { PDB0 }
+/** Interrupt vectors for the PDB peripheral type */
+#define PDB_IRQS { PDB0_IRQn }
+
+/*!
+ * @}
+ */ /* end of group PDB_Peripheral_Access_Layer */
+
+
+/* ----------------------------------------------------------------------------
+ -- PIT Peripheral Access Layer
+ ---------------------------------------------------------------------------- */
+
+/*!
+ * @addtogroup PIT_Peripheral_Access_Layer PIT Peripheral Access Layer
+ * @{
+ */
+
+/** PIT - Register Layout Typedef */
+typedef struct {
+ __IO uint32_t MCR; /**< PIT Module Control Register, offset: 0x0 */
+ uint8_t RESERVED_0[252];
+ struct { /* offset: 0x100, array step: 0x10 */
+ __IO uint32_t LDVAL; /**< Timer Load Value Register, array offset: 0x100, array step: 0x10 */
+ __I uint32_t CVAL; /**< Current Timer Value Register, array offset: 0x104, array step: 0x10 */
+ __IO uint32_t TCTRL; /**< Timer Control Register, array offset: 0x108, array step: 0x10 */
+ __IO uint32_t TFLG; /**< Timer Flag Register, array offset: 0x10C, array step: 0x10 */
+ } CHANNEL[4];
+} PIT_Type;
+
+/* ----------------------------------------------------------------------------
+ -- PIT Register Masks
+ ---------------------------------------------------------------------------- */
+
+/*!
+ * @addtogroup PIT_Register_Masks PIT Register Masks
+ * @{
+ */
+
+/*! @name MCR - PIT Module Control Register */
+#define PIT_MCR_FRZ_MASK (0x1U)
+#define PIT_MCR_FRZ_SHIFT (0U)
+#define PIT_MCR_FRZ(x) (((uint32_t)(((uint32_t)(x)) << PIT_MCR_FRZ_SHIFT)) & PIT_MCR_FRZ_MASK)
+#define PIT_MCR_MDIS_MASK (0x2U)
+#define PIT_MCR_MDIS_SHIFT (1U)
+#define PIT_MCR_MDIS(x) (((uint32_t)(((uint32_t)(x)) << PIT_MCR_MDIS_SHIFT)) & PIT_MCR_MDIS_MASK)
+
+/*! @name LDVAL - Timer Load Value Register */
+#define PIT_LDVAL_TSV_MASK (0xFFFFFFFFU)
+#define PIT_LDVAL_TSV_SHIFT (0U)
+#define PIT_LDVAL_TSV(x) (((uint32_t)(((uint32_t)(x)) << PIT_LDVAL_TSV_SHIFT)) & PIT_LDVAL_TSV_MASK)
+
+/* The count of PIT_LDVAL */
+#define PIT_LDVAL_COUNT (4U)
+
+/*! @name CVAL - Current Timer Value Register */
+#define PIT_CVAL_TVL_MASK (0xFFFFFFFFU)
+#define PIT_CVAL_TVL_SHIFT (0U)
+#define PIT_CVAL_TVL(x) (((uint32_t)(((uint32_t)(x)) << PIT_CVAL_TVL_SHIFT)) & PIT_CVAL_TVL_MASK)
+
+/* The count of PIT_CVAL */
+#define PIT_CVAL_COUNT (4U)
+
+/*! @name TCTRL - Timer Control Register */
+#define PIT_TCTRL_TEN_MASK (0x1U)
+#define PIT_TCTRL_TEN_SHIFT (0U)
+#define PIT_TCTRL_TEN(x) (((uint32_t)(((uint32_t)(x)) << PIT_TCTRL_TEN_SHIFT)) & PIT_TCTRL_TEN_MASK)
+#define PIT_TCTRL_TIE_MASK (0x2U)
+#define PIT_TCTRL_TIE_SHIFT (1U)
+#define PIT_TCTRL_TIE(x) (((uint32_t)(((uint32_t)(x)) << PIT_TCTRL_TIE_SHIFT)) & PIT_TCTRL_TIE_MASK)
+#define PIT_TCTRL_CHN_MASK (0x4U)
+#define PIT_TCTRL_CHN_SHIFT (2U)
+#define PIT_TCTRL_CHN(x) (((uint32_t)(((uint32_t)(x)) << PIT_TCTRL_CHN_SHIFT)) & PIT_TCTRL_CHN_MASK)
+
+/* The count of PIT_TCTRL */
+#define PIT_TCTRL_COUNT (4U)
+
+/*! @name TFLG - Timer Flag Register */
+#define PIT_TFLG_TIF_MASK (0x1U)
+#define PIT_TFLG_TIF_SHIFT (0U)
+#define PIT_TFLG_TIF(x) (((uint32_t)(((uint32_t)(x)) << PIT_TFLG_TIF_SHIFT)) & PIT_TFLG_TIF_MASK)
+
+/* The count of PIT_TFLG */
+#define PIT_TFLG_COUNT (4U)
+
+
+/*!
+ * @}
+ */ /* end of group PIT_Register_Masks */
+
+
+/* PIT - Peripheral instance base addresses */
+/** Peripheral PIT base address */
+#define PIT_BASE (0x40037000u)
+/** Peripheral PIT base pointer */
+#define PIT ((PIT_Type *)PIT_BASE)
+/** Array initializer of PIT peripheral base addresses */
+#define PIT_BASE_ADDRS { PIT_BASE }
+/** Array initializer of PIT peripheral base pointers */
+#define PIT_BASE_PTRS { PIT }
+/** Interrupt vectors for the PIT peripheral type */
+#define PIT_IRQS { { PIT0_IRQn, PIT1_IRQn, PIT2_IRQn, PIT3_IRQn } }
+
+/*!
+ * @}
+ */ /* end of group PIT_Peripheral_Access_Layer */
+
+
+/* ----------------------------------------------------------------------------
+ -- PMC Peripheral Access Layer
+ ---------------------------------------------------------------------------- */
+
+/*!
+ * @addtogroup PMC_Peripheral_Access_Layer PMC Peripheral Access Layer
+ * @{
+ */
+
+/** PMC - Register Layout Typedef */
+typedef struct {
+ __IO uint8_t LVDSC1; /**< Low Voltage Detect Status And Control 1 register, offset: 0x0 */
+ __IO uint8_t LVDSC2; /**< Low Voltage Detect Status And Control 2 register, offset: 0x1 */
+ __IO uint8_t REGSC; /**< Regulator Status And Control register, offset: 0x2 */
+} PMC_Type;
+
+/* ----------------------------------------------------------------------------
+ -- PMC Register Masks
+ ---------------------------------------------------------------------------- */
+
+/*!
+ * @addtogroup PMC_Register_Masks PMC Register Masks
+ * @{
+ */
+
+/*! @name LVDSC1 - Low Voltage Detect Status And Control 1 register */
+#define PMC_LVDSC1_LVDV_MASK (0x3U)
+#define PMC_LVDSC1_LVDV_SHIFT (0U)
+#define PMC_LVDSC1_LVDV(x) (((uint8_t)(((uint8_t)(x)) << PMC_LVDSC1_LVDV_SHIFT)) & PMC_LVDSC1_LVDV_MASK)
+#define PMC_LVDSC1_LVDRE_MASK (0x10U)
+#define PMC_LVDSC1_LVDRE_SHIFT (4U)
+#define PMC_LVDSC1_LVDRE(x) (((uint8_t)(((uint8_t)(x)) << PMC_LVDSC1_LVDRE_SHIFT)) & PMC_LVDSC1_LVDRE_MASK)
+#define PMC_LVDSC1_LVDIE_MASK (0x20U)
+#define PMC_LVDSC1_LVDIE_SHIFT (5U)
+#define PMC_LVDSC1_LVDIE(x) (((uint8_t)(((uint8_t)(x)) << PMC_LVDSC1_LVDIE_SHIFT)) & PMC_LVDSC1_LVDIE_MASK)
+#define PMC_LVDSC1_LVDACK_MASK (0x40U)
+#define PMC_LVDSC1_LVDACK_SHIFT (6U)
+#define PMC_LVDSC1_LVDACK(x) (((uint8_t)(((uint8_t)(x)) << PMC_LVDSC1_LVDACK_SHIFT)) & PMC_LVDSC1_LVDACK_MASK)
+#define PMC_LVDSC1_LVDF_MASK (0x80U)
+#define PMC_LVDSC1_LVDF_SHIFT (7U)
+#define PMC_LVDSC1_LVDF(x) (((uint8_t)(((uint8_t)(x)) << PMC_LVDSC1_LVDF_SHIFT)) & PMC_LVDSC1_LVDF_MASK)
+
+/*! @name LVDSC2 - Low Voltage Detect Status And Control 2 register */
+#define PMC_LVDSC2_LVWV_MASK (0x3U)
+#define PMC_LVDSC2_LVWV_SHIFT (0U)
+#define PMC_LVDSC2_LVWV(x) (((uint8_t)(((uint8_t)(x)) << PMC_LVDSC2_LVWV_SHIFT)) & PMC_LVDSC2_LVWV_MASK)
+#define PMC_LVDSC2_LVWIE_MASK (0x20U)
+#define PMC_LVDSC2_LVWIE_SHIFT (5U)
+#define PMC_LVDSC2_LVWIE(x) (((uint8_t)(((uint8_t)(x)) << PMC_LVDSC2_LVWIE_SHIFT)) & PMC_LVDSC2_LVWIE_MASK)
+#define PMC_LVDSC2_LVWACK_MASK (0x40U)
+#define PMC_LVDSC2_LVWACK_SHIFT (6U)
+#define PMC_LVDSC2_LVWACK(x) (((uint8_t)(((uint8_t)(x)) << PMC_LVDSC2_LVWACK_SHIFT)) & PMC_LVDSC2_LVWACK_MASK)
+#define PMC_LVDSC2_LVWF_MASK (0x80U)
+#define PMC_LVDSC2_LVWF_SHIFT (7U)
+#define PMC_LVDSC2_LVWF(x) (((uint8_t)(((uint8_t)(x)) << PMC_LVDSC2_LVWF_SHIFT)) & PMC_LVDSC2_LVWF_MASK)
+
+/*! @name REGSC - Regulator Status And Control register */
+#define PMC_REGSC_BGBE_MASK (0x1U)
+#define PMC_REGSC_BGBE_SHIFT (0U)
+#define PMC_REGSC_BGBE(x) (((uint8_t)(((uint8_t)(x)) << PMC_REGSC_BGBE_SHIFT)) & PMC_REGSC_BGBE_MASK)
+#define PMC_REGSC_REGONS_MASK (0x4U)
+#define PMC_REGSC_REGONS_SHIFT (2U)
+#define PMC_REGSC_REGONS(x) (((uint8_t)(((uint8_t)(x)) << PMC_REGSC_REGONS_SHIFT)) & PMC_REGSC_REGONS_MASK)
+#define PMC_REGSC_ACKISO_MASK (0x8U)
+#define PMC_REGSC_ACKISO_SHIFT (3U)
+#define PMC_REGSC_ACKISO(x) (((uint8_t)(((uint8_t)(x)) << PMC_REGSC_ACKISO_SHIFT)) & PMC_REGSC_ACKISO_MASK)
+#define PMC_REGSC_BGEN_MASK (0x10U)
+#define PMC_REGSC_BGEN_SHIFT (4U)
+#define PMC_REGSC_BGEN(x) (((uint8_t)(((uint8_t)(x)) << PMC_REGSC_BGEN_SHIFT)) & PMC_REGSC_BGEN_MASK)
+
+
+/*!
+ * @}
+ */ /* end of group PMC_Register_Masks */
+
+
+/* PMC - Peripheral instance base addresses */
+/** Peripheral PMC base address */
+#define PMC_BASE (0x4007D000u)
+/** Peripheral PMC base pointer */
+#define PMC ((PMC_Type *)PMC_BASE)
+/** Array initializer of PMC peripheral base addresses */
+#define PMC_BASE_ADDRS { PMC_BASE }
+/** Array initializer of PMC peripheral base pointers */
+#define PMC_BASE_PTRS { PMC }
+/** Interrupt vectors for the PMC peripheral type */
+#define PMC_IRQS { LVD_LVW_IRQn }
+
+/*!
+ * @}
+ */ /* end of group PMC_Peripheral_Access_Layer */
+
+
+/* ----------------------------------------------------------------------------
+ -- PORT Peripheral Access Layer
+ ---------------------------------------------------------------------------- */
+
+/*!
+ * @addtogroup PORT_Peripheral_Access_Layer PORT Peripheral Access Layer
+ * @{
+ */
+
+/** PORT - Register Layout Typedef */
+typedef struct {
+ __IO uint32_t PCR[32]; /**< Pin Control Register n, array offset: 0x0, array step: 0x4 */
+ __O uint32_t GPCLR; /**< Global Pin Control Low Register, offset: 0x80 */
+ __O uint32_t GPCHR; /**< Global Pin Control High Register, offset: 0x84 */
+ uint8_t RESERVED_0[24];
+ __IO uint32_t ISFR; /**< Interrupt Status Flag Register, offset: 0xA0 */
+ uint8_t RESERVED_1[28];
+ __IO uint32_t DFER; /**< Digital Filter Enable Register, offset: 0xC0 */
+ __IO uint32_t DFCR; /**< Digital Filter Clock Register, offset: 0xC4 */
+ __IO uint32_t DFWR; /**< Digital Filter Width Register, offset: 0xC8 */
+} PORT_Type;
+
+/* ----------------------------------------------------------------------------
+ -- PORT Register Masks
+ ---------------------------------------------------------------------------- */
+
+/*!
+ * @addtogroup PORT_Register_Masks PORT Register Masks
+ * @{
+ */
+
+/*! @name PCR - Pin Control Register n */
+#define PORT_PCR_PS_MASK (0x1U)
+#define PORT_PCR_PS_SHIFT (0U)
+#define PORT_PCR_PS(x) (((uint32_t)(((uint32_t)(x)) << PORT_PCR_PS_SHIFT)) & PORT_PCR_PS_MASK)
+#define PORT_PCR_PE_MASK (0x2U)
+#define PORT_PCR_PE_SHIFT (1U)
+#define PORT_PCR_PE(x) (((uint32_t)(((uint32_t)(x)) << PORT_PCR_PE_SHIFT)) & PORT_PCR_PE_MASK)
+#define PORT_PCR_SRE_MASK (0x4U)
+#define PORT_PCR_SRE_SHIFT (2U)
+#define PORT_PCR_SRE(x) (((uint32_t)(((uint32_t)(x)) << PORT_PCR_SRE_SHIFT)) & PORT_PCR_SRE_MASK)
+#define PORT_PCR_PFE_MASK (0x10U)
+#define PORT_PCR_PFE_SHIFT (4U)
+#define PORT_PCR_PFE(x) (((uint32_t)(((uint32_t)(x)) << PORT_PCR_PFE_SHIFT)) & PORT_PCR_PFE_MASK)
+#define PORT_PCR_ODE_MASK (0x20U)
+#define PORT_PCR_ODE_SHIFT (5U)
+#define PORT_PCR_ODE(x) (((uint32_t)(((uint32_t)(x)) << PORT_PCR_ODE_SHIFT)) & PORT_PCR_ODE_MASK)
+#define PORT_PCR_DSE_MASK (0x40U)
+#define PORT_PCR_DSE_SHIFT (6U)
+#define PORT_PCR_DSE(x) (((uint32_t)(((uint32_t)(x)) << PORT_PCR_DSE_SHIFT)) & PORT_PCR_DSE_MASK)
+#define PORT_PCR_MUX_MASK (0x700U)
+#define PORT_PCR_MUX_SHIFT (8U)
+#define PORT_PCR_MUX(x) (((uint32_t)(((uint32_t)(x)) << PORT_PCR_MUX_SHIFT)) & PORT_PCR_MUX_MASK)
+#define PORT_PCR_LK_MASK (0x8000U)
+#define PORT_PCR_LK_SHIFT (15U)
+#define PORT_PCR_LK(x) (((uint32_t)(((uint32_t)(x)) << PORT_PCR_LK_SHIFT)) & PORT_PCR_LK_MASK)
+#define PORT_PCR_IRQC_MASK (0xF0000U)
+#define PORT_PCR_IRQC_SHIFT (16U)
+#define PORT_PCR_IRQC(x) (((uint32_t)(((uint32_t)(x)) << PORT_PCR_IRQC_SHIFT)) & PORT_PCR_IRQC_MASK)
+#define PORT_PCR_ISF_MASK (0x1000000U)
+#define PORT_PCR_ISF_SHIFT (24U)
+#define PORT_PCR_ISF(x) (((uint32_t)(((uint32_t)(x)) << PORT_PCR_ISF_SHIFT)) & PORT_PCR_ISF_MASK)
+
+/* The count of PORT_PCR */
+#define PORT_PCR_COUNT (32U)
+
+/*! @name GPCLR - Global Pin Control Low Register */
+#define PORT_GPCLR_GPWD_MASK (0xFFFFU)
+#define PORT_GPCLR_GPWD_SHIFT (0U)
+#define PORT_GPCLR_GPWD(x) (((uint32_t)(((uint32_t)(x)) << PORT_GPCLR_GPWD_SHIFT)) & PORT_GPCLR_GPWD_MASK)
+#define PORT_GPCLR_GPWE_MASK (0xFFFF0000U)
+#define PORT_GPCLR_GPWE_SHIFT (16U)
+#define PORT_GPCLR_GPWE(x) (((uint32_t)(((uint32_t)(x)) << PORT_GPCLR_GPWE_SHIFT)) & PORT_GPCLR_GPWE_MASK)
+
+/*! @name GPCHR - Global Pin Control High Register */
+#define PORT_GPCHR_GPWD_MASK (0xFFFFU)
+#define PORT_GPCHR_GPWD_SHIFT (0U)
+#define PORT_GPCHR_GPWD(x) (((uint32_t)(((uint32_t)(x)) << PORT_GPCHR_GPWD_SHIFT)) & PORT_GPCHR_GPWD_MASK)
+#define PORT_GPCHR_GPWE_MASK (0xFFFF0000U)
+#define PORT_GPCHR_GPWE_SHIFT (16U)
+#define PORT_GPCHR_GPWE(x) (((uint32_t)(((uint32_t)(x)) << PORT_GPCHR_GPWE_SHIFT)) & PORT_GPCHR_GPWE_MASK)
+
+/*! @name ISFR - Interrupt Status Flag Register */
+#define PORT_ISFR_ISF_MASK (0xFFFFFFFFU)
+#define PORT_ISFR_ISF_SHIFT (0U)
+#define PORT_ISFR_ISF(x) (((uint32_t)(((uint32_t)(x)) << PORT_ISFR_ISF_SHIFT)) & PORT_ISFR_ISF_MASK)
+
+/*! @name DFER - Digital Filter Enable Register */
+#define PORT_DFER_DFE_MASK (0xFFFFFFFFU)
+#define PORT_DFER_DFE_SHIFT (0U)
+#define PORT_DFER_DFE(x) (((uint32_t)(((uint32_t)(x)) << PORT_DFER_DFE_SHIFT)) & PORT_DFER_DFE_MASK)
+
+/*! @name DFCR - Digital Filter Clock Register */
+#define PORT_DFCR_CS_MASK (0x1U)
+#define PORT_DFCR_CS_SHIFT (0U)
+#define PORT_DFCR_CS(x) (((uint32_t)(((uint32_t)(x)) << PORT_DFCR_CS_SHIFT)) & PORT_DFCR_CS_MASK)
+
+/*! @name DFWR - Digital Filter Width Register */
+#define PORT_DFWR_FILT_MASK (0x1FU)
+#define PORT_DFWR_FILT_SHIFT (0U)
+#define PORT_DFWR_FILT(x) (((uint32_t)(((uint32_t)(x)) << PORT_DFWR_FILT_SHIFT)) & PORT_DFWR_FILT_MASK)
+
+
+/*!
+ * @}
+ */ /* end of group PORT_Register_Masks */
+
+
+/* PORT - Peripheral instance base addresses */
+/** Peripheral PORTA base address */
+#define PORTA_BASE (0x40049000u)
+/** Peripheral PORTA base pointer */
+#define PORTA ((PORT_Type *)PORTA_BASE)
+/** Peripheral PORTB base address */
+#define PORTB_BASE (0x4004A000u)
+/** Peripheral PORTB base pointer */
+#define PORTB ((PORT_Type *)PORTB_BASE)
+/** Peripheral PORTC base address */
+#define PORTC_BASE (0x4004B000u)
+/** Peripheral PORTC base pointer */
+#define PORTC ((PORT_Type *)PORTC_BASE)
+/** Peripheral PORTD base address */
+#define PORTD_BASE (0x4004C000u)
+/** Peripheral PORTD base pointer */
+#define PORTD ((PORT_Type *)PORTD_BASE)
+/** Peripheral PORTE base address */
+#define PORTE_BASE (0x4004D000u)
+/** Peripheral PORTE base pointer */
+#define PORTE ((PORT_Type *)PORTE_BASE)
+/** Array initializer of PORT peripheral base addresses */
+#define PORT_BASE_ADDRS { PORTA_BASE, PORTB_BASE, PORTC_BASE, PORTD_BASE, PORTE_BASE }
+/** Array initializer of PORT peripheral base pointers */
+#define PORT_BASE_PTRS { PORTA, PORTB, PORTC, PORTD, PORTE }
+/** Interrupt vectors for the PORT peripheral type */
+#define PORT_IRQS { PORTA_IRQn, PORTB_IRQn, PORTC_IRQn, PORTD_IRQn, PORTE_IRQn }
+
+/*!
+ * @}
+ */ /* end of group PORT_Peripheral_Access_Layer */
+
+
+/* ----------------------------------------------------------------------------
+ -- RCM Peripheral Access Layer
+ ---------------------------------------------------------------------------- */
+
+/*!
+ * @addtogroup RCM_Peripheral_Access_Layer RCM Peripheral Access Layer
+ * @{
+ */
+
+/** RCM - Register Layout Typedef */
+typedef struct {
+ __I uint8_t SRS0; /**< System Reset Status Register 0, offset: 0x0 */
+ __I uint8_t SRS1; /**< System Reset Status Register 1, offset: 0x1 */
+ uint8_t RESERVED_0[2];
+ __IO uint8_t RPFC; /**< Reset Pin Filter Control register, offset: 0x4 */
+ __IO uint8_t RPFW; /**< Reset Pin Filter Width register, offset: 0x5 */
+ uint8_t RESERVED_1[2];
+ __IO uint8_t SSRS0; /**< Sticky System Reset Status Register 0, offset: 0x8 */
+ __IO uint8_t SSRS1; /**< Sticky System Reset Status Register 1, offset: 0x9 */
+} RCM_Type;
+
+/* ----------------------------------------------------------------------------
+ -- RCM Register Masks
+ ---------------------------------------------------------------------------- */
+
+/*!
+ * @addtogroup RCM_Register_Masks RCM Register Masks
+ * @{
+ */
+
+/*! @name SRS0 - System Reset Status Register 0 */
+#define RCM_SRS0_WAKEUP_MASK (0x1U)
+#define RCM_SRS0_WAKEUP_SHIFT (0U)
+#define RCM_SRS0_WAKEUP(x) (((uint8_t)(((uint8_t)(x)) << RCM_SRS0_WAKEUP_SHIFT)) & RCM_SRS0_WAKEUP_MASK)
+#define RCM_SRS0_LVD_MASK (0x2U)
+#define RCM_SRS0_LVD_SHIFT (1U)
+#define RCM_SRS0_LVD(x) (((uint8_t)(((uint8_t)(x)) << RCM_SRS0_LVD_SHIFT)) & RCM_SRS0_LVD_MASK)
+#define RCM_SRS0_LOC_MASK (0x4U)
+#define RCM_SRS0_LOC_SHIFT (2U)
+#define RCM_SRS0_LOC(x) (((uint8_t)(((uint8_t)(x)) << RCM_SRS0_LOC_SHIFT)) & RCM_SRS0_LOC_MASK)
+#define RCM_SRS0_WDOG_MASK (0x20U)
+#define RCM_SRS0_WDOG_SHIFT (5U)
+#define RCM_SRS0_WDOG(x) (((uint8_t)(((uint8_t)(x)) << RCM_SRS0_WDOG_SHIFT)) & RCM_SRS0_WDOG_MASK)
+#define RCM_SRS0_PIN_MASK (0x40U)
+#define RCM_SRS0_PIN_SHIFT (6U)
+#define RCM_SRS0_PIN(x) (((uint8_t)(((uint8_t)(x)) << RCM_SRS0_PIN_SHIFT)) & RCM_SRS0_PIN_MASK)
+#define RCM_SRS0_POR_MASK (0x80U)
+#define RCM_SRS0_POR_SHIFT (7U)
+#define RCM_SRS0_POR(x) (((uint8_t)(((uint8_t)(x)) << RCM_SRS0_POR_SHIFT)) & RCM_SRS0_POR_MASK)
+
+/*! @name SRS1 - System Reset Status Register 1 */
+#define RCM_SRS1_JTAG_MASK (0x1U)
+#define RCM_SRS1_JTAG_SHIFT (0U)
+#define RCM_SRS1_JTAG(x) (((uint8_t)(((uint8_t)(x)) << RCM_SRS1_JTAG_SHIFT)) & RCM_SRS1_JTAG_MASK)
+#define RCM_SRS1_LOCKUP_MASK (0x2U)
+#define RCM_SRS1_LOCKUP_SHIFT (1U)
+#define RCM_SRS1_LOCKUP(x) (((uint8_t)(((uint8_t)(x)) << RCM_SRS1_LOCKUP_SHIFT)) & RCM_SRS1_LOCKUP_MASK)
+#define RCM_SRS1_SW_MASK (0x4U)
+#define RCM_SRS1_SW_SHIFT (2U)
+#define RCM_SRS1_SW(x) (((uint8_t)(((uint8_t)(x)) << RCM_SRS1_SW_SHIFT)) & RCM_SRS1_SW_MASK)
+#define RCM_SRS1_MDM_AP_MASK (0x8U)
+#define RCM_SRS1_MDM_AP_SHIFT (3U)
+#define RCM_SRS1_MDM_AP(x) (((uint8_t)(((uint8_t)(x)) << RCM_SRS1_MDM_AP_SHIFT)) & RCM_SRS1_MDM_AP_MASK)
+#define RCM_SRS1_SACKERR_MASK (0x20U)
+#define RCM_SRS1_SACKERR_SHIFT (5U)
+#define RCM_SRS1_SACKERR(x) (((uint8_t)(((uint8_t)(x)) << RCM_SRS1_SACKERR_SHIFT)) & RCM_SRS1_SACKERR_MASK)
+
+/*! @name RPFC - Reset Pin Filter Control register */
+#define RCM_RPFC_RSTFLTSRW_MASK (0x3U)
+#define RCM_RPFC_RSTFLTSRW_SHIFT (0U)
+#define RCM_RPFC_RSTFLTSRW(x) (((uint8_t)(((uint8_t)(x)) << RCM_RPFC_RSTFLTSRW_SHIFT)) & RCM_RPFC_RSTFLTSRW_MASK)
+#define RCM_RPFC_RSTFLTSS_MASK (0x4U)
+#define RCM_RPFC_RSTFLTSS_SHIFT (2U)
+#define RCM_RPFC_RSTFLTSS(x) (((uint8_t)(((uint8_t)(x)) << RCM_RPFC_RSTFLTSS_SHIFT)) & RCM_RPFC_RSTFLTSS_MASK)
+
+/*! @name RPFW - Reset Pin Filter Width register */
+#define RCM_RPFW_RSTFLTSEL_MASK (0x1FU)
+#define RCM_RPFW_RSTFLTSEL_SHIFT (0U)
+#define RCM_RPFW_RSTFLTSEL(x) (((uint8_t)(((uint8_t)(x)) << RCM_RPFW_RSTFLTSEL_SHIFT)) & RCM_RPFW_RSTFLTSEL_MASK)
+
+/*! @name SSRS0 - Sticky System Reset Status Register 0 */
+#define RCM_SSRS0_SWAKEUP_MASK (0x1U)
+#define RCM_SSRS0_SWAKEUP_SHIFT (0U)
+#define RCM_SSRS0_SWAKEUP(x) (((uint8_t)(((uint8_t)(x)) << RCM_SSRS0_SWAKEUP_SHIFT)) & RCM_SSRS0_SWAKEUP_MASK)
+#define RCM_SSRS0_SLVD_MASK (0x2U)
+#define RCM_SSRS0_SLVD_SHIFT (1U)
+#define RCM_SSRS0_SLVD(x) (((uint8_t)(((uint8_t)(x)) << RCM_SSRS0_SLVD_SHIFT)) & RCM_SSRS0_SLVD_MASK)
+#define RCM_SSRS0_SLOC_MASK (0x4U)
+#define RCM_SSRS0_SLOC_SHIFT (2U)
+#define RCM_SSRS0_SLOC(x) (((uint8_t)(((uint8_t)(x)) << RCM_SSRS0_SLOC_SHIFT)) & RCM_SSRS0_SLOC_MASK)
+#define RCM_SSRS0_SWDOG_MASK (0x20U)
+#define RCM_SSRS0_SWDOG_SHIFT (5U)
+#define RCM_SSRS0_SWDOG(x) (((uint8_t)(((uint8_t)(x)) << RCM_SSRS0_SWDOG_SHIFT)) & RCM_SSRS0_SWDOG_MASK)
+#define RCM_SSRS0_SPIN_MASK (0x40U)
+#define RCM_SSRS0_SPIN_SHIFT (6U)
+#define RCM_SSRS0_SPIN(x) (((uint8_t)(((uint8_t)(x)) << RCM_SSRS0_SPIN_SHIFT)) & RCM_SSRS0_SPIN_MASK)
+#define RCM_SSRS0_SPOR_MASK (0x80U)
+#define RCM_SSRS0_SPOR_SHIFT (7U)
+#define RCM_SSRS0_SPOR(x) (((uint8_t)(((uint8_t)(x)) << RCM_SSRS0_SPOR_SHIFT)) & RCM_SSRS0_SPOR_MASK)
+
+/*! @name SSRS1 - Sticky System Reset Status Register 1 */
+#define RCM_SSRS1_SJTAG_MASK (0x1U)
+#define RCM_SSRS1_SJTAG_SHIFT (0U)
+#define RCM_SSRS1_SJTAG(x) (((uint8_t)(((uint8_t)(x)) << RCM_SSRS1_SJTAG_SHIFT)) & RCM_SSRS1_SJTAG_MASK)
+#define RCM_SSRS1_SLOCKUP_MASK (0x2U)
+#define RCM_SSRS1_SLOCKUP_SHIFT (1U)
+#define RCM_SSRS1_SLOCKUP(x) (((uint8_t)(((uint8_t)(x)) << RCM_SSRS1_SLOCKUP_SHIFT)) & RCM_SSRS1_SLOCKUP_MASK)
+#define RCM_SSRS1_SSW_MASK (0x4U)
+#define RCM_SSRS1_SSW_SHIFT (2U)
+#define RCM_SSRS1_SSW(x) (((uint8_t)(((uint8_t)(x)) << RCM_SSRS1_SSW_SHIFT)) & RCM_SSRS1_SSW_MASK)
+#define RCM_SSRS1_SMDM_AP_MASK (0x8U)
+#define RCM_SSRS1_SMDM_AP_SHIFT (3U)
+#define RCM_SSRS1_SMDM_AP(x) (((uint8_t)(((uint8_t)(x)) << RCM_SSRS1_SMDM_AP_SHIFT)) & RCM_SSRS1_SMDM_AP_MASK)
+#define RCM_SSRS1_SSACKERR_MASK (0x20U)
+#define RCM_SSRS1_SSACKERR_SHIFT (5U)
+#define RCM_SSRS1_SSACKERR(x) (((uint8_t)(((uint8_t)(x)) << RCM_SSRS1_SSACKERR_SHIFT)) & RCM_SSRS1_SSACKERR_MASK)
+
+
+/*!
+ * @}
+ */ /* end of group RCM_Register_Masks */
+
+
+/* RCM - Peripheral instance base addresses */
+/** Peripheral RCM base address */
+#define RCM_BASE (0x4007F000u)
+/** Peripheral RCM base pointer */
+#define RCM ((RCM_Type *)RCM_BASE)
+/** Array initializer of RCM peripheral base addresses */
+#define RCM_BASE_ADDRS { RCM_BASE }
+/** Array initializer of RCM peripheral base pointers */
+#define RCM_BASE_PTRS { RCM }
+
+/*!
+ * @}
+ */ /* end of group RCM_Peripheral_Access_Layer */
+
+
+/* ----------------------------------------------------------------------------
+ -- SIM Peripheral Access Layer
+ ---------------------------------------------------------------------------- */
+
+/*!
+ * @addtogroup SIM_Peripheral_Access_Layer SIM Peripheral Access Layer
+ * @{
+ */
+
+/** SIM - Register Layout Typedef */
+typedef struct {
+ __IO uint32_t SOPT1; /**< System Options Register 1, offset: 0x0 */
+ uint32_t SOPT1CFG; /**< SOPT1 Configuration Register, offset: 0x4 */
+ uint8_t RESERVED_0[4092];
+ __IO uint32_t SOPT2; /**< System Options Register 2, offset: 0x1004 */
+ uint8_t RESERVED_1[4];
+ __IO uint32_t SOPT4; /**< System Options Register 4, offset: 0x100C */
+ __IO uint32_t SOPT5; /**< System Options Register 5, offset: 0x1010 */
+ uint8_t RESERVED_2[4];
+ __IO uint32_t SOPT7; /**< System Options Register 7, offset: 0x1018 */
+ __IO uint32_t SOPT8; /**< System Options Register 8, offset: 0x101C */
+ uint8_t RESERVED_3[4];
+ __I uint32_t SDID; /**< System Device Identification Register, offset: 0x1024 */
+ uint8_t RESERVED_4[12];
+ __IO uint32_t SCGC4; /**< System Clock Gating Control Register 4, offset: 0x1034 */
+ __IO uint32_t SCGC5; /**< System Clock Gating Control Register 5, offset: 0x1038 */
+ __IO uint32_t SCGC6; /**< System Clock Gating Control Register 6, offset: 0x103C */
+ __IO uint32_t SCGC7; /**< System Clock Gating Control Register 7, offset: 0x1040 */
+ __IO uint32_t CLKDIV1; /**< System Clock Divider Register 1, offset: 0x1044 */
+ uint8_t RESERVED_5[4];
+ __IO uint32_t FCFG1; /**< Flash Configuration Register 1, offset: 0x104C */
+ __I uint32_t FCFG2; /**< Flash Configuration Register 2, offset: 0x1050 */
+ __I uint32_t UIDH; /**< Unique Identification Register High, offset: 0x1054 */
+ __I uint32_t UIDMH; /**< Unique Identification Register Mid-High, offset: 0x1058 */
+ __I uint32_t UIDML; /**< Unique Identification Register Mid Low, offset: 0x105C */
+ __I uint32_t UIDL; /**< Unique Identification Register Low, offset: 0x1060 */
+} SIM_Type;
+
+/* ----------------------------------------------------------------------------
+ -- SIM Register Masks
+ ---------------------------------------------------------------------------- */
+
+/*!
+ * @addtogroup SIM_Register_Masks SIM Register Masks
+ * @{
+ */
+
+/*! @name SOPT1 - System Options Register 1 */
+#define SIM_SOPT1_RAMSIZE_MASK (0xF000U)
+#define SIM_SOPT1_RAMSIZE_SHIFT (12U)
+#define SIM_SOPT1_RAMSIZE(x) (((uint32_t)(((uint32_t)(x)) << SIM_SOPT1_RAMSIZE_SHIFT)) & SIM_SOPT1_RAMSIZE_MASK)
+#define SIM_SOPT1_OSC32KOUT_MASK (0x30000U)
+#define SIM_SOPT1_OSC32KOUT_SHIFT (16U)
+#define SIM_SOPT1_OSC32KOUT(x) (((uint32_t)(((uint32_t)(x)) << SIM_SOPT1_OSC32KOUT_SHIFT)) & SIM_SOPT1_OSC32KOUT_MASK)
+#define SIM_SOPT1_OSC32KSEL_MASK (0xC0000U)
+#define SIM_SOPT1_OSC32KSEL_SHIFT (18U)
+#define SIM_SOPT1_OSC32KSEL(x) (((uint32_t)(((uint32_t)(x)) << SIM_SOPT1_OSC32KSEL_SHIFT)) & SIM_SOPT1_OSC32KSEL_MASK)
+
+/*! @name SOPT2 - System Options Register 2 */
+#define SIM_SOPT2_CLKOUTSEL_MASK (0xE0U)
+#define SIM_SOPT2_CLKOUTSEL_SHIFT (5U)
+#define SIM_SOPT2_CLKOUTSEL(x) (((uint32_t)(((uint32_t)(x)) << SIM_SOPT2_CLKOUTSEL_SHIFT)) & SIM_SOPT2_CLKOUTSEL_MASK)
+#define SIM_SOPT2_TRACECLKSEL_MASK (0x1000U)
+#define SIM_SOPT2_TRACECLKSEL_SHIFT (12U)
+#define SIM_SOPT2_TRACECLKSEL(x) (((uint32_t)(((uint32_t)(x)) << SIM_SOPT2_TRACECLKSEL_SHIFT)) & SIM_SOPT2_TRACECLKSEL_MASK)
+#define SIM_SOPT2_PLLFLLSEL_MASK (0x30000U)
+#define SIM_SOPT2_PLLFLLSEL_SHIFT (16U)
+#define SIM_SOPT2_PLLFLLSEL(x) (((uint32_t)(((uint32_t)(x)) << SIM_SOPT2_PLLFLLSEL_SHIFT)) & SIM_SOPT2_PLLFLLSEL_MASK)
+
+/*! @name SOPT4 - System Options Register 4 */
+#define SIM_SOPT4_FTM0FLT0_MASK (0x1U)
+#define SIM_SOPT4_FTM0FLT0_SHIFT (0U)
+#define SIM_SOPT4_FTM0FLT0(x) (((uint32_t)(((uint32_t)(x)) << SIM_SOPT4_FTM0FLT0_SHIFT)) & SIM_SOPT4_FTM0FLT0_MASK)
+#define SIM_SOPT4_FTM0FLT1_MASK (0x2U)
+#define SIM_SOPT4_FTM0FLT1_SHIFT (1U)
+#define SIM_SOPT4_FTM0FLT1(x) (((uint32_t)(((uint32_t)(x)) << SIM_SOPT4_FTM0FLT1_SHIFT)) & SIM_SOPT4_FTM0FLT1_MASK)
+#define SIM_SOPT4_FTM1FLT0_MASK (0x10U)
+#define SIM_SOPT4_FTM1FLT0_SHIFT (4U)
+#define SIM_SOPT4_FTM1FLT0(x) (((uint32_t)(((uint32_t)(x)) << SIM_SOPT4_FTM1FLT0_SHIFT)) & SIM_SOPT4_FTM1FLT0_MASK)
+#define SIM_SOPT4_FTM2FLT0_MASK (0x100U)
+#define SIM_SOPT4_FTM2FLT0_SHIFT (8U)
+#define SIM_SOPT4_FTM2FLT0(x) (((uint32_t)(((uint32_t)(x)) << SIM_SOPT4_FTM2FLT0_SHIFT)) & SIM_SOPT4_FTM2FLT0_MASK)
+#define SIM_SOPT4_FTM1CH0SRC_MASK (0xC0000U)
+#define SIM_SOPT4_FTM1CH0SRC_SHIFT (18U)
+#define SIM_SOPT4_FTM1CH0SRC(x) (((uint32_t)(((uint32_t)(x)) << SIM_SOPT4_FTM1CH0SRC_SHIFT)) & SIM_SOPT4_FTM1CH0SRC_MASK)
+#define SIM_SOPT4_FTM2CH0SRC_MASK (0x300000U)
+#define SIM_SOPT4_FTM2CH0SRC_SHIFT (20U)
+#define SIM_SOPT4_FTM2CH0SRC(x) (((uint32_t)(((uint32_t)(x)) << SIM_SOPT4_FTM2CH0SRC_SHIFT)) & SIM_SOPT4_FTM2CH0SRC_MASK)
+#define SIM_SOPT4_FTM2CH1SRC_MASK (0x400000U)
+#define SIM_SOPT4_FTM2CH1SRC_SHIFT (22U)
+#define SIM_SOPT4_FTM2CH1SRC(x) (((uint32_t)(((uint32_t)(x)) << SIM_SOPT4_FTM2CH1SRC_SHIFT)) & SIM_SOPT4_FTM2CH1SRC_MASK)
+#define SIM_SOPT4_FTM0CLKSEL_MASK (0x1000000U)
+#define SIM_SOPT4_FTM0CLKSEL_SHIFT (24U)
+#define SIM_SOPT4_FTM0CLKSEL(x) (((uint32_t)(((uint32_t)(x)) << SIM_SOPT4_FTM0CLKSEL_SHIFT)) & SIM_SOPT4_FTM0CLKSEL_MASK)
+#define SIM_SOPT4_FTM1CLKSEL_MASK (0x2000000U)
+#define SIM_SOPT4_FTM1CLKSEL_SHIFT (25U)
+#define SIM_SOPT4_FTM1CLKSEL(x) (((uint32_t)(((uint32_t)(x)) << SIM_SOPT4_FTM1CLKSEL_SHIFT)) & SIM_SOPT4_FTM1CLKSEL_MASK)
+#define SIM_SOPT4_FTM2CLKSEL_MASK (0x4000000U)
+#define SIM_SOPT4_FTM2CLKSEL_SHIFT (26U)
+#define SIM_SOPT4_FTM2CLKSEL(x) (((uint32_t)(((uint32_t)(x)) << SIM_SOPT4_FTM2CLKSEL_SHIFT)) & SIM_SOPT4_FTM2CLKSEL_MASK)
+#define SIM_SOPT4_FTM0TRG0SRC_MASK (0x10000000U)
+#define SIM_SOPT4_FTM0TRG0SRC_SHIFT (28U)
+#define SIM_SOPT4_FTM0TRG0SRC(x) (((uint32_t)(((uint32_t)(x)) << SIM_SOPT4_FTM0TRG0SRC_SHIFT)) & SIM_SOPT4_FTM0TRG0SRC_MASK)
+#define SIM_SOPT4_FTM0TRG1SRC_MASK (0x20000000U)
+#define SIM_SOPT4_FTM0TRG1SRC_SHIFT (29U)
+#define SIM_SOPT4_FTM0TRG1SRC(x) (((uint32_t)(((uint32_t)(x)) << SIM_SOPT4_FTM0TRG1SRC_SHIFT)) & SIM_SOPT4_FTM0TRG1SRC_MASK)
+
+/*! @name SOPT5 - System Options Register 5 */
+#define SIM_SOPT5_UART0TXSRC_MASK (0x3U)
+#define SIM_SOPT5_UART0TXSRC_SHIFT (0U)
+#define SIM_SOPT5_UART0TXSRC(x) (((uint32_t)(((uint32_t)(x)) << SIM_SOPT5_UART0TXSRC_SHIFT)) & SIM_SOPT5_UART0TXSRC_MASK)
+#define SIM_SOPT5_UART0RXSRC_MASK (0xCU)
+#define SIM_SOPT5_UART0RXSRC_SHIFT (2U)
+#define SIM_SOPT5_UART0RXSRC(x) (((uint32_t)(((uint32_t)(x)) << SIM_SOPT5_UART0RXSRC_SHIFT)) & SIM_SOPT5_UART0RXSRC_MASK)
+#define SIM_SOPT5_UART1TXSRC_MASK (0x30U)
+#define SIM_SOPT5_UART1TXSRC_SHIFT (4U)
+#define SIM_SOPT5_UART1TXSRC(x) (((uint32_t)(((uint32_t)(x)) << SIM_SOPT5_UART1TXSRC_SHIFT)) & SIM_SOPT5_UART1TXSRC_MASK)
+#define SIM_SOPT5_UART1RXSRC_MASK (0xC0U)
+#define SIM_SOPT5_UART1RXSRC_SHIFT (6U)
+#define SIM_SOPT5_UART1RXSRC(x) (((uint32_t)(((uint32_t)(x)) << SIM_SOPT5_UART1RXSRC_SHIFT)) & SIM_SOPT5_UART1RXSRC_MASK)
+
+/*! @name SOPT7 - System Options Register 7 */
+#define SIM_SOPT7_ADC0TRGSEL_MASK (0xFU)
+#define SIM_SOPT7_ADC0TRGSEL_SHIFT (0U)
+#define SIM_SOPT7_ADC0TRGSEL(x) (((uint32_t)(((uint32_t)(x)) << SIM_SOPT7_ADC0TRGSEL_SHIFT)) & SIM_SOPT7_ADC0TRGSEL_MASK)
+#define SIM_SOPT7_ADC0PRETRGSEL_MASK (0x10U)
+#define SIM_SOPT7_ADC0PRETRGSEL_SHIFT (4U)
+#define SIM_SOPT7_ADC0PRETRGSEL(x) (((uint32_t)(((uint32_t)(x)) << SIM_SOPT7_ADC0PRETRGSEL_SHIFT)) & SIM_SOPT7_ADC0PRETRGSEL_MASK)
+#define SIM_SOPT7_ADC0ALTTRGEN_MASK (0x80U)
+#define SIM_SOPT7_ADC0ALTTRGEN_SHIFT (7U)
+#define SIM_SOPT7_ADC0ALTTRGEN(x) (((uint32_t)(((uint32_t)(x)) << SIM_SOPT7_ADC0ALTTRGEN_SHIFT)) & SIM_SOPT7_ADC0ALTTRGEN_MASK)
+
+/*! @name SOPT8 - System Options Register 8 */
+#define SIM_SOPT8_FTM0SYNCBIT_MASK (0x1U)
+#define SIM_SOPT8_FTM0SYNCBIT_SHIFT (0U)
+#define SIM_SOPT8_FTM0SYNCBIT(x) (((uint32_t)(((uint32_t)(x)) << SIM_SOPT8_FTM0SYNCBIT_SHIFT)) & SIM_SOPT8_FTM0SYNCBIT_MASK)
+#define SIM_SOPT8_FTM1SYNCBIT_MASK (0x2U)
+#define SIM_SOPT8_FTM1SYNCBIT_SHIFT (1U)
+#define SIM_SOPT8_FTM1SYNCBIT(x) (((uint32_t)(((uint32_t)(x)) << SIM_SOPT8_FTM1SYNCBIT_SHIFT)) & SIM_SOPT8_FTM1SYNCBIT_MASK)
+#define SIM_SOPT8_FTM2SYNCBIT_MASK (0x4U)
+#define SIM_SOPT8_FTM2SYNCBIT_SHIFT (2U)
+#define SIM_SOPT8_FTM2SYNCBIT(x) (((uint32_t)(((uint32_t)(x)) << SIM_SOPT8_FTM2SYNCBIT_SHIFT)) & SIM_SOPT8_FTM2SYNCBIT_MASK)
+#define SIM_SOPT8_FTM0OCH0SRC_MASK (0x10000U)
+#define SIM_SOPT8_FTM0OCH0SRC_SHIFT (16U)
+#define SIM_SOPT8_FTM0OCH0SRC(x) (((uint32_t)(((uint32_t)(x)) << SIM_SOPT8_FTM0OCH0SRC_SHIFT)) & SIM_SOPT8_FTM0OCH0SRC_MASK)
+#define SIM_SOPT8_FTM0OCH1SRC_MASK (0x20000U)
+#define SIM_SOPT8_FTM0OCH1SRC_SHIFT (17U)
+#define SIM_SOPT8_FTM0OCH1SRC(x) (((uint32_t)(((uint32_t)(x)) << SIM_SOPT8_FTM0OCH1SRC_SHIFT)) & SIM_SOPT8_FTM0OCH1SRC_MASK)
+#define SIM_SOPT8_FTM0OCH2SRC_MASK (0x40000U)
+#define SIM_SOPT8_FTM0OCH2SRC_SHIFT (18U)
+#define SIM_SOPT8_FTM0OCH2SRC(x) (((uint32_t)(((uint32_t)(x)) << SIM_SOPT8_FTM0OCH2SRC_SHIFT)) & SIM_SOPT8_FTM0OCH2SRC_MASK)
+#define SIM_SOPT8_FTM0OCH3SRC_MASK (0x80000U)
+#define SIM_SOPT8_FTM0OCH3SRC_SHIFT (19U)
+#define SIM_SOPT8_FTM0OCH3SRC(x) (((uint32_t)(((uint32_t)(x)) << SIM_SOPT8_FTM0OCH3SRC_SHIFT)) & SIM_SOPT8_FTM0OCH3SRC_MASK)
+#define SIM_SOPT8_FTM0OCH4SRC_MASK (0x100000U)
+#define SIM_SOPT8_FTM0OCH4SRC_SHIFT (20U)
+#define SIM_SOPT8_FTM0OCH4SRC(x) (((uint32_t)(((uint32_t)(x)) << SIM_SOPT8_FTM0OCH4SRC_SHIFT)) & SIM_SOPT8_FTM0OCH4SRC_MASK)
+#define SIM_SOPT8_FTM0OCH5SRC_MASK (0x200000U)
+#define SIM_SOPT8_FTM0OCH5SRC_SHIFT (21U)
+#define SIM_SOPT8_FTM0OCH5SRC(x) (((uint32_t)(((uint32_t)(x)) << SIM_SOPT8_FTM0OCH5SRC_SHIFT)) & SIM_SOPT8_FTM0OCH5SRC_MASK)
+
+/*! @name SDID - System Device Identification Register */
+#define SIM_SDID_PINID_MASK (0xFU)
+#define SIM_SDID_PINID_SHIFT (0U)
+#define SIM_SDID_PINID(x) (((uint32_t)(((uint32_t)(x)) << SIM_SDID_PINID_SHIFT)) & SIM_SDID_PINID_MASK)
+#define SIM_SDID_FAMID_MASK (0x70U)
+#define SIM_SDID_FAMID_SHIFT (4U)
+#define SIM_SDID_FAMID(x) (((uint32_t)(((uint32_t)(x)) << SIM_SDID_FAMID_SHIFT)) & SIM_SDID_FAMID_MASK)
+#define SIM_SDID_DIEID_MASK (0xF80U)
+#define SIM_SDID_DIEID_SHIFT (7U)
+#define SIM_SDID_DIEID(x) (((uint32_t)(((uint32_t)(x)) << SIM_SDID_DIEID_SHIFT)) & SIM_SDID_DIEID_MASK)
+#define SIM_SDID_REVID_MASK (0xF000U)
+#define SIM_SDID_REVID_SHIFT (12U)
+#define SIM_SDID_REVID(x) (((uint32_t)(((uint32_t)(x)) << SIM_SDID_REVID_SHIFT)) & SIM_SDID_REVID_MASK)
+#define SIM_SDID_SERIESID_MASK (0xF00000U)
+#define SIM_SDID_SERIESID_SHIFT (20U)
+#define SIM_SDID_SERIESID(x) (((uint32_t)(((uint32_t)(x)) << SIM_SDID_SERIESID_SHIFT)) & SIM_SDID_SERIESID_MASK)
+#define SIM_SDID_SUBFAMID_MASK (0xF000000U)
+#define SIM_SDID_SUBFAMID_SHIFT (24U)
+#define SIM_SDID_SUBFAMID(x) (((uint32_t)(((uint32_t)(x)) << SIM_SDID_SUBFAMID_SHIFT)) & SIM_SDID_SUBFAMID_MASK)
+#define SIM_SDID_FAMILYID_MASK (0xF0000000U)
+#define SIM_SDID_FAMILYID_SHIFT (28U)
+#define SIM_SDID_FAMILYID(x) (((uint32_t)(((uint32_t)(x)) << SIM_SDID_FAMILYID_SHIFT)) & SIM_SDID_FAMILYID_MASK)
+
+/*! @name SCGC4 - System Clock Gating Control Register 4 */
+#define SIM_SCGC4_EWM_MASK (0x2U)
+#define SIM_SCGC4_EWM_SHIFT (1U)
+#define SIM_SCGC4_EWM(x) (((uint32_t)(((uint32_t)(x)) << SIM_SCGC4_EWM_SHIFT)) & SIM_SCGC4_EWM_MASK)
+#define SIM_SCGC4_I2C0_MASK (0x40U)
+#define SIM_SCGC4_I2C0_SHIFT (6U)
+#define SIM_SCGC4_I2C0(x) (((uint32_t)(((uint32_t)(x)) << SIM_SCGC4_I2C0_SHIFT)) & SIM_SCGC4_I2C0_MASK)
+#define SIM_SCGC4_UART0_MASK (0x400U)
+#define SIM_SCGC4_UART0_SHIFT (10U)
+#define SIM_SCGC4_UART0(x) (((uint32_t)(((uint32_t)(x)) << SIM_SCGC4_UART0_SHIFT)) & SIM_SCGC4_UART0_MASK)
+#define SIM_SCGC4_UART1_MASK (0x800U)
+#define SIM_SCGC4_UART1_SHIFT (11U)
+#define SIM_SCGC4_UART1(x) (((uint32_t)(((uint32_t)(x)) << SIM_SCGC4_UART1_SHIFT)) & SIM_SCGC4_UART1_MASK)
+#define SIM_SCGC4_CMP_MASK (0x80000U)
+#define SIM_SCGC4_CMP_SHIFT (19U)
+#define SIM_SCGC4_CMP(x) (((uint32_t)(((uint32_t)(x)) << SIM_SCGC4_CMP_SHIFT)) & SIM_SCGC4_CMP_MASK)
+#define SIM_SCGC4_VREF_MASK (0x100000U)
+#define SIM_SCGC4_VREF_SHIFT (20U)
+#define SIM_SCGC4_VREF(x) (((uint32_t)(((uint32_t)(x)) << SIM_SCGC4_VREF_SHIFT)) & SIM_SCGC4_VREF_MASK)
+
+/*! @name SCGC5 - System Clock Gating Control Register 5 */
+#define SIM_SCGC5_LPTMR_MASK (0x1U)
+#define SIM_SCGC5_LPTMR_SHIFT (0U)
+#define SIM_SCGC5_LPTMR(x) (((uint32_t)(((uint32_t)(x)) << SIM_SCGC5_LPTMR_SHIFT)) & SIM_SCGC5_LPTMR_MASK)
+#define SIM_SCGC5_PORTA_MASK (0x200U)
+#define SIM_SCGC5_PORTA_SHIFT (9U)
+#define SIM_SCGC5_PORTA(x) (((uint32_t)(((uint32_t)(x)) << SIM_SCGC5_PORTA_SHIFT)) & SIM_SCGC5_PORTA_MASK)
+#define SIM_SCGC5_PORTB_MASK (0x400U)
+#define SIM_SCGC5_PORTB_SHIFT (10U)
+#define SIM_SCGC5_PORTB(x) (((uint32_t)(((uint32_t)(x)) << SIM_SCGC5_PORTB_SHIFT)) & SIM_SCGC5_PORTB_MASK)
+#define SIM_SCGC5_PORTC_MASK (0x800U)
+#define SIM_SCGC5_PORTC_SHIFT (11U)
+#define SIM_SCGC5_PORTC(x) (((uint32_t)(((uint32_t)(x)) << SIM_SCGC5_PORTC_SHIFT)) & SIM_SCGC5_PORTC_MASK)
+#define SIM_SCGC5_PORTD_MASK (0x1000U)
+#define SIM_SCGC5_PORTD_SHIFT (12U)
+#define SIM_SCGC5_PORTD(x) (((uint32_t)(((uint32_t)(x)) << SIM_SCGC5_PORTD_SHIFT)) & SIM_SCGC5_PORTD_MASK)
+#define SIM_SCGC5_PORTE_MASK (0x2000U)
+#define SIM_SCGC5_PORTE_SHIFT (13U)
+#define SIM_SCGC5_PORTE(x) (((uint32_t)(((uint32_t)(x)) << SIM_SCGC5_PORTE_SHIFT)) & SIM_SCGC5_PORTE_MASK)
+
+/*! @name SCGC6 - System Clock Gating Control Register 6 */
+#define SIM_SCGC6_FTF_MASK (0x1U)
+#define SIM_SCGC6_FTF_SHIFT (0U)
+#define SIM_SCGC6_FTF(x) (((uint32_t)(((uint32_t)(x)) << SIM_SCGC6_FTF_SHIFT)) & SIM_SCGC6_FTF_MASK)
+#define SIM_SCGC6_DMAMUX_MASK (0x2U)
+#define SIM_SCGC6_DMAMUX_SHIFT (1U)
+#define SIM_SCGC6_DMAMUX(x) (((uint32_t)(((uint32_t)(x)) << SIM_SCGC6_DMAMUX_SHIFT)) & SIM_SCGC6_DMAMUX_MASK)
+#define SIM_SCGC6_SPI0_MASK (0x1000U)
+#define SIM_SCGC6_SPI0_SHIFT (12U)
+#define SIM_SCGC6_SPI0(x) (((uint32_t)(((uint32_t)(x)) << SIM_SCGC6_SPI0_SHIFT)) & SIM_SCGC6_SPI0_MASK)
+#define SIM_SCGC6_CRC_MASK (0x40000U)
+#define SIM_SCGC6_CRC_SHIFT (18U)
+#define SIM_SCGC6_CRC(x) (((uint32_t)(((uint32_t)(x)) << SIM_SCGC6_CRC_SHIFT)) & SIM_SCGC6_CRC_MASK)
+#define SIM_SCGC6_PDB_MASK (0x400000U)
+#define SIM_SCGC6_PDB_SHIFT (22U)
+#define SIM_SCGC6_PDB(x) (((uint32_t)(((uint32_t)(x)) << SIM_SCGC6_PDB_SHIFT)) & SIM_SCGC6_PDB_MASK)
+#define SIM_SCGC6_PIT_MASK (0x800000U)
+#define SIM_SCGC6_PIT_SHIFT (23U)
+#define SIM_SCGC6_PIT(x) (((uint32_t)(((uint32_t)(x)) << SIM_SCGC6_PIT_SHIFT)) & SIM_SCGC6_PIT_MASK)
+#define SIM_SCGC6_FTM0_MASK (0x1000000U)
+#define SIM_SCGC6_FTM0_SHIFT (24U)
+#define SIM_SCGC6_FTM0(x) (((uint32_t)(((uint32_t)(x)) << SIM_SCGC6_FTM0_SHIFT)) & SIM_SCGC6_FTM0_MASK)
+#define SIM_SCGC6_FTM1_MASK (0x2000000U)
+#define SIM_SCGC6_FTM1_SHIFT (25U)
+#define SIM_SCGC6_FTM1(x) (((uint32_t)(((uint32_t)(x)) << SIM_SCGC6_FTM1_SHIFT)) & SIM_SCGC6_FTM1_MASK)
+#define SIM_SCGC6_FTM2_MASK (0x4000000U)
+#define SIM_SCGC6_FTM2_SHIFT (26U)
+#define SIM_SCGC6_FTM2(x) (((uint32_t)(((uint32_t)(x)) << SIM_SCGC6_FTM2_SHIFT)) & SIM_SCGC6_FTM2_MASK)
+#define SIM_SCGC6_ADC0_MASK (0x8000000U)
+#define SIM_SCGC6_ADC0_SHIFT (27U)
+#define SIM_SCGC6_ADC0(x) (((uint32_t)(((uint32_t)(x)) << SIM_SCGC6_ADC0_SHIFT)) & SIM_SCGC6_ADC0_MASK)
+#define SIM_SCGC6_DAC0_MASK (0x80000000U)
+#define SIM_SCGC6_DAC0_SHIFT (31U)
+#define SIM_SCGC6_DAC0(x) (((uint32_t)(((uint32_t)(x)) << SIM_SCGC6_DAC0_SHIFT)) & SIM_SCGC6_DAC0_MASK)
+
+/*! @name SCGC7 - System Clock Gating Control Register 7 */
+#define SIM_SCGC7_DMA_MASK (0x2U)
+#define SIM_SCGC7_DMA_SHIFT (1U)
+#define SIM_SCGC7_DMA(x) (((uint32_t)(((uint32_t)(x)) << SIM_SCGC7_DMA_SHIFT)) & SIM_SCGC7_DMA_MASK)
+
+/*! @name CLKDIV1 - System Clock Divider Register 1 */
+#define SIM_CLKDIV1_OUTDIV4_MASK (0xF0000U)
+#define SIM_CLKDIV1_OUTDIV4_SHIFT (16U)
+#define SIM_CLKDIV1_OUTDIV4(x) (((uint32_t)(((uint32_t)(x)) << SIM_CLKDIV1_OUTDIV4_SHIFT)) & SIM_CLKDIV1_OUTDIV4_MASK)
+#define SIM_CLKDIV1_OUTDIV2_MASK (0xF000000U)
+#define SIM_CLKDIV1_OUTDIV2_SHIFT (24U)
+#define SIM_CLKDIV1_OUTDIV2(x) (((uint32_t)(((uint32_t)(x)) << SIM_CLKDIV1_OUTDIV2_SHIFT)) & SIM_CLKDIV1_OUTDIV2_MASK)
+#define SIM_CLKDIV1_OUTDIV1_MASK (0xF0000000U)
+#define SIM_CLKDIV1_OUTDIV1_SHIFT (28U)
+#define SIM_CLKDIV1_OUTDIV1(x) (((uint32_t)(((uint32_t)(x)) << SIM_CLKDIV1_OUTDIV1_SHIFT)) & SIM_CLKDIV1_OUTDIV1_MASK)
+
+/*! @name FCFG1 - Flash Configuration Register 1 */
+#define SIM_FCFG1_FLASHDIS_MASK (0x1U)
+#define SIM_FCFG1_FLASHDIS_SHIFT (0U)
+#define SIM_FCFG1_FLASHDIS(x) (((uint32_t)(((uint32_t)(x)) << SIM_FCFG1_FLASHDIS_SHIFT)) & SIM_FCFG1_FLASHDIS_MASK)
+#define SIM_FCFG1_FLASHDOZE_MASK (0x2U)
+#define SIM_FCFG1_FLASHDOZE_SHIFT (1U)
+#define SIM_FCFG1_FLASHDOZE(x) (((uint32_t)(((uint32_t)(x)) << SIM_FCFG1_FLASHDOZE_SHIFT)) & SIM_FCFG1_FLASHDOZE_MASK)
+#define SIM_FCFG1_PFSIZE_MASK (0xF000000U)
+#define SIM_FCFG1_PFSIZE_SHIFT (24U)
+#define SIM_FCFG1_PFSIZE(x) (((uint32_t)(((uint32_t)(x)) << SIM_FCFG1_PFSIZE_SHIFT)) & SIM_FCFG1_PFSIZE_MASK)
+
+/*! @name FCFG2 - Flash Configuration Register 2 */
+#define SIM_FCFG2_MAXADDR0_MASK (0x7F000000U)
+#define SIM_FCFG2_MAXADDR0_SHIFT (24U)
+#define SIM_FCFG2_MAXADDR0(x) (((uint32_t)(((uint32_t)(x)) << SIM_FCFG2_MAXADDR0_SHIFT)) & SIM_FCFG2_MAXADDR0_MASK)
+
+/*! @name UIDH - Unique Identification Register High */
+#define SIM_UIDH_UID_MASK (0xFFFFFFFFU)
+#define SIM_UIDH_UID_SHIFT (0U)
+#define SIM_UIDH_UID(x) (((uint32_t)(((uint32_t)(x)) << SIM_UIDH_UID_SHIFT)) & SIM_UIDH_UID_MASK)
+
+/*! @name UIDMH - Unique Identification Register Mid-High */
+#define SIM_UIDMH_UID_MASK (0xFFFFFFFFU)
+#define SIM_UIDMH_UID_SHIFT (0U)
+#define SIM_UIDMH_UID(x) (((uint32_t)(((uint32_t)(x)) << SIM_UIDMH_UID_SHIFT)) & SIM_UIDMH_UID_MASK)
+
+/*! @name UIDML - Unique Identification Register Mid Low */
+#define SIM_UIDML_UID_MASK (0xFFFFFFFFU)
+#define SIM_UIDML_UID_SHIFT (0U)
+#define SIM_UIDML_UID(x) (((uint32_t)(((uint32_t)(x)) << SIM_UIDML_UID_SHIFT)) & SIM_UIDML_UID_MASK)
+
+/*! @name UIDL - Unique Identification Register Low */
+#define SIM_UIDL_UID_MASK (0xFFFFFFFFU)
+#define SIM_UIDL_UID_SHIFT (0U)
+#define SIM_UIDL_UID(x) (((uint32_t)(((uint32_t)(x)) << SIM_UIDL_UID_SHIFT)) & SIM_UIDL_UID_MASK)
+
+
+/*!
+ * @}
+ */ /* end of group SIM_Register_Masks */
+
+
+/* SIM - Peripheral instance base addresses */
+/** Peripheral SIM base address */
+#define SIM_BASE (0x40047000u)
+/** Peripheral SIM base pointer */
+#define SIM ((SIM_Type *)SIM_BASE)
+/** Array initializer of SIM peripheral base addresses */
+#define SIM_BASE_ADDRS { SIM_BASE }
+/** Array initializer of SIM peripheral base pointers */
+#define SIM_BASE_PTRS { SIM }
+
+/*!
+ * @}
+ */ /* end of group SIM_Peripheral_Access_Layer */
+
+
+/* ----------------------------------------------------------------------------
+ -- SMC Peripheral Access Layer
+ ---------------------------------------------------------------------------- */
+
+/*!
+ * @addtogroup SMC_Peripheral_Access_Layer SMC Peripheral Access Layer
+ * @{
+ */
+
+/** SMC - Register Layout Typedef */
+typedef struct {
+ __IO uint8_t PMPROT; /**< Power Mode Protection register, offset: 0x0 */
+ __IO uint8_t PMCTRL; /**< Power Mode Control register, offset: 0x1 */
+ __IO uint8_t STOPCTRL; /**< Stop Control Register, offset: 0x2 */
+ __I uint8_t PMSTAT; /**< Power Mode Status register, offset: 0x3 */
+} SMC_Type;
+
+/* ----------------------------------------------------------------------------
+ -- SMC Register Masks
+ ---------------------------------------------------------------------------- */
+
+/*!
+ * @addtogroup SMC_Register_Masks SMC Register Masks
+ * @{
+ */
+
+/*! @name PMPROT - Power Mode Protection register */
+#define SMC_PMPROT_AVLLS_MASK (0x2U)
+#define SMC_PMPROT_AVLLS_SHIFT (1U)
+#define SMC_PMPROT_AVLLS(x) (((uint8_t)(((uint8_t)(x)) << SMC_PMPROT_AVLLS_SHIFT)) & SMC_PMPROT_AVLLS_MASK)
+#define SMC_PMPROT_ALLS_MASK (0x8U)
+#define SMC_PMPROT_ALLS_SHIFT (3U)
+#define SMC_PMPROT_ALLS(x) (((uint8_t)(((uint8_t)(x)) << SMC_PMPROT_ALLS_SHIFT)) & SMC_PMPROT_ALLS_MASK)
+#define SMC_PMPROT_AVLP_MASK (0x20U)
+#define SMC_PMPROT_AVLP_SHIFT (5U)
+#define SMC_PMPROT_AVLP(x) (((uint8_t)(((uint8_t)(x)) << SMC_PMPROT_AVLP_SHIFT)) & SMC_PMPROT_AVLP_MASK)
+#define SMC_PMPROT_AHSRUN_MASK (0x80U)
+#define SMC_PMPROT_AHSRUN_SHIFT (7U)
+#define SMC_PMPROT_AHSRUN(x) (((uint8_t)(((uint8_t)(x)) << SMC_PMPROT_AHSRUN_SHIFT)) & SMC_PMPROT_AHSRUN_MASK)
+
+/*! @name PMCTRL - Power Mode Control register */
+#define SMC_PMCTRL_STOPM_MASK (0x7U)
+#define SMC_PMCTRL_STOPM_SHIFT (0U)
+#define SMC_PMCTRL_STOPM(x) (((uint8_t)(((uint8_t)(x)) << SMC_PMCTRL_STOPM_SHIFT)) & SMC_PMCTRL_STOPM_MASK)
+#define SMC_PMCTRL_STOPA_MASK (0x8U)
+#define SMC_PMCTRL_STOPA_SHIFT (3U)
+#define SMC_PMCTRL_STOPA(x) (((uint8_t)(((uint8_t)(x)) << SMC_PMCTRL_STOPA_SHIFT)) & SMC_PMCTRL_STOPA_MASK)
+#define SMC_PMCTRL_RUNM_MASK (0x60U)
+#define SMC_PMCTRL_RUNM_SHIFT (5U)
+#define SMC_PMCTRL_RUNM(x) (((uint8_t)(((uint8_t)(x)) << SMC_PMCTRL_RUNM_SHIFT)) & SMC_PMCTRL_RUNM_MASK)
+
+/*! @name STOPCTRL - Stop Control Register */
+#define SMC_STOPCTRL_LLSM_MASK (0x7U)
+#define SMC_STOPCTRL_LLSM_SHIFT (0U)
+#define SMC_STOPCTRL_LLSM(x) (((uint8_t)(((uint8_t)(x)) << SMC_STOPCTRL_LLSM_SHIFT)) & SMC_STOPCTRL_LLSM_MASK)
+#define SMC_STOPCTRL_PORPO_MASK (0x20U)
+#define SMC_STOPCTRL_PORPO_SHIFT (5U)
+#define SMC_STOPCTRL_PORPO(x) (((uint8_t)(((uint8_t)(x)) << SMC_STOPCTRL_PORPO_SHIFT)) & SMC_STOPCTRL_PORPO_MASK)
+#define SMC_STOPCTRL_PSTOPO_MASK (0xC0U)
+#define SMC_STOPCTRL_PSTOPO_SHIFT (6U)
+#define SMC_STOPCTRL_PSTOPO(x) (((uint8_t)(((uint8_t)(x)) << SMC_STOPCTRL_PSTOPO_SHIFT)) & SMC_STOPCTRL_PSTOPO_MASK)
+
+/*! @name PMSTAT - Power Mode Status register */
+#define SMC_PMSTAT_PMSTAT_MASK (0xFFU)
+#define SMC_PMSTAT_PMSTAT_SHIFT (0U)
+#define SMC_PMSTAT_PMSTAT(x) (((uint8_t)(((uint8_t)(x)) << SMC_PMSTAT_PMSTAT_SHIFT)) & SMC_PMSTAT_PMSTAT_MASK)
+
+
+/*!
+ * @}
+ */ /* end of group SMC_Register_Masks */
+
+
+/* SMC - Peripheral instance base addresses */
+/** Peripheral SMC base address */
+#define SMC_BASE (0x4007E000u)
+/** Peripheral SMC base pointer */
+#define SMC ((SMC_Type *)SMC_BASE)
+/** Array initializer of SMC peripheral base addresses */
+#define SMC_BASE_ADDRS { SMC_BASE }
+/** Array initializer of SMC peripheral base pointers */
+#define SMC_BASE_PTRS { SMC }
+
+/*!
+ * @}
+ */ /* end of group SMC_Peripheral_Access_Layer */
+
+
+/* ----------------------------------------------------------------------------
+ -- SPI Peripheral Access Layer
+ ---------------------------------------------------------------------------- */
+
+/*!
+ * @addtogroup SPI_Peripheral_Access_Layer SPI Peripheral Access Layer
+ * @{
+ */
+
+/** SPI - Register Layout Typedef */
+typedef struct {
+ __IO uint32_t MCR; /**< Module Configuration Register, offset: 0x0 */
+ uint8_t RESERVED_0[4];
+ __IO uint32_t TCR; /**< Transfer Count Register, offset: 0x8 */
+ union { /* offset: 0xC */
+ __IO uint32_t CTAR[2]; /**< Clock and Transfer Attributes Register (In Master Mode), array offset: 0xC, array step: 0x4 */
+ __IO uint32_t CTAR_SLAVE[1]; /**< Clock and Transfer Attributes Register (In Slave Mode), array offset: 0xC, array step: 0x4 */
+ };
+ uint8_t RESERVED_1[24];
+ __IO uint32_t SR; /**< Status Register, offset: 0x2C */
+ __IO uint32_t RSER; /**< DMA/Interrupt Request Select and Enable Register, offset: 0x30 */
+ union { /* offset: 0x34 */
+ __IO uint32_t PUSHR; /**< PUSH TX FIFO Register In Master Mode, offset: 0x34 */
+ __IO uint32_t PUSHR_SLAVE; /**< PUSH TX FIFO Register In Slave Mode, offset: 0x34 */
+ };
+ __I uint32_t POPR; /**< POP RX FIFO Register, offset: 0x38 */
+ __I uint32_t TXFR0; /**< Transmit FIFO Registers, offset: 0x3C */
+ __I uint32_t TXFR1; /**< Transmit FIFO Registers, offset: 0x40 */
+ __I uint32_t TXFR2; /**< Transmit FIFO Registers, offset: 0x44 */
+ __I uint32_t TXFR3; /**< Transmit FIFO Registers, offset: 0x48 */
+ uint8_t RESERVED_2[48];
+ __I uint32_t RXFR0; /**< Receive FIFO Registers, offset: 0x7C */
+ __I uint32_t RXFR1; /**< Receive FIFO Registers, offset: 0x80 */
+ __I uint32_t RXFR2; /**< Receive FIFO Registers, offset: 0x84 */
+ __I uint32_t RXFR3; /**< Receive FIFO Registers, offset: 0x88 */
+} SPI_Type;
+
+/* ----------------------------------------------------------------------------
+ -- SPI Register Masks
+ ---------------------------------------------------------------------------- */
+
+/*!
+ * @addtogroup SPI_Register_Masks SPI Register Masks
+ * @{
+ */
+
+/*! @name MCR - Module Configuration Register */
+#define SPI_MCR_HALT_MASK (0x1U)
+#define SPI_MCR_HALT_SHIFT (0U)
+#define SPI_MCR_HALT(x) (((uint32_t)(((uint32_t)(x)) << SPI_MCR_HALT_SHIFT)) & SPI_MCR_HALT_MASK)
+#define SPI_MCR_SMPL_PT_MASK (0x300U)
+#define SPI_MCR_SMPL_PT_SHIFT (8U)
+#define SPI_MCR_SMPL_PT(x) (((uint32_t)(((uint32_t)(x)) << SPI_MCR_SMPL_PT_SHIFT)) & SPI_MCR_SMPL_PT_MASK)
+#define SPI_MCR_CLR_RXF_MASK (0x400U)
+#define SPI_MCR_CLR_RXF_SHIFT (10U)
+#define SPI_MCR_CLR_RXF(x) (((uint32_t)(((uint32_t)(x)) << SPI_MCR_CLR_RXF_SHIFT)) & SPI_MCR_CLR_RXF_MASK)
+#define SPI_MCR_CLR_TXF_MASK (0x800U)
+#define SPI_MCR_CLR_TXF_SHIFT (11U)
+#define SPI_MCR_CLR_TXF(x) (((uint32_t)(((uint32_t)(x)) << SPI_MCR_CLR_TXF_SHIFT)) & SPI_MCR_CLR_TXF_MASK)
+#define SPI_MCR_DIS_RXF_MASK (0x1000U)
+#define SPI_MCR_DIS_RXF_SHIFT (12U)
+#define SPI_MCR_DIS_RXF(x) (((uint32_t)(((uint32_t)(x)) << SPI_MCR_DIS_RXF_SHIFT)) & SPI_MCR_DIS_RXF_MASK)
+#define SPI_MCR_DIS_TXF_MASK (0x2000U)
+#define SPI_MCR_DIS_TXF_SHIFT (13U)
+#define SPI_MCR_DIS_TXF(x) (((uint32_t)(((uint32_t)(x)) << SPI_MCR_DIS_TXF_SHIFT)) & SPI_MCR_DIS_TXF_MASK)
+#define SPI_MCR_MDIS_MASK (0x4000U)
+#define SPI_MCR_MDIS_SHIFT (14U)
+#define SPI_MCR_MDIS(x) (((uint32_t)(((uint32_t)(x)) << SPI_MCR_MDIS_SHIFT)) & SPI_MCR_MDIS_MASK)
+#define SPI_MCR_DOZE_MASK (0x8000U)
+#define SPI_MCR_DOZE_SHIFT (15U)
+#define SPI_MCR_DOZE(x) (((uint32_t)(((uint32_t)(x)) << SPI_MCR_DOZE_SHIFT)) & SPI_MCR_DOZE_MASK)
+#define SPI_MCR_PCSIS_MASK (0x3F0000U)
+#define SPI_MCR_PCSIS_SHIFT (16U)
+#define SPI_MCR_PCSIS(x) (((uint32_t)(((uint32_t)(x)) << SPI_MCR_PCSIS_SHIFT)) & SPI_MCR_PCSIS_MASK)
+#define SPI_MCR_ROOE_MASK (0x1000000U)
+#define SPI_MCR_ROOE_SHIFT (24U)
+#define SPI_MCR_ROOE(x) (((uint32_t)(((uint32_t)(x)) << SPI_MCR_ROOE_SHIFT)) & SPI_MCR_ROOE_MASK)
+#define SPI_MCR_PCSSE_MASK (0x2000000U)
+#define SPI_MCR_PCSSE_SHIFT (25U)
+#define SPI_MCR_PCSSE(x) (((uint32_t)(((uint32_t)(x)) << SPI_MCR_PCSSE_SHIFT)) & SPI_MCR_PCSSE_MASK)
+#define SPI_MCR_MTFE_MASK (0x4000000U)
+#define SPI_MCR_MTFE_SHIFT (26U)
+#define SPI_MCR_MTFE(x) (((uint32_t)(((uint32_t)(x)) << SPI_MCR_MTFE_SHIFT)) & SPI_MCR_MTFE_MASK)
+#define SPI_MCR_FRZ_MASK (0x8000000U)
+#define SPI_MCR_FRZ_SHIFT (27U)
+#define SPI_MCR_FRZ(x) (((uint32_t)(((uint32_t)(x)) << SPI_MCR_FRZ_SHIFT)) & SPI_MCR_FRZ_MASK)
+#define SPI_MCR_DCONF_MASK (0x30000000U)
+#define SPI_MCR_DCONF_SHIFT (28U)
+#define SPI_MCR_DCONF(x) (((uint32_t)(((uint32_t)(x)) << SPI_MCR_DCONF_SHIFT)) & SPI_MCR_DCONF_MASK)
+#define SPI_MCR_CONT_SCKE_MASK (0x40000000U)
+#define SPI_MCR_CONT_SCKE_SHIFT (30U)
+#define SPI_MCR_CONT_SCKE(x) (((uint32_t)(((uint32_t)(x)) << SPI_MCR_CONT_SCKE_SHIFT)) & SPI_MCR_CONT_SCKE_MASK)
+#define SPI_MCR_MSTR_MASK (0x80000000U)
+#define SPI_MCR_MSTR_SHIFT (31U)
+#define SPI_MCR_MSTR(x) (((uint32_t)(((uint32_t)(x)) << SPI_MCR_MSTR_SHIFT)) & SPI_MCR_MSTR_MASK)
+
+/*! @name TCR - Transfer Count Register */
+#define SPI_TCR_SPI_TCNT_MASK (0xFFFF0000U)
+#define SPI_TCR_SPI_TCNT_SHIFT (16U)
+#define SPI_TCR_SPI_TCNT(x) (((uint32_t)(((uint32_t)(x)) << SPI_TCR_SPI_TCNT_SHIFT)) & SPI_TCR_SPI_TCNT_MASK)
+
+/*! @name CTAR - Clock and Transfer Attributes Register (In Master Mode) */
+#define SPI_CTAR_BR_MASK (0xFU)
+#define SPI_CTAR_BR_SHIFT (0U)
+#define SPI_CTAR_BR(x) (((uint32_t)(((uint32_t)(x)) << SPI_CTAR_BR_SHIFT)) & SPI_CTAR_BR_MASK)
+#define SPI_CTAR_DT_MASK (0xF0U)
+#define SPI_CTAR_DT_SHIFT (4U)
+#define SPI_CTAR_DT(x) (((uint32_t)(((uint32_t)(x)) << SPI_CTAR_DT_SHIFT)) & SPI_CTAR_DT_MASK)
+#define SPI_CTAR_ASC_MASK (0xF00U)
+#define SPI_CTAR_ASC_SHIFT (8U)
+#define SPI_CTAR_ASC(x) (((uint32_t)(((uint32_t)(x)) << SPI_CTAR_ASC_SHIFT)) & SPI_CTAR_ASC_MASK)
+#define SPI_CTAR_CSSCK_MASK (0xF000U)
+#define SPI_CTAR_CSSCK_SHIFT (12U)
+#define SPI_CTAR_CSSCK(x) (((uint32_t)(((uint32_t)(x)) << SPI_CTAR_CSSCK_SHIFT)) & SPI_CTAR_CSSCK_MASK)
+#define SPI_CTAR_PBR_MASK (0x30000U)
+#define SPI_CTAR_PBR_SHIFT (16U)
+#define SPI_CTAR_PBR(x) (((uint32_t)(((uint32_t)(x)) << SPI_CTAR_PBR_SHIFT)) & SPI_CTAR_PBR_MASK)
+#define SPI_CTAR_PDT_MASK (0xC0000U)
+#define SPI_CTAR_PDT_SHIFT (18U)
+#define SPI_CTAR_PDT(x) (((uint32_t)(((uint32_t)(x)) << SPI_CTAR_PDT_SHIFT)) & SPI_CTAR_PDT_MASK)
+#define SPI_CTAR_PASC_MASK (0x300000U)
+#define SPI_CTAR_PASC_SHIFT (20U)
+#define SPI_CTAR_PASC(x) (((uint32_t)(((uint32_t)(x)) << SPI_CTAR_PASC_SHIFT)) & SPI_CTAR_PASC_MASK)
+#define SPI_CTAR_PCSSCK_MASK (0xC00000U)
+#define SPI_CTAR_PCSSCK_SHIFT (22U)
+#define SPI_CTAR_PCSSCK(x) (((uint32_t)(((uint32_t)(x)) << SPI_CTAR_PCSSCK_SHIFT)) & SPI_CTAR_PCSSCK_MASK)
+#define SPI_CTAR_LSBFE_MASK (0x1000000U)
+#define SPI_CTAR_LSBFE_SHIFT (24U)
+#define SPI_CTAR_LSBFE(x) (((uint32_t)(((uint32_t)(x)) << SPI_CTAR_LSBFE_SHIFT)) & SPI_CTAR_LSBFE_MASK)
+#define SPI_CTAR_CPHA_MASK (0x2000000U)
+#define SPI_CTAR_CPHA_SHIFT (25U)
+#define SPI_CTAR_CPHA(x) (((uint32_t)(((uint32_t)(x)) << SPI_CTAR_CPHA_SHIFT)) & SPI_CTAR_CPHA_MASK)
+#define SPI_CTAR_CPOL_MASK (0x4000000U)
+#define SPI_CTAR_CPOL_SHIFT (26U)
+#define SPI_CTAR_CPOL(x) (((uint32_t)(((uint32_t)(x)) << SPI_CTAR_CPOL_SHIFT)) & SPI_CTAR_CPOL_MASK)
+#define SPI_CTAR_FMSZ_MASK (0x78000000U)
+#define SPI_CTAR_FMSZ_SHIFT (27U)
+#define SPI_CTAR_FMSZ(x) (((uint32_t)(((uint32_t)(x)) << SPI_CTAR_FMSZ_SHIFT)) & SPI_CTAR_FMSZ_MASK)
+#define SPI_CTAR_DBR_MASK (0x80000000U)
+#define SPI_CTAR_DBR_SHIFT (31U)
+#define SPI_CTAR_DBR(x) (((uint32_t)(((uint32_t)(x)) << SPI_CTAR_DBR_SHIFT)) & SPI_CTAR_DBR_MASK)
+
+/* The count of SPI_CTAR */
+#define SPI_CTAR_COUNT (2U)
+
+/*! @name CTAR_SLAVE - Clock and Transfer Attributes Register (In Slave Mode) */
+#define SPI_CTAR_SLAVE_CPHA_MASK (0x2000000U)
+#define SPI_CTAR_SLAVE_CPHA_SHIFT (25U)
+#define SPI_CTAR_SLAVE_CPHA(x) (((uint32_t)(((uint32_t)(x)) << SPI_CTAR_SLAVE_CPHA_SHIFT)) & SPI_CTAR_SLAVE_CPHA_MASK)
+#define SPI_CTAR_SLAVE_CPOL_MASK (0x4000000U)
+#define SPI_CTAR_SLAVE_CPOL_SHIFT (26U)
+#define SPI_CTAR_SLAVE_CPOL(x) (((uint32_t)(((uint32_t)(x)) << SPI_CTAR_SLAVE_CPOL_SHIFT)) & SPI_CTAR_SLAVE_CPOL_MASK)
+#define SPI_CTAR_SLAVE_FMSZ_MASK (0xF8000000U)
+#define SPI_CTAR_SLAVE_FMSZ_SHIFT (27U)
+#define SPI_CTAR_SLAVE_FMSZ(x) (((uint32_t)(((uint32_t)(x)) << SPI_CTAR_SLAVE_FMSZ_SHIFT)) & SPI_CTAR_SLAVE_FMSZ_MASK)
+
+/* The count of SPI_CTAR_SLAVE */
+#define SPI_CTAR_SLAVE_COUNT (1U)
+
+/*! @name SR - Status Register */
+#define SPI_SR_POPNXTPTR_MASK (0xFU)
+#define SPI_SR_POPNXTPTR_SHIFT (0U)
+#define SPI_SR_POPNXTPTR(x) (((uint32_t)(((uint32_t)(x)) << SPI_SR_POPNXTPTR_SHIFT)) & SPI_SR_POPNXTPTR_MASK)
+#define SPI_SR_RXCTR_MASK (0xF0U)
+#define SPI_SR_RXCTR_SHIFT (4U)
+#define SPI_SR_RXCTR(x) (((uint32_t)(((uint32_t)(x)) << SPI_SR_RXCTR_SHIFT)) & SPI_SR_RXCTR_MASK)
+#define SPI_SR_TXNXTPTR_MASK (0xF00U)
+#define SPI_SR_TXNXTPTR_SHIFT (8U)
+#define SPI_SR_TXNXTPTR(x) (((uint32_t)(((uint32_t)(x)) << SPI_SR_TXNXTPTR_SHIFT)) & SPI_SR_TXNXTPTR_MASK)
+#define SPI_SR_TXCTR_MASK (0xF000U)
+#define SPI_SR_TXCTR_SHIFT (12U)
+#define SPI_SR_TXCTR(x) (((uint32_t)(((uint32_t)(x)) << SPI_SR_TXCTR_SHIFT)) & SPI_SR_TXCTR_MASK)
+#define SPI_SR_RFDF_MASK (0x20000U)
+#define SPI_SR_RFDF_SHIFT (17U)
+#define SPI_SR_RFDF(x) (((uint32_t)(((uint32_t)(x)) << SPI_SR_RFDF_SHIFT)) & SPI_SR_RFDF_MASK)
+#define SPI_SR_RFOF_MASK (0x80000U)
+#define SPI_SR_RFOF_SHIFT (19U)
+#define SPI_SR_RFOF(x) (((uint32_t)(((uint32_t)(x)) << SPI_SR_RFOF_SHIFT)) & SPI_SR_RFOF_MASK)
+#define SPI_SR_TFFF_MASK (0x2000000U)
+#define SPI_SR_TFFF_SHIFT (25U)
+#define SPI_SR_TFFF(x) (((uint32_t)(((uint32_t)(x)) << SPI_SR_TFFF_SHIFT)) & SPI_SR_TFFF_MASK)
+#define SPI_SR_TFUF_MASK (0x8000000U)
+#define SPI_SR_TFUF_SHIFT (27U)
+#define SPI_SR_TFUF(x) (((uint32_t)(((uint32_t)(x)) << SPI_SR_TFUF_SHIFT)) & SPI_SR_TFUF_MASK)
+#define SPI_SR_EOQF_MASK (0x10000000U)
+#define SPI_SR_EOQF_SHIFT (28U)
+#define SPI_SR_EOQF(x) (((uint32_t)(((uint32_t)(x)) << SPI_SR_EOQF_SHIFT)) & SPI_SR_EOQF_MASK)
+#define SPI_SR_TXRXS_MASK (0x40000000U)
+#define SPI_SR_TXRXS_SHIFT (30U)
+#define SPI_SR_TXRXS(x) (((uint32_t)(((uint32_t)(x)) << SPI_SR_TXRXS_SHIFT)) & SPI_SR_TXRXS_MASK)
+#define SPI_SR_TCF_MASK (0x80000000U)
+#define SPI_SR_TCF_SHIFT (31U)
+#define SPI_SR_TCF(x) (((uint32_t)(((uint32_t)(x)) << SPI_SR_TCF_SHIFT)) & SPI_SR_TCF_MASK)
+
+/*! @name RSER - DMA/Interrupt Request Select and Enable Register */
+#define SPI_RSER_RFDF_DIRS_MASK (0x10000U)
+#define SPI_RSER_RFDF_DIRS_SHIFT (16U)
+#define SPI_RSER_RFDF_DIRS(x) (((uint32_t)(((uint32_t)(x)) << SPI_RSER_RFDF_DIRS_SHIFT)) & SPI_RSER_RFDF_DIRS_MASK)
+#define SPI_RSER_RFDF_RE_MASK (0x20000U)
+#define SPI_RSER_RFDF_RE_SHIFT (17U)
+#define SPI_RSER_RFDF_RE(x) (((uint32_t)(((uint32_t)(x)) << SPI_RSER_RFDF_RE_SHIFT)) & SPI_RSER_RFDF_RE_MASK)
+#define SPI_RSER_RFOF_RE_MASK (0x80000U)
+#define SPI_RSER_RFOF_RE_SHIFT (19U)
+#define SPI_RSER_RFOF_RE(x) (((uint32_t)(((uint32_t)(x)) << SPI_RSER_RFOF_RE_SHIFT)) & SPI_RSER_RFOF_RE_MASK)
+#define SPI_RSER_TFFF_DIRS_MASK (0x1000000U)
+#define SPI_RSER_TFFF_DIRS_SHIFT (24U)
+#define SPI_RSER_TFFF_DIRS(x) (((uint32_t)(((uint32_t)(x)) << SPI_RSER_TFFF_DIRS_SHIFT)) & SPI_RSER_TFFF_DIRS_MASK)
+#define SPI_RSER_TFFF_RE_MASK (0x2000000U)
+#define SPI_RSER_TFFF_RE_SHIFT (25U)
+#define SPI_RSER_TFFF_RE(x) (((uint32_t)(((uint32_t)(x)) << SPI_RSER_TFFF_RE_SHIFT)) & SPI_RSER_TFFF_RE_MASK)
+#define SPI_RSER_TFUF_RE_MASK (0x8000000U)
+#define SPI_RSER_TFUF_RE_SHIFT (27U)
+#define SPI_RSER_TFUF_RE(x) (((uint32_t)(((uint32_t)(x)) << SPI_RSER_TFUF_RE_SHIFT)) & SPI_RSER_TFUF_RE_MASK)
+#define SPI_RSER_EOQF_RE_MASK (0x10000000U)
+#define SPI_RSER_EOQF_RE_SHIFT (28U)
+#define SPI_RSER_EOQF_RE(x) (((uint32_t)(((uint32_t)(x)) << SPI_RSER_EOQF_RE_SHIFT)) & SPI_RSER_EOQF_RE_MASK)
+#define SPI_RSER_TCF_RE_MASK (0x80000000U)
+#define SPI_RSER_TCF_RE_SHIFT (31U)
+#define SPI_RSER_TCF_RE(x) (((uint32_t)(((uint32_t)(x)) << SPI_RSER_TCF_RE_SHIFT)) & SPI_RSER_TCF_RE_MASK)
+
+/*! @name PUSHR - PUSH TX FIFO Register In Master Mode */
+#define SPI_PUSHR_TXDATA_MASK (0xFFFFU)
+#define SPI_PUSHR_TXDATA_SHIFT (0U)
+#define SPI_PUSHR_TXDATA(x) (((uint32_t)(((uint32_t)(x)) << SPI_PUSHR_TXDATA_SHIFT)) & SPI_PUSHR_TXDATA_MASK)
+#define SPI_PUSHR_PCS_MASK (0x3F0000U)
+#define SPI_PUSHR_PCS_SHIFT (16U)
+#define SPI_PUSHR_PCS(x) (((uint32_t)(((uint32_t)(x)) << SPI_PUSHR_PCS_SHIFT)) & SPI_PUSHR_PCS_MASK)
+#define SPI_PUSHR_CTCNT_MASK (0x4000000U)
+#define SPI_PUSHR_CTCNT_SHIFT (26U)
+#define SPI_PUSHR_CTCNT(x) (((uint32_t)(((uint32_t)(x)) << SPI_PUSHR_CTCNT_SHIFT)) & SPI_PUSHR_CTCNT_MASK)
+#define SPI_PUSHR_EOQ_MASK (0x8000000U)
+#define SPI_PUSHR_EOQ_SHIFT (27U)
+#define SPI_PUSHR_EOQ(x) (((uint32_t)(((uint32_t)(x)) << SPI_PUSHR_EOQ_SHIFT)) & SPI_PUSHR_EOQ_MASK)
+#define SPI_PUSHR_CTAS_MASK (0x70000000U)
+#define SPI_PUSHR_CTAS_SHIFT (28U)
+#define SPI_PUSHR_CTAS(x) (((uint32_t)(((uint32_t)(x)) << SPI_PUSHR_CTAS_SHIFT)) & SPI_PUSHR_CTAS_MASK)
+#define SPI_PUSHR_CONT_MASK (0x80000000U)
+#define SPI_PUSHR_CONT_SHIFT (31U)
+#define SPI_PUSHR_CONT(x) (((uint32_t)(((uint32_t)(x)) << SPI_PUSHR_CONT_SHIFT)) & SPI_PUSHR_CONT_MASK)
+
+/*! @name PUSHR_SLAVE - PUSH TX FIFO Register In Slave Mode */
+#define SPI_PUSHR_SLAVE_TXDATA_MASK (0xFFFFFFFFU)
+#define SPI_PUSHR_SLAVE_TXDATA_SHIFT (0U)
+#define SPI_PUSHR_SLAVE_TXDATA(x) (((uint32_t)(((uint32_t)(x)) << SPI_PUSHR_SLAVE_TXDATA_SHIFT)) & SPI_PUSHR_SLAVE_TXDATA_MASK)
+
+/*! @name POPR - POP RX FIFO Register */
+#define SPI_POPR_RXDATA_MASK (0xFFFFFFFFU)
+#define SPI_POPR_RXDATA_SHIFT (0U)
+#define SPI_POPR_RXDATA(x) (((uint32_t)(((uint32_t)(x)) << SPI_POPR_RXDATA_SHIFT)) & SPI_POPR_RXDATA_MASK)
+
+/*! @name TXFR0 - Transmit FIFO Registers */
+#define SPI_TXFR0_TXDATA_MASK (0xFFFFU)
+#define SPI_TXFR0_TXDATA_SHIFT (0U)
+#define SPI_TXFR0_TXDATA(x) (((uint32_t)(((uint32_t)(x)) << SPI_TXFR0_TXDATA_SHIFT)) & SPI_TXFR0_TXDATA_MASK)
+#define SPI_TXFR0_TXCMD_TXDATA_MASK (0xFFFF0000U)
+#define SPI_TXFR0_TXCMD_TXDATA_SHIFT (16U)
+#define SPI_TXFR0_TXCMD_TXDATA(x) (((uint32_t)(((uint32_t)(x)) << SPI_TXFR0_TXCMD_TXDATA_SHIFT)) & SPI_TXFR0_TXCMD_TXDATA_MASK)
+
+/*! @name TXFR1 - Transmit FIFO Registers */
+#define SPI_TXFR1_TXDATA_MASK (0xFFFFU)
+#define SPI_TXFR1_TXDATA_SHIFT (0U)
+#define SPI_TXFR1_TXDATA(x) (((uint32_t)(((uint32_t)(x)) << SPI_TXFR1_TXDATA_SHIFT)) & SPI_TXFR1_TXDATA_MASK)
+#define SPI_TXFR1_TXCMD_TXDATA_MASK (0xFFFF0000U)
+#define SPI_TXFR1_TXCMD_TXDATA_SHIFT (16U)
+#define SPI_TXFR1_TXCMD_TXDATA(x) (((uint32_t)(((uint32_t)(x)) << SPI_TXFR1_TXCMD_TXDATA_SHIFT)) & SPI_TXFR1_TXCMD_TXDATA_MASK)
+
+/*! @name TXFR2 - Transmit FIFO Registers */
+#define SPI_TXFR2_TXDATA_MASK (0xFFFFU)
+#define SPI_TXFR2_TXDATA_SHIFT (0U)
+#define SPI_TXFR2_TXDATA(x) (((uint32_t)(((uint32_t)(x)) << SPI_TXFR2_TXDATA_SHIFT)) & SPI_TXFR2_TXDATA_MASK)
+#define SPI_TXFR2_TXCMD_TXDATA_MASK (0xFFFF0000U)
+#define SPI_TXFR2_TXCMD_TXDATA_SHIFT (16U)
+#define SPI_TXFR2_TXCMD_TXDATA(x) (((uint32_t)(((uint32_t)(x)) << SPI_TXFR2_TXCMD_TXDATA_SHIFT)) & SPI_TXFR2_TXCMD_TXDATA_MASK)
+
+/*! @name TXFR3 - Transmit FIFO Registers */
+#define SPI_TXFR3_TXDATA_MASK (0xFFFFU)
+#define SPI_TXFR3_TXDATA_SHIFT (0U)
+#define SPI_TXFR3_TXDATA(x) (((uint32_t)(((uint32_t)(x)) << SPI_TXFR3_TXDATA_SHIFT)) & SPI_TXFR3_TXDATA_MASK)
+#define SPI_TXFR3_TXCMD_TXDATA_MASK (0xFFFF0000U)
+#define SPI_TXFR3_TXCMD_TXDATA_SHIFT (16U)
+#define SPI_TXFR3_TXCMD_TXDATA(x) (((uint32_t)(((uint32_t)(x)) << SPI_TXFR3_TXCMD_TXDATA_SHIFT)) & SPI_TXFR3_TXCMD_TXDATA_MASK)
+
+/*! @name RXFR0 - Receive FIFO Registers */
+#define SPI_RXFR0_RXDATA_MASK (0xFFFFFFFFU)
+#define SPI_RXFR0_RXDATA_SHIFT (0U)
+#define SPI_RXFR0_RXDATA(x) (((uint32_t)(((uint32_t)(x)) << SPI_RXFR0_RXDATA_SHIFT)) & SPI_RXFR0_RXDATA_MASK)
+
+/*! @name RXFR1 - Receive FIFO Registers */
+#define SPI_RXFR1_RXDATA_MASK (0xFFFFFFFFU)
+#define SPI_RXFR1_RXDATA_SHIFT (0U)
+#define SPI_RXFR1_RXDATA(x) (((uint32_t)(((uint32_t)(x)) << SPI_RXFR1_RXDATA_SHIFT)) & SPI_RXFR1_RXDATA_MASK)
+
+/*! @name RXFR2 - Receive FIFO Registers */
+#define SPI_RXFR2_RXDATA_MASK (0xFFFFFFFFU)
+#define SPI_RXFR2_RXDATA_SHIFT (0U)
+#define SPI_RXFR2_RXDATA(x) (((uint32_t)(((uint32_t)(x)) << SPI_RXFR2_RXDATA_SHIFT)) & SPI_RXFR2_RXDATA_MASK)
+
+/*! @name RXFR3 - Receive FIFO Registers */
+#define SPI_RXFR3_RXDATA_MASK (0xFFFFFFFFU)
+#define SPI_RXFR3_RXDATA_SHIFT (0U)
+#define SPI_RXFR3_RXDATA(x) (((uint32_t)(((uint32_t)(x)) << SPI_RXFR3_RXDATA_SHIFT)) & SPI_RXFR3_RXDATA_MASK)
+
+
+/*!
+ * @}
+ */ /* end of group SPI_Register_Masks */
+
+
+/* SPI - Peripheral instance base addresses */
+/** Peripheral SPI0 base address */
+#define SPI0_BASE (0x4002C000u)
+/** Peripheral SPI0 base pointer */
+#define SPI0 ((SPI_Type *)SPI0_BASE)
+/** Array initializer of SPI peripheral base addresses */
+#define SPI_BASE_ADDRS { SPI0_BASE }
+/** Array initializer of SPI peripheral base pointers */
+#define SPI_BASE_PTRS { SPI0 }
+/** Interrupt vectors for the SPI peripheral type */
+#define SPI_IRQS { SPI0_IRQn }
+
+/*!
+ * @}
+ */ /* end of group SPI_Peripheral_Access_Layer */
+
+
+/* ----------------------------------------------------------------------------
+ -- UART Peripheral Access Layer
+ ---------------------------------------------------------------------------- */
+
+/*!
+ * @addtogroup UART_Peripheral_Access_Layer UART Peripheral Access Layer
+ * @{
+ */
+
+/** UART - Register Layout Typedef */
+typedef struct {
+ __IO uint8_t BDH; /**< UART Baud Rate Registers: High, offset: 0x0 */
+ __IO uint8_t BDL; /**< UART Baud Rate Registers: Low, offset: 0x1 */
+ __IO uint8_t C1; /**< UART Control Register 1, offset: 0x2 */
+ __IO uint8_t C2; /**< UART Control Register 2, offset: 0x3 */
+ __I uint8_t S1; /**< UART Status Register 1, offset: 0x4 */
+ __IO uint8_t S2; /**< UART Status Register 2, offset: 0x5 */
+ __IO uint8_t C3; /**< UART Control Register 3, offset: 0x6 */
+ __IO uint8_t D; /**< UART Data Register, offset: 0x7 */
+ __IO uint8_t MA1; /**< UART Match Address Registers 1, offset: 0x8 */
+ __IO uint8_t MA2; /**< UART Match Address Registers 2, offset: 0x9 */
+ __IO uint8_t C4; /**< UART Control Register 4, offset: 0xA */
+ __IO uint8_t C5; /**< UART Control Register 5, offset: 0xB */
+ __I uint8_t ED; /**< UART Extended Data Register, offset: 0xC */
+ __IO uint8_t MODEM; /**< UART Modem Register, offset: 0xD */
+ __IO uint8_t IR; /**< UART Infrared Register, offset: 0xE */
+ uint8_t RESERVED_0[1];
+ __IO uint8_t PFIFO; /**< UART FIFO Parameters, offset: 0x10 */
+ __IO uint8_t CFIFO; /**< UART FIFO Control Register, offset: 0x11 */
+ __IO uint8_t SFIFO; /**< UART FIFO Status Register, offset: 0x12 */
+ __IO uint8_t TWFIFO; /**< UART FIFO Transmit Watermark, offset: 0x13 */
+ __I uint8_t TCFIFO; /**< UART FIFO Transmit Count, offset: 0x14 */
+ __IO uint8_t RWFIFO; /**< UART FIFO Receive Watermark, offset: 0x15 */
+ __I uint8_t RCFIFO; /**< UART FIFO Receive Count, offset: 0x16 */
+} UART_Type;
+
+/* ----------------------------------------------------------------------------
+ -- UART Register Masks
+ ---------------------------------------------------------------------------- */
+
+/*!
+ * @addtogroup UART_Register_Masks UART Register Masks
+ * @{
+ */
+
+/*! @name BDH - UART Baud Rate Registers: High */
+#define UART_BDH_SBR_MASK (0x1FU)
+#define UART_BDH_SBR_SHIFT (0U)
+#define UART_BDH_SBR(x) (((uint8_t)(((uint8_t)(x)) << UART_BDH_SBR_SHIFT)) & UART_BDH_SBR_MASK)
+#define UART_BDH_RXEDGIE_MASK (0x40U)
+#define UART_BDH_RXEDGIE_SHIFT (6U)
+#define UART_BDH_RXEDGIE(x) (((uint8_t)(((uint8_t)(x)) << UART_BDH_RXEDGIE_SHIFT)) & UART_BDH_RXEDGIE_MASK)
+#define UART_BDH_LBKDIE_MASK (0x80U)
+#define UART_BDH_LBKDIE_SHIFT (7U)
+#define UART_BDH_LBKDIE(x) (((uint8_t)(((uint8_t)(x)) << UART_BDH_LBKDIE_SHIFT)) & UART_BDH_LBKDIE_MASK)
+
+/*! @name BDL - UART Baud Rate Registers: Low */
+#define UART_BDL_SBR_MASK (0xFFU)
+#define UART_BDL_SBR_SHIFT (0U)
+#define UART_BDL_SBR(x) (((uint8_t)(((uint8_t)(x)) << UART_BDL_SBR_SHIFT)) & UART_BDL_SBR_MASK)
+
+/*! @name C1 - UART Control Register 1 */
+#define UART_C1_PT_MASK (0x1U)
+#define UART_C1_PT_SHIFT (0U)
+#define UART_C1_PT(x) (((uint8_t)(((uint8_t)(x)) << UART_C1_PT_SHIFT)) & UART_C1_PT_MASK)
+#define UART_C1_PE_MASK (0x2U)
+#define UART_C1_PE_SHIFT (1U)
+#define UART_C1_PE(x) (((uint8_t)(((uint8_t)(x)) << UART_C1_PE_SHIFT)) & UART_C1_PE_MASK)
+#define UART_C1_ILT_MASK (0x4U)
+#define UART_C1_ILT_SHIFT (2U)
+#define UART_C1_ILT(x) (((uint8_t)(((uint8_t)(x)) << UART_C1_ILT_SHIFT)) & UART_C1_ILT_MASK)
+#define UART_C1_WAKE_MASK (0x8U)
+#define UART_C1_WAKE_SHIFT (3U)
+#define UART_C1_WAKE(x) (((uint8_t)(((uint8_t)(x)) << UART_C1_WAKE_SHIFT)) & UART_C1_WAKE_MASK)
+#define UART_C1_M_MASK (0x10U)
+#define UART_C1_M_SHIFT (4U)
+#define UART_C1_M(x) (((uint8_t)(((uint8_t)(x)) << UART_C1_M_SHIFT)) & UART_C1_M_MASK)
+#define UART_C1_RSRC_MASK (0x20U)
+#define UART_C1_RSRC_SHIFT (5U)
+#define UART_C1_RSRC(x) (((uint8_t)(((uint8_t)(x)) << UART_C1_RSRC_SHIFT)) & UART_C1_RSRC_MASK)
+#define UART_C1_UARTSWAI_MASK (0x40U)
+#define UART_C1_UARTSWAI_SHIFT (6U)
+#define UART_C1_UARTSWAI(x) (((uint8_t)(((uint8_t)(x)) << UART_C1_UARTSWAI_SHIFT)) & UART_C1_UARTSWAI_MASK)
+#define UART_C1_LOOPS_MASK (0x80U)
+#define UART_C1_LOOPS_SHIFT (7U)
+#define UART_C1_LOOPS(x) (((uint8_t)(((uint8_t)(x)) << UART_C1_LOOPS_SHIFT)) & UART_C1_LOOPS_MASK)
+
+/*! @name C2 - UART Control Register 2 */
+#define UART_C2_SBK_MASK (0x1U)
+#define UART_C2_SBK_SHIFT (0U)
+#define UART_C2_SBK(x) (((uint8_t)(((uint8_t)(x)) << UART_C2_SBK_SHIFT)) & UART_C2_SBK_MASK)
+#define UART_C2_RWU_MASK (0x2U)
+#define UART_C2_RWU_SHIFT (1U)
+#define UART_C2_RWU(x) (((uint8_t)(((uint8_t)(x)) << UART_C2_RWU_SHIFT)) & UART_C2_RWU_MASK)
+#define UART_C2_RE_MASK (0x4U)
+#define UART_C2_RE_SHIFT (2U)
+#define UART_C2_RE(x) (((uint8_t)(((uint8_t)(x)) << UART_C2_RE_SHIFT)) & UART_C2_RE_MASK)
+#define UART_C2_TE_MASK (0x8U)
+#define UART_C2_TE_SHIFT (3U)
+#define UART_C2_TE(x) (((uint8_t)(((uint8_t)(x)) << UART_C2_TE_SHIFT)) & UART_C2_TE_MASK)
+#define UART_C2_ILIE_MASK (0x10U)
+#define UART_C2_ILIE_SHIFT (4U)
+#define UART_C2_ILIE(x) (((uint8_t)(((uint8_t)(x)) << UART_C2_ILIE_SHIFT)) & UART_C2_ILIE_MASK)
+#define UART_C2_RIE_MASK (0x20U)
+#define UART_C2_RIE_SHIFT (5U)
+#define UART_C2_RIE(x) (((uint8_t)(((uint8_t)(x)) << UART_C2_RIE_SHIFT)) & UART_C2_RIE_MASK)
+#define UART_C2_TCIE_MASK (0x40U)
+#define UART_C2_TCIE_SHIFT (6U)
+#define UART_C2_TCIE(x) (((uint8_t)(((uint8_t)(x)) << UART_C2_TCIE_SHIFT)) & UART_C2_TCIE_MASK)
+#define UART_C2_TIE_MASK (0x80U)
+#define UART_C2_TIE_SHIFT (7U)
+#define UART_C2_TIE(x) (((uint8_t)(((uint8_t)(x)) << UART_C2_TIE_SHIFT)) & UART_C2_TIE_MASK)
+
+/*! @name S1 - UART Status Register 1 */
+#define UART_S1_PF_MASK (0x1U)
+#define UART_S1_PF_SHIFT (0U)
+#define UART_S1_PF(x) (((uint8_t)(((uint8_t)(x)) << UART_S1_PF_SHIFT)) & UART_S1_PF_MASK)
+#define UART_S1_FE_MASK (0x2U)
+#define UART_S1_FE_SHIFT (1U)
+#define UART_S1_FE(x) (((uint8_t)(((uint8_t)(x)) << UART_S1_FE_SHIFT)) & UART_S1_FE_MASK)
+#define UART_S1_NF_MASK (0x4U)
+#define UART_S1_NF_SHIFT (2U)
+#define UART_S1_NF(x) (((uint8_t)(((uint8_t)(x)) << UART_S1_NF_SHIFT)) & UART_S1_NF_MASK)
+#define UART_S1_OR_MASK (0x8U)
+#define UART_S1_OR_SHIFT (3U)
+#define UART_S1_OR(x) (((uint8_t)(((uint8_t)(x)) << UART_S1_OR_SHIFT)) & UART_S1_OR_MASK)
+#define UART_S1_IDLE_MASK (0x10U)
+#define UART_S1_IDLE_SHIFT (4U)
+#define UART_S1_IDLE(x) (((uint8_t)(((uint8_t)(x)) << UART_S1_IDLE_SHIFT)) & UART_S1_IDLE_MASK)
+#define UART_S1_RDRF_MASK (0x20U)
+#define UART_S1_RDRF_SHIFT (5U)
+#define UART_S1_RDRF(x) (((uint8_t)(((uint8_t)(x)) << UART_S1_RDRF_SHIFT)) & UART_S1_RDRF_MASK)
+#define UART_S1_TC_MASK (0x40U)
+#define UART_S1_TC_SHIFT (6U)
+#define UART_S1_TC(x) (((uint8_t)(((uint8_t)(x)) << UART_S1_TC_SHIFT)) & UART_S1_TC_MASK)
+#define UART_S1_TDRE_MASK (0x80U)
+#define UART_S1_TDRE_SHIFT (7U)
+#define UART_S1_TDRE(x) (((uint8_t)(((uint8_t)(x)) << UART_S1_TDRE_SHIFT)) & UART_S1_TDRE_MASK)
+
+/*! @name S2 - UART Status Register 2 */
+#define UART_S2_RAF_MASK (0x1U)
+#define UART_S2_RAF_SHIFT (0U)
+#define UART_S2_RAF(x) (((uint8_t)(((uint8_t)(x)) << UART_S2_RAF_SHIFT)) & UART_S2_RAF_MASK)
+#define UART_S2_LBKDE_MASK (0x2U)
+#define UART_S2_LBKDE_SHIFT (1U)
+#define UART_S2_LBKDE(x) (((uint8_t)(((uint8_t)(x)) << UART_S2_LBKDE_SHIFT)) & UART_S2_LBKDE_MASK)
+#define UART_S2_BRK13_MASK (0x4U)
+#define UART_S2_BRK13_SHIFT (2U)
+#define UART_S2_BRK13(x) (((uint8_t)(((uint8_t)(x)) << UART_S2_BRK13_SHIFT)) & UART_S2_BRK13_MASK)
+#define UART_S2_RWUID_MASK (0x8U)
+#define UART_S2_RWUID_SHIFT (3U)
+#define UART_S2_RWUID(x) (((uint8_t)(((uint8_t)(x)) << UART_S2_RWUID_SHIFT)) & UART_S2_RWUID_MASK)
+#define UART_S2_RXINV_MASK (0x10U)
+#define UART_S2_RXINV_SHIFT (4U)
+#define UART_S2_RXINV(x) (((uint8_t)(((uint8_t)(x)) << UART_S2_RXINV_SHIFT)) & UART_S2_RXINV_MASK)
+#define UART_S2_MSBF_MASK (0x20U)
+#define UART_S2_MSBF_SHIFT (5U)
+#define UART_S2_MSBF(x) (((uint8_t)(((uint8_t)(x)) << UART_S2_MSBF_SHIFT)) & UART_S2_MSBF_MASK)
+#define UART_S2_RXEDGIF_MASK (0x40U)
+#define UART_S2_RXEDGIF_SHIFT (6U)
+#define UART_S2_RXEDGIF(x) (((uint8_t)(((uint8_t)(x)) << UART_S2_RXEDGIF_SHIFT)) & UART_S2_RXEDGIF_MASK)
+#define UART_S2_LBKDIF_MASK (0x80U)
+#define UART_S2_LBKDIF_SHIFT (7U)
+#define UART_S2_LBKDIF(x) (((uint8_t)(((uint8_t)(x)) << UART_S2_LBKDIF_SHIFT)) & UART_S2_LBKDIF_MASK)
+
+/*! @name C3 - UART Control Register 3 */
+#define UART_C3_PEIE_MASK (0x1U)
+#define UART_C3_PEIE_SHIFT (0U)
+#define UART_C3_PEIE(x) (((uint8_t)(((uint8_t)(x)) << UART_C3_PEIE_SHIFT)) & UART_C3_PEIE_MASK)
+#define UART_C3_FEIE_MASK (0x2U)
+#define UART_C3_FEIE_SHIFT (1U)
+#define UART_C3_FEIE(x) (((uint8_t)(((uint8_t)(x)) << UART_C3_FEIE_SHIFT)) & UART_C3_FEIE_MASK)
+#define UART_C3_NEIE_MASK (0x4U)
+#define UART_C3_NEIE_SHIFT (2U)
+#define UART_C3_NEIE(x) (((uint8_t)(((uint8_t)(x)) << UART_C3_NEIE_SHIFT)) & UART_C3_NEIE_MASK)
+#define UART_C3_ORIE_MASK (0x8U)
+#define UART_C3_ORIE_SHIFT (3U)
+#define UART_C3_ORIE(x) (((uint8_t)(((uint8_t)(x)) << UART_C3_ORIE_SHIFT)) & UART_C3_ORIE_MASK)
+#define UART_C3_TXINV_MASK (0x10U)
+#define UART_C3_TXINV_SHIFT (4U)
+#define UART_C3_TXINV(x) (((uint8_t)(((uint8_t)(x)) << UART_C3_TXINV_SHIFT)) & UART_C3_TXINV_MASK)
+#define UART_C3_TXDIR_MASK (0x20U)
+#define UART_C3_TXDIR_SHIFT (5U)
+#define UART_C3_TXDIR(x) (((uint8_t)(((uint8_t)(x)) << UART_C3_TXDIR_SHIFT)) & UART_C3_TXDIR_MASK)
+#define UART_C3_T8_MASK (0x40U)
+#define UART_C3_T8_SHIFT (6U)
+#define UART_C3_T8(x) (((uint8_t)(((uint8_t)(x)) << UART_C3_T8_SHIFT)) & UART_C3_T8_MASK)
+#define UART_C3_R8_MASK (0x80U)
+#define UART_C3_R8_SHIFT (7U)
+#define UART_C3_R8(x) (((uint8_t)(((uint8_t)(x)) << UART_C3_R8_SHIFT)) & UART_C3_R8_MASK)
+
+/*! @name D - UART Data Register */
+#define UART_D_RT_MASK (0xFFU)
+#define UART_D_RT_SHIFT (0U)
+#define UART_D_RT(x) (((uint8_t)(((uint8_t)(x)) << UART_D_RT_SHIFT)) & UART_D_RT_MASK)
+
+/*! @name MA1 - UART Match Address Registers 1 */
+#define UART_MA1_MA_MASK (0xFFU)
+#define UART_MA1_MA_SHIFT (0U)
+#define UART_MA1_MA(x) (((uint8_t)(((uint8_t)(x)) << UART_MA1_MA_SHIFT)) & UART_MA1_MA_MASK)
+
+/*! @name MA2 - UART Match Address Registers 2 */
+#define UART_MA2_MA_MASK (0xFFU)
+#define UART_MA2_MA_SHIFT (0U)
+#define UART_MA2_MA(x) (((uint8_t)(((uint8_t)(x)) << UART_MA2_MA_SHIFT)) & UART_MA2_MA_MASK)
+
+/*! @name C4 - UART Control Register 4 */
+#define UART_C4_BRFA_MASK (0x1FU)
+#define UART_C4_BRFA_SHIFT (0U)
+#define UART_C4_BRFA(x) (((uint8_t)(((uint8_t)(x)) << UART_C4_BRFA_SHIFT)) & UART_C4_BRFA_MASK)
+#define UART_C4_M10_MASK (0x20U)
+#define UART_C4_M10_SHIFT (5U)
+#define UART_C4_M10(x) (((uint8_t)(((uint8_t)(x)) << UART_C4_M10_SHIFT)) & UART_C4_M10_MASK)
+#define UART_C4_MAEN2_MASK (0x40U)
+#define UART_C4_MAEN2_SHIFT (6U)
+#define UART_C4_MAEN2(x) (((uint8_t)(((uint8_t)(x)) << UART_C4_MAEN2_SHIFT)) & UART_C4_MAEN2_MASK)
+#define UART_C4_MAEN1_MASK (0x80U)
+#define UART_C4_MAEN1_SHIFT (7U)
+#define UART_C4_MAEN1(x) (((uint8_t)(((uint8_t)(x)) << UART_C4_MAEN1_SHIFT)) & UART_C4_MAEN1_MASK)
+
+/*! @name C5 - UART Control Register 5 */
+#define UART_C5_RDMAS_MASK (0x20U)
+#define UART_C5_RDMAS_SHIFT (5U)
+#define UART_C5_RDMAS(x) (((uint8_t)(((uint8_t)(x)) << UART_C5_RDMAS_SHIFT)) & UART_C5_RDMAS_MASK)
+#define UART_C5_TDMAS_MASK (0x80U)
+#define UART_C5_TDMAS_SHIFT (7U)
+#define UART_C5_TDMAS(x) (((uint8_t)(((uint8_t)(x)) << UART_C5_TDMAS_SHIFT)) & UART_C5_TDMAS_MASK)
+
+/*! @name ED - UART Extended Data Register */
+#define UART_ED_PARITYE_MASK (0x40U)
+#define UART_ED_PARITYE_SHIFT (6U)
+#define UART_ED_PARITYE(x) (((uint8_t)(((uint8_t)(x)) << UART_ED_PARITYE_SHIFT)) & UART_ED_PARITYE_MASK)
+#define UART_ED_NOISY_MASK (0x80U)
+#define UART_ED_NOISY_SHIFT (7U)
+#define UART_ED_NOISY(x) (((uint8_t)(((uint8_t)(x)) << UART_ED_NOISY_SHIFT)) & UART_ED_NOISY_MASK)
+
+/*! @name MODEM - UART Modem Register */
+#define UART_MODEM_TXCTSE_MASK (0x1U)
+#define UART_MODEM_TXCTSE_SHIFT (0U)
+#define UART_MODEM_TXCTSE(x) (((uint8_t)(((uint8_t)(x)) << UART_MODEM_TXCTSE_SHIFT)) & UART_MODEM_TXCTSE_MASK)
+#define UART_MODEM_TXRTSE_MASK (0x2U)
+#define UART_MODEM_TXRTSE_SHIFT (1U)
+#define UART_MODEM_TXRTSE(x) (((uint8_t)(((uint8_t)(x)) << UART_MODEM_TXRTSE_SHIFT)) & UART_MODEM_TXRTSE_MASK)
+#define UART_MODEM_TXRTSPOL_MASK (0x4U)
+#define UART_MODEM_TXRTSPOL_SHIFT (2U)
+#define UART_MODEM_TXRTSPOL(x) (((uint8_t)(((uint8_t)(x)) << UART_MODEM_TXRTSPOL_SHIFT)) & UART_MODEM_TXRTSPOL_MASK)
+#define UART_MODEM_RXRTSE_MASK (0x8U)
+#define UART_MODEM_RXRTSE_SHIFT (3U)
+#define UART_MODEM_RXRTSE(x) (((uint8_t)(((uint8_t)(x)) << UART_MODEM_RXRTSE_SHIFT)) & UART_MODEM_RXRTSE_MASK)
+
+/*! @name IR - UART Infrared Register */
+#define UART_IR_TNP_MASK (0x3U)
+#define UART_IR_TNP_SHIFT (0U)
+#define UART_IR_TNP(x) (((uint8_t)(((uint8_t)(x)) << UART_IR_TNP_SHIFT)) & UART_IR_TNP_MASK)
+#define UART_IR_IREN_MASK (0x4U)
+#define UART_IR_IREN_SHIFT (2U)
+#define UART_IR_IREN(x) (((uint8_t)(((uint8_t)(x)) << UART_IR_IREN_SHIFT)) & UART_IR_IREN_MASK)
+
+/*! @name PFIFO - UART FIFO Parameters */
+#define UART_PFIFO_RXFIFOSIZE_MASK (0x7U)
+#define UART_PFIFO_RXFIFOSIZE_SHIFT (0U)
+#define UART_PFIFO_RXFIFOSIZE(x) (((uint8_t)(((uint8_t)(x)) << UART_PFIFO_RXFIFOSIZE_SHIFT)) & UART_PFIFO_RXFIFOSIZE_MASK)
+#define UART_PFIFO_RXFE_MASK (0x8U)
+#define UART_PFIFO_RXFE_SHIFT (3U)
+#define UART_PFIFO_RXFE(x) (((uint8_t)(((uint8_t)(x)) << UART_PFIFO_RXFE_SHIFT)) & UART_PFIFO_RXFE_MASK)
+#define UART_PFIFO_TXFIFOSIZE_MASK (0x70U)
+#define UART_PFIFO_TXFIFOSIZE_SHIFT (4U)
+#define UART_PFIFO_TXFIFOSIZE(x) (((uint8_t)(((uint8_t)(x)) << UART_PFIFO_TXFIFOSIZE_SHIFT)) & UART_PFIFO_TXFIFOSIZE_MASK)
+#define UART_PFIFO_TXFE_MASK (0x80U)
+#define UART_PFIFO_TXFE_SHIFT (7U)
+#define UART_PFIFO_TXFE(x) (((uint8_t)(((uint8_t)(x)) << UART_PFIFO_TXFE_SHIFT)) & UART_PFIFO_TXFE_MASK)
+
+/*! @name CFIFO - UART FIFO Control Register */
+#define UART_CFIFO_RXUFE_MASK (0x1U)
+#define UART_CFIFO_RXUFE_SHIFT (0U)
+#define UART_CFIFO_RXUFE(x) (((uint8_t)(((uint8_t)(x)) << UART_CFIFO_RXUFE_SHIFT)) & UART_CFIFO_RXUFE_MASK)
+#define UART_CFIFO_TXOFE_MASK (0x2U)
+#define UART_CFIFO_TXOFE_SHIFT (1U)
+#define UART_CFIFO_TXOFE(x) (((uint8_t)(((uint8_t)(x)) << UART_CFIFO_TXOFE_SHIFT)) & UART_CFIFO_TXOFE_MASK)
+#define UART_CFIFO_RXOFE_MASK (0x4U)
+#define UART_CFIFO_RXOFE_SHIFT (2U)
+#define UART_CFIFO_RXOFE(x) (((uint8_t)(((uint8_t)(x)) << UART_CFIFO_RXOFE_SHIFT)) & UART_CFIFO_RXOFE_MASK)
+#define UART_CFIFO_RXFLUSH_MASK (0x40U)
+#define UART_CFIFO_RXFLUSH_SHIFT (6U)
+#define UART_CFIFO_RXFLUSH(x) (((uint8_t)(((uint8_t)(x)) << UART_CFIFO_RXFLUSH_SHIFT)) & UART_CFIFO_RXFLUSH_MASK)
+#define UART_CFIFO_TXFLUSH_MASK (0x80U)
+#define UART_CFIFO_TXFLUSH_SHIFT (7U)
+#define UART_CFIFO_TXFLUSH(x) (((uint8_t)(((uint8_t)(x)) << UART_CFIFO_TXFLUSH_SHIFT)) & UART_CFIFO_TXFLUSH_MASK)
+
+/*! @name SFIFO - UART FIFO Status Register */
+#define UART_SFIFO_RXUF_MASK (0x1U)
+#define UART_SFIFO_RXUF_SHIFT (0U)
+#define UART_SFIFO_RXUF(x) (((uint8_t)(((uint8_t)(x)) << UART_SFIFO_RXUF_SHIFT)) & UART_SFIFO_RXUF_MASK)
+#define UART_SFIFO_TXOF_MASK (0x2U)
+#define UART_SFIFO_TXOF_SHIFT (1U)
+#define UART_SFIFO_TXOF(x) (((uint8_t)(((uint8_t)(x)) << UART_SFIFO_TXOF_SHIFT)) & UART_SFIFO_TXOF_MASK)
+#define UART_SFIFO_RXOF_MASK (0x4U)
+#define UART_SFIFO_RXOF_SHIFT (2U)
+#define UART_SFIFO_RXOF(x) (((uint8_t)(((uint8_t)(x)) << UART_SFIFO_RXOF_SHIFT)) & UART_SFIFO_RXOF_MASK)
+#define UART_SFIFO_RXEMPT_MASK (0x40U)
+#define UART_SFIFO_RXEMPT_SHIFT (6U)
+#define UART_SFIFO_RXEMPT(x) (((uint8_t)(((uint8_t)(x)) << UART_SFIFO_RXEMPT_SHIFT)) & UART_SFIFO_RXEMPT_MASK)
+#define UART_SFIFO_TXEMPT_MASK (0x80U)
+#define UART_SFIFO_TXEMPT_SHIFT (7U)
+#define UART_SFIFO_TXEMPT(x) (((uint8_t)(((uint8_t)(x)) << UART_SFIFO_TXEMPT_SHIFT)) & UART_SFIFO_TXEMPT_MASK)
+
+/*! @name TWFIFO - UART FIFO Transmit Watermark */
+#define UART_TWFIFO_TXWATER_MASK (0xFFU)
+#define UART_TWFIFO_TXWATER_SHIFT (0U)
+#define UART_TWFIFO_TXWATER(x) (((uint8_t)(((uint8_t)(x)) << UART_TWFIFO_TXWATER_SHIFT)) & UART_TWFIFO_TXWATER_MASK)
+
+/*! @name TCFIFO - UART FIFO Transmit Count */
+#define UART_TCFIFO_TXCOUNT_MASK (0xFFU)
+#define UART_TCFIFO_TXCOUNT_SHIFT (0U)
+#define UART_TCFIFO_TXCOUNT(x) (((uint8_t)(((uint8_t)(x)) << UART_TCFIFO_TXCOUNT_SHIFT)) & UART_TCFIFO_TXCOUNT_MASK)
+
+/*! @name RWFIFO - UART FIFO Receive Watermark */
+#define UART_RWFIFO_RXWATER_MASK (0xFFU)
+#define UART_RWFIFO_RXWATER_SHIFT (0U)
+#define UART_RWFIFO_RXWATER(x) (((uint8_t)(((uint8_t)(x)) << UART_RWFIFO_RXWATER_SHIFT)) & UART_RWFIFO_RXWATER_MASK)
+
+/*! @name RCFIFO - UART FIFO Receive Count */
+#define UART_RCFIFO_RXCOUNT_MASK (0xFFU)
+#define UART_RCFIFO_RXCOUNT_SHIFT (0U)
+#define UART_RCFIFO_RXCOUNT(x) (((uint8_t)(((uint8_t)(x)) << UART_RCFIFO_RXCOUNT_SHIFT)) & UART_RCFIFO_RXCOUNT_MASK)
+
+
+/*!
+ * @}
+ */ /* end of group UART_Register_Masks */
+
+
+/* UART - Peripheral instance base addresses */
+/** Peripheral UART0 base address */
+#define UART0_BASE (0x4006A000u)
+/** Peripheral UART0 base pointer */
+#define UART0 ((UART_Type *)UART0_BASE)
+/** Peripheral UART1 base address */
+#define UART1_BASE (0x4006B000u)
+/** Peripheral UART1 base pointer */
+#define UART1 ((UART_Type *)UART1_BASE)
+/** Array initializer of UART peripheral base addresses */
+#define UART_BASE_ADDRS { UART0_BASE, UART1_BASE }
+/** Array initializer of UART peripheral base pointers */
+#define UART_BASE_PTRS { UART0, UART1 }
+/** Interrupt vectors for the UART peripheral type */
+#define UART_RX_TX_IRQS { UART0_RX_TX_IRQn, UART1_RX_TX_IRQn }
+#define UART_ERR_IRQS { UART0_ERR_IRQn, UART1_ERR_IRQn }
+
+/*!
+ * @}
+ */ /* end of group UART_Peripheral_Access_Layer */
+
+
+/* ----------------------------------------------------------------------------
+ -- VREF Peripheral Access Layer
+ ---------------------------------------------------------------------------- */
+
+/*!
+ * @addtogroup VREF_Peripheral_Access_Layer VREF Peripheral Access Layer
+ * @{
+ */
+
+/** VREF - Register Layout Typedef */
+typedef struct {
+ __IO uint8_t TRM; /**< VREF Trim Register, offset: 0x0 */
+ __IO uint8_t SC; /**< VREF Status and Control Register, offset: 0x1 */
+} VREF_Type;
+
+/* ----------------------------------------------------------------------------
+ -- VREF Register Masks
+ ---------------------------------------------------------------------------- */
+
+/*!
+ * @addtogroup VREF_Register_Masks VREF Register Masks
+ * @{
+ */
+
+/*! @name TRM - VREF Trim Register */
+#define VREF_TRM_TRIM_MASK (0x3FU)
+#define VREF_TRM_TRIM_SHIFT (0U)
+#define VREF_TRM_TRIM(x) (((uint8_t)(((uint8_t)(x)) << VREF_TRM_TRIM_SHIFT)) & VREF_TRM_TRIM_MASK)
+#define VREF_TRM_CHOPEN_MASK (0x40U)
+#define VREF_TRM_CHOPEN_SHIFT (6U)
+#define VREF_TRM_CHOPEN(x) (((uint8_t)(((uint8_t)(x)) << VREF_TRM_CHOPEN_SHIFT)) & VREF_TRM_CHOPEN_MASK)
+
+/*! @name SC - VREF Status and Control Register */
+#define VREF_SC_MODE_LV_MASK (0x3U)
+#define VREF_SC_MODE_LV_SHIFT (0U)
+#define VREF_SC_MODE_LV(x) (((uint8_t)(((uint8_t)(x)) << VREF_SC_MODE_LV_SHIFT)) & VREF_SC_MODE_LV_MASK)
+#define VREF_SC_VREFST_MASK (0x4U)
+#define VREF_SC_VREFST_SHIFT (2U)
+#define VREF_SC_VREFST(x) (((uint8_t)(((uint8_t)(x)) << VREF_SC_VREFST_SHIFT)) & VREF_SC_VREFST_MASK)
+#define VREF_SC_ICOMPEN_MASK (0x20U)
+#define VREF_SC_ICOMPEN_SHIFT (5U)
+#define VREF_SC_ICOMPEN(x) (((uint8_t)(((uint8_t)(x)) << VREF_SC_ICOMPEN_SHIFT)) & VREF_SC_ICOMPEN_MASK)
+#define VREF_SC_REGEN_MASK (0x40U)
+#define VREF_SC_REGEN_SHIFT (6U)
+#define VREF_SC_REGEN(x) (((uint8_t)(((uint8_t)(x)) << VREF_SC_REGEN_SHIFT)) & VREF_SC_REGEN_MASK)
+#define VREF_SC_VREFEN_MASK (0x80U)
+#define VREF_SC_VREFEN_SHIFT (7U)
+#define VREF_SC_VREFEN(x) (((uint8_t)(((uint8_t)(x)) << VREF_SC_VREFEN_SHIFT)) & VREF_SC_VREFEN_MASK)
+
+
+/*!
+ * @}
+ */ /* end of group VREF_Register_Masks */
+
+
+/* VREF - Peripheral instance base addresses */
+/** Peripheral VREF base address */
+#define VREF_BASE (0x40074000u)
+/** Peripheral VREF base pointer */
+#define VREF ((VREF_Type *)VREF_BASE)
+/** Array initializer of VREF peripheral base addresses */
+#define VREF_BASE_ADDRS { VREF_BASE }
+/** Array initializer of VREF peripheral base pointers */
+#define VREF_BASE_PTRS { VREF }
+
+/*!
+ * @}
+ */ /* end of group VREF_Peripheral_Access_Layer */
+
+
+/* ----------------------------------------------------------------------------
+ -- WDOG Peripheral Access Layer
+ ---------------------------------------------------------------------------- */
+
+/*!
+ * @addtogroup WDOG_Peripheral_Access_Layer WDOG Peripheral Access Layer
+ * @{
+ */
+
+/** WDOG - Register Layout Typedef */
+typedef struct {
+ __IO uint16_t STCTRLH; /**< Watchdog Status and Control Register High, offset: 0x0 */
+ __IO uint16_t STCTRLL; /**< Watchdog Status and Control Register Low, offset: 0x2 */
+ __IO uint16_t TOVALH; /**< Watchdog Time-out Value Register High, offset: 0x4 */
+ __IO uint16_t TOVALL; /**< Watchdog Time-out Value Register Low, offset: 0x6 */
+ __IO uint16_t WINH; /**< Watchdog Window Register High, offset: 0x8 */
+ __IO uint16_t WINL; /**< Watchdog Window Register Low, offset: 0xA */
+ __IO uint16_t REFRESH; /**< Watchdog Refresh register, offset: 0xC */
+ __IO uint16_t UNLOCK; /**< Watchdog Unlock register, offset: 0xE */
+ __IO uint16_t TMROUTH; /**< Watchdog Timer Output Register High, offset: 0x10 */
+ __IO uint16_t TMROUTL; /**< Watchdog Timer Output Register Low, offset: 0x12 */
+ __IO uint16_t RSTCNT; /**< Watchdog Reset Count register, offset: 0x14 */
+ __IO uint16_t PRESC; /**< Watchdog Prescaler register, offset: 0x16 */
+} WDOG_Type;
+
+/* ----------------------------------------------------------------------------
+ -- WDOG Register Masks
+ ---------------------------------------------------------------------------- */
+
+/*!
+ * @addtogroup WDOG_Register_Masks WDOG Register Masks
+ * @{
+ */
+
+/*! @name STCTRLH - Watchdog Status and Control Register High */
+#define WDOG_STCTRLH_WDOGEN_MASK (0x1U)
+#define WDOG_STCTRLH_WDOGEN_SHIFT (0U)
+#define WDOG_STCTRLH_WDOGEN(x) (((uint16_t)(((uint16_t)(x)) << WDOG_STCTRLH_WDOGEN_SHIFT)) & WDOG_STCTRLH_WDOGEN_MASK)
+#define WDOG_STCTRLH_CLKSRC_MASK (0x2U)
+#define WDOG_STCTRLH_CLKSRC_SHIFT (1U)
+#define WDOG_STCTRLH_CLKSRC(x) (((uint16_t)(((uint16_t)(x)) << WDOG_STCTRLH_CLKSRC_SHIFT)) & WDOG_STCTRLH_CLKSRC_MASK)
+#define WDOG_STCTRLH_IRQRSTEN_MASK (0x4U)
+#define WDOG_STCTRLH_IRQRSTEN_SHIFT (2U)
+#define WDOG_STCTRLH_IRQRSTEN(x) (((uint16_t)(((uint16_t)(x)) << WDOG_STCTRLH_IRQRSTEN_SHIFT)) & WDOG_STCTRLH_IRQRSTEN_MASK)
+#define WDOG_STCTRLH_WINEN_MASK (0x8U)
+#define WDOG_STCTRLH_WINEN_SHIFT (3U)
+#define WDOG_STCTRLH_WINEN(x) (((uint16_t)(((uint16_t)(x)) << WDOG_STCTRLH_WINEN_SHIFT)) & WDOG_STCTRLH_WINEN_MASK)
+#define WDOG_STCTRLH_ALLOWUPDATE_MASK (0x10U)
+#define WDOG_STCTRLH_ALLOWUPDATE_SHIFT (4U)
+#define WDOG_STCTRLH_ALLOWUPDATE(x) (((uint16_t)(((uint16_t)(x)) << WDOG_STCTRLH_ALLOWUPDATE_SHIFT)) & WDOG_STCTRLH_ALLOWUPDATE_MASK)
+#define WDOG_STCTRLH_DBGEN_MASK (0x20U)
+#define WDOG_STCTRLH_DBGEN_SHIFT (5U)
+#define WDOG_STCTRLH_DBGEN(x) (((uint16_t)(((uint16_t)(x)) << WDOG_STCTRLH_DBGEN_SHIFT)) & WDOG_STCTRLH_DBGEN_MASK)
+#define WDOG_STCTRLH_STOPEN_MASK (0x40U)
+#define WDOG_STCTRLH_STOPEN_SHIFT (6U)
+#define WDOG_STCTRLH_STOPEN(x) (((uint16_t)(((uint16_t)(x)) << WDOG_STCTRLH_STOPEN_SHIFT)) & WDOG_STCTRLH_STOPEN_MASK)
+#define WDOG_STCTRLH_WAITEN_MASK (0x80U)
+#define WDOG_STCTRLH_WAITEN_SHIFT (7U)
+#define WDOG_STCTRLH_WAITEN(x) (((uint16_t)(((uint16_t)(x)) << WDOG_STCTRLH_WAITEN_SHIFT)) & WDOG_STCTRLH_WAITEN_MASK)
+#define WDOG_STCTRLH_TESTWDOG_MASK (0x400U)
+#define WDOG_STCTRLH_TESTWDOG_SHIFT (10U)
+#define WDOG_STCTRLH_TESTWDOG(x) (((uint16_t)(((uint16_t)(x)) << WDOG_STCTRLH_TESTWDOG_SHIFT)) & WDOG_STCTRLH_TESTWDOG_MASK)
+#define WDOG_STCTRLH_TESTSEL_MASK (0x800U)
+#define WDOG_STCTRLH_TESTSEL_SHIFT (11U)
+#define WDOG_STCTRLH_TESTSEL(x) (((uint16_t)(((uint16_t)(x)) << WDOG_STCTRLH_TESTSEL_SHIFT)) & WDOG_STCTRLH_TESTSEL_MASK)
+#define WDOG_STCTRLH_BYTESEL_MASK (0x3000U)
+#define WDOG_STCTRLH_BYTESEL_SHIFT (12U)
+#define WDOG_STCTRLH_BYTESEL(x) (((uint16_t)(((uint16_t)(x)) << WDOG_STCTRLH_BYTESEL_SHIFT)) & WDOG_STCTRLH_BYTESEL_MASK)
+#define WDOG_STCTRLH_DISTESTWDOG_MASK (0x4000U)
+#define WDOG_STCTRLH_DISTESTWDOG_SHIFT (14U)
+#define WDOG_STCTRLH_DISTESTWDOG(x) (((uint16_t)(((uint16_t)(x)) << WDOG_STCTRLH_DISTESTWDOG_SHIFT)) & WDOG_STCTRLH_DISTESTWDOG_MASK)
+
+/*! @name STCTRLL - Watchdog Status and Control Register Low */
+#define WDOG_STCTRLL_INTFLG_MASK (0x8000U)
+#define WDOG_STCTRLL_INTFLG_SHIFT (15U)
+#define WDOG_STCTRLL_INTFLG(x) (((uint16_t)(((uint16_t)(x)) << WDOG_STCTRLL_INTFLG_SHIFT)) & WDOG_STCTRLL_INTFLG_MASK)
+
+/*! @name TOVALH - Watchdog Time-out Value Register High */
+#define WDOG_TOVALH_TOVALHIGH_MASK (0xFFFFU)
+#define WDOG_TOVALH_TOVALHIGH_SHIFT (0U)
+#define WDOG_TOVALH_TOVALHIGH(x) (((uint16_t)(((uint16_t)(x)) << WDOG_TOVALH_TOVALHIGH_SHIFT)) & WDOG_TOVALH_TOVALHIGH_MASK)
+
+/*! @name TOVALL - Watchdog Time-out Value Register Low */
+#define WDOG_TOVALL_TOVALLOW_MASK (0xFFFFU)
+#define WDOG_TOVALL_TOVALLOW_SHIFT (0U)
+#define WDOG_TOVALL_TOVALLOW(x) (((uint16_t)(((uint16_t)(x)) << WDOG_TOVALL_TOVALLOW_SHIFT)) & WDOG_TOVALL_TOVALLOW_MASK)
+
+/*! @name WINH - Watchdog Window Register High */
+#define WDOG_WINH_WINHIGH_MASK (0xFFFFU)
+#define WDOG_WINH_WINHIGH_SHIFT (0U)
+#define WDOG_WINH_WINHIGH(x) (((uint16_t)(((uint16_t)(x)) << WDOG_WINH_WINHIGH_SHIFT)) & WDOG_WINH_WINHIGH_MASK)
+
+/*! @name WINL - Watchdog Window Register Low */
+#define WDOG_WINL_WINLOW_MASK (0xFFFFU)
+#define WDOG_WINL_WINLOW_SHIFT (0U)
+#define WDOG_WINL_WINLOW(x) (((uint16_t)(((uint16_t)(x)) << WDOG_WINL_WINLOW_SHIFT)) & WDOG_WINL_WINLOW_MASK)
+
+/*! @name REFRESH - Watchdog Refresh register */
+#define WDOG_REFRESH_WDOGREFRESH_MASK (0xFFFFU)
+#define WDOG_REFRESH_WDOGREFRESH_SHIFT (0U)
+#define WDOG_REFRESH_WDOGREFRESH(x) (((uint16_t)(((uint16_t)(x)) << WDOG_REFRESH_WDOGREFRESH_SHIFT)) & WDOG_REFRESH_WDOGREFRESH_MASK)
+
+/*! @name UNLOCK - Watchdog Unlock register */
+#define WDOG_UNLOCK_WDOGUNLOCK_MASK (0xFFFFU)
+#define WDOG_UNLOCK_WDOGUNLOCK_SHIFT (0U)
+#define WDOG_UNLOCK_WDOGUNLOCK(x) (((uint16_t)(((uint16_t)(x)) << WDOG_UNLOCK_WDOGUNLOCK_SHIFT)) & WDOG_UNLOCK_WDOGUNLOCK_MASK)
+
+/*! @name TMROUTH - Watchdog Timer Output Register High */
+#define WDOG_TMROUTH_TIMEROUTHIGH_MASK (0xFFFFU)
+#define WDOG_TMROUTH_TIMEROUTHIGH_SHIFT (0U)
+#define WDOG_TMROUTH_TIMEROUTHIGH(x) (((uint16_t)(((uint16_t)(x)) << WDOG_TMROUTH_TIMEROUTHIGH_SHIFT)) & WDOG_TMROUTH_TIMEROUTHIGH_MASK)
+
+/*! @name TMROUTL - Watchdog Timer Output Register Low */
+#define WDOG_TMROUTL_TIMEROUTLOW_MASK (0xFFFFU)
+#define WDOG_TMROUTL_TIMEROUTLOW_SHIFT (0U)
+#define WDOG_TMROUTL_TIMEROUTLOW(x) (((uint16_t)(((uint16_t)(x)) << WDOG_TMROUTL_TIMEROUTLOW_SHIFT)) & WDOG_TMROUTL_TIMEROUTLOW_MASK)
+
+/*! @name RSTCNT - Watchdog Reset Count register */
+#define WDOG_RSTCNT_RSTCNT_MASK (0xFFFFU)
+#define WDOG_RSTCNT_RSTCNT_SHIFT (0U)
+#define WDOG_RSTCNT_RSTCNT(x) (((uint16_t)(((uint16_t)(x)) << WDOG_RSTCNT_RSTCNT_SHIFT)) & WDOG_RSTCNT_RSTCNT_MASK)
+
+/*! @name PRESC - Watchdog Prescaler register */
+#define WDOG_PRESC_PRESCVAL_MASK (0x700U)
+#define WDOG_PRESC_PRESCVAL_SHIFT (8U)
+#define WDOG_PRESC_PRESCVAL(x) (((uint16_t)(((uint16_t)(x)) << WDOG_PRESC_PRESCVAL_SHIFT)) & WDOG_PRESC_PRESCVAL_MASK)
+
+
+/*!
+ * @}
+ */ /* end of group WDOG_Register_Masks */
+
+
+/* WDOG - Peripheral instance base addresses */
+/** Peripheral WDOG base address */
+#define WDOG_BASE (0x40052000u)
+/** Peripheral WDOG base pointer */
+#define WDOG ((WDOG_Type *)WDOG_BASE)
+/** Array initializer of WDOG peripheral base addresses */
+#define WDOG_BASE_ADDRS { WDOG_BASE }
+/** Array initializer of WDOG peripheral base pointers */
+#define WDOG_BASE_PTRS { WDOG }
+/** Interrupt vectors for the WDOG peripheral type */
+#define WDOG_IRQS { WDOG_EWM_IRQn }
+
+/*!
+ * @}
+ */ /* end of group WDOG_Peripheral_Access_Layer */
+
+
+/*
+** End of section using anonymous unions
+*/
+
+#if defined(__ARMCC_VERSION)
+ #if (__ARMCC_VERSION >= 6010050)
+ #pragma clang diagnostic pop
+ #else
+ #pragma pop
+ #endif
+#elif defined(__CWCC__)
+ #pragma pop
+#elif defined(__GNUC__)
+ /* leave anonymous unions enabled */
+#elif defined(__IAR_SYSTEMS_ICC__)
+ #pragma language=default
+#else
+ #error Not supported compiler type
+#endif
+
+/*!
+ * @}
+ */ /* end of group Peripheral_access_layer */
+
+
+/* ----------------------------------------------------------------------------
+ -- Macros for use with bit field definitions (xxx_SHIFT, xxx_MASK).
+ ---------------------------------------------------------------------------- */
+
+/*!
+ * @addtogroup Bit_Field_Generic_Macros Macros for use with bit field definitions (xxx_SHIFT, xxx_MASK).
+ * @{
+ */
+
+#if defined(__ARMCC_VERSION)
+ #if (__ARMCC_VERSION >= 6010050)
+ #pragma clang system_header
+ #endif
+#elif defined(__IAR_SYSTEMS_ICC__)
+ #pragma system_include
+#endif
+
+/**
+ * @brief Mask and left-shift a bit field value for use in a register bit range.
+ * @param field Name of the register bit field.
+ * @param value Value of the bit field.
+ * @return Masked and shifted value.
+ */
+#define NXP_VAL2FLD(field, value) (((value) << (field ## _SHIFT)) & (field ## _MASK))
+/**
+ * @brief Mask and right-shift a register value to extract a bit field value.
+ * @param field Name of the register bit field.
+ * @param value Value of the register.
+ * @return Masked and shifted bit field value.
+ */
+#define NXP_FLD2VAL(field, value) (((value) & (field ## _MASK)) >> (field ## _SHIFT))
+
+/*!
+ * @}
+ */ /* end of group Bit_Field_Generic_Macros */
+
+
+/* ----------------------------------------------------------------------------
+ -- SDK Compatibility
+ ---------------------------------------------------------------------------- */
+
+/*!
+ * @addtogroup SDK_Compatibility_Symbols SDK Compatibility
+ * @{
+ */
+
+#define MCM_ISR_REG(base) MCM_ISCR_REG(base)
+#define MCM_ISR_FIOC_MASK MCM_ISCR_FIOC_MASK
+#define MCM_ISR_FIOC_SHIFT MCM_ISCR_FIOC_SHIFT
+#define MCM_ISR_FDZC_MASK MCM_ISCR_FDZC_MASK
+#define MCM_ISR_FDZC_SHIFT MCM_ISCR_FDZC_SHIFT
+#define MCM_ISR_FOFC_MASK MCM_ISCR_FOFC_MASK
+#define MCM_ISR_FOFC_SHIFT MCM_ISCR_FOFC_SHIFT
+#define MCM_ISR_FUFC_MASK MCM_ISCR_FUFC_MASK
+#define MCM_ISR_FUFC_SHIFT MCM_ISCR_FUFC_SHIFT
+#define MCM_ISR_FIXC_MASK MCM_ISCR_FIXC_MASK
+#define MCM_ISR_FIXC_SHIFT MCM_ISCR_FIXC_SHIFT
+#define MCM_ISR_FIDC_MASK MCM_ISCR_FIDC_MASK
+#define MCM_ISR_FIDC_SHIFT MCM_ISCR_FIDC_SHIFT
+#define MCM_ISR_FIOCE_MASK MCM_ISCR_FIOCE_MASK
+#define MCM_ISR_FIOCE_SHIFT MCM_ISCR_FIOCE_SHIFT
+#define MCM_ISR_FDZCE_MASK MCM_ISCR_FDZCE_MASK
+#define MCM_ISR_FDZCE_SHIFT MCM_ISCR_FDZCE_SHIFT
+#define MCM_ISR_FOFCE_MASK MCM_ISCR_FOFCE_MASK
+#define MCM_ISR_FOFCE_SHIFT MCM_ISCR_FOFCE_SHIFT
+#define MCM_ISR_FUFCE_MASK MCM_ISCR_FUFCE_MASK
+#define MCM_ISR_FUFCE_SHIFT MCM_ISCR_FUFCE_SHIFT
+#define MCM_ISR_FIXCE_MASK MCM_ISCR_FIXCE_MASK
+#define MCM_ISR_FIXCE_SHIFT MCM_ISCR_FIXCE_SHIFT
+#define MCM_ISR_FIDCE_MASK MCM_ISCR_FIDCE_MASK
+#define MCM_ISR_FIDCE_SHIFT MCM_ISCR_FIDCE_SHIFT
+#define DSPI0 SPI0
+#define PTA_BASE GPIOA_BASE
+#define PTA GPIOA
+#define PTB_BASE GPIOB_BASE
+#define PTB GPIOB
+#define PTC_BASE GPIOC_BASE
+#define PTC GPIOC
+#define PTD_BASE GPIOD_BASE
+#define PTD GPIOD
+#define PTE_BASE GPIOE_BASE
+#define PTE GPIOE
+#define Watchdog_IRQn WDOG_EWM_IRQn
+#define Watchdog_IRQHandler WDOG_EWM_IRQHandler
+#define LPTimer_IRQn LPTMR0_IRQn
+#define LPTimer_IRQHandler LPTMR0_IRQHandler
+#define LLW_IRQn LLWU_IRQn
+#define LLW_IRQHandler LLWU_IRQHandler
+#define DMAMUX0 DMAMUX
+#define WDOG0 WDOG
+#define MCM0 MCM
+#define RTC0 RTC
+
+/*!
+ * @}
+ */ /* end of group SDK_Compatibility_Symbols */
+
+
+#endif /* _MK02F12810_H_ */
+
diff --git a/CMSIS/MK02F12810_features.h b/CMSIS/MK02F12810_features.h
new file mode 100644
index 0000000..676315c
--- /dev/null
+++ b/CMSIS/MK02F12810_features.h
@@ -0,0 +1,2013 @@
+/*
+** ###################################################################
+** Version: rev. 0.9, 2015-06-08
+** Build: b180410
+**
+** Abstract:
+** Chip specific module features.
+**
+** The Clear BSD License
+** Copyright 2016 Freescale Semiconductor, Inc.
+** Copyright 2016-2018 NXP
+** All rights reserved.
+**
+** Redistribution and use in source and binary forms, with or without
+** modification, are permitted (subject to the limitations in the
+** disclaimer below) provided that the following conditions are met:
+**
+** * Redistributions of source code must retain the above copyright
+** notice, this list of conditions and the following disclaimer.
+**
+** * 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.
+**
+** * Neither the name of the copyright holder nor the names of its
+** contributors may be used to endorse or promote products derived from
+** this software without specific prior written permission.
+**
+** NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE
+** GRANTED BY THIS LICENSE. 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.
+**
+** http: www.nxp.com
+** mail: support@nxp.com
+**
+** Revisions:
+** - rev. 0.1 (2014-02-24)
+** Initial version
+** - rev. 0.2 (2014-07-15)
+** Module access macro module_BASES replaced by module_BASE_PTRS.
+** Update of system and startup files.
+** - rev. 0.3 (2014-08-28)
+** Update of system files - default clock configuration changed.
+** Update of startup files - possibility to override DefaultISR added.
+** - rev. 0.4 (2014-10-14)
+** Interrupt INT_LPTimer renamed to INT_LPTMR0, interrupt INT_Watchdog renamed to INT_WDOG_EWM.
+** - rev. 0.5 (2015-01-21)
+** Added FSL_FEATURE_SOC_peripheral_COUNT with number of peripheral instances
+** - rev. 0.6 (2015-02-19)
+** Renamed interrupt vector LLW to LLWU.
+** - rev. 0.7 (2015-05-19)
+** FSL_FEATURE_SOC_CAU_COUNT remamed to FSL_FEATURE_SOC_MMCAU_COUNT.
+** Added FSL_FEATURE_SOC_peripheral_COUNT for TRNG and HSADC.
+** Added features for PDB and PORT.
+** - rev. 0.8 (2015-05-25)
+** Added FSL_FEATURE_FLASH_PFLASH_START_ADDRESS
+** - rev. 0.9 (2015-06-08)
+** FTM features BUS_CLOCK and FAST_CLOCK removed.
+**
+** ###################################################################
+*/
+
+#ifndef _MK02F12810_FEATURES_H_
+#define _MK02F12810_FEATURES_H_
+
+/* SOC module features */
+
+/* @brief ADC16 availability on the SoC. */
+#define FSL_FEATURE_SOC_ADC16_COUNT (1)
+/* @brief CMP availability on the SoC. */
+#define FSL_FEATURE_SOC_CMP_COUNT (2)
+/* @brief CRC availability on the SoC. */
+#define FSL_FEATURE_SOC_CRC_COUNT (1)
+/* @brief DAC availability on the SoC. */
+#define FSL_FEATURE_SOC_DAC_COUNT (1)
+/* @brief EDMA availability on the SoC. */
+#define FSL_FEATURE_SOC_EDMA_COUNT (1)
+/* @brief DMAMUX availability on the SoC. */
+#define FSL_FEATURE_SOC_DMAMUX_COUNT (1)
+/* @brief DSPI availability on the SoC. */
+#define FSL_FEATURE_SOC_DSPI_COUNT (1)
+/* @brief EWM availability on the SoC. */
+#define FSL_FEATURE_SOC_EWM_COUNT (1)
+/* @brief FMC availability on the SoC. */
+#define FSL_FEATURE_SOC_FMC_COUNT (1)
+/* @brief FTFA availability on the SoC. */
+#define FSL_FEATURE_SOC_FTFA_COUNT (1)
+/* @brief FTM availability on the SoC. */
+#define FSL_FEATURE_SOC_FTM_COUNT (3)
+/* @brief GPIO availability on the SoC. */
+#define FSL_FEATURE_SOC_GPIO_COUNT (5)
+/* @brief I2C availability on the SoC. */
+#define FSL_FEATURE_SOC_I2C_COUNT (1)
+/* @brief LLWU availability on the SoC. */
+#define FSL_FEATURE_SOC_LLWU_COUNT (1)
+/* @brief LPTMR availability on the SoC. */
+#define FSL_FEATURE_SOC_LPTMR_COUNT (1)
+/* @brief MCG availability on the SoC. */
+#define FSL_FEATURE_SOC_MCG_COUNT (1)
+/* @brief MCM availability on the SoC. */
+#define FSL_FEATURE_SOC_MCM_COUNT (1)
+/* @brief OSC availability on the SoC. */
+#define FSL_FEATURE_SOC_OSC_COUNT (1)
+/* @brief PDB availability on the SoC. */
+#define FSL_FEATURE_SOC_PDB_COUNT (1)
+/* @brief PIT availability on the SoC. */
+#define FSL_FEATURE_SOC_PIT_COUNT (1)
+/* @brief PMC availability on the SoC. */
+#define FSL_FEATURE_SOC_PMC_COUNT (1)
+/* @brief PORT availability on the SoC. */
+#define FSL_FEATURE_SOC_PORT_COUNT (5)
+/* @brief RCM availability on the SoC. */
+#define FSL_FEATURE_SOC_RCM_COUNT (1)
+/* @brief SIM availability on the SoC. */
+#define FSL_FEATURE_SOC_SIM_COUNT (1)
+/* @brief SMC availability on the SoC. */
+#define FSL_FEATURE_SOC_SMC_COUNT (1)
+/* @brief UART availability on the SoC. */
+#define FSL_FEATURE_SOC_UART_COUNT (2)
+/* @brief VREF availability on the SoC. */
+#define FSL_FEATURE_SOC_VREF_COUNT (1)
+/* @brief WDOG availability on the SoC. */
+#define FSL_FEATURE_SOC_WDOG_COUNT (1)
+
+/* ADC16 module features */
+
+/* @brief Has Programmable Gain Amplifier (PGA) in ADC (register PGA). */
+#define FSL_FEATURE_ADC16_HAS_PGA (0)
+/* @brief Has PGA chopping control in ADC (bit PGA[PGACHPb] or PGA[PGACHP]). */
+#define FSL_FEATURE_ADC16_HAS_PGA_CHOPPING (0)
+/* @brief Has PGA offset measurement mode in ADC (bit PGA[PGAOFSM]). */
+#define FSL_FEATURE_ADC16_HAS_PGA_OFFSET_MEASUREMENT (0)
+/* @brief Has DMA support (bit SC2[DMAEN] or SC4[DMAEN]). */
+#define FSL_FEATURE_ADC16_HAS_DMA (1)
+/* @brief Has differential mode (bitfield SC1x[DIFF]). */
+#define FSL_FEATURE_ADC16_HAS_DIFF_MODE (1)
+/* @brief Has FIFO (bit SC4[AFDEP]). */
+#define FSL_FEATURE_ADC16_HAS_FIFO (0)
+/* @brief FIFO size if available (bitfield SC4[AFDEP]). */
+#define FSL_FEATURE_ADC16_FIFO_SIZE (0)
+/* @brief Has channel set a/b multiplexor (bitfield CFG2[MUXSEL]). */
+#define FSL_FEATURE_ADC16_HAS_MUX_SELECT (1)
+/* @brief Has HW trigger masking (bitfield SC5[HTRGMASKE]. */
+#define FSL_FEATURE_ADC16_HAS_HW_TRIGGER_MASK (0)
+/* @brief Has calibration feature (bit SC3[CAL] and registers CLPx, CLMx). */
+#define FSL_FEATURE_ADC16_HAS_CALIBRATION (1)
+/* @brief Has HW averaging (bit SC3[AVGE]). */
+#define FSL_FEATURE_ADC16_HAS_HW_AVERAGE (1)
+/* @brief Has offset correction (register OFS). */
+#define FSL_FEATURE_ADC16_HAS_OFFSET_CORRECTION (1)
+/* @brief Maximum ADC resolution. */
+#define FSL_FEATURE_ADC16_MAX_RESOLUTION (16)
+/* @brief Number of SC1x and Rx register pairs (conversion control and result registers). */
+#define FSL_FEATURE_ADC16_CONVERSION_CONTROL_COUNT (2)
+
+/* CMP module features */
+
+/* @brief Has Trigger mode in CMP (register bit field CR1[TRIGM]). */
+#define FSL_FEATURE_CMP_HAS_TRIGGER_MODE (1)
+/* @brief Has Window mode in CMP (register bit field CR1[WE]). */
+#define FSL_FEATURE_CMP_HAS_WINDOW_MODE (1)
+/* @brief Has External sample supported in CMP (register bit field CR1[SE]). */
+#define FSL_FEATURE_CMP_HAS_EXTERNAL_SAMPLE_SUPPORT (1)
+/* @brief Has DMA support in CMP (register bit field SCR[DMAEN]). */
+#define FSL_FEATURE_CMP_HAS_DMA (1)
+/* @brief Has Pass Through mode in CMP (register bit field MUXCR[PSTM]). */
+#define FSL_FEATURE_CMP_HAS_PASS_THROUGH_MODE (0)
+/* @brief Has DAC Test function in CMP (register DACTEST). */
+#define FSL_FEATURE_CMP_HAS_DAC_TEST (0)
+
+/* CRC module features */
+
+/* @brief Has data register with name CRC */
+#define FSL_FEATURE_CRC_HAS_CRC_REG (0)
+
+/* DAC module features */
+
+/* @brief Define the size of hardware buffer */
+#define FSL_FEATURE_DAC_BUFFER_SIZE (16)
+/* @brief Define whether the buffer supports watermark event detection or not. */
+#define FSL_FEATURE_DAC_HAS_WATERMARK_DETECTION (1)
+/* @brief Define whether the buffer supports watermark selection detection or not. */
+#define FSL_FEATURE_DAC_HAS_WATERMARK_SELECTION (1)
+/* @brief Define whether the buffer supports watermark event 1 word before buffer upper limit. */
+#define FSL_FEATURE_DAC_HAS_WATERMARK_1_WORD (1)
+/* @brief Define whether the buffer supports watermark event 2 words before buffer upper limit. */
+#define FSL_FEATURE_DAC_HAS_WATERMARK_2_WORDS (1)
+/* @brief Define whether the buffer supports watermark event 3 words before buffer upper limit. */
+#define FSL_FEATURE_DAC_HAS_WATERMARK_3_WORDS (1)
+/* @brief Define whether the buffer supports watermark event 4 words before buffer upper limit. */
+#define FSL_FEATURE_DAC_HAS_WATERMARK_4_WORDS (1)
+/* @brief Define whether FIFO buffer mode is available or not. */
+#define FSL_FEATURE_DAC_HAS_BUFFER_FIFO_MODE (1)
+/* @brief Define whether swing buffer mode is available or not.. */
+#define FSL_FEATURE_DAC_HAS_BUFFER_SWING_MODE (1)
+
+/* EDMA module features */
+
+/* @brief Number of DMA channels (related to number of registers TCD, DCHPRI, bit fields ERQ[ERQn], EEI[EEIn], INT[INTn], ERR[ERRn], HRS[HRSn] and bit field widths ES[ERRCHN], CEEI[CEEI], SEEI[SEEI], CERQ[CERQ], SERQ[SERQ], CDNE[CDNE], SSRT[SSRT], CERR[CERR], CINT[CINT], TCDn_CITER_ELINKYES[LINKCH], TCDn_CSR[MAJORLINKCH], TCDn_BITER_ELINKYES[LINKCH]). (Valid only for eDMA modules.) */
+#define FSL_FEATURE_EDMA_MODULE_CHANNEL (4)
+/* @brief Total number of DMA channels on all modules. */
+#define FSL_FEATURE_EDMA_DMAMUX_CHANNELS (FSL_FEATURE_SOC_EDMA_COUNT * 4)
+/* @brief Number of DMA channel groups (register bit fields CR[ERGA], CR[GRPnPRI], ES[GPE], DCHPRIn[GRPPRI]). (Valid only for eDMA modules.) */
+#define FSL_FEATURE_EDMA_CHANNEL_GROUP_COUNT (1)
+/* @brief Has DMA_Error interrupt vector. */
+#define FSL_FEATURE_EDMA_HAS_ERROR_IRQ (1)
+/* @brief Number of DMA channels with asynchronous request capability (register EARS). (Valid only for eDMA modules.) */
+#define FSL_FEATURE_EDMA_ASYNCHRO_REQUEST_CHANNEL_COUNT (4)
+
+/* DMAMUX module features */
+
+/* @brief Number of DMA channels (related to number of register CHCFGn). */
+#define FSL_FEATURE_DMAMUX_MODULE_CHANNEL (4)
+/* @brief Total number of DMA channels on all modules. */
+#define FSL_FEATURE_DMAMUX_DMAMUX_CHANNELS (FSL_FEATURE_SOC_DMAMUX_COUNT * 4)
+/* @brief Has the periodic trigger capability for the triggered DMA channel (register bit CHCFG0[TRIG]). */
+#define FSL_FEATURE_DMAMUX_HAS_TRIG (1)
+
+/* EWM module features */
+
+/* @brief Has clock select (register CLKCTRL). */
+#define FSL_FEATURE_EWM_HAS_CLOCK_SELECT (0)
+/* @brief Has clock prescaler (register CLKPRESCALER). */
+#define FSL_FEATURE_EWM_HAS_PRESCALER (1)
+
+/* FLASH module features */
+
+#if defined(CPU_MK02FN128VFM10) || defined(CPU_MK02FN128VLF10) || defined(CPU_MK02FN128VLH10)
+ /* @brief Is of type FTFA. */
+ #define FSL_FEATURE_FLASH_IS_FTFA (1)
+ /* @brief Is of type FTFE. */
+ #define FSL_FEATURE_FLASH_IS_FTFE (0)
+ /* @brief Is of type FTFL. */
+ #define FSL_FEATURE_FLASH_IS_FTFL (0)
+ /* @brief Has flags indicating the status of the FlexRAM (register bits FCNFG[EEERDY], FCNFG[RAMRDY] and FCNFG[PFLSH]). */
+ #define FSL_FEATURE_FLASH_HAS_FLEX_RAM_FLAGS (0)
+ /* @brief Has program flash swapping status flag (register bit FCNFG[SWAP]). */
+ #define FSL_FEATURE_FLASH_HAS_PFLASH_SWAPPING_STATUS_FLAG (0)
+ /* @brief Has EEPROM region protection (register FEPROT). */
+ #define FSL_FEATURE_FLASH_HAS_EEROM_REGION_PROTECTION (0)
+ /* @brief Has data flash region protection (register FDPROT). */
+ #define FSL_FEATURE_FLASH_HAS_DATA_FLASH_REGION_PROTECTION (0)
+ /* @brief Has flash access control (registers XACCHn, SACCHn, where n is a number, FACSS and FACSN). */
+ #define FSL_FEATURE_FLASH_HAS_ACCESS_CONTROL (1)
+ /* @brief Has flash cache control in FMC module. */
+ #define FSL_FEATURE_FLASH_HAS_FMC_FLASH_CACHE_CONTROLS (1)
+ /* @brief Has flash cache control in MCM module. */
+ #define FSL_FEATURE_FLASH_HAS_MCM_FLASH_CACHE_CONTROLS (0)
+ /* @brief Has flash cache control in MSCM module. */
+ #define FSL_FEATURE_FLASH_HAS_MSCM_FLASH_CACHE_CONTROLS (0)
+ /* @brief Has prefetch speculation control in flash, such as kv5x. */
+ #define FSL_FEATURE_FLASH_PREFETCH_SPECULATION_CONTROL_IN_FLASH (0)
+ /* @brief P-Flash flash size coding rule version, value 0 for K1 and K2, value 1 for K3. */
+ #define FSL_FEATURE_FLASH_SIZE_ENCODING_RULE_VERSION (0)
+ /* @brief P-Flash start address. */
+ #define FSL_FEATURE_FLASH_PFLASH_START_ADDRESS (0x00000000)
+ /* @brief P-Flash block count. */
+ #define FSL_FEATURE_FLASH_PFLASH_BLOCK_COUNT (1)
+ /* @brief P-Flash block size. */
+ #define FSL_FEATURE_FLASH_PFLASH_BLOCK_SIZE (131072)
+ /* @brief P-Flash sector size. */
+ #define FSL_FEATURE_FLASH_PFLASH_BLOCK_SECTOR_SIZE (2048)
+ /* @brief P-Flash write unit size. */
+ #define FSL_FEATURE_FLASH_PFLASH_BLOCK_WRITE_UNIT_SIZE (4)
+ /* @brief P-Flash data path width. */
+ #define FSL_FEATURE_FLASH_PFLASH_BLOCK_DATA_PATH_WIDTH (8)
+ /* @brief P-Flash block swap feature. */
+ #define FSL_FEATURE_FLASH_HAS_PFLASH_BLOCK_SWAP (0)
+ /* @brief P-Flash protection region count. */
+ #define FSL_FEATURE_FLASH_PFLASH_PROTECTION_REGION_COUNT (32)
+ /* @brief Has FlexNVM memory. */
+ #define FSL_FEATURE_FLASH_HAS_FLEX_NVM (0)
+ /* @brief FlexNVM start address. (Valid only if FlexNVM is available.) */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_START_ADDRESS (0x00000000)
+ /* @brief FlexNVM block count. */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_BLOCK_COUNT (0)
+ /* @brief FlexNVM block size. */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_BLOCK_SIZE (0)
+ /* @brief FlexNVM sector size. */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_BLOCK_SECTOR_SIZE (0)
+ /* @brief FlexNVM write unit size. */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_BLOCK_WRITE_UNIT_SIZE (0)
+ /* @brief FlexNVM data path width. */
+ #define FSL_FEATURE_FLASH_FLEX_BLOCK_DATA_PATH_WIDTH (0)
+ /* @brief Has FlexRAM memory. */
+ #define FSL_FEATURE_FLASH_HAS_FLEX_RAM (0)
+ /* @brief FlexRAM start address. (Valid only if FlexRAM is available.) */
+ #define FSL_FEATURE_FLASH_FLEX_RAM_START_ADDRESS (0x00000000)
+ /* @brief FlexRAM size. */
+ #define FSL_FEATURE_FLASH_FLEX_RAM_SIZE (0)
+ /* @brief Has 0x00 Read 1s Block command. */
+ #define FSL_FEATURE_FLASH_HAS_READ_1S_BLOCK_CMD (0)
+ /* @brief Has 0x01 Read 1s Section command. */
+ #define FSL_FEATURE_FLASH_HAS_READ_1S_SECTION_CMD (1)
+ /* @brief Has 0x02 Program Check command. */
+ #define FSL_FEATURE_FLASH_HAS_PROGRAM_CHECK_CMD (1)
+ /* @brief Has 0x03 Read Resource command. */
+ #define FSL_FEATURE_FLASH_HAS_READ_RESOURCE_CMD (1)
+ /* @brief Has 0x06 Program Longword command. */
+ #define FSL_FEATURE_FLASH_HAS_PROGRAM_LONGWORD_CMD (1)
+ /* @brief Has 0x07 Program Phrase command. */
+ #define FSL_FEATURE_FLASH_HAS_PROGRAM_PHRASE_CMD (0)
+ /* @brief Has 0x08 Erase Flash Block command. */
+ #define FSL_FEATURE_FLASH_HAS_ERASE_FLASH_BLOCK_CMD (0)
+ /* @brief Has 0x09 Erase Flash Sector command. */
+ #define FSL_FEATURE_FLASH_HAS_ERASE_FLASH_SECTOR_CMD (1)
+ /* @brief Has 0x0B Program Section command. */
+ #define FSL_FEATURE_FLASH_HAS_PROGRAM_SECTION_CMD (0)
+ /* @brief Has 0x40 Read 1s All Blocks command. */
+ #define FSL_FEATURE_FLASH_HAS_READ_1S_ALL_BLOCKS_CMD (1)
+ /* @brief Has 0x41 Read Once command. */
+ #define FSL_FEATURE_FLASH_HAS_READ_ONCE_CMD (1)
+ /* @brief Has 0x43 Program Once command. */
+ #define FSL_FEATURE_FLASH_HAS_PROGRAM_ONCE_CMD (1)
+ /* @brief Has 0x44 Erase All Blocks command. */
+ #define FSL_FEATURE_FLASH_HAS_ERASE_ALL_BLOCKS_CMD (1)
+ /* @brief Has 0x45 Verify Backdoor Access Key command. */
+ #define FSL_FEATURE_FLASH_HAS_VERIFY_BACKDOOR_ACCESS_KEY_CMD (1)
+ /* @brief Has 0x46 Swap Control command. */
+ #define FSL_FEATURE_FLASH_HAS_SWAP_CONTROL_CMD (0)
+ /* @brief Has 0x49 Erase All Blocks Unsecure command. */
+ #define FSL_FEATURE_FLASH_HAS_ERASE_ALL_BLOCKS_UNSECURE_CMD (0)
+ /* @brief Has 0x4A Read 1s All Execute-only Segments command. */
+ #define FSL_FEATURE_FLASH_HAS_READ_1S_ALL_EXECUTE_ONLY_SEGMENTS_CMD (0)
+ /* @brief Has 0x4B Erase All Execute-only Segments command. */
+ #define FSL_FEATURE_FLASH_HAS_ERASE_ALL_EXECUTE_ONLY_SEGMENTS_CMD (0)
+ /* @brief Has 0x80 Program Partition command. */
+ #define FSL_FEATURE_FLASH_HAS_PROGRAM_PARTITION_CMD (0)
+ /* @brief Has 0x81 Set FlexRAM Function command. */
+ #define FSL_FEATURE_FLASH_HAS_SET_FLEXRAM_FUNCTION_CMD (0)
+ /* @brief P-Flash Erase/Read 1st all block command address alignment. */
+ #define FSL_FEATURE_FLASH_PFLASH_BLOCK_CMD_ADDRESS_ALIGMENT (4)
+ /* @brief P-Flash Erase sector command address alignment. */
+ #define FSL_FEATURE_FLASH_PFLASH_SECTOR_CMD_ADDRESS_ALIGMENT (8)
+ /* @brief P-Flash Rrogram/Verify section command address alignment. */
+ #define FSL_FEATURE_FLASH_PFLASH_SECTION_CMD_ADDRESS_ALIGMENT (8)
+ /* @brief P-Flash Read resource command address alignment. */
+ #define FSL_FEATURE_FLASH_PFLASH_RESOURCE_CMD_ADDRESS_ALIGMENT (4)
+ /* @brief P-Flash Program check command address alignment. */
+ #define FSL_FEATURE_FLASH_PFLASH_CHECK_CMD_ADDRESS_ALIGMENT (4)
+ /* @brief P-Flash Program check command address alignment. */
+ #define FSL_FEATURE_FLASH_PFLASH_SWAP_CONTROL_CMD_ADDRESS_ALIGMENT (0)
+ /* @brief FlexNVM Erase/Read 1st all block command address alignment. */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_BLOCK_CMD_ADDRESS_ALIGMENT (0)
+ /* @brief FlexNVM Erase sector command address alignment. */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_SECTOR_CMD_ADDRESS_ALIGMENT (0)
+ /* @brief FlexNVM Rrogram/Verify section command address alignment. */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_SECTION_CMD_ADDRESS_ALIGMENT (0)
+ /* @brief FlexNVM Read resource command address alignment. */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_RESOURCE_CMD_ADDRESS_ALIGMENT (0)
+ /* @brief FlexNVM Program check command address alignment. */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_CHECK_CMD_ADDRESS_ALIGMENT (0)
+ /* @brief FlexNVM partition code 0000 mapping to data flash size in bytes (0xFFFFFFFF = reserved). */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_0000 (0xFFFFFFFF)
+ /* @brief FlexNVM partition code 0001 mapping to data flash size in bytes (0xFFFFFFFF = reserved). */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_0001 (0xFFFFFFFF)
+ /* @brief FlexNVM partition code 0010 mapping to data flash size in bytes (0xFFFFFFFF = reserved). */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_0010 (0xFFFFFFFF)
+ /* @brief FlexNVM partition code 0011 mapping to data flash size in bytes (0xFFFFFFFF = reserved). */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_0011 (0xFFFFFFFF)
+ /* @brief FlexNVM partition code 0100 mapping to data flash size in bytes (0xFFFFFFFF = reserved). */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_0100 (0xFFFFFFFF)
+ /* @brief FlexNVM partition code 0101 mapping to data flash size in bytes (0xFFFFFFFF = reserved). */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_0101 (0xFFFFFFFF)
+ /* @brief FlexNVM partition code 0110 mapping to data flash size in bytes (0xFFFFFFFF = reserved). */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_0110 (0xFFFFFFFF)
+ /* @brief FlexNVM partition code 0111 mapping to data flash size in bytes (0xFFFFFFFF = reserved). */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_0111 (0xFFFFFFFF)
+ /* @brief FlexNVM partition code 1000 mapping to data flash size in bytes (0xFFFFFFFF = reserved). */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_1000 (0xFFFFFFFF)
+ /* @brief FlexNVM partition code 1001 mapping to data flash size in bytes (0xFFFFFFFF = reserved). */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_1001 (0xFFFFFFFF)
+ /* @brief FlexNVM partition code 1010 mapping to data flash size in bytes (0xFFFFFFFF = reserved). */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_1010 (0xFFFFFFFF)
+ /* @brief FlexNVM partition code 1011 mapping to data flash size in bytes (0xFFFFFFFF = reserved). */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_1011 (0xFFFFFFFF)
+ /* @brief FlexNVM partition code 1100 mapping to data flash size in bytes (0xFFFFFFFF = reserved). */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_1100 (0xFFFFFFFF)
+ /* @brief FlexNVM partition code 1101 mapping to data flash size in bytes (0xFFFFFFFF = reserved). */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_1101 (0xFFFFFFFF)
+ /* @brief FlexNVM partition code 1110 mapping to data flash size in bytes (0xFFFFFFFF = reserved). */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_1110 (0xFFFFFFFF)
+ /* @brief FlexNVM partition code 1111 mapping to data flash size in bytes (0xFFFFFFFF = reserved). */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_1111 (0xFFFFFFFF)
+ /* @brief Emulated eeprom size code 0000 mapping to emulated eeprom size in bytes (0xFFFF = reserved). */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_EEPROM_SIZE_FOR_EEESIZE_0000 (0xFFFF)
+ /* @brief Emulated eeprom size code 0001 mapping to emulated eeprom size in bytes (0xFFFF = reserved). */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_EEPROM_SIZE_FOR_EEESIZE_0001 (0xFFFF)
+ /* @brief Emulated eeprom size code 0010 mapping to emulated eeprom size in bytes (0xFFFF = reserved). */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_EEPROM_SIZE_FOR_EEESIZE_0010 (0xFFFF)
+ /* @brief Emulated eeprom size code 0011 mapping to emulated eeprom size in bytes (0xFFFF = reserved). */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_EEPROM_SIZE_FOR_EEESIZE_0011 (0xFFFF)
+ /* @brief Emulated eeprom size code 0100 mapping to emulated eeprom size in bytes (0xFFFF = reserved). */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_EEPROM_SIZE_FOR_EEESIZE_0100 (0xFFFF)
+ /* @brief Emulated eeprom size code 0101 mapping to emulated eeprom size in bytes (0xFFFF = reserved). */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_EEPROM_SIZE_FOR_EEESIZE_0101 (0xFFFF)
+ /* @brief Emulated eeprom size code 0110 mapping to emulated eeprom size in bytes (0xFFFF = reserved). */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_EEPROM_SIZE_FOR_EEESIZE_0110 (0xFFFF)
+ /* @brief Emulated eeprom size code 0111 mapping to emulated eeprom size in bytes (0xFFFF = reserved). */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_EEPROM_SIZE_FOR_EEESIZE_0111 (0xFFFF)
+ /* @brief Emulated eeprom size code 1000 mapping to emulated eeprom size in bytes (0xFFFF = reserved). */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_EEPROM_SIZE_FOR_EEESIZE_1000 (0xFFFF)
+ /* @brief Emulated eeprom size code 1001 mapping to emulated eeprom size in bytes (0xFFFF = reserved). */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_EEPROM_SIZE_FOR_EEESIZE_1001 (0xFFFF)
+ /* @brief Emulated eeprom size code 1010 mapping to emulated eeprom size in bytes (0xFFFF = reserved). */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_EEPROM_SIZE_FOR_EEESIZE_1010 (0xFFFF)
+ /* @brief Emulated eeprom size code 1011 mapping to emulated eeprom size in bytes (0xFFFF = reserved). */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_EEPROM_SIZE_FOR_EEESIZE_1011 (0xFFFF)
+ /* @brief Emulated eeprom size code 1100 mapping to emulated eeprom size in bytes (0xFFFF = reserved). */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_EEPROM_SIZE_FOR_EEESIZE_1100 (0xFFFF)
+ /* @brief Emulated eeprom size code 1101 mapping to emulated eeprom size in bytes (0xFFFF = reserved). */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_EEPROM_SIZE_FOR_EEESIZE_1101 (0xFFFF)
+ /* @brief Emulated eeprom size code 1110 mapping to emulated eeprom size in bytes (0xFFFF = reserved). */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_EEPROM_SIZE_FOR_EEESIZE_1110 (0xFFFF)
+ /* @brief Emulated eeprom size code 1111 mapping to emulated eeprom size in bytes (0xFFFF = reserved). */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_EEPROM_SIZE_FOR_EEESIZE_1111 (0xFFFF)
+#elif defined(CPU_MK02FN64VFM10) || defined(CPU_MK02FN64VLF10) || defined(CPU_MK02FN64VLH10)
+ /* @brief Is of type FTFA. */
+ #define FSL_FEATURE_FLASH_IS_FTFA (1)
+ /* @brief Is of type FTFE. */
+ #define FSL_FEATURE_FLASH_IS_FTFE (0)
+ /* @brief Is of type FTFL. */
+ #define FSL_FEATURE_FLASH_IS_FTFL (0)
+ /* @brief Has flags indicating the status of the FlexRAM (register bits FCNFG[EEERDY], FCNFG[RAMRDY] and FCNFG[PFLSH]). */
+ #define FSL_FEATURE_FLASH_HAS_FLEX_RAM_FLAGS (0)
+ /* @brief Has program flash swapping status flag (register bit FCNFG[SWAP]). */
+ #define FSL_FEATURE_FLASH_HAS_PFLASH_SWAPPING_STATUS_FLAG (0)
+ /* @brief Has EEPROM region protection (register FEPROT). */
+ #define FSL_FEATURE_FLASH_HAS_EEROM_REGION_PROTECTION (0)
+ /* @brief Has data flash region protection (register FDPROT). */
+ #define FSL_FEATURE_FLASH_HAS_DATA_FLASH_REGION_PROTECTION (0)
+ /* @brief Has flash access control (registers XACCHn, SACCHn, where n is a number, FACSS and FACSN). */
+ #define FSL_FEATURE_FLASH_HAS_ACCESS_CONTROL (1)
+ /* @brief Has flash cache control in FMC module. */
+ #define FSL_FEATURE_FLASH_HAS_FMC_FLASH_CACHE_CONTROLS (1)
+ /* @brief Has flash cache control in MCM module. */
+ #define FSL_FEATURE_FLASH_HAS_MCM_FLASH_CACHE_CONTROLS (0)
+ /* @brief Has flash cache control in MSCM module. */
+ #define FSL_FEATURE_FLASH_HAS_MSCM_FLASH_CACHE_CONTROLS (0)
+ /* @brief Has prefetch speculation control in flash, such as kv5x. */
+ #define FSL_FEATURE_FLASH_PREFETCH_SPECULATION_CONTROL_IN_FLASH (0)
+ /* @brief P-Flash flash size coding rule version, value 0 for K1 and K2, value 1 for K3. */
+ #define FSL_FEATURE_FLASH_SIZE_ENCODING_RULE_VERSION (0)
+ /* @brief P-Flash start address. */
+ #define FSL_FEATURE_FLASH_PFLASH_START_ADDRESS (0x00000000)
+ /* @brief P-Flash block count. */
+ #define FSL_FEATURE_FLASH_PFLASH_BLOCK_COUNT (1)
+ /* @brief P-Flash block size. */
+ #define FSL_FEATURE_FLASH_PFLASH_BLOCK_SIZE (65536)
+ /* @brief P-Flash sector size. */
+ #define FSL_FEATURE_FLASH_PFLASH_BLOCK_SECTOR_SIZE (2048)
+ /* @brief P-Flash write unit size. */
+ #define FSL_FEATURE_FLASH_PFLASH_BLOCK_WRITE_UNIT_SIZE (4)
+ /* @brief P-Flash data path width. */
+ #define FSL_FEATURE_FLASH_PFLASH_BLOCK_DATA_PATH_WIDTH (8)
+ /* @brief P-Flash block swap feature. */
+ #define FSL_FEATURE_FLASH_HAS_PFLASH_BLOCK_SWAP (0)
+ /* @brief P-Flash protection region count. */
+ #define FSL_FEATURE_FLASH_PFLASH_PROTECTION_REGION_COUNT (32)
+ /* @brief Has FlexNVM memory. */
+ #define FSL_FEATURE_FLASH_HAS_FLEX_NVM (0)
+ /* @brief FlexNVM start address. (Valid only if FlexNVM is available.) */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_START_ADDRESS (0x00000000)
+ /* @brief FlexNVM block count. */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_BLOCK_COUNT (0)
+ /* @brief FlexNVM block size. */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_BLOCK_SIZE (0)
+ /* @brief FlexNVM sector size. */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_BLOCK_SECTOR_SIZE (0)
+ /* @brief FlexNVM write unit size. */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_BLOCK_WRITE_UNIT_SIZE (0)
+ /* @brief FlexNVM data path width. */
+ #define FSL_FEATURE_FLASH_FLEX_BLOCK_DATA_PATH_WIDTH (0)
+ /* @brief Has FlexRAM memory. */
+ #define FSL_FEATURE_FLASH_HAS_FLEX_RAM (0)
+ /* @brief FlexRAM start address. (Valid only if FlexRAM is available.) */
+ #define FSL_FEATURE_FLASH_FLEX_RAM_START_ADDRESS (0x00000000)
+ /* @brief FlexRAM size. */
+ #define FSL_FEATURE_FLASH_FLEX_RAM_SIZE (0)
+ /* @brief Has 0x00 Read 1s Block command. */
+ #define FSL_FEATURE_FLASH_HAS_READ_1S_BLOCK_CMD (0)
+ /* @brief Has 0x01 Read 1s Section command. */
+ #define FSL_FEATURE_FLASH_HAS_READ_1S_SECTION_CMD (1)
+ /* @brief Has 0x02 Program Check command. */
+ #define FSL_FEATURE_FLASH_HAS_PROGRAM_CHECK_CMD (1)
+ /* @brief Has 0x03 Read Resource command. */
+ #define FSL_FEATURE_FLASH_HAS_READ_RESOURCE_CMD (1)
+ /* @brief Has 0x06 Program Longword command. */
+ #define FSL_FEATURE_FLASH_HAS_PROGRAM_LONGWORD_CMD (1)
+ /* @brief Has 0x07 Program Phrase command. */
+ #define FSL_FEATURE_FLASH_HAS_PROGRAM_PHRASE_CMD (0)
+ /* @brief Has 0x08 Erase Flash Block command. */
+ #define FSL_FEATURE_FLASH_HAS_ERASE_FLASH_BLOCK_CMD (0)
+ /* @brief Has 0x09 Erase Flash Sector command. */
+ #define FSL_FEATURE_FLASH_HAS_ERASE_FLASH_SECTOR_CMD (1)
+ /* @brief Has 0x0B Program Section command. */
+ #define FSL_FEATURE_FLASH_HAS_PROGRAM_SECTION_CMD (0)
+ /* @brief Has 0x40 Read 1s All Blocks command. */
+ #define FSL_FEATURE_FLASH_HAS_READ_1S_ALL_BLOCKS_CMD (1)
+ /* @brief Has 0x41 Read Once command. */
+ #define FSL_FEATURE_FLASH_HAS_READ_ONCE_CMD (1)
+ /* @brief Has 0x43 Program Once command. */
+ #define FSL_FEATURE_FLASH_HAS_PROGRAM_ONCE_CMD (1)
+ /* @brief Has 0x44 Erase All Blocks command. */
+ #define FSL_FEATURE_FLASH_HAS_ERASE_ALL_BLOCKS_CMD (1)
+ /* @brief Has 0x45 Verify Backdoor Access Key command. */
+ #define FSL_FEATURE_FLASH_HAS_VERIFY_BACKDOOR_ACCESS_KEY_CMD (1)
+ /* @brief Has 0x46 Swap Control command. */
+ #define FSL_FEATURE_FLASH_HAS_SWAP_CONTROL_CMD (0)
+ /* @brief Has 0x49 Erase All Blocks Unsecure command. */
+ #define FSL_FEATURE_FLASH_HAS_ERASE_ALL_BLOCKS_UNSECURE_CMD (0)
+ /* @brief Has 0x4A Read 1s All Execute-only Segments command. */
+ #define FSL_FEATURE_FLASH_HAS_READ_1S_ALL_EXECUTE_ONLY_SEGMENTS_CMD (0)
+ /* @brief Has 0x4B Erase All Execute-only Segments command. */
+ #define FSL_FEATURE_FLASH_HAS_ERASE_ALL_EXECUTE_ONLY_SEGMENTS_CMD (0)
+ /* @brief Has 0x80 Program Partition command. */
+ #define FSL_FEATURE_FLASH_HAS_PROGRAM_PARTITION_CMD (0)
+ /* @brief Has 0x81 Set FlexRAM Function command. */
+ #define FSL_FEATURE_FLASH_HAS_SET_FLEXRAM_FUNCTION_CMD (0)
+ /* @brief P-Flash Erase/Read 1st all block command address alignment. */
+ #define FSL_FEATURE_FLASH_PFLASH_BLOCK_CMD_ADDRESS_ALIGMENT (4)
+ /* @brief P-Flash Erase sector command address alignment. */
+ #define FSL_FEATURE_FLASH_PFLASH_SECTOR_CMD_ADDRESS_ALIGMENT (8)
+ /* @brief P-Flash Rrogram/Verify section command address alignment. */
+ #define FSL_FEATURE_FLASH_PFLASH_SECTION_CMD_ADDRESS_ALIGMENT (8)
+ /* @brief P-Flash Read resource command address alignment. */
+ #define FSL_FEATURE_FLASH_PFLASH_RESOURCE_CMD_ADDRESS_ALIGMENT (4)
+ /* @brief P-Flash Program check command address alignment. */
+ #define FSL_FEATURE_FLASH_PFLASH_CHECK_CMD_ADDRESS_ALIGMENT (4)
+ /* @brief P-Flash Program check command address alignment. */
+ #define FSL_FEATURE_FLASH_PFLASH_SWAP_CONTROL_CMD_ADDRESS_ALIGMENT (0)
+ /* @brief FlexNVM Erase/Read 1st all block command address alignment. */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_BLOCK_CMD_ADDRESS_ALIGMENT (0)
+ /* @brief FlexNVM Erase sector command address alignment. */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_SECTOR_CMD_ADDRESS_ALIGMENT (0)
+ /* @brief FlexNVM Rrogram/Verify section command address alignment. */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_SECTION_CMD_ADDRESS_ALIGMENT (0)
+ /* @brief FlexNVM Read resource command address alignment. */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_RESOURCE_CMD_ADDRESS_ALIGMENT (0)
+ /* @brief FlexNVM Program check command address alignment. */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_CHECK_CMD_ADDRESS_ALIGMENT (0)
+ /* @brief FlexNVM partition code 0000 mapping to data flash size in bytes (0xFFFFFFFF = reserved). */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_0000 (0xFFFFFFFF)
+ /* @brief FlexNVM partition code 0001 mapping to data flash size in bytes (0xFFFFFFFF = reserved). */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_0001 (0xFFFFFFFF)
+ /* @brief FlexNVM partition code 0010 mapping to data flash size in bytes (0xFFFFFFFF = reserved). */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_0010 (0xFFFFFFFF)
+ /* @brief FlexNVM partition code 0011 mapping to data flash size in bytes (0xFFFFFFFF = reserved). */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_0011 (0xFFFFFFFF)
+ /* @brief FlexNVM partition code 0100 mapping to data flash size in bytes (0xFFFFFFFF = reserved). */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_0100 (0xFFFFFFFF)
+ /* @brief FlexNVM partition code 0101 mapping to data flash size in bytes (0xFFFFFFFF = reserved). */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_0101 (0xFFFFFFFF)
+ /* @brief FlexNVM partition code 0110 mapping to data flash size in bytes (0xFFFFFFFF = reserved). */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_0110 (0xFFFFFFFF)
+ /* @brief FlexNVM partition code 0111 mapping to data flash size in bytes (0xFFFFFFFF = reserved). */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_0111 (0xFFFFFFFF)
+ /* @brief FlexNVM partition code 1000 mapping to data flash size in bytes (0xFFFFFFFF = reserved). */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_1000 (0xFFFFFFFF)
+ /* @brief FlexNVM partition code 1001 mapping to data flash size in bytes (0xFFFFFFFF = reserved). */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_1001 (0xFFFFFFFF)
+ /* @brief FlexNVM partition code 1010 mapping to data flash size in bytes (0xFFFFFFFF = reserved). */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_1010 (0xFFFFFFFF)
+ /* @brief FlexNVM partition code 1011 mapping to data flash size in bytes (0xFFFFFFFF = reserved). */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_1011 (0xFFFFFFFF)
+ /* @brief FlexNVM partition code 1100 mapping to data flash size in bytes (0xFFFFFFFF = reserved). */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_1100 (0xFFFFFFFF)
+ /* @brief FlexNVM partition code 1101 mapping to data flash size in bytes (0xFFFFFFFF = reserved). */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_1101 (0xFFFFFFFF)
+ /* @brief FlexNVM partition code 1110 mapping to data flash size in bytes (0xFFFFFFFF = reserved). */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_1110 (0xFFFFFFFF)
+ /* @brief FlexNVM partition code 1111 mapping to data flash size in bytes (0xFFFFFFFF = reserved). */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_1111 (0xFFFFFFFF)
+ /* @brief Emulated eeprom size code 0000 mapping to emulated eeprom size in bytes (0xFFFF = reserved). */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_EEPROM_SIZE_FOR_EEESIZE_0000 (0xFFFF)
+ /* @brief Emulated eeprom size code 0001 mapping to emulated eeprom size in bytes (0xFFFF = reserved). */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_EEPROM_SIZE_FOR_EEESIZE_0001 (0xFFFF)
+ /* @brief Emulated eeprom size code 0010 mapping to emulated eeprom size in bytes (0xFFFF = reserved). */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_EEPROM_SIZE_FOR_EEESIZE_0010 (0xFFFF)
+ /* @brief Emulated eeprom size code 0011 mapping to emulated eeprom size in bytes (0xFFFF = reserved). */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_EEPROM_SIZE_FOR_EEESIZE_0011 (0xFFFF)
+ /* @brief Emulated eeprom size code 0100 mapping to emulated eeprom size in bytes (0xFFFF = reserved). */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_EEPROM_SIZE_FOR_EEESIZE_0100 (0xFFFF)
+ /* @brief Emulated eeprom size code 0101 mapping to emulated eeprom size in bytes (0xFFFF = reserved). */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_EEPROM_SIZE_FOR_EEESIZE_0101 (0xFFFF)
+ /* @brief Emulated eeprom size code 0110 mapping to emulated eeprom size in bytes (0xFFFF = reserved). */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_EEPROM_SIZE_FOR_EEESIZE_0110 (0xFFFF)
+ /* @brief Emulated eeprom size code 0111 mapping to emulated eeprom size in bytes (0xFFFF = reserved). */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_EEPROM_SIZE_FOR_EEESIZE_0111 (0xFFFF)
+ /* @brief Emulated eeprom size code 1000 mapping to emulated eeprom size in bytes (0xFFFF = reserved). */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_EEPROM_SIZE_FOR_EEESIZE_1000 (0xFFFF)
+ /* @brief Emulated eeprom size code 1001 mapping to emulated eeprom size in bytes (0xFFFF = reserved). */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_EEPROM_SIZE_FOR_EEESIZE_1001 (0xFFFF)
+ /* @brief Emulated eeprom size code 1010 mapping to emulated eeprom size in bytes (0xFFFF = reserved). */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_EEPROM_SIZE_FOR_EEESIZE_1010 (0xFFFF)
+ /* @brief Emulated eeprom size code 1011 mapping to emulated eeprom size in bytes (0xFFFF = reserved). */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_EEPROM_SIZE_FOR_EEESIZE_1011 (0xFFFF)
+ /* @brief Emulated eeprom size code 1100 mapping to emulated eeprom size in bytes (0xFFFF = reserved). */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_EEPROM_SIZE_FOR_EEESIZE_1100 (0xFFFF)
+ /* @brief Emulated eeprom size code 1101 mapping to emulated eeprom size in bytes (0xFFFF = reserved). */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_EEPROM_SIZE_FOR_EEESIZE_1101 (0xFFFF)
+ /* @brief Emulated eeprom size code 1110 mapping to emulated eeprom size in bytes (0xFFFF = reserved). */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_EEPROM_SIZE_FOR_EEESIZE_1110 (0xFFFF)
+ /* @brief Emulated eeprom size code 1111 mapping to emulated eeprom size in bytes (0xFFFF = reserved). */
+ #define FSL_FEATURE_FLASH_FLEX_NVM_EEPROM_SIZE_FOR_EEESIZE_1111 (0xFFFF)
+#endif /* defined(CPU_MK02FN128VFM10) || defined(CPU_MK02FN128VLF10) || defined(CPU_MK02FN128VLH10) */
+
+/* FTM module features */
+
+/* @brief Number of channels. */
+#define FSL_FEATURE_FTM_CHANNEL_COUNTn(x) \
+ ((x) == FTM0 ? (6) : \
+ ((x) == FTM1 ? (2) : \
+ ((x) == FTM2 ? (2) : (-1))))
+/* @brief Has counter reset by the selected input capture event (register bits C0SC[ICRST], C1SC[ICRST], ...). */
+#define FSL_FEATURE_FTM_HAS_COUNTER_RESET_BY_CAPTURE_EVENT (1)
+/* @brief Has extended deadtime value. */
+#define FSL_FEATURE_FTM_HAS_EXTENDED_DEADTIME_VALUE (0)
+/* @brief Enable pwm output for the module. */
+#define FSL_FEATURE_FTM_HAS_ENABLE_PWM_OUTPUT (0)
+/* @brief Has half-cycle reload for the module. */
+#define FSL_FEATURE_FTM_HAS_HALFCYCLE_RELOAD (0)
+/* @brief Has reload interrupt. */
+#define FSL_FEATURE_FTM_HAS_RELOAD_INTERRUPT (0)
+/* @brief Has reload initialization trigger. */
+#define FSL_FEATURE_FTM_HAS_RELOAD_INITIALIZATION_TRIGGER (0)
+/* @brief Has DMA support, bitfield CnSC[DMA]. */
+#define FSL_FEATURE_FTM_HAS_DMA_SUPPORT (1)
+/* @brief Has no QDCTRL. */
+#define FSL_FEATURE_FTM_HAS_NO_QDCTRL (0)
+
+/* GPIO module features */
+
+/* @brief Has fast (single cycle) access capability via a dedicated memory region. */
+#define FSL_FEATURE_GPIO_HAS_FAST_GPIO (0)
+/* @brief Has port input disable register (PIDR). */
+#define FSL_FEATURE_GPIO_HAS_INPUT_DISABLE (0)
+/* @brief Has dedicated interrupt vector. */
+#define FSL_FEATURE_GPIO_HAS_PORT_INTERRUPT_VECTOR (1)
+
+/* I2C module features */
+
+/* @brief Has System Management Bus support (registers SMB, A2, SLTL and SLTH). */
+#define FSL_FEATURE_I2C_HAS_SMBUS (1)
+/* @brief Maximum supported baud rate in kilobit per second. */
+#define FSL_FEATURE_I2C_MAX_BAUD_KBPS (400)
+/* @brief Is affected by errata with ID 6070 (repeat start cannot be generated if the F[MULT] bit field is set to a non-zero value). */
+#define FSL_FEATURE_I2C_HAS_ERRATA_6070 (0)
+/* @brief Has DMA support (register bit C1[DMAEN]). */
+#define FSL_FEATURE_I2C_HAS_DMA_SUPPORT (1)
+/* @brief Has I2C bus start and stop detection (register bits FLT[SSIE], FLT[STARTF] and FLT[STOPF]). */
+#define FSL_FEATURE_I2C_HAS_START_STOP_DETECT (1)
+/* @brief Has I2C bus stop detection (register bits FLT[STOPIE] and FLT[STOPF]). */
+#define FSL_FEATURE_I2C_HAS_STOP_DETECT (0)
+/* @brief Has I2C bus stop hold off (register bit FLT[SHEN]). */
+#define FSL_FEATURE_I2C_HAS_STOP_HOLD_OFF (1)
+/* @brief Maximum width of the glitch filter in number of bus clocks. */
+#define FSL_FEATURE_I2C_MAX_GLITCH_FILTER_WIDTH (15)
+/* @brief Has control of the drive capability of the I2C pins. */
+#define FSL_FEATURE_I2C_HAS_HIGH_DRIVE_SELECTION (1)
+/* @brief Has double buffering support (register S2). */
+#define FSL_FEATURE_I2C_HAS_DOUBLE_BUFFERING (0)
+/* @brief Has double buffer enable. */
+#define FSL_FEATURE_I2C_HAS_DOUBLE_BUFFER_ENABLE (0)
+
+/* LLWU module features */
+
+#if defined(CPU_MK02FN128VFM10) || defined(CPU_MK02FN64VFM10)
+ /* @brief Maximum number of pins (maximal index plus one) connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN (16)
+ /* @brief Has pins 8-15 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_EXTERNAL_PIN_GROUP2 (1)
+ /* @brief Maximum number of internal modules connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_INTERNAL_MODULE (3)
+ /* @brief Number of digital filters. */
+ #define FSL_FEATURE_LLWU_HAS_PIN_FILTER (2)
+ /* @brief Has MF register. */
+ #define FSL_FEATURE_LLWU_HAS_MF (0)
+ /* @brief Has PF register. */
+ #define FSL_FEATURE_LLWU_HAS_PF (0)
+ /* @brief Has possibility to enable reset in low leakage power mode and enable digital filter for RESET pin (register LLWU_RST). */
+ #define FSL_FEATURE_LLWU_HAS_RESET_ENABLE (0)
+ /* @brief Has no internal module wakeup flag register. */
+ #define FSL_FEATURE_LLWU_HAS_NO_INTERNAL_MODULE_WAKEUP_FLAG_REG (0)
+ /* @brief Has external pin 0 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN0 (0)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN0_GPIO_IDX (0)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN0_GPIO_PIN (0)
+ /* @brief Has external pin 1 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN1 (0)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN1_GPIO_IDX (0)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN1_GPIO_PIN (0)
+ /* @brief Has external pin 2 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN2 (0)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN2_GPIO_IDX (0)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN2_GPIO_PIN (0)
+ /* @brief Has external pin 3 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN3 (1)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN3_GPIO_IDX (GPIOA_IDX)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN3_GPIO_PIN (4)
+ /* @brief Has external pin 4 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN4 (0)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN4_GPIO_IDX (0)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN4_GPIO_PIN (0)
+ /* @brief Has external pin 5 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN5 (1)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN5_GPIO_IDX (GPIOB_IDX)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN5_GPIO_PIN (0)
+ /* @brief Has external pin 6 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN6 (1)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN6_GPIO_IDX (GPIOC_IDX)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN6_GPIO_PIN (1)
+ /* @brief Has external pin 7 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN7 (1)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN7_GPIO_IDX (GPIOC_IDX)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN7_GPIO_PIN (3)
+ /* @brief Has external pin 8 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN8 (1)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN8_GPIO_IDX (GPIOC_IDX)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN8_GPIO_PIN (4)
+ /* @brief Has external pin 9 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN9 (1)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN9_GPIO_IDX (GPIOC_IDX)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN9_GPIO_PIN (5)
+ /* @brief Has external pin 10 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN10 (1)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN10_GPIO_IDX (GPIOC_IDX)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN10_GPIO_PIN (6)
+ /* @brief Has external pin 11 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN11 (0)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN11_GPIO_IDX (0)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN11_GPIO_PIN (0)
+ /* @brief Has external pin 12 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN12 (0)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN12_GPIO_IDX (0)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN12_GPIO_PIN (0)
+ /* @brief Has external pin 13 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN13 (0)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN13_GPIO_IDX (0)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN13_GPIO_PIN (0)
+ /* @brief Has external pin 14 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN14 (1)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN14_GPIO_IDX (GPIOD_IDX)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN14_GPIO_PIN (4)
+ /* @brief Has external pin 15 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN15 (1)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN15_GPIO_IDX (GPIOD_IDX)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN15_GPIO_PIN (6)
+ /* @brief Has external pin 16 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN16 (0)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN16_GPIO_IDX (0)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN16_GPIO_PIN (0)
+ /* @brief Has external pin 17 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN17 (0)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN17_GPIO_IDX (0)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN17_GPIO_PIN (0)
+ /* @brief Has external pin 18 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN18 (0)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN18_GPIO_IDX (0)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN18_GPIO_PIN (0)
+ /* @brief Has external pin 19 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN19 (0)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN19_GPIO_IDX (0)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN19_GPIO_PIN (0)
+ /* @brief Has external pin 20 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN20 (0)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN20_GPIO_IDX (0)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN20_GPIO_PIN (0)
+ /* @brief Has external pin 21 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN21 (0)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN21_GPIO_IDX (0)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN21_GPIO_PIN (0)
+ /* @brief Has external pin 22 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN22 (0)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN22_GPIO_IDX (0)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN22_GPIO_PIN (0)
+ /* @brief Has external pin 23 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN23 (0)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN23_GPIO_IDX (0)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN23_GPIO_PIN (0)
+ /* @brief Has external pin 24 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN24 (0)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN24_GPIO_IDX (0)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN24_GPIO_PIN (0)
+ /* @brief Has external pin 25 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN25 (0)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN25_GPIO_IDX (0)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN25_GPIO_PIN (0)
+ /* @brief Has external pin 26 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN26 (0)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN26_GPIO_IDX (0)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN26_GPIO_PIN (0)
+ /* @brief Has external pin 27 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN27 (0)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN27_GPIO_IDX (0)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN27_GPIO_PIN (0)
+ /* @brief Has external pin 28 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN28 (0)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN28_GPIO_IDX (0)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN28_GPIO_PIN (0)
+ /* @brief Has external pin 29 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN29 (0)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN29_GPIO_IDX (0)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN29_GPIO_PIN (0)
+ /* @brief Has external pin 30 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN30 (0)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN30_GPIO_IDX (0)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN30_GPIO_PIN (0)
+ /* @brief Has external pin 31 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN31 (0)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN31_GPIO_IDX (0)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN31_GPIO_PIN (0)
+ /* @brief Has internal module 0 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_INTERNAL_MODULE0 (1)
+ /* @brief Has internal module 1 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_INTERNAL_MODULE1 (1)
+ /* @brief Has internal module 2 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_INTERNAL_MODULE2 (1)
+ /* @brief Has internal module 3 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_INTERNAL_MODULE3 (0)
+ /* @brief Has internal module 4 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_INTERNAL_MODULE4 (0)
+ /* @brief Has internal module 5 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_INTERNAL_MODULE5 (0)
+ /* @brief Has internal module 6 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_INTERNAL_MODULE6 (0)
+ /* @brief Has internal module 7 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_INTERNAL_MODULE7 (0)
+ /* @brief Has Version ID Register (LLWU_VERID). */
+ #define FSL_FEATURE_LLWU_HAS_VERID (0)
+ /* @brief Has Parameter Register (LLWU_PARAM). */
+ #define FSL_FEATURE_LLWU_HAS_PARAM (0)
+ /* @brief Width of registers of the LLWU. */
+ #define FSL_FEATURE_LLWU_REG_BITWIDTH (8)
+ /* @brief Has DMA Enable register (LLWU_DE). */
+ #define FSL_FEATURE_LLWU_HAS_DMA_ENABLE_REG (0)
+#elif defined(CPU_MK02FN128VLF10) || defined(CPU_MK02FN64VLF10)
+ /* @brief Maximum number of pins (maximal index plus one) connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN (16)
+ /* @brief Has pins 8-15 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_EXTERNAL_PIN_GROUP2 (1)
+ /* @brief Maximum number of internal modules connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_INTERNAL_MODULE (3)
+ /* @brief Number of digital filters. */
+ #define FSL_FEATURE_LLWU_HAS_PIN_FILTER (2)
+ /* @brief Has MF register. */
+ #define FSL_FEATURE_LLWU_HAS_MF (0)
+ /* @brief Has PF register. */
+ #define FSL_FEATURE_LLWU_HAS_PF (0)
+ /* @brief Has possibility to enable reset in low leakage power mode and enable digital filter for RESET pin (register LLWU_RST). */
+ #define FSL_FEATURE_LLWU_HAS_RESET_ENABLE (0)
+ /* @brief Has no internal module wakeup flag register. */
+ #define FSL_FEATURE_LLWU_HAS_NO_INTERNAL_MODULE_WAKEUP_FLAG_REG (0)
+ /* @brief Has external pin 0 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN0 (0)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN0_GPIO_IDX (0)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN0_GPIO_PIN (0)
+ /* @brief Has external pin 1 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN1 (0)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN1_GPIO_IDX (0)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN1_GPIO_PIN (0)
+ /* @brief Has external pin 2 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN2 (0)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN2_GPIO_IDX (0)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN2_GPIO_PIN (0)
+ /* @brief Has external pin 3 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN3 (1)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN3_GPIO_IDX (GPIOA_IDX)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN3_GPIO_PIN (4)
+ /* @brief Has external pin 4 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN4 (0)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN4_GPIO_IDX (0)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN4_GPIO_PIN (0)
+ /* @brief Has external pin 5 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN5 (1)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN5_GPIO_IDX (GPIOB_IDX)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN5_GPIO_PIN (0)
+ /* @brief Has external pin 6 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN6 (1)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN6_GPIO_IDX (GPIOC_IDX)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN6_GPIO_PIN (1)
+ /* @brief Has external pin 7 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN7 (1)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN7_GPIO_IDX (GPIOC_IDX)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN7_GPIO_PIN (3)
+ /* @brief Has external pin 8 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN8 (1)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN8_GPIO_IDX (GPIOC_IDX)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN8_GPIO_PIN (4)
+ /* @brief Has external pin 9 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN9 (1)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN9_GPIO_IDX (GPIOC_IDX)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN9_GPIO_PIN (5)
+ /* @brief Has external pin 10 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN10 (1)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN10_GPIO_IDX (GPIOC_IDX)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN10_GPIO_PIN (6)
+ /* @brief Has external pin 11 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN11 (0)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN11_GPIO_IDX (0)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN11_GPIO_PIN (0)
+ /* @brief Has external pin 12 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN12 (1)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN12_GPIO_IDX (GPIOD_IDX)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN12_GPIO_PIN (0)
+ /* @brief Has external pin 13 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN13 (1)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN13_GPIO_IDX (GPIOD_IDX)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN13_GPIO_PIN (2)
+ /* @brief Has external pin 14 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN14 (1)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN14_GPIO_IDX (GPIOD_IDX)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN14_GPIO_PIN (4)
+ /* @brief Has external pin 15 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN15 (1)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN15_GPIO_IDX (GPIOD_IDX)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN15_GPIO_PIN (6)
+ /* @brief Has external pin 16 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN16 (0)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN16_GPIO_IDX (0)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN16_GPIO_PIN (0)
+ /* @brief Has external pin 17 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN17 (0)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN17_GPIO_IDX (0)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN17_GPIO_PIN (0)
+ /* @brief Has external pin 18 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN18 (0)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN18_GPIO_IDX (0)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN18_GPIO_PIN (0)
+ /* @brief Has external pin 19 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN19 (0)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN19_GPIO_IDX (0)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN19_GPIO_PIN (0)
+ /* @brief Has external pin 20 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN20 (0)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN20_GPIO_IDX (0)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN20_GPIO_PIN (0)
+ /* @brief Has external pin 21 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN21 (0)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN21_GPIO_IDX (0)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN21_GPIO_PIN (0)
+ /* @brief Has external pin 22 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN22 (0)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN22_GPIO_IDX (0)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN22_GPIO_PIN (0)
+ /* @brief Has external pin 23 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN23 (0)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN23_GPIO_IDX (0)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN23_GPIO_PIN (0)
+ /* @brief Has external pin 24 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN24 (0)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN24_GPIO_IDX (0)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN24_GPIO_PIN (0)
+ /* @brief Has external pin 25 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN25 (0)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN25_GPIO_IDX (0)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN25_GPIO_PIN (0)
+ /* @brief Has external pin 26 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN26 (0)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN26_GPIO_IDX (0)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN26_GPIO_PIN (0)
+ /* @brief Has external pin 27 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN27 (0)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN27_GPIO_IDX (0)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN27_GPIO_PIN (0)
+ /* @brief Has external pin 28 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN28 (0)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN28_GPIO_IDX (0)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN28_GPIO_PIN (0)
+ /* @brief Has external pin 29 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN29 (0)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN29_GPIO_IDX (0)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN29_GPIO_PIN (0)
+ /* @brief Has external pin 30 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN30 (0)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN30_GPIO_IDX (0)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN30_GPIO_PIN (0)
+ /* @brief Has external pin 31 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN31 (0)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN31_GPIO_IDX (0)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN31_GPIO_PIN (0)
+ /* @brief Has internal module 0 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_INTERNAL_MODULE0 (1)
+ /* @brief Has internal module 1 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_INTERNAL_MODULE1 (1)
+ /* @brief Has internal module 2 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_INTERNAL_MODULE2 (1)
+ /* @brief Has internal module 3 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_INTERNAL_MODULE3 (0)
+ /* @brief Has internal module 4 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_INTERNAL_MODULE4 (0)
+ /* @brief Has internal module 5 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_INTERNAL_MODULE5 (0)
+ /* @brief Has internal module 6 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_INTERNAL_MODULE6 (0)
+ /* @brief Has internal module 7 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_INTERNAL_MODULE7 (0)
+ /* @brief Has Version ID Register (LLWU_VERID). */
+ #define FSL_FEATURE_LLWU_HAS_VERID (0)
+ /* @brief Has Parameter Register (LLWU_PARAM). */
+ #define FSL_FEATURE_LLWU_HAS_PARAM (0)
+ /* @brief Width of registers of the LLWU. */
+ #define FSL_FEATURE_LLWU_REG_BITWIDTH (8)
+ /* @brief Has DMA Enable register (LLWU_DE). */
+ #define FSL_FEATURE_LLWU_HAS_DMA_ENABLE_REG (0)
+#elif defined(CPU_MK02FN128VLH10) || defined(CPU_MK02FN64VLH10)
+ /* @brief Maximum number of pins (maximal index plus one) connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN (16)
+ /* @brief Has pins 8-15 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_EXTERNAL_PIN_GROUP2 (1)
+ /* @brief Maximum number of internal modules connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_INTERNAL_MODULE (3)
+ /* @brief Number of digital filters. */
+ #define FSL_FEATURE_LLWU_HAS_PIN_FILTER (2)
+ /* @brief Has MF register. */
+ #define FSL_FEATURE_LLWU_HAS_MF (0)
+ /* @brief Has PF register. */
+ #define FSL_FEATURE_LLWU_HAS_PF (0)
+ /* @brief Has possibility to enable reset in low leakage power mode and enable digital filter for RESET pin (register LLWU_RST). */
+ #define FSL_FEATURE_LLWU_HAS_RESET_ENABLE (0)
+ /* @brief Has no internal module wakeup flag register. */
+ #define FSL_FEATURE_LLWU_HAS_NO_INTERNAL_MODULE_WAKEUP_FLAG_REG (0)
+ /* @brief Has external pin 0 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN0 (1)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN0_GPIO_IDX (GPIOE_IDX)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN0_GPIO_PIN (1)
+ /* @brief Has external pin 1 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN1 (0)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN1_GPIO_IDX (0)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN1_GPIO_PIN (0)
+ /* @brief Has external pin 2 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN2 (0)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN2_GPIO_IDX (0)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN2_GPIO_PIN (0)
+ /* @brief Has external pin 3 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN3 (1)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN3_GPIO_IDX (GPIOA_IDX)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN3_GPIO_PIN (4)
+ /* @brief Has external pin 4 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN4 (1)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN4_GPIO_IDX (GPIOA_IDX)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN4_GPIO_PIN (13)
+ /* @brief Has external pin 5 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN5 (1)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN5_GPIO_IDX (GPIOB_IDX)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN5_GPIO_PIN (0)
+ /* @brief Has external pin 6 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN6 (1)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN6_GPIO_IDX (GPIOC_IDX)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN6_GPIO_PIN (1)
+ /* @brief Has external pin 7 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN7 (1)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN7_GPIO_IDX (GPIOC_IDX)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN7_GPIO_PIN (3)
+ /* @brief Has external pin 8 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN8 (1)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN8_GPIO_IDX (GPIOC_IDX)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN8_GPIO_PIN (4)
+ /* @brief Has external pin 9 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN9 (1)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN9_GPIO_IDX (GPIOC_IDX)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN9_GPIO_PIN (5)
+ /* @brief Has external pin 10 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN10 (1)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN10_GPIO_IDX (GPIOC_IDX)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN10_GPIO_PIN (6)
+ /* @brief Has external pin 11 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN11 (1)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN11_GPIO_IDX (GPIOC_IDX)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN11_GPIO_PIN (11)
+ /* @brief Has external pin 12 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN12 (1)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN12_GPIO_IDX (GPIOD_IDX)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN12_GPIO_PIN (0)
+ /* @brief Has external pin 13 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN13 (1)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN13_GPIO_IDX (GPIOD_IDX)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN13_GPIO_PIN (2)
+ /* @brief Has external pin 14 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN14 (1)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN14_GPIO_IDX (GPIOD_IDX)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN14_GPIO_PIN (4)
+ /* @brief Has external pin 15 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN15 (1)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN15_GPIO_IDX (GPIOD_IDX)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN15_GPIO_PIN (6)
+ /* @brief Has external pin 16 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN16 (0)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN16_GPIO_IDX (0)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN16_GPIO_PIN (0)
+ /* @brief Has external pin 17 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN17 (0)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN17_GPIO_IDX (0)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN17_GPIO_PIN (0)
+ /* @brief Has external pin 18 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN18 (0)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN18_GPIO_IDX (0)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN18_GPIO_PIN (0)
+ /* @brief Has external pin 19 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN19 (0)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN19_GPIO_IDX (0)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN19_GPIO_PIN (0)
+ /* @brief Has external pin 20 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN20 (0)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN20_GPIO_IDX (0)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN20_GPIO_PIN (0)
+ /* @brief Has external pin 21 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN21 (0)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN21_GPIO_IDX (0)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN21_GPIO_PIN (0)
+ /* @brief Has external pin 22 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN22 (0)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN22_GPIO_IDX (0)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN22_GPIO_PIN (0)
+ /* @brief Has external pin 23 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN23 (0)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN23_GPIO_IDX (0)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN23_GPIO_PIN (0)
+ /* @brief Has external pin 24 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN24 (0)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN24_GPIO_IDX (0)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN24_GPIO_PIN (0)
+ /* @brief Has external pin 25 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN25 (0)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN25_GPIO_IDX (0)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN25_GPIO_PIN (0)
+ /* @brief Has external pin 26 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN26 (0)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN26_GPIO_IDX (0)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN26_GPIO_PIN (0)
+ /* @brief Has external pin 27 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN27 (0)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN27_GPIO_IDX (0)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN27_GPIO_PIN (0)
+ /* @brief Has external pin 28 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN28 (0)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN28_GPIO_IDX (0)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN28_GPIO_PIN (0)
+ /* @brief Has external pin 29 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN29 (0)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN29_GPIO_IDX (0)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN29_GPIO_PIN (0)
+ /* @brief Has external pin 30 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN30 (0)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN30_GPIO_IDX (0)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN30_GPIO_PIN (0)
+ /* @brief Has external pin 31 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN31 (0)
+ /* @brief Index of port of external pin. */
+ #define FSL_FEATURE_LLWU_PIN31_GPIO_IDX (0)
+ /* @brief Number of external pin port on specified port. */
+ #define FSL_FEATURE_LLWU_PIN31_GPIO_PIN (0)
+ /* @brief Has internal module 0 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_INTERNAL_MODULE0 (1)
+ /* @brief Has internal module 1 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_INTERNAL_MODULE1 (1)
+ /* @brief Has internal module 2 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_INTERNAL_MODULE2 (1)
+ /* @brief Has internal module 3 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_INTERNAL_MODULE3 (0)
+ /* @brief Has internal module 4 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_INTERNAL_MODULE4 (0)
+ /* @brief Has internal module 5 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_INTERNAL_MODULE5 (0)
+ /* @brief Has internal module 6 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_INTERNAL_MODULE6 (0)
+ /* @brief Has internal module 7 connected to LLWU device. */
+ #define FSL_FEATURE_LLWU_HAS_INTERNAL_MODULE7 (0)
+ /* @brief Has Version ID Register (LLWU_VERID). */
+ #define FSL_FEATURE_LLWU_HAS_VERID (0)
+ /* @brief Has Parameter Register (LLWU_PARAM). */
+ #define FSL_FEATURE_LLWU_HAS_PARAM (0)
+ /* @brief Width of registers of the LLWU. */
+ #define FSL_FEATURE_LLWU_REG_BITWIDTH (8)
+ /* @brief Has DMA Enable register (LLWU_DE). */
+ #define FSL_FEATURE_LLWU_HAS_DMA_ENABLE_REG (0)
+#endif /* defined(CPU_MK02FN128VFM10) || defined(CPU_MK02FN64VFM10) */
+
+/* LPTMR module features */
+
+/* @brief Has shared interrupt handler with another LPTMR module. */
+#define FSL_FEATURE_LPTMR_HAS_SHARED_IRQ_HANDLER (0)
+/* @brief Whether LPTMR counter is 32 bits width. */
+#define FSL_FEATURE_LPTMR_CNR_WIDTH_IS_32B (0)
+/* @brief Has timer DMA request enable (register bit CSR[TDRE]). */
+#define FSL_FEATURE_LPTMR_HAS_CSR_TDRE (0)
+
+/* MCG module features */
+
+/* @brief PRDIV base value (divider of register bit field [PRDIV] zero value). */
+#define FSL_FEATURE_MCG_PLL_PRDIV_BASE (0)
+/* @brief Maximum PLL external reference divider value (max. value of register bit field C5[PRVDIV]). */
+#define FSL_FEATURE_MCG_PLL_PRDIV_MAX (0)
+/* @brief VCO divider base value (multiply factor of register bit field C6[VDIV] zero value). */
+#define FSL_FEATURE_MCG_PLL_VDIV_BASE (0)
+/* @brief PLL reference clock low range. OSCCLK/PLL_R. */
+#define FSL_FEATURE_MCG_PLL_REF_MIN (0)
+/* @brief PLL reference clock high range. OSCCLK/PLL_R. */
+#define FSL_FEATURE_MCG_PLL_REF_MAX (0)
+/* @brief The PLL clock is divided by 2 before VCO divider. */
+#define FSL_FEATURE_MCG_HAS_PLL_INTERNAL_DIV (0)
+/* @brief FRDIV supports 1280. */
+#define FSL_FEATURE_MCG_FRDIV_SUPPORT_1280 (1)
+/* @brief FRDIV supports 1536. */
+#define FSL_FEATURE_MCG_FRDIV_SUPPORT_1536 (1)
+/* @brief MCGFFCLK divider. */
+#define FSL_FEATURE_MCG_FFCLK_DIV (1)
+/* @brief Is PLL clock divided by 2 before MCG PLL/FLL clock selection in the SIM module. */
+#define FSL_FEATURE_MCG_HAS_PLL_EXTRA_DIV (0)
+/* @brief Has 32kHz RTC external reference clock (register bits C8[LOCS1], C8[CME1], C8[LOCRE1] and RTC module are present). */
+#define FSL_FEATURE_MCG_HAS_RTC_32K (0)
+/* @brief Has PLL1 external reference clock (registers C10, C11, C12, S2). */
+#define FSL_FEATURE_MCG_HAS_PLL1 (0)
+/* @brief Has 48MHz internal oscillator. */
+#define FSL_FEATURE_MCG_HAS_IRC_48M (1)
+/* @brief Has OSC1 external oscillator (registers C10, C11, C12, S2). */
+#define FSL_FEATURE_MCG_HAS_OSC1 (0)
+/* @brief Has fast internal reference clock fine trim (register bit C2[FCFTRIM]). */
+#define FSL_FEATURE_MCG_HAS_FCFTRIM (1)
+/* @brief Has PLL loss of lock reset (register bit C8[LOLRE]). */
+#define FSL_FEATURE_MCG_HAS_LOLRE (0)
+/* @brief Has MCG OSC clock selection (register bit C7[OSCSEL]). */
+#define FSL_FEATURE_MCG_USE_OSCSEL (1)
+/* @brief Has PLL external reference selection (register bits C5[PLLREFSEL0] and C11[PLLREFSEL1]). */
+#define FSL_FEATURE_MCG_USE_PLLREFSEL (0)
+/* @brief TBD */
+#define FSL_FEATURE_MCG_USE_SYSTEM_CLOCK (0)
+/* @brief Has phase-locked loop (PLL) (register C5 and bits C6[VDIV], C6[PLLS], C6[LOLIE0], S[PLLST], S[LOCK0], S[LOLS0]). */
+#define FSL_FEATURE_MCG_HAS_PLL (0)
+/* @brief Has phase-locked loop (PLL) PRDIV (register C5[PRDIV]. */
+#define FSL_FEATURE_MCG_HAS_PLL_PRDIV (0)
+/* @brief Has phase-locked loop (PLL) VDIV (register C6[VDIV]. */
+#define FSL_FEATURE_MCG_HAS_PLL_VDIV (0)
+/* @brief PLL/OSC related register bit fields have PLL/OSC index in their name. */
+#define FSL_FEATURE_MCG_HAS_PLL_OSC_INDEX (0)
+/* @brief Has frequency-locked loop (FLL) (register ATCVH, ATCVL and bits C1[IREFS], C1[FRDIV]). */
+#define FSL_FEATURE_MCG_HAS_FLL (1)
+/* @brief Has PLL external to MCG (C9[PLL_CME], C9[PLL_LOCRE], C9[EXT_PLL_LOCS]). */
+#define FSL_FEATURE_MCG_HAS_EXTERNAL_PLL (0)
+/* @brief Has crystal oscillator or external reference clock low power controls (register bits C2[HGO], C2[RANGE]). */
+#define FSL_FEATURE_MCG_HAS_EXT_REF_LOW_POWER_CONTROL (1)
+/* @brief Has PLL/FLL selection as MCG output (register bit C6[PLLS]). */
+#define FSL_FEATURE_MCG_HAS_PLL_FLL_SELECTION (0)
+/* @brief Has PLL output selection (PLL0/PLL1, PLL/external PLL) (register bit C11[PLLCS]). */
+#define FSL_FEATURE_MCG_HAS_PLL_OUTPUT_SELECTION (0)
+/* @brief Has automatic trim machine (registers ATCVH, ATCVL and bits SC[ATMF], SC[ATMS], SC[ATME]). */
+#define FSL_FEATURE_MCG_HAS_AUTO_TRIM_MACHINE (1)
+/* @brief Has external clock monitor (register bit C6[CME]). */
+#define FSL_FEATURE_MCG_HAS_EXTERNAL_CLOCK_MONITOR (1)
+/* @brief Has low frequency internal reference clock (IRC) (registers LTRIMRNG, LFRIM, LSTRIM and bit MC[LIRC_DIV2]). */
+#define FSL_FEATURE_MCG_HAS_LOW_FREQ_IRC (0)
+/* @brief Has high frequency internal reference clock (IRC) (registers HCTRIM, HTTRIM, HFTRIM and bit MC[HIRCEN]). */
+#define FSL_FEATURE_MCG_HAS_HIGH_FREQ_IRC (0)
+/* @brief Has PEI mode or PBI mode. */
+#define FSL_FEATURE_MCG_HAS_PLL_INTERNAL_MODE (0)
+/* @brief Reset clock mode is BLPI. */
+#define FSL_FEATURE_MCG_RESET_IS_BLPI (0)
+
+/* interrupt module features */
+
+/* @brief Lowest interrupt request number. */
+#define FSL_FEATURE_INTERRUPT_IRQ_MIN (-14)
+/* @brief Highest interrupt request number. */
+#define FSL_FEATURE_INTERRUPT_IRQ_MAX (73)
+
+/* OSC module features */
+
+/* @brief Has OSC1 external oscillator. */
+#define FSL_FEATURE_OSC_HAS_OSC1 (0)
+/* @brief Has OSC0 external oscillator. */
+#define FSL_FEATURE_OSC_HAS_OSC0 (0)
+/* @brief Has OSC external oscillator (without index). */
+#define FSL_FEATURE_OSC_HAS_OSC (1)
+/* @brief Number of OSC external oscillators. */
+#define FSL_FEATURE_OSC_OSC_COUNT (1)
+/* @brief Has external reference clock divider (register bit field DIV[ERPS]). */
+#define FSL_FEATURE_OSC_HAS_EXT_REF_CLOCK_DIVIDER (1)
+
+/* PDB module features */
+
+/* @brief Define the count of supporting ADC pre-trigger for each channel. */
+#define FSL_FEATURE_PDB_ADC_PRE_CHANNEL_COUNT (2)
+/* @brief Has DAC support. */
+#define FSL_FEATURE_PDB_HAS_DAC (1)
+/* @brief Has shared interrupt handler (has not individual interrupt handler for each channel). */
+#define FSL_FEATURE_PDB_HAS_SHARED_IRQ_HANDLER (0)
+
+/* PIT module features */
+
+/* @brief Number of channels (related to number of registers LDVALn, CVALn, TCTRLn, TFLGn). */
+#define FSL_FEATURE_PIT_TIMER_COUNT (4)
+/* @brief Has lifetime timer (related to existence of registers LTMR64L and LTMR64H). */
+#define FSL_FEATURE_PIT_HAS_LIFETIME_TIMER (0)
+/* @brief Has chain mode (related to existence of register bit field TCTRLn[CHN]). */
+#define FSL_FEATURE_PIT_HAS_CHAIN_MODE (1)
+/* @brief Has shared interrupt handler (has not individual interrupt handler for each channel). */
+#define FSL_FEATURE_PIT_HAS_SHARED_IRQ_HANDLER (0)
+/* @brief Has timer enable control. */
+#define FSL_FEATURE_PIT_HAS_MDIS (1)
+
+/* PMC module features */
+
+/* @brief Has Bandgap Enable In VLPx Operation support. */
+#define FSL_FEATURE_PMC_HAS_BGEN (1)
+/* @brief Has Bandgap Buffer Enable. */
+#define FSL_FEATURE_PMC_HAS_BGBE (1)
+/* @brief Has Bandgap Buffer Drive Select. */
+#define FSL_FEATURE_PMC_HAS_BGBDS (0)
+/* @brief Has Low-Voltage Detect Voltage Select support. */
+#define FSL_FEATURE_PMC_HAS_LVDV (1)
+/* @brief Has Low-Voltage Warning Voltage Select support. */
+#define FSL_FEATURE_PMC_HAS_LVWV (1)
+/* @brief Has LPO. */
+#define FSL_FEATURE_PMC_HAS_LPO (0)
+/* @brief Has VLPx option PMC_REGSC[VLPO]. */
+#define FSL_FEATURE_PMC_HAS_VLPO (0)
+/* @brief Has acknowledge isolation support. */
+#define FSL_FEATURE_PMC_HAS_ACKISO (1)
+/* @brief Has Regulator In Full Performance Mode Status Bit PMC_REGSC[REGFPM]. */
+#define FSL_FEATURE_PMC_HAS_REGFPM (0)
+/* @brief Has Regulator In Run Regulation Status Bit PMC_REGSC[REGONS]. */
+#define FSL_FEATURE_PMC_HAS_REGONS (1)
+/* @brief Has PMC_HVDSC1. */
+#define FSL_FEATURE_PMC_HAS_HVDSC1 (0)
+/* @brief Has PMC_PARAM. */
+#define FSL_FEATURE_PMC_HAS_PARAM (0)
+/* @brief Has PMC_VERID. */
+#define FSL_FEATURE_PMC_HAS_VERID (0)
+
+/* PORT module features */
+
+/* @brief Has control lock (register bit PCR[LK]). */
+#define FSL_FEATURE_PORT_HAS_PIN_CONTROL_LOCK (1)
+/* @brief Has open drain control (register bit PCR[ODE]). */
+#define FSL_FEATURE_PORT_HAS_OPEN_DRAIN (1)
+/* @brief Has digital filter (registers DFER, DFCR and DFWR). */
+#define FSL_FEATURE_PORT_HAS_DIGITAL_FILTER (1)
+/* @brief Has DMA request (register bit field PCR[IRQC] values). */
+#define FSL_FEATURE_PORT_HAS_DMA_REQUEST (1)
+/* @brief Has pull resistor selection available. */
+#define FSL_FEATURE_PORT_HAS_PULL_SELECTION (1)
+/* @brief Has pull resistor enable (register bit PCR[PE]). */
+#define FSL_FEATURE_PORT_HAS_PULL_ENABLE (1)
+/* @brief Has slew rate control (register bit PCR[SRE]). */
+#define FSL_FEATURE_PORT_HAS_SLEW_RATE (1)
+/* @brief Has passive filter (register bit field PCR[PFE]). */
+#define FSL_FEATURE_PORT_HAS_PASSIVE_FILTER (1)
+/* @brief Has drive strength control (register bit PCR[DSE]). */
+#define FSL_FEATURE_PORT_HAS_DRIVE_STRENGTH (1)
+/* @brief Has separate drive strength register (HDRVE). */
+#define FSL_FEATURE_PORT_HAS_DRIVE_STRENGTH_REGISTER (0)
+/* @brief Has glitch filter (register IOFLT). */
+#define FSL_FEATURE_PORT_HAS_GLITCH_FILTER (0)
+/* @brief Defines width of PCR[MUX] field. */
+#define FSL_FEATURE_PORT_PCR_MUX_WIDTH (3)
+/* @brief Has dedicated interrupt vector. */
+#define FSL_FEATURE_PORT_HAS_INTERRUPT_VECTOR (1)
+/* @brief Has multiple pin IRQ configuration (register GICLR and GICHR). */
+#define FSL_FEATURE_PORT_HAS_MULTIPLE_IRQ_CONFIG (0)
+/* @brief Defines whether PCR[IRQC] bit-field has flag states. */
+#define FSL_FEATURE_PORT_HAS_IRQC_FLAG (0)
+/* @brief Defines whether PCR[IRQC] bit-field has trigger states. */
+#define FSL_FEATURE_PORT_HAS_IRQC_TRIGGER (0)
+
+/* RCM module features */
+
+/* @brief Has Loss-of-Lock Reset support. */
+#define FSL_FEATURE_RCM_HAS_LOL (0)
+/* @brief Has Loss-of-Clock Reset support. */
+#define FSL_FEATURE_RCM_HAS_LOC (1)
+/* @brief Has JTAG generated Reset support. */
+#define FSL_FEATURE_RCM_HAS_JTAG (1)
+/* @brief Has EzPort generated Reset support. */
+#define FSL_FEATURE_RCM_HAS_EZPORT (0)
+/* @brief Has bit-field indicating EZP_MS_B pin state during last reset. */
+#define FSL_FEATURE_RCM_HAS_EZPMS (0)
+/* @brief Has boot ROM configuration, MR[BOOTROM], FM[FORCEROM] */
+#define FSL_FEATURE_RCM_HAS_BOOTROM (0)
+/* @brief Has sticky system reset status register RCM_SSRS0 and RCM_SSRS1. */
+#define FSL_FEATURE_RCM_HAS_SSRS (1)
+/* @brief Has Version ID Register (RCM_VERID). */
+#define FSL_FEATURE_RCM_HAS_VERID (0)
+/* @brief Has Parameter Register (RCM_PARAM). */
+#define FSL_FEATURE_RCM_HAS_PARAM (0)
+/* @brief Has Reset Interrupt Enable Register RCM_SRIE. */
+#define FSL_FEATURE_RCM_HAS_SRIE (0)
+/* @brief Width of registers of the RCM. */
+#define FSL_FEATURE_RCM_REG_WIDTH (8)
+/* @brief Has Core 1 generated Reset support RCM_SRS[CORE1] */
+#define FSL_FEATURE_RCM_HAS_CORE1 (0)
+/* @brief Has MDM-AP system reset support RCM_SRS1[MDM_AP] */
+#define FSL_FEATURE_RCM_HAS_MDM_AP (1)
+/* @brief Has wakeup reset feature. Register bit SRS[WAKEUP]. */
+#define FSL_FEATURE_RCM_HAS_WAKEUP (1)
+
+/* SIM module features */
+
+/* @brief Has USB FS divider. */
+#define FSL_FEATURE_SIM_USBFS_USE_SPECIAL_DIVIDER (0)
+/* @brief Is PLL clock divided by 2 before MCG PLL/FLL clock selection. */
+#define FSL_FEATURE_SIM_PLLCLK_USE_SPECIAL_DIVIDER (0)
+/* @brief Has RAM size specification (register bit field SOPT1[RAMSIZE]). */
+#define FSL_FEATURE_SIM_OPT_HAS_RAMSIZE (1)
+/* @brief Has 32k oscillator clock output (register bit SOPT1[OSC32KOUT]). */
+#define FSL_FEATURE_SIM_OPT_HAS_OSC32K_OUT (1)
+/* @brief Has 32k oscillator clock selection (register bit field SOPT1[OSC32KSEL]). */
+#define FSL_FEATURE_SIM_OPT_HAS_OSC32K_SELECTION (1)
+/* @brief 32k oscillator clock selection width (width of register bit field SOPT1[OSC32KSEL]). */
+#define FSL_FEATURE_SIM_OPT_OSC32K_SELECTION_WIDTH (2)
+/* @brief Has RTC clock output selection (register bit SOPT2[RTCCLKOUTSEL]). */
+#define FSL_FEATURE_SIM_OPT_HAS_RTC_CLOCK_OUT_SELECTION (0)
+/* @brief Has USB voltage regulator (register bits SOPT1[USBVSTBY], SOPT1[USBSSTBY], SOPT1[USBREGEN], SOPT1CFG[URWE], SOPT1CFG[UVSWE], SOPT1CFG[USSWE]). */
+#define FSL_FEATURE_SIM_OPT_HAS_USB_VOLTAGE_REGULATOR (0)
+/* @brief USB has integrated PHY (register bits USBPHYCTL[USBVREGSEL], USBPHYCTL[USBVREGPD], USBPHYCTL[USB3VOUTTRG], USBPHYCTL[USBDISILIM], SOPT2[USBSLSRC], SOPT2[USBREGEN]). */
+#define FSL_FEATURE_SIM_OPT_HAS_USB_PHY (0)
+/* @brief Has PTD7 pad drive strength control (register bit SOPT2[PTD7PAD]). */
+#define FSL_FEATURE_SIM_OPT_HAS_PTD7PAD (0)
+/* @brief Has FlexBus security level selection (register bit SOPT2[FBSL]). */
+#define FSL_FEATURE_SIM_OPT_HAS_FBSL (0)
+/* @brief Has number of FlexBus hold cycle before FlexBus can release bus (register bit SOPT6[PCR]). */
+#define FSL_FEATURE_SIM_OPT_HAS_PCR (0)
+/* @brief Has number of NFC hold cycle in case of FlexBus request (register bit SOPT6[MCC]). */
+#define FSL_FEATURE_SIM_OPT_HAS_MCC (0)
+/* @brief Has UART open drain enable (register bits UARTnODE, where n is a number, in register SOPT5). */
+#define FSL_FEATURE_SIM_OPT_HAS_ODE (0)
+/* @brief Number of LPUART modules (number of register bits LPUARTn, where n is a number, in register SCGC5). */
+#define FSL_FEATURE_SIM_OPT_LPUART_COUNT (0)
+/* @brief Number of UART modules (number of register bits UARTn, where n is a number, in register SCGC4). */
+#define FSL_FEATURE_SIM_OPT_UART_COUNT (2)
+/* @brief Has UART0 open drain enable (register bit SOPT5[UART0ODE]). */
+#define FSL_FEATURE_SIM_OPT_HAS_UART0_ODE (0)
+/* @brief Has UART1 open drain enable (register bit SOPT5[UART1ODE]). */
+#define FSL_FEATURE_SIM_OPT_HAS_UART1_ODE (0)
+/* @brief Has UART2 open drain enable (register bit SOPT5[UART2ODE]). */
+#define FSL_FEATURE_SIM_OPT_HAS_UART2_ODE (0)
+/* @brief Has LPUART0 open drain enable (register bit SOPT5[LPUART0ODE]). */
+#define FSL_FEATURE_SIM_OPT_HAS_LPUART0_ODE (0)
+/* @brief Has LPUART1 open drain enable (register bit SOPT5[LPUART1ODE]). */
+#define FSL_FEATURE_SIM_OPT_HAS_LPUART1_ODE (0)
+/* @brief Has CMT/UART pad drive strength control (register bit SOPT2[CMTUARTPAD]). */
+#define FSL_FEATURE_SIM_OPT_HAS_CMTUARTPAD (0)
+/* @brief Has LPUART0 transmit data source selection (register bit SOPT5[LPUART0TXSRC]). */
+#define FSL_FEATURE_SIM_OPT_HAS_LPUART0_TX_SRC (0)
+/* @brief Has LPUART0 receive data source selection (register bit SOPT5[LPUART0RXSRC]). */
+#define FSL_FEATURE_SIM_OPT_HAS_LPUART0_RX_SRC (0)
+/* @brief Has LPUART1 transmit data source selection (register bit SOPT5[LPUART1TXSRC]). */
+#define FSL_FEATURE_SIM_OPT_HAS_LPUART1_TX_SRC (0)
+/* @brief Has LPUART1 receive data source selection (register bit SOPT5[LPUART1RXSRC]). */
+#define FSL_FEATURE_SIM_OPT_HAS_LPUART1_RX_SRC (0)
+/* @brief Has UART0 transmit data source selection (register bit SOPT5[UART0TXSRC]). */
+#define FSL_FEATURE_SIM_OPT_HAS_UART0_TX_SRC (1)
+/* @brief UART0 transmit data source selection width (width of register bit SOPT5[UART0TXSRC]). */
+#define FSL_FEATURE_SIM_OPT_UART0_TX_SRC_WIDTH (2)
+/* @brief Has UART0 receive data source selection (register bit SOPT5[UART0RXSRC]). */
+#define FSL_FEATURE_SIM_OPT_HAS_UART0_RX_SRC (1)
+/* @brief UART0 receive data source selection width (width of register bit SOPT5[UART0RXSRC]). */
+#define FSL_FEATURE_SIM_OPT_UART0_RX_SRC_WIDTH (2)
+/* @brief Has UART1 transmit data source selection (register bit SOPT5[UART1TXSRC]). */
+#define FSL_FEATURE_SIM_OPT_HAS_UART1_TX_SRC (1)
+/* @brief Has UART1 receive data source selection (register bit SOPT5[UART1RXSRC]). */
+#define FSL_FEATURE_SIM_OPT_HAS_UART1_RX_SRC (1)
+/* @brief UART1 receive data source selection width (width of register bit SOPT5[UART1RXSRC]). */
+#define FSL_FEATURE_SIM_OPT_UART1_RX_SRC_WIDTH (2)
+/* @brief Has FTM module(s) configuration. */
+#define FSL_FEATURE_SIM_OPT_HAS_FTM (1)
+/* @brief Number of FTM modules. */
+#define FSL_FEATURE_SIM_OPT_FTM_COUNT (3)
+/* @brief Number of FTM triggers with selectable source. */
+#define FSL_FEATURE_SIM_OPT_FTM_TRIGGER_COUNT (2)
+/* @brief Has FTM0 triggers source selection (register bits SOPT4[FTM0TRGnSRC], where n is a number). */
+#define FSL_FEATURE_SIM_OPT_HAS_FTM0_TRIGGER (1)
+/* @brief Has FTM3 triggers source selection (register bits SOPT4[FTM3TRGnSRC], where n is a number). */
+#define FSL_FEATURE_SIM_OPT_HAS_FTM3_TRIGGER (0)
+/* @brief Has FTM1 channel 0 input capture source selection (register bit SOPT4[FTM1CH0SRC]). */
+#define FSL_FEATURE_SIM_OPT_HAS_FTM1_CHANNELS (1)
+/* @brief Has FTM2 channel 0 input capture source selection (register bit SOPT4[FTM2CH0SRC]). */
+#define FSL_FEATURE_SIM_OPT_HAS_FTM2_CHANNELS (1)
+/* @brief Has FTM3 channel 0 input capture source selection (register bit SOPT4[FTM3CH0SRC]). */
+#define FSL_FEATURE_SIM_OPT_HAS_FTM3_CHANNELS (0)
+/* @brief Has FTM2 channel 1 input capture source selection (register bit SOPT4[FTM2CH1SRC]). */
+#define FSL_FEATURE_SIM_OPT_HAS_FTM2_CHANNEL1 (1)
+/* @brief Number of configurable FTM0 fault detection input (number of register bits SOPT4[FTM0FLTn], where n is a number starting from zero). */
+#define FSL_FEATURE_SIM_OPT_FTM0_FAULT_COUNT (2)
+/* @brief Number of configurable FTM1 fault detection input (number of register bits SOPT4[FTM1FLTn], where n is a number starting from zero). */
+#define FSL_FEATURE_SIM_OPT_FTM1_FAULT_COUNT (1)
+/* @brief Number of configurable FTM2 fault detection input (number of register bits SOPT4[FTM2FLTn], where n is a number starting from zero). */
+#define FSL_FEATURE_SIM_OPT_FTM2_FAULT_COUNT (1)
+/* @brief Number of configurable FTM3 fault detection input (number of register bits SOPT4[FTM3FLTn], where n is a number starting from zero). */
+#define FSL_FEATURE_SIM_OPT_FTM3_FAULT_COUNT (0)
+/* @brief Has FTM hardware trigger 0 software synchronization (register bit SOPT8[FTMnSYNCBIT], where n is a module instance index). */
+#define FSL_FEATURE_SIM_OPT_HAS_FTM_TRIGGER_SYNC (1)
+/* @brief Has FTM channels output source selection (register bit SOPT8[FTMxOCHnSRC], where x is a module instance index and n is a channel index). */
+#define FSL_FEATURE_SIM_OPT_HAS_FTM_CHANNELS_OUTPUT_SRC (1)
+/* @brief Has TPM module(s) configuration. */
+#define FSL_FEATURE_SIM_OPT_HAS_TPM (0)
+/* @brief The highest TPM module index. */
+#define FSL_FEATURE_SIM_OPT_MAX_TPM_INDEX (0)
+/* @brief Has TPM module with index 0. */
+#define FSL_FEATURE_SIM_OPT_HAS_TPM0 (0)
+/* @brief Has TPM0 clock selection (register bit field SOPT4[TPM0CLKSEL]). */
+#define FSL_FEATURE_SIM_OPT_HAS_TPM0_CLK_SEL (0)
+/* @brief Is TPM channels configuration in the SOPT4 (not SOPT9) register (register bits TPMnCH0SRC, TPMnCLKSEL, where n is a module instance index). */
+#define FSL_FEATURE_SIM_OPT_HAS_TPM_CHANNELS_CONFIG_IN_SOPT4_REG (0)
+/* @brief Has TPM1 channel 0 input capture source selection (register bit field SOPT4[TPM1CH0SRC] or SOPT9[TPM1CH0SRC]). */
+#define FSL_FEATURE_SIM_OPT_HAS_TPM1_CH0_SRC_SELECTION (0)
+/* @brief Has TPM1 clock selection (register bit field SOPT4[TPM1CLKSEL]). */
+#define FSL_FEATURE_SIM_OPT_HAS_TPM1_CLK_SEL (0)
+/* @brief TPM1 channel 0 input capture source selection width (width of register bit field SOPT4[TPM1CH0SRC] or SOPT9[TPM1CH0SRC]). */
+#define FSL_FEATURE_SIM_OPT_TPM1_CH0_SRC_SELECTION_WIDTH (0)
+/* @brief Has TPM2 channel 0 input capture source selection (register bit field SOPT4[TPM2CH0SRC]). */
+#define FSL_FEATURE_SIM_OPT_HAS_TPM2_CH0_SRC_SELECTION (0)
+/* @brief Has TPM2 clock selection (register bit field SOPT4[TPM2CLKSEL]). */
+#define FSL_FEATURE_SIM_OPT_HAS_TPM2_CLK_SEL (0)
+/* @brief Has PLL/FLL clock selection (register bit field SOPT2[PLLFLLSEL]). */
+#define FSL_FEATURE_SIM_OPT_HAS_PLL_FLL_SELECTION (1)
+/* @brief PLL/FLL clock selection width (width of register bit field SOPT2[PLLFLLSEL]). */
+#define FSL_FEATURE_SIM_OPT_PLL_FLL_SELECTION_WIDTH (1)
+/* @brief Has NFC clock source selection (register bit SOPT2[NFCSRC]). */
+#define FSL_FEATURE_SIM_OPT_HAS_NFCSRC (0)
+/* @brief Has eSDHC clock source selection (register bit SOPT2[ESDHCSRC]). */
+#define FSL_FEATURE_SIM_OPT_HAS_ESDHCSRC (0)
+/* @brief Has SDHC clock source selection (register bit SOPT2[SDHCSRC]). */
+#define FSL_FEATURE_SIM_OPT_HAS_SDHCSRC (0)
+/* @brief Has LCDC clock source selection (register bits SOPT2[LCDCSRC], SOPT2[LCDC_CLKSEL]). */
+#define FSL_FEATURE_SIM_OPT_HAS_LCDCSRC (0)
+/* @brief Has ENET timestamp clock source selection (register bit SOPT2[TIMESRC]). */
+#define FSL_FEATURE_SIM_OPT_HAS_TIMESRC (0)
+/* @brief Has ENET RMII clock source selection (register bit SOPT2[RMIISRC]). */
+#define FSL_FEATURE_SIM_OPT_HAS_RMIISRC (0)
+/* @brief Has USB clock source selection (register bit SOPT2[USBSRC]). */
+#define FSL_FEATURE_SIM_OPT_HAS_USBSRC (0)
+/* @brief Has USB FS clock source selection (register bit SOPT2[USBFSRC]). */
+#define FSL_FEATURE_SIM_OPT_HAS_USBFSRC (0)
+/* @brief Has USB HS clock source selection (register bit SOPT2[USBHSRC]). */
+#define FSL_FEATURE_SIM_OPT_HAS_USBHSRC (0)
+/* @brief Has LPUART clock source selection (register bit SOPT2[LPUARTSRC]). */
+#define FSL_FEATURE_SIM_OPT_HAS_LPUARTSRC (0)
+/* @brief Has LPUART0 clock source selection (register bit SOPT2[LPUART0SRC]). */
+#define FSL_FEATURE_SIM_OPT_HAS_LPUART0SRC (0)
+/* @brief Has LPUART1 clock source selection (register bit SOPT2[LPUART1SRC]). */
+#define FSL_FEATURE_SIM_OPT_HAS_LPUART1SRC (0)
+/* @brief Has FLEXIOSRC clock source selection (register bit SOPT2[FLEXIOSRC]). */
+#define FSL_FEATURE_SIM_OPT_HAS_FLEXIOSRC (0)
+/* @brief Has UART0 clock source selection (register bit SOPT2[UART0SRC]). */
+#define FSL_FEATURE_SIM_OPT_HAS_UART0SRC (0)
+/* @brief Has TPM clock source selection (register bit SOPT2[TPMSRC]). */
+#define FSL_FEATURE_SIM_OPT_HAS_TPMSRC (0)
+/* @brief Has debug trace clock selection (register bit SOPT2[TRACECLKSEL]). */
+#define FSL_FEATURE_SIM_OPT_HAS_TRACE_CLKSEL (1)
+/* @brief Number of ADC modules (register bits SOPT7[ADCnTRGSEL], SOPT7[ADCnPRETRGSEL], SOPT7[ADCnALTTRGSEL], where n is a module instance index). */
+#define FSL_FEATURE_SIM_OPT_ADC_COUNT (1)
+/* @brief ADC0 alternate trigger enable width (width of bit field ADC0ALTTRGEN of register SOPT7). */
+#define FSL_FEATURE_SIM_OPT_ADC0ALTTRGEN_WIDTH (1)
+/* @brief ADC1 alternate trigger enable width (width of bit field ADC1ALTTRGEN of register SOPT7). */
+#define FSL_FEATURE_SIM_OPT_ADC1ALTTRGEN_WIDTH (0)
+/* @brief ADC2 alternate trigger enable width (width of bit field ADC2ALTTRGEN of register SOPT7). */
+#define FSL_FEATURE_SIM_OPT_ADC2ALTTRGEN_WIDTH (0)
+/* @brief ADC3 alternate trigger enable width (width of bit field ADC3ALTTRGEN of register SOPT7). */
+#define FSL_FEATURE_SIM_OPT_ADC3ALTTRGEN_WIDTH (0)
+/* @brief HSADC0 converter A alternate trigger enable width (width of bit field HSADC0AALTTRGEN of register SOPT7). */
+#define FSL_FEATURE_SIM_OPT_HSADC0AALTTRGEN_WIDTH (0)
+/* @brief HSADC1 converter A alternate trigger enable width (width of bit field HSADC1AALTTRGEN of register SOPT7). */
+#define FSL_FEATURE_SIM_OPT_HSADC1AALTTRGEN_WIDTH (0)
+/* @brief ADC converter A alternate trigger enable width (width of bit field ADCAALTTRGEN of register SOPT7). */
+#define FSL_FEATURE_SIM_OPT_ADCAALTTRGEN_WIDTH (0)
+/* @brief HSADC0 converter B alternate trigger enable width (width of bit field HSADC0BALTTRGEN of register SOPT7). */
+#define FSL_FEATURE_SIM_OPT_HSADC0BALTTRGEN_WIDTH (0)
+/* @brief HSADC1 converter B alternate trigger enable width (width of bit field HSADC1BALTTRGEN of register SOPT7). */
+#define FSL_FEATURE_SIM_OPT_HSADC1BALTTRGEN_WIDTH (0)
+/* @brief ADC converter B alternate trigger enable width (width of bit field ADCBALTTRGEN of register SOPT7). */
+#define FSL_FEATURE_SIM_OPT_ADCBALTTRGEN_WIDTH (0)
+/* @brief Has clock 2 output divider (register bit field CLKDIV1[OUTDIV2]). */
+#define FSL_FEATURE_SIM_DIVIDER_HAS_OUTDIV2 (1)
+/* @brief Has clock 3 output divider (register bit field CLKDIV1[OUTDIV3]). */
+#define FSL_FEATURE_SIM_DIVIDER_HAS_OUTDIV3 (0)
+/* @brief Has clock 4 output divider (register bit field CLKDIV1[OUTDIV4]). */
+#define FSL_FEATURE_SIM_DIVIDER_HAS_OUTDIV4 (1)
+/* @brief Clock 4 output divider width (width of register bit field CLKDIV1[OUTDIV4]). */
+#define FSL_FEATURE_SIM_DIVIDER_OUTDIV4_WIDTH (4)
+/* @brief Has clock 5 output divider (register bit field CLKDIV1[OUTDIV5]). */
+#define FSL_FEATURE_SIM_DIVIDER_HAS_OUTDIV5 (0)
+/* @brief Has USB clock divider (register bit field CLKDIV2[USBDIV] and CLKDIV2[USBFRAC]). */
+#define FSL_FEATURE_SIM_DIVIDER_HAS_USBDIV (0)
+/* @brief Has USB FS clock divider (register bit field CLKDIV2[USBFSDIV] and CLKDIV2[USBFSFRAC]). */
+#define FSL_FEATURE_SIM_DIVIDER_HAS_USBFSDIV (0)
+/* @brief Has USB HS clock divider (register bit field CLKDIV2[USBHSDIV] and CLKDIV2[USBHSFRAC]). */
+#define FSL_FEATURE_SIM_DIVIDER_HAS_USBHSDIV (0)
+/* @brief Has PLL/FLL clock divider (register bit field CLKDIV3[PLLFLLDIV] and CLKDIV3[PLLFLLFRAC]). */
+#define FSL_FEATURE_SIM_DIVIDER_HAS_PLLFLLDIV (0)
+/* @brief Has LCDC clock divider (register bit field CLKDIV3[LCDCDIV] and CLKDIV3[LCDCFRAC]). */
+#define FSL_FEATURE_SIM_DIVIDER_HAS_LCDCDIV (0)
+/* @brief Has trace clock divider (register bit field CLKDIV4[TRACEDIV] and CLKDIV4[TRACEFRAC]). */
+#define FSL_FEATURE_SIM_DIVIDER_HAS_TRACEDIV (0)
+/* @brief Has NFC clock divider (register bit field CLKDIV4[NFCDIV] and CLKDIV4[NFCFRAC]). */
+#define FSL_FEATURE_SIM_DIVIDER_HAS_NFCDIV (0)
+/* @brief Has Kinetis family ID (register bit field SDID[FAMILYID]). */
+#define FSL_FEATURE_SIM_SDID_HAS_FAMILYID (1)
+/* @brief Has Kinetis family ID (register bit field SDID[FAMID]). */
+#define FSL_FEATURE_SIM_SDID_HAS_FAMID (1)
+/* @brief Has Kinetis sub-family ID (register bit field SDID[SUBFAMID]). */
+#define FSL_FEATURE_SIM_SDID_HAS_SUBFAMID (1)
+/* @brief Has Kinetis series ID (register bit field SDID[SERIESID]). */
+#define FSL_FEATURE_SIM_SDID_HAS_SERIESID (1)
+/* @brief Has device die ID (register bit field SDID[DIEID]). */
+#define FSL_FEATURE_SIM_SDID_HAS_DIEID (1)
+/* @brief Has system SRAM size specifier (register bit field SDID[SRAMSIZE]). */
+#define FSL_FEATURE_SIM_SDID_HAS_SRAMSIZE (0)
+/* @brief Has flash mode (register bit FCFG1[FLASHDOZE]). */
+#define FSL_FEATURE_SIM_FCFG_HAS_FLASHDOZE (1)
+/* @brief Has flash disable (register bit FCFG1[FLASHDIS]). */
+#define FSL_FEATURE_SIM_FCFG_HAS_FLASHDIS (1)
+/* @brief Has FTFE disable (register bit FCFG1[FTFDIS]). */
+#define FSL_FEATURE_SIM_FCFG_HAS_FTFDIS (0)
+/* @brief Has FlexNVM size specifier (register bit field FCFG1[NVMSIZE]). */
+#define FSL_FEATURE_SIM_FCFG_HAS_NVMSIZE (0)
+/* @brief Has EEPROM size specifier (register bit field FCFG1[EESIZE]). */
+#define FSL_FEATURE_SIM_FCFG_HAS_EESIZE (0)
+/* @brief Has FlexNVM partition (register bit field FCFG1[DEPART]). */
+#define FSL_FEATURE_SIM_FCFG_HAS_DEPART (0)
+/* @brief Maximum flash address block 0 address specifier (register bit field FCFG2[MAXADDR0]). */
+#define FSL_FEATURE_SIM_FCFG_HAS_MAXADDR0 (1)
+/* @brief Maximum flash address block 1 address specifier (register bit field FCFG2[MAXADDR1]). */
+#define FSL_FEATURE_SIM_FCFG_HAS_MAXADDR1 (0)
+/* @brief Maximum flash address block 0 or 1 address specifier (register bit field FCFG2[MAXADDR01]). */
+#define FSL_FEATURE_SIM_FCFG_HAS_MAXADDR01 (0)
+/* @brief Maximum flash address block 2 or 3 address specifier (register bit field FCFG2[MAXADDR23]). */
+#define FSL_FEATURE_SIM_FCFG_HAS_MAXADDR23 (0)
+/* @brief Has program flash availability specifier (register bit FCFG2[PFLSH]). */
+#define FSL_FEATURE_SIM_FCFG_HAS_PFLSH (0)
+/* @brief Has program flash swapping (register bit FCFG2[SWAPPFLSH]). */
+#define FSL_FEATURE_SIM_FCFG_HAS_PFLSH_SWAP (0)
+/* @brief Has miscellanious control register (register MCR). */
+#define FSL_FEATURE_SIM_HAS_MISC_CONTROLS (0)
+/* @brief Has COP watchdog (registers COPC and SRVCOP). */
+#define FSL_FEATURE_SIM_HAS_COP_WATCHDOG (0)
+/* @brief Has COP watchdog stop (register bits COPC[COPSTPEN], COPC[COPDBGEN] and COPC[COPCLKSEL]). */
+#define FSL_FEATURE_SIM_HAS_COP_STOP (0)
+/* @brief Has LLWU clock gate bit (e.g SIM_SCGC4). */
+#define FSL_FEATURE_SIM_HAS_SCGC_LLWU (0)
+
+/* SMC module features */
+
+/* @brief Has partial stop option (register bit STOPCTRL[PSTOPO]). */
+#define FSL_FEATURE_SMC_HAS_PSTOPO (1)
+/* @brief Has LPO power option (register bit STOPCTRL[LPOPO]). */
+#define FSL_FEATURE_SMC_HAS_LPOPO (0)
+/* @brief Has POR power option (register bit STOPCTRL[PORPO] or VLLSCTRL[PORPO]). */
+#define FSL_FEATURE_SMC_HAS_PORPO (1)
+/* @brief Has low power wakeup on interrupt (register bit PMCTRL[LPWUI]). */
+#define FSL_FEATURE_SMC_HAS_LPWUI (0)
+/* @brief Has LLS or VLLS mode control (register bit STOPCTRL[LLSM]). */
+#define FSL_FEATURE_SMC_HAS_LLS_SUBMODE (1)
+/* @brief Has VLLS mode control (register bit VLLSCTRL[VLLSM]). */
+#define FSL_FEATURE_SMC_USE_VLLSCTRL_REG (0)
+/* @brief Has VLLS mode control (register bit STOPCTRL[VLLSM]). */
+#define FSL_FEATURE_SMC_USE_STOPCTRL_VLLSM (0)
+/* @brief Has RAM partition 2 power option (register bit STOPCTRL[RAM2PO]). */
+#define FSL_FEATURE_SMC_HAS_RAM2_POWER_OPTION (0)
+/* @brief Has high speed run mode (register bit PMPROT[AHSRUN]). */
+#define FSL_FEATURE_SMC_HAS_HIGH_SPEED_RUN_MODE (1)
+/* @brief Has low leakage stop mode (register bit PMPROT[ALLS]). */
+#define FSL_FEATURE_SMC_HAS_LOW_LEAKAGE_STOP_MODE (1)
+/* @brief Has very low leakage stop mode (register bit PMPROT[AVLLS]). */
+#define FSL_FEATURE_SMC_HAS_VERY_LOW_LEAKAGE_STOP_MODE (1)
+/* @brief Has stop submode. */
+#define FSL_FEATURE_SMC_HAS_SUB_STOP_MODE (1)
+/* @brief Has stop submode 0(VLLS0). */
+#define FSL_FEATURE_SMC_HAS_STOP_SUBMODE0 (1)
+/* @brief Has stop submode 1(VLLS1). */
+#define FSL_FEATURE_SMC_HAS_STOP_SUBMODE1 (1)
+/* @brief Has stop submode 2(VLLS2). */
+#define FSL_FEATURE_SMC_HAS_STOP_SUBMODE2 (1)
+/* @brief Has SMC_PARAM. */
+#define FSL_FEATURE_SMC_HAS_PARAM (0)
+/* @brief Has SMC_VERID. */
+#define FSL_FEATURE_SMC_HAS_VERID (0)
+/* @brief Has stop abort flag (register bit PMCTRL[STOPA]). */
+#define FSL_FEATURE_SMC_HAS_PMCTRL_STOPA (1)
+/* @brief Has tamper reset (register bit SRS[TAMPER]). */
+#define FSL_FEATURE_SMC_HAS_SRS_TAMPER (0)
+/* @brief Has security violation reset (register bit SRS[SECVIO]). */
+#define FSL_FEATURE_SMC_HAS_SRS_SECVIO (0)
+
+/* DSPI module features */
+
+#if defined(CPU_MK02FN128VFM10) || defined(CPU_MK02FN64VFM10)
+ /* @brief Receive/transmit FIFO size in number of items. */
+ #define FSL_FEATURE_DSPI_FIFO_SIZEn(x) (4)
+ /* @brief Maximum transfer data width in bits. */
+ #define FSL_FEATURE_DSPI_MAX_DATA_WIDTH (16)
+ /* @brief Maximum number of chip select pins. (Reflects the width of register bit field PUSHR[PCS].) */
+ #define FSL_FEATURE_DSPI_MAX_CHIP_SELECT_COUNT (6)
+ /* @brief Number of chip select pins. */
+ #define FSL_FEATURE_DSPI_CHIP_SELECT_COUNT (4)
+ /* @brief Number of CTAR registers. */
+ #define FSL_FEATURE_DSPI_CTAR_COUNT (2)
+ /* @brief Has chip select strobe capability on the PCS5 pin. */
+ #define FSL_FEATURE_DSPI_HAS_CHIP_SELECT_STROBE (1)
+ /* @brief Has separated TXDATA and CMD FIFOs (register SREX). */
+ #define FSL_FEATURE_DSPI_HAS_SEPARATE_TXDATA_CMD_FIFO (0)
+ /* @brief Has 16-bit data transfer support. */
+ #define FSL_FEATURE_DSPI_16BIT_TRANSFERS (1)
+ /* @brief Has separate DMA RX and TX requests. */
+ #define FSL_FEATURE_DSPI_HAS_SEPARATE_DMA_RX_TX_REQn(x) (1)
+#elif defined(CPU_MK02FN128VLF10) || defined(CPU_MK02FN128VLH10) || defined(CPU_MK02FN64VLF10) || defined(CPU_MK02FN64VLH10)
+ /* @brief Receive/transmit FIFO size in number of items. */
+ #define FSL_FEATURE_DSPI_FIFO_SIZEn(x) (4)
+ /* @brief Maximum transfer data width in bits. */
+ #define FSL_FEATURE_DSPI_MAX_DATA_WIDTH (16)
+ /* @brief Maximum number of chip select pins. (Reflects the width of register bit field PUSHR[PCS].) */
+ #define FSL_FEATURE_DSPI_MAX_CHIP_SELECT_COUNT (6)
+ /* @brief Number of chip select pins. */
+ #define FSL_FEATURE_DSPI_CHIP_SELECT_COUNT (5)
+ /* @brief Number of CTAR registers. */
+ #define FSL_FEATURE_DSPI_CTAR_COUNT (2)
+ /* @brief Has chip select strobe capability on the PCS5 pin. */
+ #define FSL_FEATURE_DSPI_HAS_CHIP_SELECT_STROBE (1)
+ /* @brief Has separated TXDATA and CMD FIFOs (register SREX). */
+ #define FSL_FEATURE_DSPI_HAS_SEPARATE_TXDATA_CMD_FIFO (0)
+ /* @brief Has 16-bit data transfer support. */
+ #define FSL_FEATURE_DSPI_16BIT_TRANSFERS (1)
+ /* @brief Has separate DMA RX and TX requests. */
+ #define FSL_FEATURE_DSPI_HAS_SEPARATE_DMA_RX_TX_REQn(x) (1)
+#endif /* defined(CPU_MK02FN128VFM10) || defined(CPU_MK02FN64VFM10) */
+
+/* SysTick module features */
+
+/* @brief Systick has external reference clock. */
+#define FSL_FEATURE_SYSTICK_HAS_EXT_REF (0)
+/* @brief Systick external reference clock is core clock divided by this value. */
+#define FSL_FEATURE_SYSTICK_EXT_REF_CORE_DIV (0)
+
+/* UART module features */
+
+/* @brief Has receive FIFO overflow detection (bit field CFIFO[RXOFE]). */
+#define FSL_FEATURE_UART_HAS_IRQ_EXTENDED_FUNCTIONS (1)
+/* @brief Has low power features (can be enabled in wait mode via register bit C1[DOZEEN] or CTRL[DOZEEN] if the registers are 32-bit wide). */
+#define FSL_FEATURE_UART_HAS_LOW_POWER_UART_SUPPORT (0)
+/* @brief Has extended data register ED (or extra flags in the DATA register if the registers are 32-bit wide). */
+#define FSL_FEATURE_UART_HAS_EXTENDED_DATA_REGISTER_FLAGS (1)
+/* @brief Capacity (number of entries) of the transmit/receive FIFO (or zero if no FIFO is available). */
+#define FSL_FEATURE_UART_HAS_FIFO (1)
+/* @brief Hardware flow control (RTS, CTS) is supported. */
+#define FSL_FEATURE_UART_HAS_MODEM_SUPPORT (1)
+/* @brief Infrared (modulation) is supported. */
+#define FSL_FEATURE_UART_HAS_IR_SUPPORT (1)
+/* @brief 2 bits long stop bit is available. */
+#define FSL_FEATURE_UART_HAS_STOP_BIT_CONFIG_SUPPORT (0)
+/* @brief If 10-bit mode is supported. */
+#define FSL_FEATURE_UART_HAS_10BIT_DATA_SUPPORT (1)
+/* @brief Baud rate fine adjustment is available. */
+#define FSL_FEATURE_UART_HAS_BAUD_RATE_FINE_ADJUST_SUPPORT (1)
+/* @brief Baud rate oversampling is available (has bit fields C4[OSR], C5[BOTHEDGE], C5[RESYNCDIS] or BAUD[OSR], BAUD[BOTHEDGE], BAUD[RESYNCDIS] if the registers are 32-bit wide). */
+#define FSL_FEATURE_UART_HAS_BAUD_RATE_OVER_SAMPLING_SUPPORT (0)
+/* @brief Baud rate oversampling is available. */
+#define FSL_FEATURE_UART_HAS_RX_RESYNC_SUPPORT (0)
+/* @brief Baud rate oversampling is available. */
+#define FSL_FEATURE_UART_HAS_BOTH_EDGE_SAMPLING_SUPPORT (0)
+/* @brief Peripheral type. */
+#define FSL_FEATURE_UART_IS_SCI (0)
+/* @brief Capacity (number of entries) of the transmit/receive FIFO (or zero if no FIFO is available). */
+#define FSL_FEATURE_UART_FIFO_SIZEn(x) \
+ ((x) == UART0 ? (8) : \
+ ((x) == UART1 ? (1) : (-1)))
+/* @brief Maximal data width without parity bit. */
+#define FSL_FEATURE_UART_MAX_DATA_WIDTH_WITH_NO_PARITY (9)
+/* @brief Maximal data width with parity bit. */
+#define FSL_FEATURE_UART_MAX_DATA_WIDTH_WITH_PARITY (10)
+/* @brief Supports two match addresses to filter incoming frames. */
+#define FSL_FEATURE_UART_HAS_ADDRESS_MATCHING (1)
+/* @brief Has transmitter/receiver DMA enable bits C5[TDMAE]/C5[RDMAE] (or BAUD[TDMAE]/BAUD[RDMAE] if the registers are 32-bit wide). */
+#define FSL_FEATURE_UART_HAS_DMA_ENABLE (0)
+/* @brief Has transmitter/receiver DMA select bits C4[TDMAS]/C4[RDMAS], resp. C5[TDMAS]/C5[RDMAS] if IS_SCI = 0. */
+#define FSL_FEATURE_UART_HAS_DMA_SELECT (1)
+/* @brief Data character bit order selection is supported (bit field S2[MSBF] or STAT[MSBF] if the registers are 32-bit wide). */
+#define FSL_FEATURE_UART_HAS_BIT_ORDER_SELECT (1)
+/* @brief Has smart card (ISO7816 protocol) support and no improved smart card support. */
+#define FSL_FEATURE_UART_HAS_SMART_CARD_SUPPORT (0)
+/* @brief Has improved smart card (ISO7816 protocol) support. */
+#define FSL_FEATURE_UART_HAS_IMPROVED_SMART_CARD_SUPPORT (0)
+/* @brief Has local operation network (CEA709.1-B protocol) support. */
+#define FSL_FEATURE_UART_HAS_LOCAL_OPERATION_NETWORK_SUPPORT (0)
+/* @brief Has 32-bit registers (BAUD, STAT, CTRL, DATA, MATCH, MODIR) instead of 8-bit (BDH, BDL, C1, S1, D, etc.). */
+#define FSL_FEATURE_UART_HAS_32BIT_REGISTERS (0)
+/* @brief Lin break detect available (has bit BDH[LBKDIE]). */
+#define FSL_FEATURE_UART_HAS_LIN_BREAK_DETECT (1)
+/* @brief UART stops in Wait mode available (has bit C1[UARTSWAI]). */
+#define FSL_FEATURE_UART_HAS_WAIT_MODE_OPERATION (1)
+/* @brief Has separate DMA RX and TX requests. */
+#define FSL_FEATURE_UART_HAS_SEPARATE_DMA_RX_TX_REQn(x) (1)
+
+/* VREF module features */
+
+/* @brief Has chop oscillator (bit TRM[CHOPEN]) */
+#define FSL_FEATURE_VREF_HAS_CHOP_OSC (1)
+/* @brief Has second order curvature compensation (bit SC[ICOMPEN]) */
+#define FSL_FEATURE_VREF_HAS_COMPENSATION (1)
+/* @brief If high/low buffer mode supported */
+#define FSL_FEATURE_VREF_MODE_LV_TYPE (1)
+/* @brief Module has also low reference (registers VREFL/VREFH) */
+#define FSL_FEATURE_VREF_HAS_LOW_REFERENCE (0)
+/* @brief Has VREF_TRM4. */
+#define FSL_FEATURE_VREF_HAS_TRM4 (0)
+
+/* WDOG module features */
+
+/* @brief Watchdog is available. */
+#define FSL_FEATURE_WDOG_HAS_WATCHDOG (1)
+/* @brief Has Wait mode support. */
+#define FSL_FEATURE_WDOG_HAS_WAITEN (1)
+
+#endif /* _MK02F12810_FEATURES_H_ */
+
diff --git a/CMSIS/arm_common_tables.h b/CMSIS/arm_common_tables.h
new file mode 100644
index 0000000..dfea746
--- /dev/null
+++ b/CMSIS/arm_common_tables.h
@@ -0,0 +1,121 @@
+/* ----------------------------------------------------------------------
+ * Project: CMSIS DSP Library
+ * Title: arm_common_tables.h
+ * Description: Extern declaration for common tables
+ *
+ * $Date: 27. January 2017
+ * $Revision: V.1.5.1
+ *
+ * Target Processor: Cortex-M cores
+ * -------------------------------------------------------------------- */
+/*
+ * Copyright (C) 2010-2017 ARM Limited or its affiliates. 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 _ARM_COMMON_TABLES_H
+#define _ARM_COMMON_TABLES_H
+
+#include "arm_math.h"
+
+extern const uint16_t armBitRevTable[1024];
+extern const q15_t armRecipTableQ15[64];
+extern const q31_t armRecipTableQ31[64];
+extern const float32_t twiddleCoef_16[32];
+extern const float32_t twiddleCoef_32[64];
+extern const float32_t twiddleCoef_64[128];
+extern const float32_t twiddleCoef_128[256];
+extern const float32_t twiddleCoef_256[512];
+extern const float32_t twiddleCoef_512[1024];
+extern const float32_t twiddleCoef_1024[2048];
+extern const float32_t twiddleCoef_2048[4096];
+extern const float32_t twiddleCoef_4096[8192];
+#define twiddleCoef twiddleCoef_4096
+extern const q31_t twiddleCoef_16_q31[24];
+extern const q31_t twiddleCoef_32_q31[48];
+extern const q31_t twiddleCoef_64_q31[96];
+extern const q31_t twiddleCoef_128_q31[192];
+extern const q31_t twiddleCoef_256_q31[384];
+extern const q31_t twiddleCoef_512_q31[768];
+extern const q31_t twiddleCoef_1024_q31[1536];
+extern const q31_t twiddleCoef_2048_q31[3072];
+extern const q31_t twiddleCoef_4096_q31[6144];
+extern const q15_t twiddleCoef_16_q15[24];
+extern const q15_t twiddleCoef_32_q15[48];
+extern const q15_t twiddleCoef_64_q15[96];
+extern const q15_t twiddleCoef_128_q15[192];
+extern const q15_t twiddleCoef_256_q15[384];
+extern const q15_t twiddleCoef_512_q15[768];
+extern const q15_t twiddleCoef_1024_q15[1536];
+extern const q15_t twiddleCoef_2048_q15[3072];
+extern const q15_t twiddleCoef_4096_q15[6144];
+extern const float32_t twiddleCoef_rfft_32[32];
+extern const float32_t twiddleCoef_rfft_64[64];
+extern const float32_t twiddleCoef_rfft_128[128];
+extern const float32_t twiddleCoef_rfft_256[256];
+extern const float32_t twiddleCoef_rfft_512[512];
+extern const float32_t twiddleCoef_rfft_1024[1024];
+extern const float32_t twiddleCoef_rfft_2048[2048];
+extern const float32_t twiddleCoef_rfft_4096[4096];
+
+/* floating-point bit reversal tables */
+#define ARMBITREVINDEXTABLE_16_TABLE_LENGTH ((uint16_t)20)
+#define ARMBITREVINDEXTABLE_32_TABLE_LENGTH ((uint16_t)48)
+#define ARMBITREVINDEXTABLE_64_TABLE_LENGTH ((uint16_t)56)
+#define ARMBITREVINDEXTABLE_128_TABLE_LENGTH ((uint16_t)208)
+#define ARMBITREVINDEXTABLE_256_TABLE_LENGTH ((uint16_t)440)
+#define ARMBITREVINDEXTABLE_512_TABLE_LENGTH ((uint16_t)448)
+#define ARMBITREVINDEXTABLE_1024_TABLE_LENGTH ((uint16_t)1800)
+#define ARMBITREVINDEXTABLE_2048_TABLE_LENGTH ((uint16_t)3808)
+#define ARMBITREVINDEXTABLE_4096_TABLE_LENGTH ((uint16_t)4032)
+
+extern const uint16_t armBitRevIndexTable16[ARMBITREVINDEXTABLE_16_TABLE_LENGTH];
+extern const uint16_t armBitRevIndexTable32[ARMBITREVINDEXTABLE_32_TABLE_LENGTH];
+extern const uint16_t armBitRevIndexTable64[ARMBITREVINDEXTABLE_64_TABLE_LENGTH];
+extern const uint16_t armBitRevIndexTable128[ARMBITREVINDEXTABLE_128_TABLE_LENGTH];
+extern const uint16_t armBitRevIndexTable256[ARMBITREVINDEXTABLE_256_TABLE_LENGTH];
+extern const uint16_t armBitRevIndexTable512[ARMBITREVINDEXTABLE_512_TABLE_LENGTH];
+extern const uint16_t armBitRevIndexTable1024[ARMBITREVINDEXTABLE_1024_TABLE_LENGTH];
+extern const uint16_t armBitRevIndexTable2048[ARMBITREVINDEXTABLE_2048_TABLE_LENGTH];
+extern const uint16_t armBitRevIndexTable4096[ARMBITREVINDEXTABLE_4096_TABLE_LENGTH];
+
+/* fixed-point bit reversal tables */
+#define ARMBITREVINDEXTABLE_FIXED_16_TABLE_LENGTH ((uint16_t)12)
+#define ARMBITREVINDEXTABLE_FIXED_32_TABLE_LENGTH ((uint16_t)24)
+#define ARMBITREVINDEXTABLE_FIXED_64_TABLE_LENGTH ((uint16_t)56)
+#define ARMBITREVINDEXTABLE_FIXED_128_TABLE_LENGTH ((uint16_t)112)
+#define ARMBITREVINDEXTABLE_FIXED_256_TABLE_LENGTH ((uint16_t)240)
+#define ARMBITREVINDEXTABLE_FIXED_512_TABLE_LENGTH ((uint16_t)480)
+#define ARMBITREVINDEXTABLE_FIXED_1024_TABLE_LENGTH ((uint16_t)992)
+#define ARMBITREVINDEXTABLE_FIXED_2048_TABLE_LENGTH ((uint16_t)1984)
+#define ARMBITREVINDEXTABLE_FIXED_4096_TABLE_LENGTH ((uint16_t)4032)
+
+extern const uint16_t armBitRevIndexTable_fixed_16[ARMBITREVINDEXTABLE_FIXED_16_TABLE_LENGTH];
+extern const uint16_t armBitRevIndexTable_fixed_32[ARMBITREVINDEXTABLE_FIXED_32_TABLE_LENGTH];
+extern const uint16_t armBitRevIndexTable_fixed_64[ARMBITREVINDEXTABLE_FIXED_64_TABLE_LENGTH];
+extern const uint16_t armBitRevIndexTable_fixed_128[ARMBITREVINDEXTABLE_FIXED_128_TABLE_LENGTH];
+extern const uint16_t armBitRevIndexTable_fixed_256[ARMBITREVINDEXTABLE_FIXED_256_TABLE_LENGTH];
+extern const uint16_t armBitRevIndexTable_fixed_512[ARMBITREVINDEXTABLE_FIXED_512_TABLE_LENGTH];
+extern const uint16_t armBitRevIndexTable_fixed_1024[ARMBITREVINDEXTABLE_FIXED_1024_TABLE_LENGTH];
+extern const uint16_t armBitRevIndexTable_fixed_2048[ARMBITREVINDEXTABLE_FIXED_2048_TABLE_LENGTH];
+extern const uint16_t armBitRevIndexTable_fixed_4096[ARMBITREVINDEXTABLE_FIXED_4096_TABLE_LENGTH];
+
+/* Tables for Fast Math Sine and Cosine */
+extern const float32_t sinTable_f32[FAST_MATH_TABLE_SIZE + 1];
+extern const q31_t sinTable_q31[FAST_MATH_TABLE_SIZE + 1];
+extern const q15_t sinTable_q15[FAST_MATH_TABLE_SIZE + 1];
+
+#endif /* ARM_COMMON_TABLES_H */
diff --git a/CMSIS/arm_const_structs.h b/CMSIS/arm_const_structs.h
new file mode 100644
index 0000000..80a3e8b
--- /dev/null
+++ b/CMSIS/arm_const_structs.h
@@ -0,0 +1,66 @@
+/* ----------------------------------------------------------------------
+ * Project: CMSIS DSP Library
+ * Title: arm_const_structs.h
+ * Description: Constant structs that are initialized for user convenience.
+ * For example, some can be given as arguments to the arm_cfft_f32() function.
+ *
+ * $Date: 27. January 2017
+ * $Revision: V.1.5.1
+ *
+ * Target Processor: Cortex-M cores
+ * -------------------------------------------------------------------- */
+/*
+ * Copyright (C) 2010-2017 ARM Limited or its affiliates. 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 _ARM_CONST_STRUCTS_H
+#define _ARM_CONST_STRUCTS_H
+
+#include "arm_math.h"
+#include "arm_common_tables.h"
+
+ extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len16;
+ extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len32;
+ extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len64;
+ extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len128;
+ extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len256;
+ extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len512;
+ extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len1024;
+ extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len2048;
+ extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len4096;
+
+ extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len16;
+ extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len32;
+ extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len64;
+ extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len128;
+ extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len256;
+ extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len512;
+ extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len1024;
+ extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len2048;
+ extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len4096;
+
+ extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len16;
+ extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len32;
+ extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len64;
+ extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len128;
+ extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len256;
+ extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len512;
+ extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len1024;
+ extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len2048;
+ extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len4096;
+
+#endif
diff --git a/CMSIS/arm_math.h b/CMSIS/arm_math.h
new file mode 100644
index 0000000..ea9dd26
--- /dev/null
+++ b/CMSIS/arm_math.h
@@ -0,0 +1,7157 @@
+/******************************************************************************
+ * @file arm_math.h
+ * @brief Public header file for CMSIS DSP LibraryU
+ * @version V1.5.3
+ * @date 10. January 2018
+ ******************************************************************************/
+/*
+ * Copyright (c) 2010-2018 Arm Limited or its affiliates. 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.
+ */
+
+/**
+ \mainpage CMSIS DSP Software Library
+ *
+ * Introduction
+ * ------------
+ *
+ * This user manual describes the CMSIS DSP software library,
+ * a suite of common signal processing functions for use on Cortex-M processor based devices.
+ *
+ * The library is divided into a number of functions each covering a specific category:
+ * - Basic math functions
+ * - Fast math functions
+ * - Complex math functions
+ * - Filters
+ * - Matrix functions
+ * - Transforms
+ * - Motor control functions
+ * - Statistical functions
+ * - Support functions
+ * - Interpolation functions
+ *
+ * The library has separate functions for operating on 8-bit integers, 16-bit integers,
+ * 32-bit integer and 32-bit floating-point values.
+ *
+ * Using the Library
+ * ------------
+ *
+ * The library installer contains prebuilt versions of the libraries in the <code>Lib</code> folder.
+ * - arm_cortexM7lfdp_math.lib (Cortex-M7, Little endian, Double Precision Floating Point Unit)
+ * - arm_cortexM7bfdp_math.lib (Cortex-M7, Big endian, Double Precision Floating Point Unit)
+ * - arm_cortexM7lfsp_math.lib (Cortex-M7, Little endian, Single Precision Floating Point Unit)
+ * - arm_cortexM7bfsp_math.lib (Cortex-M7, Big endian and Single Precision Floating Point Unit on)
+ * - arm_cortexM7l_math.lib (Cortex-M7, Little endian)
+ * - arm_cortexM7b_math.lib (Cortex-M7, Big endian)
+ * - arm_cortexM4lf_math.lib (Cortex-M4, Little endian, Floating Point Unit)
+ * - arm_cortexM4bf_math.lib (Cortex-M4, Big endian, Floating Point Unit)
+ * - arm_cortexM4l_math.lib (Cortex-M4, Little endian)
+ * - arm_cortexM4b_math.lib (Cortex-M4, Big endian)
+ * - arm_cortexM3l_math.lib (Cortex-M3, Little endian)
+ * - arm_cortexM3b_math.lib (Cortex-M3, Big endian)
+ * - arm_cortexM0l_math.lib (Cortex-M0 / Cortex-M0+, Little endian)
+ * - arm_cortexM0b_math.lib (Cortex-M0 / Cortex-M0+, Big endian)
+ * - arm_ARMv8MBLl_math.lib (Armv8-M Baseline, Little endian)
+ * - arm_ARMv8MMLl_math.lib (Armv8-M Mainline, Little endian)
+ * - arm_ARMv8MMLlfsp_math.lib (Armv8-M Mainline, Little endian, Single Precision Floating Point Unit)
+ * - arm_ARMv8MMLld_math.lib (Armv8-M Mainline, Little endian, DSP instructions)
+ * - arm_ARMv8MMLldfsp_math.lib (Armv8-M Mainline, Little endian, DSP instructions, Single Precision Floating Point Unit)
+ *
+ * The library functions are declared in the public file <code>arm_math.h</code> which is placed in the <code>Include</code> folder.
+ * Simply include this file and link the appropriate library in the application and begin calling the library functions. The Library supports single
+ * public header file <code> arm_math.h</code> for Cortex-M cores with little endian and big endian. Same header file will be used for floating point unit(FPU) variants.
+ * Define the appropriate preprocessor macro ARM_MATH_CM7 or ARM_MATH_CM4 or ARM_MATH_CM3 or
+ * ARM_MATH_CM0 or ARM_MATH_CM0PLUS depending on the target processor in the application.
+ * For Armv8-M cores define preprocessor macro ARM_MATH_ARMV8MBL or ARM_MATH_ARMV8MML.
+ * Set preprocessor macro __DSP_PRESENT if Armv8-M Mainline core supports DSP instructions.
+ *
+ *
+ * Examples
+ * --------
+ *
+ * The library ships with a number of examples which demonstrate how to use the library functions.
+ *
+ * Toolchain Support
+ * ------------
+ *
+ * The library has been developed and tested with MDK version 5.14.0.0
+ * The library is being tested in GCC and IAR toolchains and updates on this activity will be made available shortly.
+ *
+ * Building the Library
+ * ------------
+ *
+ * The library installer contains a project file to rebuild libraries on MDK toolchain in the <code>CMSIS\\DSP_Lib\\Source\\ARM</code> folder.
+ * - arm_cortexM_math.uvprojx
+ *
+ *
+ * The libraries can be built by opening the arm_cortexM_math.uvprojx project in MDK-ARM, selecting a specific target, and defining the optional preprocessor macros detailed above.
+ *
+ * Preprocessor Macros
+ * ------------
+ *
+ * Each library project have different preprocessor macros.
+ *
+ * - UNALIGNED_SUPPORT_DISABLE:
+ *
+ * Define macro UNALIGNED_SUPPORT_DISABLE, If the silicon does not support unaligned memory access
+ *
+ * - ARM_MATH_BIG_ENDIAN:
+ *
+ * Define macro ARM_MATH_BIG_ENDIAN to build the library for big endian targets. By default library builds for little endian targets.
+ *
+ * - ARM_MATH_MATRIX_CHECK:
+ *
+ * Define macro ARM_MATH_MATRIX_CHECK for checking on the input and output sizes of matrices
+ *
+ * - ARM_MATH_ROUNDING:
+ *
+ * Define macro ARM_MATH_ROUNDING for rounding on support functions
+ *
+ * - ARM_MATH_CMx:
+ *
+ * Define macro ARM_MATH_CM4 for building the library on Cortex-M4 target, ARM_MATH_CM3 for building library on Cortex-M3 target
+ * and ARM_MATH_CM0 for building library on Cortex-M0 target, ARM_MATH_CM0PLUS for building library on Cortex-M0+ target, and
+ * ARM_MATH_CM7 for building the library on cortex-M7.
+ *
+ * - ARM_MATH_ARMV8MxL:
+ *
+ * Define macro ARM_MATH_ARMV8MBL for building the library on Armv8-M Baseline target, ARM_MATH_ARMV8MML for building library
+ * on Armv8-M Mainline target.
+ *
+ * - __FPU_PRESENT:
+ *
+ * Initialize macro __FPU_PRESENT = 1 when building on FPU supported Targets. Enable this macro for floating point libraries.
+ *
+ * - __DSP_PRESENT:
+ *
+ * Initialize macro __DSP_PRESENT = 1 when Armv8-M Mainline core supports DSP instructions.
+ *
+ * <hr>
+ * CMSIS-DSP in ARM::CMSIS Pack
+ * -----------------------------
+ *
+ * The following files relevant to CMSIS-DSP are present in the <b>ARM::CMSIS</b> Pack directories:
+ * |File/Folder |Content |
+ * |------------------------------|------------------------------------------------------------------------|
+ * |\b CMSIS\\Documentation\\DSP | This documentation |
+ * |\b CMSIS\\DSP_Lib | Software license agreement (license.txt) |
+ * |\b CMSIS\\DSP_Lib\\Examples | Example projects demonstrating the usage of the library functions |
+ * |\b CMSIS\\DSP_Lib\\Source | Source files for rebuilding the library |
+ *
+ * <hr>
+ * Revision History of CMSIS-DSP
+ * ------------
+ * Please refer to \ref ChangeLog_pg.
+ *
+ * Copyright Notice
+ * ------------
+ *
+ * Copyright (C) 2010-2015 Arm Limited. All rights reserved.
+ */
+
+
+/**
+ * @defgroup groupMath Basic Math Functions
+ */
+
+/**
+ * @defgroup groupFastMath Fast Math Functions
+ * This set of functions provides a fast approximation to sine, cosine, and square root.
+ * As compared to most of the other functions in the CMSIS math library, the fast math functions
+ * operate on individual values and not arrays.
+ * There are separate functions for Q15, Q31, and floating-point data.
+ *
+ */
+
+/**
+ * @defgroup groupCmplxMath Complex Math Functions
+ * This set of functions operates on complex data vectors.
+ * The data in the complex arrays is stored in an interleaved fashion
+ * (real, imag, real, imag, ...).
+ * In the API functions, the number of samples in a complex array refers
+ * to the number of complex values; the array contains twice this number of
+ * real values.
+ */
+
+/**
+ * @defgroup groupFilters Filtering Functions
+ */
+
+/**
+ * @defgroup groupMatrix Matrix Functions
+ *
+ * This set of functions provides basic matrix math operations.
+ * The functions operate on matrix data structures. For example,
+ * the type
+ * definition for the floating-point matrix structure is shown
+ * below:
+ * <pre>
+ * typedef struct
+ * {
+ * uint16_t numRows; // number of rows of the matrix.
+ * uint16_t numCols; // number of columns of the matrix.
+ * float32_t *pData; // points to the data of the matrix.
+ * } arm_matrix_instance_f32;
+ * </pre>
+ * There are similar definitions for Q15 and Q31 data types.
+ *
+ * The structure specifies the size of the matrix and then points to
+ * an array of data. The array is of size <code>numRows X numCols</code>
+ * and the values are arranged in row order. That is, the
+ * matrix element (i, j) is stored at:
+ * <pre>
+ * pData[i*numCols + j]
+ * </pre>
+ *
+ * \par Init Functions
+ * There is an associated initialization function for each type of matrix
+ * data structure.
+ * The initialization function sets the values of the internal structure fields.
+ * Refer to the function <code>arm_mat_init_f32()</code>, <code>arm_mat_init_q31()</code>
+ * and <code>arm_mat_init_q15()</code> for floating-point, Q31 and Q15 types, respectively.
+ *
+ * \par
+ * Use of the initialization function is optional. However, if initialization function is used
+ * then the instance structure cannot be placed into a const data section.
+ * To place the instance structure in a const data
+ * section, manually initialize the data structure. For example:
+ * <pre>
+ * <code>arm_matrix_instance_f32 S = {nRows, nColumns, pData};</code>
+ * <code>arm_matrix_instance_q31 S = {nRows, nColumns, pData};</code>
+ * <code>arm_matrix_instance_q15 S = {nRows, nColumns, pData};</code>
+ * </pre>
+ * where <code>nRows</code> specifies the number of rows, <code>nColumns</code>
+ * specifies the number of columns, and <code>pData</code> points to the
+ * data array.
+ *
+ * \par Size Checking
+ * By default all of the matrix functions perform size checking on the input and
+ * output matrices. For example, the matrix addition function verifies that the
+ * two input matrices and the output matrix all have the same number of rows and
+ * columns. If the size check fails the functions return:
+ * <pre>
+ * ARM_MATH_SIZE_MISMATCH
+ * </pre>
+ * Otherwise the functions return
+ * <pre>
+ * ARM_MATH_SUCCESS
+ * </pre>
+ * There is some overhead associated with this matrix size checking.
+ * The matrix size checking is enabled via the \#define
+ * <pre>
+ * ARM_MATH_MATRIX_CHECK
+ * </pre>
+ * within the library project settings. By default this macro is defined
+ * and size checking is enabled. By changing the project settings and
+ * undefining this macro size checking is eliminated and the functions
+ * run a bit faster. With size checking disabled the functions always
+ * return <code>ARM_MATH_SUCCESS</code>.
+ */
+
+/**
+ * @defgroup groupTransforms Transform Functions
+ */
+
+/**
+ * @defgroup groupController Controller Functions
+ */
+
+/**
+ * @defgroup groupStats Statistics Functions
+ */
+/**
+ * @defgroup groupSupport Support Functions
+ */
+
+/**
+ * @defgroup groupInterpolation Interpolation Functions
+ * These functions perform 1- and 2-dimensional interpolation of data.
+ * Linear interpolation is used for 1-dimensional data and
+ * bilinear interpolation is used for 2-dimensional data.
+ */
+
+/**
+ * @defgroup groupExamples Examples
+ */
+#ifndef _ARM_MATH_H
+#define _ARM_MATH_H
+
+/* Compiler specific diagnostic adjustment */
+#if defined ( __CC_ARM )
+
+#elif defined ( __ARMCC_VERSION ) && ( __ARMCC_VERSION >= 6010050 )
+
+#elif defined ( __GNUC__ )
+#pragma GCC diagnostic push
+#pragma GCC diagnostic ignored "-Wsign-conversion"
+#pragma GCC diagnostic ignored "-Wconversion"
+#pragma GCC diagnostic ignored "-Wunused-parameter"
+
+#elif defined ( __ICCARM__ )
+
+#elif defined ( __TI_ARM__ )
+
+#elif defined ( __CSMC__ )
+
+#elif defined ( __TASKING__ )
+
+#else
+ #error Unknown compiler
+#endif
+
+
+#define __CMSIS_GENERIC /* disable NVIC and Systick functions */
+
+#if defined(ARM_MATH_CM7)
+ #include "core_cm7.h"
+ #define ARM_MATH_DSP
+#elif defined (ARM_MATH_CM4)
+ #include "core_cm4.h"
+ #define ARM_MATH_DSP
+#elif defined (ARM_MATH_CM3)
+ #include "core_cm3.h"
+#elif defined (ARM_MATH_CM0)
+ #include "core_cm0.h"
+ #define ARM_MATH_CM0_FAMILY
+#elif defined (ARM_MATH_CM0PLUS)
+ #include "core_cm0plus.h"
+ #define ARM_MATH_CM0_FAMILY
+#elif defined (ARM_MATH_ARMV8MBL)
+ #include "core_armv8mbl.h"
+ #define ARM_MATH_CM0_FAMILY
+#elif defined (ARM_MATH_ARMV8MML)
+ #include "core_armv8mml.h"
+ #if (defined (__DSP_PRESENT) && (__DSP_PRESENT == 1))
+ #define ARM_MATH_DSP
+ #endif
+#else
+ #error "Define according the used Cortex core ARM_MATH_CM7, ARM_MATH_CM4, ARM_MATH_CM3, ARM_MATH_CM0PLUS, ARM_MATH_CM0, ARM_MATH_ARMV8MBL, ARM_MATH_ARMV8MML"
+#endif
+
+#undef __CMSIS_GENERIC /* enable NVIC and Systick functions */
+#include "string.h"
+#include "math.h"
+#ifdef __cplusplus
+extern "C"
+{
+#endif
+
+
+ /**
+ * @brief Macros required for reciprocal calculation in Normalized LMS
+ */
+
+#define DELTA_Q31 (0x100)
+#define DELTA_Q15 0x5
+#define INDEX_MASK 0x0000003F
+#ifndef PI
+ #define PI 3.14159265358979f
+#endif
+
+ /**
+ * @brief Macros required for SINE and COSINE Fast math approximations
+ */
+
+#define FAST_MATH_TABLE_SIZE 512
+#define FAST_MATH_Q31_SHIFT (32 - 10)
+#define FAST_MATH_Q15_SHIFT (16 - 10)
+#define CONTROLLER_Q31_SHIFT (32 - 9)
+#define TABLE_SPACING_Q31 0x400000
+#define TABLE_SPACING_Q15 0x80
+
+ /**
+ * @brief Macros required for SINE and COSINE Controller functions
+ */
+ /* 1.31(q31) Fixed value of 2/360 */
+ /* -1 to +1 is divided into 360 values so total spacing is (2/360) */
+#define INPUT_SPACING 0xB60B61
+
+ /**
+ * @brief Macro for Unaligned Support
+ */
+#ifndef UNALIGNED_SUPPORT_DISABLE
+ #define ALIGN4
+#else
+ #if defined (__GNUC__)
+ #define ALIGN4 __attribute__((aligned(4)))
+ #else
+ #define ALIGN4 __align(4)
+ #endif
+#endif /* #ifndef UNALIGNED_SUPPORT_DISABLE */
+
+ /**
+ * @brief Error status returned by some functions in the library.
+ */
+
+ typedef enum
+ {
+ ARM_MATH_SUCCESS = 0, /**< No error */
+ ARM_MATH_ARGUMENT_ERROR = -1, /**< One or more arguments are incorrect */
+ ARM_MATH_LENGTH_ERROR = -2, /**< Length of data buffer is incorrect */
+ ARM_MATH_SIZE_MISMATCH = -3, /**< Size of matrices is not compatible with the operation. */
+ ARM_MATH_NANINF = -4, /**< Not-a-number (NaN) or infinity is generated */
+ ARM_MATH_SINGULAR = -5, /**< Generated by matrix inversion if the input matrix is singular and cannot be inverted. */
+ ARM_MATH_TEST_FAILURE = -6 /**< Test Failed */
+ } arm_status;
+
+ /**
+ * @brief 8-bit fractional data type in 1.7 format.
+ */
+ typedef int8_t q7_t;
+
+ /**
+ * @brief 16-bit fractional data type in 1.15 format.
+ */
+ typedef int16_t q15_t;
+
+ /**
+ * @brief 32-bit fractional data type in 1.31 format.
+ */
+ typedef int32_t q31_t;
+
+ /**
+ * @brief 64-bit fractional data type in 1.63 format.
+ */
+ typedef int64_t q63_t;
+
+ /**
+ * @brief 32-bit floating-point type definition.
+ */
+ typedef float float32_t;
+
+ /**
+ * @brief 64-bit floating-point type definition.
+ */
+ typedef double float64_t;
+
+ /**
+ * @brief definition to read/write two 16 bit values.
+ */
+#if defined ( __CC_ARM )
+ #define __SIMD32_TYPE int32_t __packed
+ #define CMSIS_UNUSED __attribute__((unused))
+ #define CMSIS_INLINE __attribute__((always_inline))
+
+#elif defined ( __ARMCC_VERSION ) && ( __ARMCC_VERSION >= 6010050 )
+ #define __SIMD32_TYPE int32_t
+ #define CMSIS_UNUSED __attribute__((unused))
+ #define CMSIS_INLINE __attribute__((always_inline))
+
+#elif defined ( __GNUC__ )
+ #define __SIMD32_TYPE int32_t
+ #define CMSIS_UNUSED __attribute__((unused))
+ #define CMSIS_INLINE __attribute__((always_inline))
+
+#elif defined ( __ICCARM__ )
+ #define __SIMD32_TYPE int32_t __packed
+ #define CMSIS_UNUSED
+ #define CMSIS_INLINE
+
+#elif defined ( __TI_ARM__ )
+ #define __SIMD32_TYPE int32_t
+ #define CMSIS_UNUSED __attribute__((unused))
+ #define CMSIS_INLINE
+
+#elif defined ( __CSMC__ )
+ #define __SIMD32_TYPE int32_t
+ #define CMSIS_UNUSED
+ #define CMSIS_INLINE
+
+#elif defined ( __TASKING__ )
+ #define __SIMD32_TYPE __unaligned int32_t
+ #define CMSIS_UNUSED
+ #define CMSIS_INLINE
+
+#else
+ #error Unknown compiler
+#endif
+
+#define __SIMD32(addr) (*(__SIMD32_TYPE **) & (addr))
+#define __SIMD32_CONST(addr) ((__SIMD32_TYPE *)(addr))
+#define _SIMD32_OFFSET(addr) (*(__SIMD32_TYPE *) (addr))
+#define __SIMD64(addr) (*(int64_t **) & (addr))
+
+#if !defined (ARM_MATH_DSP)
+ /**
+ * @brief definition to pack two 16 bit values.
+ */
+#define __PKHBT(ARG1, ARG2, ARG3) ( (((int32_t)(ARG1) << 0) & (int32_t)0x0000FFFF) | \
+ (((int32_t)(ARG2) << ARG3) & (int32_t)0xFFFF0000) )
+#define __PKHTB(ARG1, ARG2, ARG3) ( (((int32_t)(ARG1) << 0) & (int32_t)0xFFFF0000) | \
+ (((int32_t)(ARG2) >> ARG3) & (int32_t)0x0000FFFF) )
+
+#endif /* !defined (ARM_MATH_DSP) */
+
+ /**
+ * @brief definition to pack four 8 bit values.
+ */
+#ifndef ARM_MATH_BIG_ENDIAN
+
+#define __PACKq7(v0,v1,v2,v3) ( (((int32_t)(v0) << 0) & (int32_t)0x000000FF) | \
+ (((int32_t)(v1) << 8) & (int32_t)0x0000FF00) | \
+ (((int32_t)(v2) << 16) & (int32_t)0x00FF0000) | \
+ (((int32_t)(v3) << 24) & (int32_t)0xFF000000) )
+#else
+
+#define __PACKq7(v0,v1,v2,v3) ( (((int32_t)(v3) << 0) & (int32_t)0x000000FF) | \
+ (((int32_t)(v2) << 8) & (int32_t)0x0000FF00) | \
+ (((int32_t)(v1) << 16) & (int32_t)0x00FF0000) | \
+ (((int32_t)(v0) << 24) & (int32_t)0xFF000000) )
+
+#endif
+
+
+ /**
+ * @brief Clips Q63 to Q31 values.
+ */
+ CMSIS_INLINE __STATIC_INLINE q31_t clip_q63_to_q31(
+ q63_t x)
+ {
+ return ((q31_t) (x >> 32) != ((q31_t) x >> 31)) ?
+ ((0x7FFFFFFF ^ ((q31_t) (x >> 63)))) : (q31_t) x;
+ }
+
+ /**
+ * @brief Clips Q63 to Q15 values.
+ */
+ CMSIS_INLINE __STATIC_INLINE q15_t clip_q63_to_q15(
+ q63_t x)
+ {
+ return ((q31_t) (x >> 32) != ((q31_t) x >> 31)) ?
+ ((0x7FFF ^ ((q15_t) (x >> 63)))) : (q15_t) (x >> 15);
+ }
+
+ /**
+ * @brief Clips Q31 to Q7 values.
+ */
+ CMSIS_INLINE __STATIC_INLINE q7_t clip_q31_to_q7(
+ q31_t x)
+ {
+ return ((q31_t) (x >> 24) != ((q31_t) x >> 23)) ?
+ ((0x7F ^ ((q7_t) (x >> 31)))) : (q7_t) x;
+ }
+
+ /**
+ * @brief Clips Q31 to Q15 values.
+ */
+ CMSIS_INLINE __STATIC_INLINE q15_t clip_q31_to_q15(
+ q31_t x)
+ {
+ return ((q31_t) (x >> 16) != ((q31_t) x >> 15)) ?
+ ((0x7FFF ^ ((q15_t) (x >> 31)))) : (q15_t) x;
+ }
+
+ /**
+ * @brief Multiplies 32 X 64 and returns 32 bit result in 2.30 format.
+ */
+
+ CMSIS_INLINE __STATIC_INLINE q63_t mult32x64(
+ q63_t x,
+ q31_t y)
+ {
+ return ((((q63_t) (x & 0x00000000FFFFFFFF) * y) >> 32) +
+ (((q63_t) (x >> 32) * y)));
+ }
+
+ /**
+ * @brief Function to Calculates 1/in (reciprocal) value of Q31 Data type.
+ */
+
+ CMSIS_INLINE __STATIC_INLINE uint32_t arm_recip_q31(
+ q31_t in,
+ q31_t * dst,
+ q31_t * pRecipTable)
+ {
+ q31_t out;
+ uint32_t tempVal;
+ uint32_t index, i;
+ uint32_t signBits;
+
+ if (in > 0)
+ {
+ signBits = ((uint32_t) (__CLZ( in) - 1));
+ }
+ else
+ {
+ signBits = ((uint32_t) (__CLZ(-in) - 1));
+ }
+
+ /* Convert input sample to 1.31 format */
+ in = (in << signBits);
+
+ /* calculation of index for initial approximated Val */
+ index = (uint32_t)(in >> 24);
+ index = (index & INDEX_MASK);
+
+ /* 1.31 with exp 1 */
+ out = pRecipTable[index];
+
+ /* calculation of reciprocal value */
+ /* running approximation for two iterations */
+ for (i = 0U; i < 2U; i++)
+ {
+ tempVal = (uint32_t) (((q63_t) in * out) >> 31);
+ tempVal = 0x7FFFFFFFu - tempVal;
+ /* 1.31 with exp 1 */
+ /* out = (q31_t) (((q63_t) out * tempVal) >> 30); */
+ out = clip_q63_to_q31(((q63_t) out * tempVal) >> 30);
+ }
+
+ /* write output */
+ *dst = out;
+
+ /* return num of signbits of out = 1/in value */
+ return (signBits + 1U);
+ }
+
+
+ /**
+ * @brief Function to Calculates 1/in (reciprocal) value of Q15 Data type.
+ */
+ CMSIS_INLINE __STATIC_INLINE uint32_t arm_recip_q15(
+ q15_t in,
+ q15_t * dst,
+ q15_t * pRecipTable)
+ {
+ q15_t out = 0;
+ uint32_t tempVal = 0;
+ uint32_t index = 0, i = 0;
+ uint32_t signBits = 0;
+
+ if (in > 0)
+ {
+ signBits = ((uint32_t)(__CLZ( in) - 17));
+ }
+ else
+ {
+ signBits = ((uint32_t)(__CLZ(-in) - 17));
+ }
+
+ /* Convert input sample to 1.15 format */
+ in = (in << signBits);
+
+ /* calculation of index for initial approximated Val */
+ index = (uint32_t)(in >> 8);
+ index = (index & INDEX_MASK);
+
+ /* 1.15 with exp 1 */
+ out = pRecipTable[index];
+
+ /* calculation of reciprocal value */
+ /* running approximation for two iterations */
+ for (i = 0U; i < 2U; i++)
+ {
+ tempVal = (uint32_t) (((q31_t) in * out) >> 15);
+ tempVal = 0x7FFFu - tempVal;
+ /* 1.15 with exp 1 */
+ out = (q15_t) (((q31_t) out * tempVal) >> 14);
+ /* out = clip_q31_to_q15(((q31_t) out * tempVal) >> 14); */
+ }
+
+ /* write output */
+ *dst = out;
+
+ /* return num of signbits of out = 1/in value */
+ return (signBits + 1);
+ }
+
+
+/*
+ * @brief C custom defined intrinsic function for M3 and M0 processors
+ */
+#if !defined (ARM_MATH_DSP)
+
+ /*
+ * @brief C custom defined QADD8 for M3 and M0 processors
+ */
+ CMSIS_INLINE __STATIC_INLINE uint32_t __QADD8(
+ uint32_t x,
+ uint32_t y)
+ {
+ q31_t r, s, t, u;
+
+ r = __SSAT(((((q31_t)x << 24) >> 24) + (((q31_t)y << 24) >> 24)), 8) & (int32_t)0x000000FF;
+ s = __SSAT(((((q31_t)x << 16) >> 24) + (((q31_t)y << 16) >> 24)), 8) & (int32_t)0x000000FF;
+ t = __SSAT(((((q31_t)x << 8) >> 24) + (((q31_t)y << 8) >> 24)), 8) & (int32_t)0x000000FF;
+ u = __SSAT(((((q31_t)x ) >> 24) + (((q31_t)y ) >> 24)), 8) & (int32_t)0x000000FF;
+
+ return ((uint32_t)((u << 24) | (t << 16) | (s << 8) | (r )));
+ }
+
+
+ /*
+ * @brief C custom defined QSUB8 for M3 and M0 processors
+ */
+ CMSIS_INLINE __STATIC_INLINE uint32_t __QSUB8(
+ uint32_t x,
+ uint32_t y)
+ {
+ q31_t r, s, t, u;
+
+ r = __SSAT(((((q31_t)x << 24) >> 24) - (((q31_t)y << 24) >> 24)), 8) & (int32_t)0x000000FF;
+ s = __SSAT(((((q31_t)x << 16) >> 24) - (((q31_t)y << 16) >> 24)), 8) & (int32_t)0x000000FF;
+ t = __SSAT(((((q31_t)x << 8) >> 24) - (((q31_t)y << 8) >> 24)), 8) & (int32_t)0x000000FF;
+ u = __SSAT(((((q31_t)x ) >> 24) - (((q31_t)y ) >> 24)), 8) & (int32_t)0x000000FF;
+
+ return ((uint32_t)((u << 24) | (t << 16) | (s << 8) | (r )));
+ }
+
+
+ /*
+ * @brief C custom defined QADD16 for M3 and M0 processors
+ */
+ CMSIS_INLINE __STATIC_INLINE uint32_t __QADD16(
+ uint32_t x,
+ uint32_t y)
+ {
+/* q31_t r, s; without initialisation 'arm_offset_q15 test' fails but 'intrinsic' tests pass! for armCC */
+ q31_t r = 0, s = 0;
+
+ r = __SSAT(((((q31_t)x << 16) >> 16) + (((q31_t)y << 16) >> 16)), 16) & (int32_t)0x0000FFFF;
+ s = __SSAT(((((q31_t)x ) >> 16) + (((q31_t)y ) >> 16)), 16) & (int32_t)0x0000FFFF;
+
+ return ((uint32_t)((s << 16) | (r )));
+ }
+
+
+ /*
+ * @brief C custom defined SHADD16 for M3 and M0 processors
+ */
+ CMSIS_INLINE __STATIC_INLINE uint32_t __SHADD16(
+ uint32_t x,
+ uint32_t y)
+ {
+ q31_t r, s;
+
+ r = (((((q31_t)x << 16) >> 16) + (((q31_t)y << 16) >> 16)) >> 1) & (int32_t)0x0000FFFF;
+ s = (((((q31_t)x ) >> 16) + (((q31_t)y ) >> 16)) >> 1) & (int32_t)0x0000FFFF;
+
+ return ((uint32_t)((s << 16) | (r )));
+ }
+
+
+ /*
+ * @brief C custom defined QSUB16 for M3 and M0 processors
+ */
+ CMSIS_INLINE __STATIC_INLINE uint32_t __QSUB16(
+ uint32_t x,
+ uint32_t y)
+ {
+ q31_t r, s;
+
+ r = __SSAT(((((q31_t)x << 16) >> 16) - (((q31_t)y << 16) >> 16)), 16) & (int32_t)0x0000FFFF;
+ s = __SSAT(((((q31_t)x ) >> 16) - (((q31_t)y ) >> 16)), 16) & (int32_t)0x0000FFFF;
+
+ return ((uint32_t)((s << 16) | (r )));
+ }
+
+
+ /*
+ * @brief C custom defined SHSUB16 for M3 and M0 processors
+ */
+ CMSIS_INLINE __STATIC_INLINE uint32_t __SHSUB16(
+ uint32_t x,
+ uint32_t y)
+ {
+ q31_t r, s;
+
+ r = (((((q31_t)x << 16) >> 16) - (((q31_t)y << 16) >> 16)) >> 1) & (int32_t)0x0000FFFF;
+ s = (((((q31_t)x ) >> 16) - (((q31_t)y ) >> 16)) >> 1) & (int32_t)0x0000FFFF;
+
+ return ((uint32_t)((s << 16) | (r )));
+ }
+
+
+ /*
+ * @brief C custom defined QASX for M3 and M0 processors
+ */
+ CMSIS_INLINE __STATIC_INLINE uint32_t __QASX(
+ uint32_t x,
+ uint32_t y)
+ {
+ q31_t r, s;
+
+ r = __SSAT(((((q31_t)x << 16) >> 16) - (((q31_t)y ) >> 16)), 16) & (int32_t)0x0000FFFF;
+ s = __SSAT(((((q31_t)x ) >> 16) + (((q31_t)y << 16) >> 16)), 16) & (int32_t)0x0000FFFF;
+
+ return ((uint32_t)((s << 16) | (r )));
+ }
+
+
+ /*
+ * @brief C custom defined SHASX for M3 and M0 processors
+ */
+ CMSIS_INLINE __STATIC_INLINE uint32_t __SHASX(
+ uint32_t x,
+ uint32_t y)
+ {
+ q31_t r, s;
+
+ r = (((((q31_t)x << 16) >> 16) - (((q31_t)y ) >> 16)) >> 1) & (int32_t)0x0000FFFF;
+ s = (((((q31_t)x ) >> 16) + (((q31_t)y << 16) >> 16)) >> 1) & (int32_t)0x0000FFFF;
+
+ return ((uint32_t)((s << 16) | (r )));
+ }
+
+
+ /*
+ * @brief C custom defined QSAX for M3 and M0 processors
+ */
+ CMSIS_INLINE __STATIC_INLINE uint32_t __QSAX(
+ uint32_t x,
+ uint32_t y)
+ {
+ q31_t r, s;
+
+ r = __SSAT(((((q31_t)x << 16) >> 16) + (((q31_t)y ) >> 16)), 16) & (int32_t)0x0000FFFF;
+ s = __SSAT(((((q31_t)x ) >> 16) - (((q31_t)y << 16) >> 16)), 16) & (int32_t)0x0000FFFF;
+
+ return ((uint32_t)((s << 16) | (r )));
+ }
+
+
+ /*
+ * @brief C custom defined SHSAX for M3 and M0 processors
+ */
+ CMSIS_INLINE __STATIC_INLINE uint32_t __SHSAX(
+ uint32_t x,
+ uint32_t y)
+ {
+ q31_t r, s;
+
+ r = (((((q31_t)x << 16) >> 16) + (((q31_t)y ) >> 16)) >> 1) & (int32_t)0x0000FFFF;
+ s = (((((q31_t)x ) >> 16) - (((q31_t)y << 16) >> 16)) >> 1) & (int32_t)0x0000FFFF;
+
+ return ((uint32_t)((s << 16) | (r )));
+ }
+
+
+ /*
+ * @brief C custom defined SMUSDX for M3 and M0 processors
+ */
+ CMSIS_INLINE __STATIC_INLINE uint32_t __SMUSDX(
+ uint32_t x,
+ uint32_t y)
+ {
+ return ((uint32_t)(((((q31_t)x << 16) >> 16) * (((q31_t)y ) >> 16)) -
+ ((((q31_t)x ) >> 16) * (((q31_t)y << 16) >> 16)) ));
+ }
+
+ /*
+ * @brief C custom defined SMUADX for M3 and M0 processors
+ */
+ CMSIS_INLINE __STATIC_INLINE uint32_t __SMUADX(
+ uint32_t x,
+ uint32_t y)
+ {
+ return ((uint32_t)(((((q31_t)x << 16) >> 16) * (((q31_t)y ) >> 16)) +
+ ((((q31_t)x ) >> 16) * (((q31_t)y << 16) >> 16)) ));
+ }
+
+
+ /*
+ * @brief C custom defined QADD for M3 and M0 processors
+ */
+ CMSIS_INLINE __STATIC_INLINE int32_t __QADD(
+ int32_t x,
+ int32_t y)
+ {
+ return ((int32_t)(clip_q63_to_q31((q63_t)x + (q31_t)y)));
+ }
+
+
+ /*
+ * @brief C custom defined QSUB for M3 and M0 processors
+ */
+ CMSIS_INLINE __STATIC_INLINE int32_t __QSUB(
+ int32_t x,
+ int32_t y)
+ {
+ return ((int32_t)(clip_q63_to_q31((q63_t)x - (q31_t)y)));
+ }
+
+
+ /*
+ * @brief C custom defined SMLAD for M3 and M0 processors
+ */
+ CMSIS_INLINE __STATIC_INLINE uint32_t __SMLAD(
+ uint32_t x,
+ uint32_t y,
+ uint32_t sum)
+ {
+ return ((uint32_t)(((((q31_t)x << 16) >> 16) * (((q31_t)y << 16) >> 16)) +
+ ((((q31_t)x ) >> 16) * (((q31_t)y ) >> 16)) +
+ ( ((q31_t)sum ) ) ));
+ }
+
+
+ /*
+ * @brief C custom defined SMLADX for M3 and M0 processors
+ */
+ CMSIS_INLINE __STATIC_INLINE uint32_t __SMLADX(
+ uint32_t x,
+ uint32_t y,
+ uint32_t sum)
+ {
+ return ((uint32_t)(((((q31_t)x << 16) >> 16) * (((q31_t)y ) >> 16)) +
+ ((((q31_t)x ) >> 16) * (((q31_t)y << 16) >> 16)) +
+ ( ((q31_t)sum ) ) ));
+ }
+
+
+ /*
+ * @brief C custom defined SMLSDX for M3 and M0 processors
+ */
+ CMSIS_INLINE __STATIC_INLINE uint32_t __SMLSDX(
+ uint32_t x,
+ uint32_t y,
+ uint32_t sum)
+ {
+ return ((uint32_t)(((((q31_t)x << 16) >> 16) * (((q31_t)y ) >> 16)) -
+ ((((q31_t)x ) >> 16) * (((q31_t)y << 16) >> 16)) +
+ ( ((q31_t)sum ) ) ));
+ }
+
+
+ /*
+ * @brief C custom defined SMLALD for M3 and M0 processors
+ */
+ CMSIS_INLINE __STATIC_INLINE uint64_t __SMLALD(
+ uint32_t x,
+ uint32_t y,
+ uint64_t sum)
+ {
+/* return (sum + ((q15_t) (x >> 16) * (q15_t) (y >> 16)) + ((q15_t) x * (q15_t) y)); */
+ return ((uint64_t)(((((q31_t)x << 16) >> 16) * (((q31_t)y << 16) >> 16)) +
+ ((((q31_t)x ) >> 16) * (((q31_t)y ) >> 16)) +
+ ( ((q63_t)sum ) ) ));
+ }
+
+
+ /*
+ * @brief C custom defined SMLALDX for M3 and M0 processors
+ */
+ CMSIS_INLINE __STATIC_INLINE uint64_t __SMLALDX(
+ uint32_t x,
+ uint32_t y,
+ uint64_t sum)
+ {
+/* return (sum + ((q15_t) (x >> 16) * (q15_t) y)) + ((q15_t) x * (q15_t) (y >> 16)); */
+ return ((uint64_t)(((((q31_t)x << 16) >> 16) * (((q31_t)y ) >> 16)) +
+ ((((q31_t)x ) >> 16) * (((q31_t)y << 16) >> 16)) +
+ ( ((q63_t)sum ) ) ));
+ }
+
+
+ /*
+ * @brief C custom defined SMUAD for M3 and M0 processors
+ */
+ CMSIS_INLINE __STATIC_INLINE uint32_t __SMUAD(
+ uint32_t x,
+ uint32_t y)
+ {
+ return ((uint32_t)(((((q31_t)x << 16) >> 16) * (((q31_t)y << 16) >> 16)) +
+ ((((q31_t)x ) >> 16) * (((q31_t)y ) >> 16)) ));
+ }
+
+
+ /*
+ * @brief C custom defined SMUSD for M3 and M0 processors
+ */
+ CMSIS_INLINE __STATIC_INLINE uint32_t __SMUSD(
+ uint32_t x,
+ uint32_t y)
+ {
+ return ((uint32_t)(((((q31_t)x << 16) >> 16) * (((q31_t)y << 16) >> 16)) -
+ ((((q31_t)x ) >> 16) * (((q31_t)y ) >> 16)) ));
+ }
+
+
+ /*
+ * @brief C custom defined SXTB16 for M3 and M0 processors
+ */
+ CMSIS_INLINE __STATIC_INLINE uint32_t __SXTB16(
+ uint32_t x)
+ {
+ return ((uint32_t)(((((q31_t)x << 24) >> 24) & (q31_t)0x0000FFFF) |
+ ((((q31_t)x << 8) >> 8) & (q31_t)0xFFFF0000) ));
+ }
+
+ /*
+ * @brief C custom defined SMMLA for M3 and M0 processors
+ */
+ CMSIS_INLINE __STATIC_INLINE int32_t __SMMLA(
+ int32_t x,
+ int32_t y,
+ int32_t sum)
+ {
+ return (sum + (int32_t) (((int64_t) x * y) >> 32));
+ }
+
+#endif /* !defined (ARM_MATH_DSP) */
+
+
+ /**
+ * @brief Instance structure for the Q7 FIR filter.
+ */
+ typedef struct
+ {
+ uint16_t numTaps; /**< number of filter coefficients in the filter. */
+ q7_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */
+ q7_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/
+ } arm_fir_instance_q7;
+
+ /**
+ * @brief Instance structure for the Q15 FIR filter.
+ */
+ typedef struct
+ {
+ uint16_t numTaps; /**< number of filter coefficients in the filter. */
+ q15_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */
+ q15_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/
+ } arm_fir_instance_q15;
+
+ /**
+ * @brief Instance structure for the Q31 FIR filter.
+ */
+ typedef struct
+ {
+ uint16_t numTaps; /**< number of filter coefficients in the filter. */
+ q31_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */
+ q31_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps. */
+ } arm_fir_instance_q31;
+
+ /**
+ * @brief Instance structure for the floating-point FIR filter.
+ */
+ typedef struct
+ {
+ uint16_t numTaps; /**< number of filter coefficients in the filter. */
+ float32_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */
+ float32_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps. */
+ } arm_fir_instance_f32;
+
+
+ /**
+ * @brief Processing function for the Q7 FIR filter.
+ * @param[in] S points to an instance of the Q7 FIR filter structure.
+ * @param[in] pSrc points to the block of input data.
+ * @param[out] pDst points to the block of output data.
+ * @param[in] blockSize number of samples to process.
+ */
+ void arm_fir_q7(
+ const arm_fir_instance_q7 * S,
+ q7_t * pSrc,
+ q7_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Initialization function for the Q7 FIR filter.
+ * @param[in,out] S points to an instance of the Q7 FIR structure.
+ * @param[in] numTaps Number of filter coefficients in the filter.
+ * @param[in] pCoeffs points to the filter coefficients.
+ * @param[in] pState points to the state buffer.
+ * @param[in] blockSize number of samples that are processed.
+ */
+ void arm_fir_init_q7(
+ arm_fir_instance_q7 * S,
+ uint16_t numTaps,
+ q7_t * pCoeffs,
+ q7_t * pState,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Processing function for the Q15 FIR filter.
+ * @param[in] S points to an instance of the Q15 FIR structure.
+ * @param[in] pSrc points to the block of input data.
+ * @param[out] pDst points to the block of output data.
+ * @param[in] blockSize number of samples to process.
+ */
+ void arm_fir_q15(
+ const arm_fir_instance_q15 * S,
+ q15_t * pSrc,
+ q15_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Processing function for the fast Q15 FIR filter for Cortex-M3 and Cortex-M4.
+ * @param[in] S points to an instance of the Q15 FIR filter structure.
+ * @param[in] pSrc points to the block of input data.
+ * @param[out] pDst points to the block of output data.
+ * @param[in] blockSize number of samples to process.
+ */
+ void arm_fir_fast_q15(
+ const arm_fir_instance_q15 * S,
+ q15_t * pSrc,
+ q15_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Initialization function for the Q15 FIR filter.
+ * @param[in,out] S points to an instance of the Q15 FIR filter structure.
+ * @param[in] numTaps Number of filter coefficients in the filter. Must be even and greater than or equal to 4.
+ * @param[in] pCoeffs points to the filter coefficients.
+ * @param[in] pState points to the state buffer.
+ * @param[in] blockSize number of samples that are processed at a time.
+ * @return The function returns ARM_MATH_SUCCESS if initialization was successful or ARM_MATH_ARGUMENT_ERROR if
+ * <code>numTaps</code> is not a supported value.
+ */
+ arm_status arm_fir_init_q15(
+ arm_fir_instance_q15 * S,
+ uint16_t numTaps,
+ q15_t * pCoeffs,
+ q15_t * pState,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Processing function for the Q31 FIR filter.
+ * @param[in] S points to an instance of the Q31 FIR filter structure.
+ * @param[in] pSrc points to the block of input data.
+ * @param[out] pDst points to the block of output data.
+ * @param[in] blockSize number of samples to process.
+ */
+ void arm_fir_q31(
+ const arm_fir_instance_q31 * S,
+ q31_t * pSrc,
+ q31_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Processing function for the fast Q31 FIR filter for Cortex-M3 and Cortex-M4.
+ * @param[in] S points to an instance of the Q31 FIR structure.
+ * @param[in] pSrc points to the block of input data.
+ * @param[out] pDst points to the block of output data.
+ * @param[in] blockSize number of samples to process.
+ */
+ void arm_fir_fast_q31(
+ const arm_fir_instance_q31 * S,
+ q31_t * pSrc,
+ q31_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Initialization function for the Q31 FIR filter.
+ * @param[in,out] S points to an instance of the Q31 FIR structure.
+ * @param[in] numTaps Number of filter coefficients in the filter.
+ * @param[in] pCoeffs points to the filter coefficients.
+ * @param[in] pState points to the state buffer.
+ * @param[in] blockSize number of samples that are processed at a time.
+ */
+ void arm_fir_init_q31(
+ arm_fir_instance_q31 * S,
+ uint16_t numTaps,
+ q31_t * pCoeffs,
+ q31_t * pState,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Processing function for the floating-point FIR filter.
+ * @param[in] S points to an instance of the floating-point FIR structure.
+ * @param[in] pSrc points to the block of input data.
+ * @param[out] pDst points to the block of output data.
+ * @param[in] blockSize number of samples to process.
+ */
+ void arm_fir_f32(
+ const arm_fir_instance_f32 * S,
+ float32_t * pSrc,
+ float32_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Initialization function for the floating-point FIR filter.
+ * @param[in,out] S points to an instance of the floating-point FIR filter structure.
+ * @param[in] numTaps Number of filter coefficients in the filter.
+ * @param[in] pCoeffs points to the filter coefficients.
+ * @param[in] pState points to the state buffer.
+ * @param[in] blockSize number of samples that are processed at a time.
+ */
+ void arm_fir_init_f32(
+ arm_fir_instance_f32 * S,
+ uint16_t numTaps,
+ float32_t * pCoeffs,
+ float32_t * pState,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Instance structure for the Q15 Biquad cascade filter.
+ */
+ typedef struct
+ {
+ int8_t numStages; /**< number of 2nd order stages in the filter. Overall order is 2*numStages. */
+ q15_t *pState; /**< Points to the array of state coefficients. The array is of length 4*numStages. */
+ q15_t *pCoeffs; /**< Points to the array of coefficients. The array is of length 5*numStages. */
+ int8_t postShift; /**< Additional shift, in bits, applied to each output sample. */
+ } arm_biquad_casd_df1_inst_q15;
+
+ /**
+ * @brief Instance structure for the Q31 Biquad cascade filter.
+ */
+ typedef struct
+ {
+ uint32_t numStages; /**< number of 2nd order stages in the filter. Overall order is 2*numStages. */
+ q31_t *pState; /**< Points to the array of state coefficients. The array is of length 4*numStages. */
+ q31_t *pCoeffs; /**< Points to the array of coefficients. The array is of length 5*numStages. */
+ uint8_t postShift; /**< Additional shift, in bits, applied to each output sample. */
+ } arm_biquad_casd_df1_inst_q31;
+
+ /**
+ * @brief Instance structure for the floating-point Biquad cascade filter.
+ */
+ typedef struct
+ {
+ uint32_t numStages; /**< number of 2nd order stages in the filter. Overall order is 2*numStages. */
+ float32_t *pState; /**< Points to the array of state coefficients. The array is of length 4*numStages. */
+ float32_t *pCoeffs; /**< Points to the array of coefficients. The array is of length 5*numStages. */
+ } arm_biquad_casd_df1_inst_f32;
+
+
+ /**
+ * @brief Processing function for the Q15 Biquad cascade filter.
+ * @param[in] S points to an instance of the Q15 Biquad cascade structure.
+ * @param[in] pSrc points to the block of input data.
+ * @param[out] pDst points to the block of output data.
+ * @param[in] blockSize number of samples to process.
+ */
+ void arm_biquad_cascade_df1_q15(
+ const arm_biquad_casd_df1_inst_q15 * S,
+ q15_t * pSrc,
+ q15_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Initialization function for the Q15 Biquad cascade filter.
+ * @param[in,out] S points to an instance of the Q15 Biquad cascade structure.
+ * @param[in] numStages number of 2nd order stages in the filter.
+ * @param[in] pCoeffs points to the filter coefficients.
+ * @param[in] pState points to the state buffer.
+ * @param[in] postShift Shift to be applied to the output. Varies according to the coefficients format
+ */
+ void arm_biquad_cascade_df1_init_q15(
+ arm_biquad_casd_df1_inst_q15 * S,
+ uint8_t numStages,
+ q15_t * pCoeffs,
+ q15_t * pState,
+ int8_t postShift);
+
+
+ /**
+ * @brief Fast but less precise processing function for the Q15 Biquad cascade filter for Cortex-M3 and Cortex-M4.
+ * @param[in] S points to an instance of the Q15 Biquad cascade structure.
+ * @param[in] pSrc points to the block of input data.
+ * @param[out] pDst points to the block of output data.
+ * @param[in] blockSize number of samples to process.
+ */
+ void arm_biquad_cascade_df1_fast_q15(
+ const arm_biquad_casd_df1_inst_q15 * S,
+ q15_t * pSrc,
+ q15_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Processing function for the Q31 Biquad cascade filter
+ * @param[in] S points to an instance of the Q31 Biquad cascade structure.
+ * @param[in] pSrc points to the block of input data.
+ * @param[out] pDst points to the block of output data.
+ * @param[in] blockSize number of samples to process.
+ */
+ void arm_biquad_cascade_df1_q31(
+ const arm_biquad_casd_df1_inst_q31 * S,
+ q31_t * pSrc,
+ q31_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Fast but less precise processing function for the Q31 Biquad cascade filter for Cortex-M3 and Cortex-M4.
+ * @param[in] S points to an instance of the Q31 Biquad cascade structure.
+ * @param[in] pSrc points to the block of input data.
+ * @param[out] pDst points to the block of output data.
+ * @param[in] blockSize number of samples to process.
+ */
+ void arm_biquad_cascade_df1_fast_q31(
+ const arm_biquad_casd_df1_inst_q31 * S,
+ q31_t * pSrc,
+ q31_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Initialization function for the Q31 Biquad cascade filter.
+ * @param[in,out] S points to an instance of the Q31 Biquad cascade structure.
+ * @param[in] numStages number of 2nd order stages in the filter.
+ * @param[in] pCoeffs points to the filter coefficients.
+ * @param[in] pState points to the state buffer.
+ * @param[in] postShift Shift to be applied to the output. Varies according to the coefficients format
+ */
+ void arm_biquad_cascade_df1_init_q31(
+ arm_biquad_casd_df1_inst_q31 * S,
+ uint8_t numStages,
+ q31_t * pCoeffs,
+ q31_t * pState,
+ int8_t postShift);
+
+
+ /**
+ * @brief Processing function for the floating-point Biquad cascade filter.
+ * @param[in] S points to an instance of the floating-point Biquad cascade structure.
+ * @param[in] pSrc points to the block of input data.
+ * @param[out] pDst points to the block of output data.
+ * @param[in] blockSize number of samples to process.
+ */
+ void arm_biquad_cascade_df1_f32(
+ const arm_biquad_casd_df1_inst_f32 * S,
+ float32_t * pSrc,
+ float32_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Initialization function for the floating-point Biquad cascade filter.
+ * @param[in,out] S points to an instance of the floating-point Biquad cascade structure.
+ * @param[in] numStages number of 2nd order stages in the filter.
+ * @param[in] pCoeffs points to the filter coefficients.
+ * @param[in] pState points to the state buffer.
+ */
+ void arm_biquad_cascade_df1_init_f32(
+ arm_biquad_casd_df1_inst_f32 * S,
+ uint8_t numStages,
+ float32_t * pCoeffs,
+ float32_t * pState);
+
+
+ /**
+ * @brief Instance structure for the floating-point matrix structure.
+ */
+ typedef struct
+ {
+ uint16_t numRows; /**< number of rows of the matrix. */
+ uint16_t numCols; /**< number of columns of the matrix. */
+ float32_t *pData; /**< points to the data of the matrix. */
+ } arm_matrix_instance_f32;
+
+
+ /**
+ * @brief Instance structure for the floating-point matrix structure.
+ */
+ typedef struct
+ {
+ uint16_t numRows; /**< number of rows of the matrix. */
+ uint16_t numCols; /**< number of columns of the matrix. */
+ float64_t *pData; /**< points to the data of the matrix. */
+ } arm_matrix_instance_f64;
+
+ /**
+ * @brief Instance structure for the Q15 matrix structure.
+ */
+ typedef struct
+ {
+ uint16_t numRows; /**< number of rows of the matrix. */
+ uint16_t numCols; /**< number of columns of the matrix. */
+ q15_t *pData; /**< points to the data of the matrix. */
+ } arm_matrix_instance_q15;
+
+ /**
+ * @brief Instance structure for the Q31 matrix structure.
+ */
+ typedef struct
+ {
+ uint16_t numRows; /**< number of rows of the matrix. */
+ uint16_t numCols; /**< number of columns of the matrix. */
+ q31_t *pData; /**< points to the data of the matrix. */
+ } arm_matrix_instance_q31;
+
+
+ /**
+ * @brief Floating-point matrix addition.
+ * @param[in] pSrcA points to the first input matrix structure
+ * @param[in] pSrcB points to the second input matrix structure
+ * @param[out] pDst points to output matrix structure
+ * @return The function returns either
+ * <code>ARM_MATH_SIZE_MISMATCH</code> or <code>ARM_MATH_SUCCESS</code> based on the outcome of size checking.
+ */
+ arm_status arm_mat_add_f32(
+ const arm_matrix_instance_f32 * pSrcA,
+ const arm_matrix_instance_f32 * pSrcB,
+ arm_matrix_instance_f32 * pDst);
+
+
+ /**
+ * @brief Q15 matrix addition.
+ * @param[in] pSrcA points to the first input matrix structure
+ * @param[in] pSrcB points to the second input matrix structure
+ * @param[out] pDst points to output matrix structure
+ * @return The function returns either
+ * <code>ARM_MATH_SIZE_MISMATCH</code> or <code>ARM_MATH_SUCCESS</code> based on the outcome of size checking.
+ */
+ arm_status arm_mat_add_q15(
+ const arm_matrix_instance_q15 * pSrcA,
+ const arm_matrix_instance_q15 * pSrcB,
+ arm_matrix_instance_q15 * pDst);
+
+
+ /**
+ * @brief Q31 matrix addition.
+ * @param[in] pSrcA points to the first input matrix structure
+ * @param[in] pSrcB points to the second input matrix structure
+ * @param[out] pDst points to output matrix structure
+ * @return The function returns either
+ * <code>ARM_MATH_SIZE_MISMATCH</code> or <code>ARM_MATH_SUCCESS</code> based on the outcome of size checking.
+ */
+ arm_status arm_mat_add_q31(
+ const arm_matrix_instance_q31 * pSrcA,
+ const arm_matrix_instance_q31 * pSrcB,
+ arm_matrix_instance_q31 * pDst);
+
+
+ /**
+ * @brief Floating-point, complex, matrix multiplication.
+ * @param[in] pSrcA points to the first input matrix structure
+ * @param[in] pSrcB points to the second input matrix structure
+ * @param[out] pDst points to output matrix structure
+ * @return The function returns either
+ * <code>ARM_MATH_SIZE_MISMATCH</code> or <code>ARM_MATH_SUCCESS</code> based on the outcome of size checking.
+ */
+ arm_status arm_mat_cmplx_mult_f32(
+ const arm_matrix_instance_f32 * pSrcA,
+ const arm_matrix_instance_f32 * pSrcB,
+ arm_matrix_instance_f32 * pDst);
+
+
+ /**
+ * @brief Q15, complex, matrix multiplication.
+ * @param[in] pSrcA points to the first input matrix structure
+ * @param[in] pSrcB points to the second input matrix structure
+ * @param[out] pDst points to output matrix structure
+ * @return The function returns either
+ * <code>ARM_MATH_SIZE_MISMATCH</code> or <code>ARM_MATH_SUCCESS</code> based on the outcome of size checking.
+ */
+ arm_status arm_mat_cmplx_mult_q15(
+ const arm_matrix_instance_q15 * pSrcA,
+ const arm_matrix_instance_q15 * pSrcB,
+ arm_matrix_instance_q15 * pDst,
+ q15_t * pScratch);
+
+
+ /**
+ * @brief Q31, complex, matrix multiplication.
+ * @param[in] pSrcA points to the first input matrix structure
+ * @param[in] pSrcB points to the second input matrix structure
+ * @param[out] pDst points to output matrix structure
+ * @return The function returns either
+ * <code>ARM_MATH_SIZE_MISMATCH</code> or <code>ARM_MATH_SUCCESS</code> based on the outcome of size checking.
+ */
+ arm_status arm_mat_cmplx_mult_q31(
+ const arm_matrix_instance_q31 * pSrcA,
+ const arm_matrix_instance_q31 * pSrcB,
+ arm_matrix_instance_q31 * pDst);
+
+
+ /**
+ * @brief Floating-point matrix transpose.
+ * @param[in] pSrc points to the input matrix
+ * @param[out] pDst points to the output matrix
+ * @return The function returns either <code>ARM_MATH_SIZE_MISMATCH</code>
+ * or <code>ARM_MATH_SUCCESS</code> based on the outcome of size checking.
+ */
+ arm_status arm_mat_trans_f32(
+ const arm_matrix_instance_f32 * pSrc,
+ arm_matrix_instance_f32 * pDst);
+
+
+ /**
+ * @brief Q15 matrix transpose.
+ * @param[in] pSrc points to the input matrix
+ * @param[out] pDst points to the output matrix
+ * @return The function returns either <code>ARM_MATH_SIZE_MISMATCH</code>
+ * or <code>ARM_MATH_SUCCESS</code> based on the outcome of size checking.
+ */
+ arm_status arm_mat_trans_q15(
+ const arm_matrix_instance_q15 * pSrc,
+ arm_matrix_instance_q15 * pDst);
+
+
+ /**
+ * @brief Q31 matrix transpose.
+ * @param[in] pSrc points to the input matrix
+ * @param[out] pDst points to the output matrix
+ * @return The function returns either <code>ARM_MATH_SIZE_MISMATCH</code>
+ * or <code>ARM_MATH_SUCCESS</code> based on the outcome of size checking.
+ */
+ arm_status arm_mat_trans_q31(
+ const arm_matrix_instance_q31 * pSrc,
+ arm_matrix_instance_q31 * pDst);
+
+
+ /**
+ * @brief Floating-point matrix multiplication
+ * @param[in] pSrcA points to the first input matrix structure
+ * @param[in] pSrcB points to the second input matrix structure
+ * @param[out] pDst points to output matrix structure
+ * @return The function returns either
+ * <code>ARM_MATH_SIZE_MISMATCH</code> or <code>ARM_MATH_SUCCESS</code> based on the outcome of size checking.
+ */
+ arm_status arm_mat_mult_f32(
+ const arm_matrix_instance_f32 * pSrcA,
+ const arm_matrix_instance_f32 * pSrcB,
+ arm_matrix_instance_f32 * pDst);
+
+
+ /**
+ * @brief Q15 matrix multiplication
+ * @param[in] pSrcA points to the first input matrix structure
+ * @param[in] pSrcB points to the second input matrix structure
+ * @param[out] pDst points to output matrix structure
+ * @param[in] pState points to the array for storing intermediate results
+ * @return The function returns either
+ * <code>ARM_MATH_SIZE_MISMATCH</code> or <code>ARM_MATH_SUCCESS</code> based on the outcome of size checking.
+ */
+ arm_status arm_mat_mult_q15(
+ const arm_matrix_instance_q15 * pSrcA,
+ const arm_matrix_instance_q15 * pSrcB,
+ arm_matrix_instance_q15 * pDst,
+ q15_t * pState);
+
+
+ /**
+ * @brief Q15 matrix multiplication (fast variant) for Cortex-M3 and Cortex-M4
+ * @param[in] pSrcA points to the first input matrix structure
+ * @param[in] pSrcB points to the second input matrix structure
+ * @param[out] pDst points to output matrix structure
+ * @param[in] pState points to the array for storing intermediate results
+ * @return The function returns either
+ * <code>ARM_MATH_SIZE_MISMATCH</code> or <code>ARM_MATH_SUCCESS</code> based on the outcome of size checking.
+ */
+ arm_status arm_mat_mult_fast_q15(
+ const arm_matrix_instance_q15 * pSrcA,
+ const arm_matrix_instance_q15 * pSrcB,
+ arm_matrix_instance_q15 * pDst,
+ q15_t * pState);
+
+
+ /**
+ * @brief Q31 matrix multiplication
+ * @param[in] pSrcA points to the first input matrix structure
+ * @param[in] pSrcB points to the second input matrix structure
+ * @param[out] pDst points to output matrix structure
+ * @return The function returns either
+ * <code>ARM_MATH_SIZE_MISMATCH</code> or <code>ARM_MATH_SUCCESS</code> based on the outcome of size checking.
+ */
+ arm_status arm_mat_mult_q31(
+ const arm_matrix_instance_q31 * pSrcA,
+ const arm_matrix_instance_q31 * pSrcB,
+ arm_matrix_instance_q31 * pDst);
+
+
+ /**
+ * @brief Q31 matrix multiplication (fast variant) for Cortex-M3 and Cortex-M4
+ * @param[in] pSrcA points to the first input matrix structure
+ * @param[in] pSrcB points to the second input matrix structure
+ * @param[out] pDst points to output matrix structure
+ * @return The function returns either
+ * <code>ARM_MATH_SIZE_MISMATCH</code> or <code>ARM_MATH_SUCCESS</code> based on the outcome of size checking.
+ */
+ arm_status arm_mat_mult_fast_q31(
+ const arm_matrix_instance_q31 * pSrcA,
+ const arm_matrix_instance_q31 * pSrcB,
+ arm_matrix_instance_q31 * pDst);
+
+
+ /**
+ * @brief Floating-point matrix subtraction
+ * @param[in] pSrcA points to the first input matrix structure
+ * @param[in] pSrcB points to the second input matrix structure
+ * @param[out] pDst points to output matrix structure
+ * @return The function returns either
+ * <code>ARM_MATH_SIZE_MISMATCH</code> or <code>ARM_MATH_SUCCESS</code> based on the outcome of size checking.
+ */
+ arm_status arm_mat_sub_f32(
+ const arm_matrix_instance_f32 * pSrcA,
+ const arm_matrix_instance_f32 * pSrcB,
+ arm_matrix_instance_f32 * pDst);
+
+
+ /**
+ * @brief Q15 matrix subtraction
+ * @param[in] pSrcA points to the first input matrix structure
+ * @param[in] pSrcB points to the second input matrix structure
+ * @param[out] pDst points to output matrix structure
+ * @return The function returns either
+ * <code>ARM_MATH_SIZE_MISMATCH</code> or <code>ARM_MATH_SUCCESS</code> based on the outcome of size checking.
+ */
+ arm_status arm_mat_sub_q15(
+ const arm_matrix_instance_q15 * pSrcA,
+ const arm_matrix_instance_q15 * pSrcB,
+ arm_matrix_instance_q15 * pDst);
+
+
+ /**
+ * @brief Q31 matrix subtraction
+ * @param[in] pSrcA points to the first input matrix structure
+ * @param[in] pSrcB points to the second input matrix structure
+ * @param[out] pDst points to output matrix structure
+ * @return The function returns either
+ * <code>ARM_MATH_SIZE_MISMATCH</code> or <code>ARM_MATH_SUCCESS</code> based on the outcome of size checking.
+ */
+ arm_status arm_mat_sub_q31(
+ const arm_matrix_instance_q31 * pSrcA,
+ const arm_matrix_instance_q31 * pSrcB,
+ arm_matrix_instance_q31 * pDst);
+
+
+ /**
+ * @brief Floating-point matrix scaling.
+ * @param[in] pSrc points to the input matrix
+ * @param[in] scale scale factor
+ * @param[out] pDst points to the output matrix
+ * @return The function returns either
+ * <code>ARM_MATH_SIZE_MISMATCH</code> or <code>ARM_MATH_SUCCESS</code> based on the outcome of size checking.
+ */
+ arm_status arm_mat_scale_f32(
+ const arm_matrix_instance_f32 * pSrc,
+ float32_t scale,
+ arm_matrix_instance_f32 * pDst);
+
+
+ /**
+ * @brief Q15 matrix scaling.
+ * @param[in] pSrc points to input matrix
+ * @param[in] scaleFract fractional portion of the scale factor
+ * @param[in] shift number of bits to shift the result by
+ * @param[out] pDst points to output matrix
+ * @return The function returns either
+ * <code>ARM_MATH_SIZE_MISMATCH</code> or <code>ARM_MATH_SUCCESS</code> based on the outcome of size checking.
+ */
+ arm_status arm_mat_scale_q15(
+ const arm_matrix_instance_q15 * pSrc,
+ q15_t scaleFract,
+ int32_t shift,
+ arm_matrix_instance_q15 * pDst);
+
+
+ /**
+ * @brief Q31 matrix scaling.
+ * @param[in] pSrc points to input matrix
+ * @param[in] scaleFract fractional portion of the scale factor
+ * @param[in] shift number of bits to shift the result by
+ * @param[out] pDst points to output matrix structure
+ * @return The function returns either
+ * <code>ARM_MATH_SIZE_MISMATCH</code> or <code>ARM_MATH_SUCCESS</code> based on the outcome of size checking.
+ */
+ arm_status arm_mat_scale_q31(
+ const arm_matrix_instance_q31 * pSrc,
+ q31_t scaleFract,
+ int32_t shift,
+ arm_matrix_instance_q31 * pDst);
+
+
+ /**
+ * @brief Q31 matrix initialization.
+ * @param[in,out] S points to an instance of the floating-point matrix structure.
+ * @param[in] nRows number of rows in the matrix.
+ * @param[in] nColumns number of columns in the matrix.
+ * @param[in] pData points to the matrix data array.
+ */
+ void arm_mat_init_q31(
+ arm_matrix_instance_q31 * S,
+ uint16_t nRows,
+ uint16_t nColumns,
+ q31_t * pData);
+
+
+ /**
+ * @brief Q15 matrix initialization.
+ * @param[in,out] S points to an instance of the floating-point matrix structure.
+ * @param[in] nRows number of rows in the matrix.
+ * @param[in] nColumns number of columns in the matrix.
+ * @param[in] pData points to the matrix data array.
+ */
+ void arm_mat_init_q15(
+ arm_matrix_instance_q15 * S,
+ uint16_t nRows,
+ uint16_t nColumns,
+ q15_t * pData);
+
+
+ /**
+ * @brief Floating-point matrix initialization.
+ * @param[in,out] S points to an instance of the floating-point matrix structure.
+ * @param[in] nRows number of rows in the matrix.
+ * @param[in] nColumns number of columns in the matrix.
+ * @param[in] pData points to the matrix data array.
+ */
+ void arm_mat_init_f32(
+ arm_matrix_instance_f32 * S,
+ uint16_t nRows,
+ uint16_t nColumns,
+ float32_t * pData);
+
+
+
+ /**
+ * @brief Instance structure for the Q15 PID Control.
+ */
+ typedef struct
+ {
+ q15_t A0; /**< The derived gain, A0 = Kp + Ki + Kd . */
+#if !defined (ARM_MATH_DSP)
+ q15_t A1;
+ q15_t A2;
+#else
+ q31_t A1; /**< The derived gain A1 = -Kp - 2Kd | Kd.*/
+#endif
+ q15_t state[3]; /**< The state array of length 3. */
+ q15_t Kp; /**< The proportional gain. */
+ q15_t Ki; /**< The integral gain. */
+ q15_t Kd; /**< The derivative gain. */
+ } arm_pid_instance_q15;
+
+ /**
+ * @brief Instance structure for the Q31 PID Control.
+ */
+ typedef struct
+ {
+ q31_t A0; /**< The derived gain, A0 = Kp + Ki + Kd . */
+ q31_t A1; /**< The derived gain, A1 = -Kp - 2Kd. */
+ q31_t A2; /**< The derived gain, A2 = Kd . */
+ q31_t state[3]; /**< The state array of length 3. */
+ q31_t Kp; /**< The proportional gain. */
+ q31_t Ki; /**< The integral gain. */
+ q31_t Kd; /**< The derivative gain. */
+ } arm_pid_instance_q31;
+
+ /**
+ * @brief Instance structure for the floating-point PID Control.
+ */
+ typedef struct
+ {
+ float32_t A0; /**< The derived gain, A0 = Kp + Ki + Kd . */
+ float32_t A1; /**< The derived gain, A1 = -Kp - 2Kd. */
+ float32_t A2; /**< The derived gain, A2 = Kd . */
+ float32_t state[3]; /**< The state array of length 3. */
+ float32_t Kp; /**< The proportional gain. */
+ float32_t Ki; /**< The integral gain. */
+ float32_t Kd; /**< The derivative gain. */
+ } arm_pid_instance_f32;
+
+
+
+ /**
+ * @brief Initialization function for the floating-point PID Control.
+ * @param[in,out] S points to an instance of the PID structure.
+ * @param[in] resetStateFlag flag to reset the state. 0 = no change in state 1 = reset the state.
+ */
+ void arm_pid_init_f32(
+ arm_pid_instance_f32 * S,
+ int32_t resetStateFlag);
+
+
+ /**
+ * @brief Reset function for the floating-point PID Control.
+ * @param[in,out] S is an instance of the floating-point PID Control structure
+ */
+ void arm_pid_reset_f32(
+ arm_pid_instance_f32 * S);
+
+
+ /**
+ * @brief Initialization function for the Q31 PID Control.
+ * @param[in,out] S points to an instance of the Q15 PID structure.
+ * @param[in] resetStateFlag flag to reset the state. 0 = no change in state 1 = reset the state.
+ */
+ void arm_pid_init_q31(
+ arm_pid_instance_q31 * S,
+ int32_t resetStateFlag);
+
+
+ /**
+ * @brief Reset function for the Q31 PID Control.
+ * @param[in,out] S points to an instance of the Q31 PID Control structure
+ */
+
+ void arm_pid_reset_q31(
+ arm_pid_instance_q31 * S);
+
+
+ /**
+ * @brief Initialization function for the Q15 PID Control.
+ * @param[in,out] S points to an instance of the Q15 PID structure.
+ * @param[in] resetStateFlag flag to reset the state. 0 = no change in state 1 = reset the state.
+ */
+ void arm_pid_init_q15(
+ arm_pid_instance_q15 * S,
+ int32_t resetStateFlag);
+
+
+ /**
+ * @brief Reset function for the Q15 PID Control.
+ * @param[in,out] S points to an instance of the q15 PID Control structure
+ */
+ void arm_pid_reset_q15(
+ arm_pid_instance_q15 * S);
+
+
+ /**
+ * @brief Instance structure for the floating-point Linear Interpolate function.
+ */
+ typedef struct
+ {
+ uint32_t nValues; /**< nValues */
+ float32_t x1; /**< x1 */
+ float32_t xSpacing; /**< xSpacing */
+ float32_t *pYData; /**< pointer to the table of Y values */
+ } arm_linear_interp_instance_f32;
+
+ /**
+ * @brief Instance structure for the floating-point bilinear interpolation function.
+ */
+ typedef struct
+ {
+ uint16_t numRows; /**< number of rows in the data table. */
+ uint16_t numCols; /**< number of columns in the data table. */
+ float32_t *pData; /**< points to the data table. */
+ } arm_bilinear_interp_instance_f32;
+
+ /**
+ * @brief Instance structure for the Q31 bilinear interpolation function.
+ */
+ typedef struct
+ {
+ uint16_t numRows; /**< number of rows in the data table. */
+ uint16_t numCols; /**< number of columns in the data table. */
+ q31_t *pData; /**< points to the data table. */
+ } arm_bilinear_interp_instance_q31;
+
+ /**
+ * @brief Instance structure for the Q15 bilinear interpolation function.
+ */
+ typedef struct
+ {
+ uint16_t numRows; /**< number of rows in the data table. */
+ uint16_t numCols; /**< number of columns in the data table. */
+ q15_t *pData; /**< points to the data table. */
+ } arm_bilinear_interp_instance_q15;
+
+ /**
+ * @brief Instance structure for the Q15 bilinear interpolation function.
+ */
+ typedef struct
+ {
+ uint16_t numRows; /**< number of rows in the data table. */
+ uint16_t numCols; /**< number of columns in the data table. */
+ q7_t *pData; /**< points to the data table. */
+ } arm_bilinear_interp_instance_q7;
+
+
+ /**
+ * @brief Q7 vector multiplication.
+ * @param[in] pSrcA points to the first input vector
+ * @param[in] pSrcB points to the second input vector
+ * @param[out] pDst points to the output vector
+ * @param[in] blockSize number of samples in each vector
+ */
+ void arm_mult_q7(
+ q7_t * pSrcA,
+ q7_t * pSrcB,
+ q7_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Q15 vector multiplication.
+ * @param[in] pSrcA points to the first input vector
+ * @param[in] pSrcB points to the second input vector
+ * @param[out] pDst points to the output vector
+ * @param[in] blockSize number of samples in each vector
+ */
+ void arm_mult_q15(
+ q15_t * pSrcA,
+ q15_t * pSrcB,
+ q15_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Q31 vector multiplication.
+ * @param[in] pSrcA points to the first input vector
+ * @param[in] pSrcB points to the second input vector
+ * @param[out] pDst points to the output vector
+ * @param[in] blockSize number of samples in each vector
+ */
+ void arm_mult_q31(
+ q31_t * pSrcA,
+ q31_t * pSrcB,
+ q31_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Floating-point vector multiplication.
+ * @param[in] pSrcA points to the first input vector
+ * @param[in] pSrcB points to the second input vector
+ * @param[out] pDst points to the output vector
+ * @param[in] blockSize number of samples in each vector
+ */
+ void arm_mult_f32(
+ float32_t * pSrcA,
+ float32_t * pSrcB,
+ float32_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Instance structure for the Q15 CFFT/CIFFT function.
+ */
+ typedef struct
+ {
+ uint16_t fftLen; /**< length of the FFT. */
+ uint8_t ifftFlag; /**< flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. */
+ uint8_t bitReverseFlag; /**< flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. */
+ q15_t *pTwiddle; /**< points to the Sin twiddle factor table. */
+ uint16_t *pBitRevTable; /**< points to the bit reversal table. */
+ uint16_t twidCoefModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */
+ uint16_t bitRevFactor; /**< bit reversal modifier that supports different size FFTs with the same bit reversal table. */
+ } arm_cfft_radix2_instance_q15;
+
+/* Deprecated */
+ arm_status arm_cfft_radix2_init_q15(
+ arm_cfft_radix2_instance_q15 * S,
+ uint16_t fftLen,
+ uint8_t ifftFlag,
+ uint8_t bitReverseFlag);
+
+/* Deprecated */
+ void arm_cfft_radix2_q15(
+ const arm_cfft_radix2_instance_q15 * S,
+ q15_t * pSrc);
+
+
+ /**
+ * @brief Instance structure for the Q15 CFFT/CIFFT function.
+ */
+ typedef struct
+ {
+ uint16_t fftLen; /**< length of the FFT. */
+ uint8_t ifftFlag; /**< flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. */
+ uint8_t bitReverseFlag; /**< flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. */
+ q15_t *pTwiddle; /**< points to the twiddle factor table. */
+ uint16_t *pBitRevTable; /**< points to the bit reversal table. */
+ uint16_t twidCoefModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */
+ uint16_t bitRevFactor; /**< bit reversal modifier that supports different size FFTs with the same bit reversal table. */
+ } arm_cfft_radix4_instance_q15;
+
+/* Deprecated */
+ arm_status arm_cfft_radix4_init_q15(
+ arm_cfft_radix4_instance_q15 * S,
+ uint16_t fftLen,
+ uint8_t ifftFlag,
+ uint8_t bitReverseFlag);
+
+/* Deprecated */
+ void arm_cfft_radix4_q15(
+ const arm_cfft_radix4_instance_q15 * S,
+ q15_t * pSrc);
+
+ /**
+ * @brief Instance structure for the Radix-2 Q31 CFFT/CIFFT function.
+ */
+ typedef struct
+ {
+ uint16_t fftLen; /**< length of the FFT. */
+ uint8_t ifftFlag; /**< flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. */
+ uint8_t bitReverseFlag; /**< flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. */
+ q31_t *pTwiddle; /**< points to the Twiddle factor table. */
+ uint16_t *pBitRevTable; /**< points to the bit reversal table. */
+ uint16_t twidCoefModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */
+ uint16_t bitRevFactor; /**< bit reversal modifier that supports different size FFTs with the same bit reversal table. */
+ } arm_cfft_radix2_instance_q31;
+
+/* Deprecated */
+ arm_status arm_cfft_radix2_init_q31(
+ arm_cfft_radix2_instance_q31 * S,
+ uint16_t fftLen,
+ uint8_t ifftFlag,
+ uint8_t bitReverseFlag);
+
+/* Deprecated */
+ void arm_cfft_radix2_q31(
+ const arm_cfft_radix2_instance_q31 * S,
+ q31_t * pSrc);
+
+ /**
+ * @brief Instance structure for the Q31 CFFT/CIFFT function.
+ */
+ typedef struct
+ {
+ uint16_t fftLen; /**< length of the FFT. */
+ uint8_t ifftFlag; /**< flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. */
+ uint8_t bitReverseFlag; /**< flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. */
+ q31_t *pTwiddle; /**< points to the twiddle factor table. */
+ uint16_t *pBitRevTable; /**< points to the bit reversal table. */
+ uint16_t twidCoefModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */
+ uint16_t bitRevFactor; /**< bit reversal modifier that supports different size FFTs with the same bit reversal table. */
+ } arm_cfft_radix4_instance_q31;
+
+/* Deprecated */
+ void arm_cfft_radix4_q31(
+ const arm_cfft_radix4_instance_q31 * S,
+ q31_t * pSrc);
+
+/* Deprecated */
+ arm_status arm_cfft_radix4_init_q31(
+ arm_cfft_radix4_instance_q31 * S,
+ uint16_t fftLen,
+ uint8_t ifftFlag,
+ uint8_t bitReverseFlag);
+
+ /**
+ * @brief Instance structure for the floating-point CFFT/CIFFT function.
+ */
+ typedef struct
+ {
+ uint16_t fftLen; /**< length of the FFT. */
+ uint8_t ifftFlag; /**< flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. */
+ uint8_t bitReverseFlag; /**< flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. */
+ float32_t *pTwiddle; /**< points to the Twiddle factor table. */
+ uint16_t *pBitRevTable; /**< points to the bit reversal table. */
+ uint16_t twidCoefModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */
+ uint16_t bitRevFactor; /**< bit reversal modifier that supports different size FFTs with the same bit reversal table. */
+ float32_t onebyfftLen; /**< value of 1/fftLen. */
+ } arm_cfft_radix2_instance_f32;
+
+/* Deprecated */
+ arm_status arm_cfft_radix2_init_f32(
+ arm_cfft_radix2_instance_f32 * S,
+ uint16_t fftLen,
+ uint8_t ifftFlag,
+ uint8_t bitReverseFlag);
+
+/* Deprecated */
+ void arm_cfft_radix2_f32(
+ const arm_cfft_radix2_instance_f32 * S,
+ float32_t * pSrc);
+
+ /**
+ * @brief Instance structure for the floating-point CFFT/CIFFT function.
+ */
+ typedef struct
+ {
+ uint16_t fftLen; /**< length of the FFT. */
+ uint8_t ifftFlag; /**< flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. */
+ uint8_t bitReverseFlag; /**< flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. */
+ float32_t *pTwiddle; /**< points to the Twiddle factor table. */
+ uint16_t *pBitRevTable; /**< points to the bit reversal table. */
+ uint16_t twidCoefModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */
+ uint16_t bitRevFactor; /**< bit reversal modifier that supports different size FFTs with the same bit reversal table. */
+ float32_t onebyfftLen; /**< value of 1/fftLen. */
+ } arm_cfft_radix4_instance_f32;
+
+/* Deprecated */
+ arm_status arm_cfft_radix4_init_f32(
+ arm_cfft_radix4_instance_f32 * S,
+ uint16_t fftLen,
+ uint8_t ifftFlag,
+ uint8_t bitReverseFlag);
+
+/* Deprecated */
+ void arm_cfft_radix4_f32(
+ const arm_cfft_radix4_instance_f32 * S,
+ float32_t * pSrc);
+
+ /**
+ * @brief Instance structure for the fixed-point CFFT/CIFFT function.
+ */
+ typedef struct
+ {
+ uint16_t fftLen; /**< length of the FFT. */
+ const q15_t *pTwiddle; /**< points to the Twiddle factor table. */
+ const uint16_t *pBitRevTable; /**< points to the bit reversal table. */
+ uint16_t bitRevLength; /**< bit reversal table length. */
+ } arm_cfft_instance_q15;
+
+void arm_cfft_q15(
+ const arm_cfft_instance_q15 * S,
+ q15_t * p1,
+ uint8_t ifftFlag,
+ uint8_t bitReverseFlag);
+
+ /**
+ * @brief Instance structure for the fixed-point CFFT/CIFFT function.
+ */
+ typedef struct
+ {
+ uint16_t fftLen; /**< length of the FFT. */
+ const q31_t *pTwiddle; /**< points to the Twiddle factor table. */
+ const uint16_t *pBitRevTable; /**< points to the bit reversal table. */
+ uint16_t bitRevLength; /**< bit reversal table length. */
+ } arm_cfft_instance_q31;
+
+void arm_cfft_q31(
+ const arm_cfft_instance_q31 * S,
+ q31_t * p1,
+ uint8_t ifftFlag,
+ uint8_t bitReverseFlag);
+
+ /**
+ * @brief Instance structure for the floating-point CFFT/CIFFT function.
+ */
+ typedef struct
+ {
+ uint16_t fftLen; /**< length of the FFT. */
+ const float32_t *pTwiddle; /**< points to the Twiddle factor table. */
+ const uint16_t *pBitRevTable; /**< points to the bit reversal table. */
+ uint16_t bitRevLength; /**< bit reversal table length. */
+ } arm_cfft_instance_f32;
+
+ void arm_cfft_f32(
+ const arm_cfft_instance_f32 * S,
+ float32_t * p1,
+ uint8_t ifftFlag,
+ uint8_t bitReverseFlag);
+
+ /**
+ * @brief Instance structure for the Q15 RFFT/RIFFT function.
+ */
+ typedef struct
+ {
+ uint32_t fftLenReal; /**< length of the real FFT. */
+ uint8_t ifftFlagR; /**< flag that selects forward (ifftFlagR=0) or inverse (ifftFlagR=1) transform. */
+ uint8_t bitReverseFlagR; /**< flag that enables (bitReverseFlagR=1) or disables (bitReverseFlagR=0) bit reversal of output. */
+ uint32_t twidCoefRModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */
+ q15_t *pTwiddleAReal; /**< points to the real twiddle factor table. */
+ q15_t *pTwiddleBReal; /**< points to the imag twiddle factor table. */
+ const arm_cfft_instance_q15 *pCfft; /**< points to the complex FFT instance. */
+ } arm_rfft_instance_q15;
+
+ arm_status arm_rfft_init_q15(
+ arm_rfft_instance_q15 * S,
+ uint32_t fftLenReal,
+ uint32_t ifftFlagR,
+ uint32_t bitReverseFlag);
+
+ void arm_rfft_q15(
+ const arm_rfft_instance_q15 * S,
+ q15_t * pSrc,
+ q15_t * pDst);
+
+ /**
+ * @brief Instance structure for the Q31 RFFT/RIFFT function.
+ */
+ typedef struct
+ {
+ uint32_t fftLenReal; /**< length of the real FFT. */
+ uint8_t ifftFlagR; /**< flag that selects forward (ifftFlagR=0) or inverse (ifftFlagR=1) transform. */
+ uint8_t bitReverseFlagR; /**< flag that enables (bitReverseFlagR=1) or disables (bitReverseFlagR=0) bit reversal of output. */
+ uint32_t twidCoefRModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */
+ q31_t *pTwiddleAReal; /**< points to the real twiddle factor table. */
+ q31_t *pTwiddleBReal; /**< points to the imag twiddle factor table. */
+ const arm_cfft_instance_q31 *pCfft; /**< points to the complex FFT instance. */
+ } arm_rfft_instance_q31;
+
+ arm_status arm_rfft_init_q31(
+ arm_rfft_instance_q31 * S,
+ uint32_t fftLenReal,
+ uint32_t ifftFlagR,
+ uint32_t bitReverseFlag);
+
+ void arm_rfft_q31(
+ const arm_rfft_instance_q31 * S,
+ q31_t * pSrc,
+ q31_t * pDst);
+
+ /**
+ * @brief Instance structure for the floating-point RFFT/RIFFT function.
+ */
+ typedef struct
+ {
+ uint32_t fftLenReal; /**< length of the real FFT. */
+ uint16_t fftLenBy2; /**< length of the complex FFT. */
+ uint8_t ifftFlagR; /**< flag that selects forward (ifftFlagR=0) or inverse (ifftFlagR=1) transform. */
+ uint8_t bitReverseFlagR; /**< flag that enables (bitReverseFlagR=1) or disables (bitReverseFlagR=0) bit reversal of output. */
+ uint32_t twidCoefRModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */
+ float32_t *pTwiddleAReal; /**< points to the real twiddle factor table. */
+ float32_t *pTwiddleBReal; /**< points to the imag twiddle factor table. */
+ arm_cfft_radix4_instance_f32 *pCfft; /**< points to the complex FFT instance. */
+ } arm_rfft_instance_f32;
+
+ arm_status arm_rfft_init_f32(
+ arm_rfft_instance_f32 * S,
+ arm_cfft_radix4_instance_f32 * S_CFFT,
+ uint32_t fftLenReal,
+ uint32_t ifftFlagR,
+ uint32_t bitReverseFlag);
+
+ void arm_rfft_f32(
+ const arm_rfft_instance_f32 * S,
+ float32_t * pSrc,
+ float32_t * pDst);
+
+ /**
+ * @brief Instance structure for the floating-point RFFT/RIFFT function.
+ */
+typedef struct
+ {
+ arm_cfft_instance_f32 Sint; /**< Internal CFFT structure. */
+ uint16_t fftLenRFFT; /**< length of the real sequence */
+ float32_t * pTwiddleRFFT; /**< Twiddle factors real stage */
+ } arm_rfft_fast_instance_f32 ;
+
+arm_status arm_rfft_fast_init_f32 (
+ arm_rfft_fast_instance_f32 * S,
+ uint16_t fftLen);
+
+void arm_rfft_fast_f32(
+ arm_rfft_fast_instance_f32 * S,
+ float32_t * p, float32_t * pOut,
+ uint8_t ifftFlag);
+
+ /**
+ * @brief Instance structure for the floating-point DCT4/IDCT4 function.
+ */
+ typedef struct
+ {
+ uint16_t N; /**< length of the DCT4. */
+ uint16_t Nby2; /**< half of the length of the DCT4. */
+ float32_t normalize; /**< normalizing factor. */
+ float32_t *pTwiddle; /**< points to the twiddle factor table. */
+ float32_t *pCosFactor; /**< points to the cosFactor table. */
+ arm_rfft_instance_f32 *pRfft; /**< points to the real FFT instance. */
+ arm_cfft_radix4_instance_f32 *pCfft; /**< points to the complex FFT instance. */
+ } arm_dct4_instance_f32;
+
+
+ /**
+ * @brief Initialization function for the floating-point DCT4/IDCT4.
+ * @param[in,out] S points to an instance of floating-point DCT4/IDCT4 structure.
+ * @param[in] S_RFFT points to an instance of floating-point RFFT/RIFFT structure.
+ * @param[in] S_CFFT points to an instance of floating-point CFFT/CIFFT structure.
+ * @param[in] N length of the DCT4.
+ * @param[in] Nby2 half of the length of the DCT4.
+ * @param[in] normalize normalizing factor.
+ * @return arm_status function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if <code>fftLenReal</code> is not a supported transform length.
+ */
+ arm_status arm_dct4_init_f32(
+ arm_dct4_instance_f32 * S,
+ arm_rfft_instance_f32 * S_RFFT,
+ arm_cfft_radix4_instance_f32 * S_CFFT,
+ uint16_t N,
+ uint16_t Nby2,
+ float32_t normalize);
+
+
+ /**
+ * @brief Processing function for the floating-point DCT4/IDCT4.
+ * @param[in] S points to an instance of the floating-point DCT4/IDCT4 structure.
+ * @param[in] pState points to state buffer.
+ * @param[in,out] pInlineBuffer points to the in-place input and output buffer.
+ */
+ void arm_dct4_f32(
+ const arm_dct4_instance_f32 * S,
+ float32_t * pState,
+ float32_t * pInlineBuffer);
+
+
+ /**
+ * @brief Instance structure for the Q31 DCT4/IDCT4 function.
+ */
+ typedef struct
+ {
+ uint16_t N; /**< length of the DCT4. */
+ uint16_t Nby2; /**< half of the length of the DCT4. */
+ q31_t normalize; /**< normalizing factor. */
+ q31_t *pTwiddle; /**< points to the twiddle factor table. */
+ q31_t *pCosFactor; /**< points to the cosFactor table. */
+ arm_rfft_instance_q31 *pRfft; /**< points to the real FFT instance. */
+ arm_cfft_radix4_instance_q31 *pCfft; /**< points to the complex FFT instance. */
+ } arm_dct4_instance_q31;
+
+
+ /**
+ * @brief Initialization function for the Q31 DCT4/IDCT4.
+ * @param[in,out] S points to an instance of Q31 DCT4/IDCT4 structure.
+ * @param[in] S_RFFT points to an instance of Q31 RFFT/RIFFT structure
+ * @param[in] S_CFFT points to an instance of Q31 CFFT/CIFFT structure
+ * @param[in] N length of the DCT4.
+ * @param[in] Nby2 half of the length of the DCT4.
+ * @param[in] normalize normalizing factor.
+ * @return arm_status function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if <code>N</code> is not a supported transform length.
+ */
+ arm_status arm_dct4_init_q31(
+ arm_dct4_instance_q31 * S,
+ arm_rfft_instance_q31 * S_RFFT,
+ arm_cfft_radix4_instance_q31 * S_CFFT,
+ uint16_t N,
+ uint16_t Nby2,
+ q31_t normalize);
+
+
+ /**
+ * @brief Processing function for the Q31 DCT4/IDCT4.
+ * @param[in] S points to an instance of the Q31 DCT4 structure.
+ * @param[in] pState points to state buffer.
+ * @param[in,out] pInlineBuffer points to the in-place input and output buffer.
+ */
+ void arm_dct4_q31(
+ const arm_dct4_instance_q31 * S,
+ q31_t * pState,
+ q31_t * pInlineBuffer);
+
+
+ /**
+ * @brief Instance structure for the Q15 DCT4/IDCT4 function.
+ */
+ typedef struct
+ {
+ uint16_t N; /**< length of the DCT4. */
+ uint16_t Nby2; /**< half of the length of the DCT4. */
+ q15_t normalize; /**< normalizing factor. */
+ q15_t *pTwiddle; /**< points to the twiddle factor table. */
+ q15_t *pCosFactor; /**< points to the cosFactor table. */
+ arm_rfft_instance_q15 *pRfft; /**< points to the real FFT instance. */
+ arm_cfft_radix4_instance_q15 *pCfft; /**< points to the complex FFT instance. */
+ } arm_dct4_instance_q15;
+
+
+ /**
+ * @brief Initialization function for the Q15 DCT4/IDCT4.
+ * @param[in,out] S points to an instance of Q15 DCT4/IDCT4 structure.
+ * @param[in] S_RFFT points to an instance of Q15 RFFT/RIFFT structure.
+ * @param[in] S_CFFT points to an instance of Q15 CFFT/CIFFT structure.
+ * @param[in] N length of the DCT4.
+ * @param[in] Nby2 half of the length of the DCT4.
+ * @param[in] normalize normalizing factor.
+ * @return arm_status function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if <code>N</code> is not a supported transform length.
+ */
+ arm_status arm_dct4_init_q15(
+ arm_dct4_instance_q15 * S,
+ arm_rfft_instance_q15 * S_RFFT,
+ arm_cfft_radix4_instance_q15 * S_CFFT,
+ uint16_t N,
+ uint16_t Nby2,
+ q15_t normalize);
+
+
+ /**
+ * @brief Processing function for the Q15 DCT4/IDCT4.
+ * @param[in] S points to an instance of the Q15 DCT4 structure.
+ * @param[in] pState points to state buffer.
+ * @param[in,out] pInlineBuffer points to the in-place input and output buffer.
+ */
+ void arm_dct4_q15(
+ const arm_dct4_instance_q15 * S,
+ q15_t * pState,
+ q15_t * pInlineBuffer);
+
+
+ /**
+ * @brief Floating-point vector addition.
+ * @param[in] pSrcA points to the first input vector
+ * @param[in] pSrcB points to the second input vector
+ * @param[out] pDst points to the output vector
+ * @param[in] blockSize number of samples in each vector
+ */
+ void arm_add_f32(
+ float32_t * pSrcA,
+ float32_t * pSrcB,
+ float32_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Q7 vector addition.
+ * @param[in] pSrcA points to the first input vector
+ * @param[in] pSrcB points to the second input vector
+ * @param[out] pDst points to the output vector
+ * @param[in] blockSize number of samples in each vector
+ */
+ void arm_add_q7(
+ q7_t * pSrcA,
+ q7_t * pSrcB,
+ q7_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Q15 vector addition.
+ * @param[in] pSrcA points to the first input vector
+ * @param[in] pSrcB points to the second input vector
+ * @param[out] pDst points to the output vector
+ * @param[in] blockSize number of samples in each vector
+ */
+ void arm_add_q15(
+ q15_t * pSrcA,
+ q15_t * pSrcB,
+ q15_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Q31 vector addition.
+ * @param[in] pSrcA points to the first input vector
+ * @param[in] pSrcB points to the second input vector
+ * @param[out] pDst points to the output vector
+ * @param[in] blockSize number of samples in each vector
+ */
+ void arm_add_q31(
+ q31_t * pSrcA,
+ q31_t * pSrcB,
+ q31_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Floating-point vector subtraction.
+ * @param[in] pSrcA points to the first input vector
+ * @param[in] pSrcB points to the second input vector
+ * @param[out] pDst points to the output vector
+ * @param[in] blockSize number of samples in each vector
+ */
+ void arm_sub_f32(
+ float32_t * pSrcA,
+ float32_t * pSrcB,
+ float32_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Q7 vector subtraction.
+ * @param[in] pSrcA points to the first input vector
+ * @param[in] pSrcB points to the second input vector
+ * @param[out] pDst points to the output vector
+ * @param[in] blockSize number of samples in each vector
+ */
+ void arm_sub_q7(
+ q7_t * pSrcA,
+ q7_t * pSrcB,
+ q7_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Q15 vector subtraction.
+ * @param[in] pSrcA points to the first input vector
+ * @param[in] pSrcB points to the second input vector
+ * @param[out] pDst points to the output vector
+ * @param[in] blockSize number of samples in each vector
+ */
+ void arm_sub_q15(
+ q15_t * pSrcA,
+ q15_t * pSrcB,
+ q15_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Q31 vector subtraction.
+ * @param[in] pSrcA points to the first input vector
+ * @param[in] pSrcB points to the second input vector
+ * @param[out] pDst points to the output vector
+ * @param[in] blockSize number of samples in each vector
+ */
+ void arm_sub_q31(
+ q31_t * pSrcA,
+ q31_t * pSrcB,
+ q31_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Multiplies a floating-point vector by a scalar.
+ * @param[in] pSrc points to the input vector
+ * @param[in] scale scale factor to be applied
+ * @param[out] pDst points to the output vector
+ * @param[in] blockSize number of samples in the vector
+ */
+ void arm_scale_f32(
+ float32_t * pSrc,
+ float32_t scale,
+ float32_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Multiplies a Q7 vector by a scalar.
+ * @param[in] pSrc points to the input vector
+ * @param[in] scaleFract fractional portion of the scale value
+ * @param[in] shift number of bits to shift the result by
+ * @param[out] pDst points to the output vector
+ * @param[in] blockSize number of samples in the vector
+ */
+ void arm_scale_q7(
+ q7_t * pSrc,
+ q7_t scaleFract,
+ int8_t shift,
+ q7_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Multiplies a Q15 vector by a scalar.
+ * @param[in] pSrc points to the input vector
+ * @param[in] scaleFract fractional portion of the scale value
+ * @param[in] shift number of bits to shift the result by
+ * @param[out] pDst points to the output vector
+ * @param[in] blockSize number of samples in the vector
+ */
+ void arm_scale_q15(
+ q15_t * pSrc,
+ q15_t scaleFract,
+ int8_t shift,
+ q15_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Multiplies a Q31 vector by a scalar.
+ * @param[in] pSrc points to the input vector
+ * @param[in] scaleFract fractional portion of the scale value
+ * @param[in] shift number of bits to shift the result by
+ * @param[out] pDst points to the output vector
+ * @param[in] blockSize number of samples in the vector
+ */
+ void arm_scale_q31(
+ q31_t * pSrc,
+ q31_t scaleFract,
+ int8_t shift,
+ q31_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Q7 vector absolute value.
+ * @param[in] pSrc points to the input buffer
+ * @param[out] pDst points to the output buffer
+ * @param[in] blockSize number of samples in each vector
+ */
+ void arm_abs_q7(
+ q7_t * pSrc,
+ q7_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Floating-point vector absolute value.
+ * @param[in] pSrc points to the input buffer
+ * @param[out] pDst points to the output buffer
+ * @param[in] blockSize number of samples in each vector
+ */
+ void arm_abs_f32(
+ float32_t * pSrc,
+ float32_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Q15 vector absolute value.
+ * @param[in] pSrc points to the input buffer
+ * @param[out] pDst points to the output buffer
+ * @param[in] blockSize number of samples in each vector
+ */
+ void arm_abs_q15(
+ q15_t * pSrc,
+ q15_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Q31 vector absolute value.
+ * @param[in] pSrc points to the input buffer
+ * @param[out] pDst points to the output buffer
+ * @param[in] blockSize number of samples in each vector
+ */
+ void arm_abs_q31(
+ q31_t * pSrc,
+ q31_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Dot product of floating-point vectors.
+ * @param[in] pSrcA points to the first input vector
+ * @param[in] pSrcB points to the second input vector
+ * @param[in] blockSize number of samples in each vector
+ * @param[out] result output result returned here
+ */
+ void arm_dot_prod_f32(
+ float32_t * pSrcA,
+ float32_t * pSrcB,
+ uint32_t blockSize,
+ float32_t * result);
+
+
+ /**
+ * @brief Dot product of Q7 vectors.
+ * @param[in] pSrcA points to the first input vector
+ * @param[in] pSrcB points to the second input vector
+ * @param[in] blockSize number of samples in each vector
+ * @param[out] result output result returned here
+ */
+ void arm_dot_prod_q7(
+ q7_t * pSrcA,
+ q7_t * pSrcB,
+ uint32_t blockSize,
+ q31_t * result);
+
+
+ /**
+ * @brief Dot product of Q15 vectors.
+ * @param[in] pSrcA points to the first input vector
+ * @param[in] pSrcB points to the second input vector
+ * @param[in] blockSize number of samples in each vector
+ * @param[out] result output result returned here
+ */
+ void arm_dot_prod_q15(
+ q15_t * pSrcA,
+ q15_t * pSrcB,
+ uint32_t blockSize,
+ q63_t * result);
+
+
+ /**
+ * @brief Dot product of Q31 vectors.
+ * @param[in] pSrcA points to the first input vector
+ * @param[in] pSrcB points to the second input vector
+ * @param[in] blockSize number of samples in each vector
+ * @param[out] result output result returned here
+ */
+ void arm_dot_prod_q31(
+ q31_t * pSrcA,
+ q31_t * pSrcB,
+ uint32_t blockSize,
+ q63_t * result);
+
+
+ /**
+ * @brief Shifts the elements of a Q7 vector a specified number of bits.
+ * @param[in] pSrc points to the input vector
+ * @param[in] shiftBits number of bits to shift. A positive value shifts left; a negative value shifts right.
+ * @param[out] pDst points to the output vector
+ * @param[in] blockSize number of samples in the vector
+ */
+ void arm_shift_q7(
+ q7_t * pSrc,
+ int8_t shiftBits,
+ q7_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Shifts the elements of a Q15 vector a specified number of bits.
+ * @param[in] pSrc points to the input vector
+ * @param[in] shiftBits number of bits to shift. A positive value shifts left; a negative value shifts right.
+ * @param[out] pDst points to the output vector
+ * @param[in] blockSize number of samples in the vector
+ */
+ void arm_shift_q15(
+ q15_t * pSrc,
+ int8_t shiftBits,
+ q15_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Shifts the elements of a Q31 vector a specified number of bits.
+ * @param[in] pSrc points to the input vector
+ * @param[in] shiftBits number of bits to shift. A positive value shifts left; a negative value shifts right.
+ * @param[out] pDst points to the output vector
+ * @param[in] blockSize number of samples in the vector
+ */
+ void arm_shift_q31(
+ q31_t * pSrc,
+ int8_t shiftBits,
+ q31_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Adds a constant offset to a floating-point vector.
+ * @param[in] pSrc points to the input vector
+ * @param[in] offset is the offset to be added
+ * @param[out] pDst points to the output vector
+ * @param[in] blockSize number of samples in the vector
+ */
+ void arm_offset_f32(
+ float32_t * pSrc,
+ float32_t offset,
+ float32_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Adds a constant offset to a Q7 vector.
+ * @param[in] pSrc points to the input vector
+ * @param[in] offset is the offset to be added
+ * @param[out] pDst points to the output vector
+ * @param[in] blockSize number of samples in the vector
+ */
+ void arm_offset_q7(
+ q7_t * pSrc,
+ q7_t offset,
+ q7_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Adds a constant offset to a Q15 vector.
+ * @param[in] pSrc points to the input vector
+ * @param[in] offset is the offset to be added
+ * @param[out] pDst points to the output vector
+ * @param[in] blockSize number of samples in the vector
+ */
+ void arm_offset_q15(
+ q15_t * pSrc,
+ q15_t offset,
+ q15_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Adds a constant offset to a Q31 vector.
+ * @param[in] pSrc points to the input vector
+ * @param[in] offset is the offset to be added
+ * @param[out] pDst points to the output vector
+ * @param[in] blockSize number of samples in the vector
+ */
+ void arm_offset_q31(
+ q31_t * pSrc,
+ q31_t offset,
+ q31_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Negates the elements of a floating-point vector.
+ * @param[in] pSrc points to the input vector
+ * @param[out] pDst points to the output vector
+ * @param[in] blockSize number of samples in the vector
+ */
+ void arm_negate_f32(
+ float32_t * pSrc,
+ float32_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Negates the elements of a Q7 vector.
+ * @param[in] pSrc points to the input vector
+ * @param[out] pDst points to the output vector
+ * @param[in] blockSize number of samples in the vector
+ */
+ void arm_negate_q7(
+ q7_t * pSrc,
+ q7_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Negates the elements of a Q15 vector.
+ * @param[in] pSrc points to the input vector
+ * @param[out] pDst points to the output vector
+ * @param[in] blockSize number of samples in the vector
+ */
+ void arm_negate_q15(
+ q15_t * pSrc,
+ q15_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Negates the elements of a Q31 vector.
+ * @param[in] pSrc points to the input vector
+ * @param[out] pDst points to the output vector
+ * @param[in] blockSize number of samples in the vector
+ */
+ void arm_negate_q31(
+ q31_t * pSrc,
+ q31_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Copies the elements of a floating-point vector.
+ * @param[in] pSrc input pointer
+ * @param[out] pDst output pointer
+ * @param[in] blockSize number of samples to process
+ */
+ void arm_copy_f32(
+ float32_t * pSrc,
+ float32_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Copies the elements of a Q7 vector.
+ * @param[in] pSrc input pointer
+ * @param[out] pDst output pointer
+ * @param[in] blockSize number of samples to process
+ */
+ void arm_copy_q7(
+ q7_t * pSrc,
+ q7_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Copies the elements of a Q15 vector.
+ * @param[in] pSrc input pointer
+ * @param[out] pDst output pointer
+ * @param[in] blockSize number of samples to process
+ */
+ void arm_copy_q15(
+ q15_t * pSrc,
+ q15_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Copies the elements of a Q31 vector.
+ * @param[in] pSrc input pointer
+ * @param[out] pDst output pointer
+ * @param[in] blockSize number of samples to process
+ */
+ void arm_copy_q31(
+ q31_t * pSrc,
+ q31_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Fills a constant value into a floating-point vector.
+ * @param[in] value input value to be filled
+ * @param[out] pDst output pointer
+ * @param[in] blockSize number of samples to process
+ */
+ void arm_fill_f32(
+ float32_t value,
+ float32_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Fills a constant value into a Q7 vector.
+ * @param[in] value input value to be filled
+ * @param[out] pDst output pointer
+ * @param[in] blockSize number of samples to process
+ */
+ void arm_fill_q7(
+ q7_t value,
+ q7_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Fills a constant value into a Q15 vector.
+ * @param[in] value input value to be filled
+ * @param[out] pDst output pointer
+ * @param[in] blockSize number of samples to process
+ */
+ void arm_fill_q15(
+ q15_t value,
+ q15_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Fills a constant value into a Q31 vector.
+ * @param[in] value input value to be filled
+ * @param[out] pDst output pointer
+ * @param[in] blockSize number of samples to process
+ */
+ void arm_fill_q31(
+ q31_t value,
+ q31_t * pDst,
+ uint32_t blockSize);
+
+
+/**
+ * @brief Convolution of floating-point sequences.
+ * @param[in] pSrcA points to the first input sequence.
+ * @param[in] srcALen length of the first input sequence.
+ * @param[in] pSrcB points to the second input sequence.
+ * @param[in] srcBLen length of the second input sequence.
+ * @param[out] pDst points to the location where the output result is written. Length srcALen+srcBLen-1.
+ */
+ void arm_conv_f32(
+ float32_t * pSrcA,
+ uint32_t srcALen,
+ float32_t * pSrcB,
+ uint32_t srcBLen,
+ float32_t * pDst);
+
+
+ /**
+ * @brief Convolution of Q15 sequences.
+ * @param[in] pSrcA points to the first input sequence.
+ * @param[in] srcALen length of the first input sequence.
+ * @param[in] pSrcB points to the second input sequence.
+ * @param[in] srcBLen length of the second input sequence.
+ * @param[out] pDst points to the block of output data Length srcALen+srcBLen-1.
+ * @param[in] pScratch1 points to scratch buffer of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2.
+ * @param[in] pScratch2 points to scratch buffer of size min(srcALen, srcBLen).
+ */
+ void arm_conv_opt_q15(
+ q15_t * pSrcA,
+ uint32_t srcALen,
+ q15_t * pSrcB,
+ uint32_t srcBLen,
+ q15_t * pDst,
+ q15_t * pScratch1,
+ q15_t * pScratch2);
+
+
+/**
+ * @brief Convolution of Q15 sequences.
+ * @param[in] pSrcA points to the first input sequence.
+ * @param[in] srcALen length of the first input sequence.
+ * @param[in] pSrcB points to the second input sequence.
+ * @param[in] srcBLen length of the second input sequence.
+ * @param[out] pDst points to the location where the output result is written. Length srcALen+srcBLen-1.
+ */
+ void arm_conv_q15(
+ q15_t * pSrcA,
+ uint32_t srcALen,
+ q15_t * pSrcB,
+ uint32_t srcBLen,
+ q15_t * pDst);
+
+
+ /**
+ * @brief Convolution of Q15 sequences (fast version) for Cortex-M3 and Cortex-M4
+ * @param[in] pSrcA points to the first input sequence.
+ * @param[in] srcALen length of the first input sequence.
+ * @param[in] pSrcB points to the second input sequence.
+ * @param[in] srcBLen length of the second input sequence.
+ * @param[out] pDst points to the block of output data Length srcALen+srcBLen-1.
+ */
+ void arm_conv_fast_q15(
+ q15_t * pSrcA,
+ uint32_t srcALen,
+ q15_t * pSrcB,
+ uint32_t srcBLen,
+ q15_t * pDst);
+
+
+ /**
+ * @brief Convolution of Q15 sequences (fast version) for Cortex-M3 and Cortex-M4
+ * @param[in] pSrcA points to the first input sequence.
+ * @param[in] srcALen length of the first input sequence.
+ * @param[in] pSrcB points to the second input sequence.
+ * @param[in] srcBLen length of the second input sequence.
+ * @param[out] pDst points to the block of output data Length srcALen+srcBLen-1.
+ * @param[in] pScratch1 points to scratch buffer of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2.
+ * @param[in] pScratch2 points to scratch buffer of size min(srcALen, srcBLen).
+ */
+ void arm_conv_fast_opt_q15(
+ q15_t * pSrcA,
+ uint32_t srcALen,
+ q15_t * pSrcB,
+ uint32_t srcBLen,
+ q15_t * pDst,
+ q15_t * pScratch1,
+ q15_t * pScratch2);
+
+
+ /**
+ * @brief Convolution of Q31 sequences.
+ * @param[in] pSrcA points to the first input sequence.
+ * @param[in] srcALen length of the first input sequence.
+ * @param[in] pSrcB points to the second input sequence.
+ * @param[in] srcBLen length of the second input sequence.
+ * @param[out] pDst points to the block of output data Length srcALen+srcBLen-1.
+ */
+ void arm_conv_q31(
+ q31_t * pSrcA,
+ uint32_t srcALen,
+ q31_t * pSrcB,
+ uint32_t srcBLen,
+ q31_t * pDst);
+
+
+ /**
+ * @brief Convolution of Q31 sequences (fast version) for Cortex-M3 and Cortex-M4
+ * @param[in] pSrcA points to the first input sequence.
+ * @param[in] srcALen length of the first input sequence.
+ * @param[in] pSrcB points to the second input sequence.
+ * @param[in] srcBLen length of the second input sequence.
+ * @param[out] pDst points to the block of output data Length srcALen+srcBLen-1.
+ */
+ void arm_conv_fast_q31(
+ q31_t * pSrcA,
+ uint32_t srcALen,
+ q31_t * pSrcB,
+ uint32_t srcBLen,
+ q31_t * pDst);
+
+
+ /**
+ * @brief Convolution of Q7 sequences.
+ * @param[in] pSrcA points to the first input sequence.
+ * @param[in] srcALen length of the first input sequence.
+ * @param[in] pSrcB points to the second input sequence.
+ * @param[in] srcBLen length of the second input sequence.
+ * @param[out] pDst points to the block of output data Length srcALen+srcBLen-1.
+ * @param[in] pScratch1 points to scratch buffer(of type q15_t) of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2.
+ * @param[in] pScratch2 points to scratch buffer (of type q15_t) of size min(srcALen, srcBLen).
+ */
+ void arm_conv_opt_q7(
+ q7_t * pSrcA,
+ uint32_t srcALen,
+ q7_t * pSrcB,
+ uint32_t srcBLen,
+ q7_t * pDst,
+ q15_t * pScratch1,
+ q15_t * pScratch2);
+
+
+ /**
+ * @brief Convolution of Q7 sequences.
+ * @param[in] pSrcA points to the first input sequence.
+ * @param[in] srcALen length of the first input sequence.
+ * @param[in] pSrcB points to the second input sequence.
+ * @param[in] srcBLen length of the second input sequence.
+ * @param[out] pDst points to the block of output data Length srcALen+srcBLen-1.
+ */
+ void arm_conv_q7(
+ q7_t * pSrcA,
+ uint32_t srcALen,
+ q7_t * pSrcB,
+ uint32_t srcBLen,
+ q7_t * pDst);
+
+
+ /**
+ * @brief Partial convolution of floating-point sequences.
+ * @param[in] pSrcA points to the first input sequence.
+ * @param[in] srcALen length of the first input sequence.
+ * @param[in] pSrcB points to the second input sequence.
+ * @param[in] srcBLen length of the second input sequence.
+ * @param[out] pDst points to the block of output data
+ * @param[in] firstIndex is the first output sample to start with.
+ * @param[in] numPoints is the number of output points to be computed.
+ * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2].
+ */
+ arm_status arm_conv_partial_f32(
+ float32_t * pSrcA,
+ uint32_t srcALen,
+ float32_t * pSrcB,
+ uint32_t srcBLen,
+ float32_t * pDst,
+ uint32_t firstIndex,
+ uint32_t numPoints);
+
+
+ /**
+ * @brief Partial convolution of Q15 sequences.
+ * @param[in] pSrcA points to the first input sequence.
+ * @param[in] srcALen length of the first input sequence.
+ * @param[in] pSrcB points to the second input sequence.
+ * @param[in] srcBLen length of the second input sequence.
+ * @param[out] pDst points to the block of output data
+ * @param[in] firstIndex is the first output sample to start with.
+ * @param[in] numPoints is the number of output points to be computed.
+ * @param[in] pScratch1 points to scratch buffer of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2.
+ * @param[in] pScratch2 points to scratch buffer of size min(srcALen, srcBLen).
+ * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2].
+ */
+ arm_status arm_conv_partial_opt_q15(
+ q15_t * pSrcA,
+ uint32_t srcALen,
+ q15_t * pSrcB,
+ uint32_t srcBLen,
+ q15_t * pDst,
+ uint32_t firstIndex,
+ uint32_t numPoints,
+ q15_t * pScratch1,
+ q15_t * pScratch2);
+
+
+ /**
+ * @brief Partial convolution of Q15 sequences.
+ * @param[in] pSrcA points to the first input sequence.
+ * @param[in] srcALen length of the first input sequence.
+ * @param[in] pSrcB points to the second input sequence.
+ * @param[in] srcBLen length of the second input sequence.
+ * @param[out] pDst points to the block of output data
+ * @param[in] firstIndex is the first output sample to start with.
+ * @param[in] numPoints is the number of output points to be computed.
+ * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2].
+ */
+ arm_status arm_conv_partial_q15(
+ q15_t * pSrcA,
+ uint32_t srcALen,
+ q15_t * pSrcB,
+ uint32_t srcBLen,
+ q15_t * pDst,
+ uint32_t firstIndex,
+ uint32_t numPoints);
+
+
+ /**
+ * @brief Partial convolution of Q15 sequences (fast version) for Cortex-M3 and Cortex-M4
+ * @param[in] pSrcA points to the first input sequence.
+ * @param[in] srcALen length of the first input sequence.
+ * @param[in] pSrcB points to the second input sequence.
+ * @param[in] srcBLen length of the second input sequence.
+ * @param[out] pDst points to the block of output data
+ * @param[in] firstIndex is the first output sample to start with.
+ * @param[in] numPoints is the number of output points to be computed.
+ * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2].
+ */
+ arm_status arm_conv_partial_fast_q15(
+ q15_t * pSrcA,
+ uint32_t srcALen,
+ q15_t * pSrcB,
+ uint32_t srcBLen,
+ q15_t * pDst,
+ uint32_t firstIndex,
+ uint32_t numPoints);
+
+
+ /**
+ * @brief Partial convolution of Q15 sequences (fast version) for Cortex-M3 and Cortex-M4
+ * @param[in] pSrcA points to the first input sequence.
+ * @param[in] srcALen length of the first input sequence.
+ * @param[in] pSrcB points to the second input sequence.
+ * @param[in] srcBLen length of the second input sequence.
+ * @param[out] pDst points to the block of output data
+ * @param[in] firstIndex is the first output sample to start with.
+ * @param[in] numPoints is the number of output points to be computed.
+ * @param[in] pScratch1 points to scratch buffer of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2.
+ * @param[in] pScratch2 points to scratch buffer of size min(srcALen, srcBLen).
+ * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2].
+ */
+ arm_status arm_conv_partial_fast_opt_q15(
+ q15_t * pSrcA,
+ uint32_t srcALen,
+ q15_t * pSrcB,
+ uint32_t srcBLen,
+ q15_t * pDst,
+ uint32_t firstIndex,
+ uint32_t numPoints,
+ q15_t * pScratch1,
+ q15_t * pScratch2);
+
+
+ /**
+ * @brief Partial convolution of Q31 sequences.
+ * @param[in] pSrcA points to the first input sequence.
+ * @param[in] srcALen length of the first input sequence.
+ * @param[in] pSrcB points to the second input sequence.
+ * @param[in] srcBLen length of the second input sequence.
+ * @param[out] pDst points to the block of output data
+ * @param[in] firstIndex is the first output sample to start with.
+ * @param[in] numPoints is the number of output points to be computed.
+ * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2].
+ */
+ arm_status arm_conv_partial_q31(
+ q31_t * pSrcA,
+ uint32_t srcALen,
+ q31_t * pSrcB,
+ uint32_t srcBLen,
+ q31_t * pDst,
+ uint32_t firstIndex,
+ uint32_t numPoints);
+
+
+ /**
+ * @brief Partial convolution of Q31 sequences (fast version) for Cortex-M3 and Cortex-M4
+ * @param[in] pSrcA points to the first input sequence.
+ * @param[in] srcALen length of the first input sequence.
+ * @param[in] pSrcB points to the second input sequence.
+ * @param[in] srcBLen length of the second input sequence.
+ * @param[out] pDst points to the block of output data
+ * @param[in] firstIndex is the first output sample to start with.
+ * @param[in] numPoints is the number of output points to be computed.
+ * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2].
+ */
+ arm_status arm_conv_partial_fast_q31(
+ q31_t * pSrcA,
+ uint32_t srcALen,
+ q31_t * pSrcB,
+ uint32_t srcBLen,
+ q31_t * pDst,
+ uint32_t firstIndex,
+ uint32_t numPoints);
+
+
+ /**
+ * @brief Partial convolution of Q7 sequences
+ * @param[in] pSrcA points to the first input sequence.
+ * @param[in] srcALen length of the first input sequence.
+ * @param[in] pSrcB points to the second input sequence.
+ * @param[in] srcBLen length of the second input sequence.
+ * @param[out] pDst points to the block of output data
+ * @param[in] firstIndex is the first output sample to start with.
+ * @param[in] numPoints is the number of output points to be computed.
+ * @param[in] pScratch1 points to scratch buffer(of type q15_t) of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2.
+ * @param[in] pScratch2 points to scratch buffer (of type q15_t) of size min(srcALen, srcBLen).
+ * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2].
+ */
+ arm_status arm_conv_partial_opt_q7(
+ q7_t * pSrcA,
+ uint32_t srcALen,
+ q7_t * pSrcB,
+ uint32_t srcBLen,
+ q7_t * pDst,
+ uint32_t firstIndex,
+ uint32_t numPoints,
+ q15_t * pScratch1,
+ q15_t * pScratch2);
+
+
+/**
+ * @brief Partial convolution of Q7 sequences.
+ * @param[in] pSrcA points to the first input sequence.
+ * @param[in] srcALen length of the first input sequence.
+ * @param[in] pSrcB points to the second input sequence.
+ * @param[in] srcBLen length of the second input sequence.
+ * @param[out] pDst points to the block of output data
+ * @param[in] firstIndex is the first output sample to start with.
+ * @param[in] numPoints is the number of output points to be computed.
+ * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2].
+ */
+ arm_status arm_conv_partial_q7(
+ q7_t * pSrcA,
+ uint32_t srcALen,
+ q7_t * pSrcB,
+ uint32_t srcBLen,
+ q7_t * pDst,
+ uint32_t firstIndex,
+ uint32_t numPoints);
+
+
+ /**
+ * @brief Instance structure for the Q15 FIR decimator.
+ */
+ typedef struct
+ {
+ uint8_t M; /**< decimation factor. */
+ uint16_t numTaps; /**< number of coefficients in the filter. */
+ q15_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/
+ q15_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */
+ } arm_fir_decimate_instance_q15;
+
+ /**
+ * @brief Instance structure for the Q31 FIR decimator.
+ */
+ typedef struct
+ {
+ uint8_t M; /**< decimation factor. */
+ uint16_t numTaps; /**< number of coefficients in the filter. */
+ q31_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/
+ q31_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */
+ } arm_fir_decimate_instance_q31;
+
+ /**
+ * @brief Instance structure for the floating-point FIR decimator.
+ */
+ typedef struct
+ {
+ uint8_t M; /**< decimation factor. */
+ uint16_t numTaps; /**< number of coefficients in the filter. */
+ float32_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/
+ float32_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */
+ } arm_fir_decimate_instance_f32;
+
+
+ /**
+ * @brief Processing function for the floating-point FIR decimator.
+ * @param[in] S points to an instance of the floating-point FIR decimator structure.
+ * @param[in] pSrc points to the block of input data.
+ * @param[out] pDst points to the block of output data
+ * @param[in] blockSize number of input samples to process per call.
+ */
+ void arm_fir_decimate_f32(
+ const arm_fir_decimate_instance_f32 * S,
+ float32_t * pSrc,
+ float32_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Initialization function for the floating-point FIR decimator.
+ * @param[in,out] S points to an instance of the floating-point FIR decimator structure.
+ * @param[in] numTaps number of coefficients in the filter.
+ * @param[in] M decimation factor.
+ * @param[in] pCoeffs points to the filter coefficients.
+ * @param[in] pState points to the state buffer.
+ * @param[in] blockSize number of input samples to process per call.
+ * @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_LENGTH_ERROR if
+ * <code>blockSize</code> is not a multiple of <code>M</code>.
+ */
+ arm_status arm_fir_decimate_init_f32(
+ arm_fir_decimate_instance_f32 * S,
+ uint16_t numTaps,
+ uint8_t M,
+ float32_t * pCoeffs,
+ float32_t * pState,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Processing function for the Q15 FIR decimator.
+ * @param[in] S points to an instance of the Q15 FIR decimator structure.
+ * @param[in] pSrc points to the block of input data.
+ * @param[out] pDst points to the block of output data
+ * @param[in] blockSize number of input samples to process per call.
+ */
+ void arm_fir_decimate_q15(
+ const arm_fir_decimate_instance_q15 * S,
+ q15_t * pSrc,
+ q15_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Processing function for the Q15 FIR decimator (fast variant) for Cortex-M3 and Cortex-M4.
+ * @param[in] S points to an instance of the Q15 FIR decimator structure.
+ * @param[in] pSrc points to the block of input data.
+ * @param[out] pDst points to the block of output data
+ * @param[in] blockSize number of input samples to process per call.
+ */
+ void arm_fir_decimate_fast_q15(
+ const arm_fir_decimate_instance_q15 * S,
+ q15_t * pSrc,
+ q15_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Initialization function for the Q15 FIR decimator.
+ * @param[in,out] S points to an instance of the Q15 FIR decimator structure.
+ * @param[in] numTaps number of coefficients in the filter.
+ * @param[in] M decimation factor.
+ * @param[in] pCoeffs points to the filter coefficients.
+ * @param[in] pState points to the state buffer.
+ * @param[in] blockSize number of input samples to process per call.
+ * @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_LENGTH_ERROR if
+ * <code>blockSize</code> is not a multiple of <code>M</code>.
+ */
+ arm_status arm_fir_decimate_init_q15(
+ arm_fir_decimate_instance_q15 * S,
+ uint16_t numTaps,
+ uint8_t M,
+ q15_t * pCoeffs,
+ q15_t * pState,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Processing function for the Q31 FIR decimator.
+ * @param[in] S points to an instance of the Q31 FIR decimator structure.
+ * @param[in] pSrc points to the block of input data.
+ * @param[out] pDst points to the block of output data
+ * @param[in] blockSize number of input samples to process per call.
+ */
+ void arm_fir_decimate_q31(
+ const arm_fir_decimate_instance_q31 * S,
+ q31_t * pSrc,
+ q31_t * pDst,
+ uint32_t blockSize);
+
+ /**
+ * @brief Processing function for the Q31 FIR decimator (fast variant) for Cortex-M3 and Cortex-M4.
+ * @param[in] S points to an instance of the Q31 FIR decimator structure.
+ * @param[in] pSrc points to the block of input data.
+ * @param[out] pDst points to the block of output data
+ * @param[in] blockSize number of input samples to process per call.
+ */
+ void arm_fir_decimate_fast_q31(
+ arm_fir_decimate_instance_q31 * S,
+ q31_t * pSrc,
+ q31_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Initialization function for the Q31 FIR decimator.
+ * @param[in,out] S points to an instance of the Q31 FIR decimator structure.
+ * @param[in] numTaps number of coefficients in the filter.
+ * @param[in] M decimation factor.
+ * @param[in] pCoeffs points to the filter coefficients.
+ * @param[in] pState points to the state buffer.
+ * @param[in] blockSize number of input samples to process per call.
+ * @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_LENGTH_ERROR if
+ * <code>blockSize</code> is not a multiple of <code>M</code>.
+ */
+ arm_status arm_fir_decimate_init_q31(
+ arm_fir_decimate_instance_q31 * S,
+ uint16_t numTaps,
+ uint8_t M,
+ q31_t * pCoeffs,
+ q31_t * pState,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Instance structure for the Q15 FIR interpolator.
+ */
+ typedef struct
+ {
+ uint8_t L; /**< upsample factor. */
+ uint16_t phaseLength; /**< length of each polyphase filter component. */
+ q15_t *pCoeffs; /**< points to the coefficient array. The array is of length L*phaseLength. */
+ q15_t *pState; /**< points to the state variable array. The array is of length blockSize+phaseLength-1. */
+ } arm_fir_interpolate_instance_q15;
+
+ /**
+ * @brief Instance structure for the Q31 FIR interpolator.
+ */
+ typedef struct
+ {
+ uint8_t L; /**< upsample factor. */
+ uint16_t phaseLength; /**< length of each polyphase filter component. */
+ q31_t *pCoeffs; /**< points to the coefficient array. The array is of length L*phaseLength. */
+ q31_t *pState; /**< points to the state variable array. The array is of length blockSize+phaseLength-1. */
+ } arm_fir_interpolate_instance_q31;
+
+ /**
+ * @brief Instance structure for the floating-point FIR interpolator.
+ */
+ typedef struct
+ {
+ uint8_t L; /**< upsample factor. */
+ uint16_t phaseLength; /**< length of each polyphase filter component. */
+ float32_t *pCoeffs; /**< points to the coefficient array. The array is of length L*phaseLength. */
+ float32_t *pState; /**< points to the state variable array. The array is of length phaseLength+numTaps-1. */
+ } arm_fir_interpolate_instance_f32;
+
+
+ /**
+ * @brief Processing function for the Q15 FIR interpolator.
+ * @param[in] S points to an instance of the Q15 FIR interpolator structure.
+ * @param[in] pSrc points to the block of input data.
+ * @param[out] pDst points to the block of output data.
+ * @param[in] blockSize number of input samples to process per call.
+ */
+ void arm_fir_interpolate_q15(
+ const arm_fir_interpolate_instance_q15 * S,
+ q15_t * pSrc,
+ q15_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Initialization function for the Q15 FIR interpolator.
+ * @param[in,out] S points to an instance of the Q15 FIR interpolator structure.
+ * @param[in] L upsample factor.
+ * @param[in] numTaps number of filter coefficients in the filter.
+ * @param[in] pCoeffs points to the filter coefficient buffer.
+ * @param[in] pState points to the state buffer.
+ * @param[in] blockSize number of input samples to process per call.
+ * @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_LENGTH_ERROR if
+ * the filter length <code>numTaps</code> is not a multiple of the interpolation factor <code>L</code>.
+ */
+ arm_status arm_fir_interpolate_init_q15(
+ arm_fir_interpolate_instance_q15 * S,
+ uint8_t L,
+ uint16_t numTaps,
+ q15_t * pCoeffs,
+ q15_t * pState,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Processing function for the Q31 FIR interpolator.
+ * @param[in] S points to an instance of the Q15 FIR interpolator structure.
+ * @param[in] pSrc points to the block of input data.
+ * @param[out] pDst points to the block of output data.
+ * @param[in] blockSize number of input samples to process per call.
+ */
+ void arm_fir_interpolate_q31(
+ const arm_fir_interpolate_instance_q31 * S,
+ q31_t * pSrc,
+ q31_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Initialization function for the Q31 FIR interpolator.
+ * @param[in,out] S points to an instance of the Q31 FIR interpolator structure.
+ * @param[in] L upsample factor.
+ * @param[in] numTaps number of filter coefficients in the filter.
+ * @param[in] pCoeffs points to the filter coefficient buffer.
+ * @param[in] pState points to the state buffer.
+ * @param[in] blockSize number of input samples to process per call.
+ * @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_LENGTH_ERROR if
+ * the filter length <code>numTaps</code> is not a multiple of the interpolation factor <code>L</code>.
+ */
+ arm_status arm_fir_interpolate_init_q31(
+ arm_fir_interpolate_instance_q31 * S,
+ uint8_t L,
+ uint16_t numTaps,
+ q31_t * pCoeffs,
+ q31_t * pState,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Processing function for the floating-point FIR interpolator.
+ * @param[in] S points to an instance of the floating-point FIR interpolator structure.
+ * @param[in] pSrc points to the block of input data.
+ * @param[out] pDst points to the block of output data.
+ * @param[in] blockSize number of input samples to process per call.
+ */
+ void arm_fir_interpolate_f32(
+ const arm_fir_interpolate_instance_f32 * S,
+ float32_t * pSrc,
+ float32_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Initialization function for the floating-point FIR interpolator.
+ * @param[in,out] S points to an instance of the floating-point FIR interpolator structure.
+ * @param[in] L upsample factor.
+ * @param[in] numTaps number of filter coefficients in the filter.
+ * @param[in] pCoeffs points to the filter coefficient buffer.
+ * @param[in] pState points to the state buffer.
+ * @param[in] blockSize number of input samples to process per call.
+ * @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_LENGTH_ERROR if
+ * the filter length <code>numTaps</code> is not a multiple of the interpolation factor <code>L</code>.
+ */
+ arm_status arm_fir_interpolate_init_f32(
+ arm_fir_interpolate_instance_f32 * S,
+ uint8_t L,
+ uint16_t numTaps,
+ float32_t * pCoeffs,
+ float32_t * pState,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Instance structure for the high precision Q31 Biquad cascade filter.
+ */
+ typedef struct
+ {
+ uint8_t numStages; /**< number of 2nd order stages in the filter. Overall order is 2*numStages. */
+ q63_t *pState; /**< points to the array of state coefficients. The array is of length 4*numStages. */
+ q31_t *pCoeffs; /**< points to the array of coefficients. The array is of length 5*numStages. */
+ uint8_t postShift; /**< additional shift, in bits, applied to each output sample. */
+ } arm_biquad_cas_df1_32x64_ins_q31;
+
+
+ /**
+ * @param[in] S points to an instance of the high precision Q31 Biquad cascade filter structure.
+ * @param[in] pSrc points to the block of input data.
+ * @param[out] pDst points to the block of output data
+ * @param[in] blockSize number of samples to process.
+ */
+ void arm_biquad_cas_df1_32x64_q31(
+ const arm_biquad_cas_df1_32x64_ins_q31 * S,
+ q31_t * pSrc,
+ q31_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @param[in,out] S points to an instance of the high precision Q31 Biquad cascade filter structure.
+ * @param[in] numStages number of 2nd order stages in the filter.
+ * @param[in] pCoeffs points to the filter coefficients.
+ * @param[in] pState points to the state buffer.
+ * @param[in] postShift shift to be applied to the output. Varies according to the coefficients format
+ */
+ void arm_biquad_cas_df1_32x64_init_q31(
+ arm_biquad_cas_df1_32x64_ins_q31 * S,
+ uint8_t numStages,
+ q31_t * pCoeffs,
+ q63_t * pState,
+ uint8_t postShift);
+
+
+ /**
+ * @brief Instance structure for the floating-point transposed direct form II Biquad cascade filter.
+ */
+ typedef struct
+ {
+ uint8_t numStages; /**< number of 2nd order stages in the filter. Overall order is 2*numStages. */
+ float32_t *pState; /**< points to the array of state coefficients. The array is of length 2*numStages. */
+ float32_t *pCoeffs; /**< points to the array of coefficients. The array is of length 5*numStages. */
+ } arm_biquad_cascade_df2T_instance_f32;
+
+ /**
+ * @brief Instance structure for the floating-point transposed direct form II Biquad cascade filter.
+ */
+ typedef struct
+ {
+ uint8_t numStages; /**< number of 2nd order stages in the filter. Overall order is 2*numStages. */
+ float32_t *pState; /**< points to the array of state coefficients. The array is of length 4*numStages. */
+ float32_t *pCoeffs; /**< points to the array of coefficients. The array is of length 5*numStages. */
+ } arm_biquad_cascade_stereo_df2T_instance_f32;
+
+ /**
+ * @brief Instance structure for the floating-point transposed direct form II Biquad cascade filter.
+ */
+ typedef struct
+ {
+ uint8_t numStages; /**< number of 2nd order stages in the filter. Overall order is 2*numStages. */
+ float64_t *pState; /**< points to the array of state coefficients. The array is of length 2*numStages. */
+ float64_t *pCoeffs; /**< points to the array of coefficients. The array is of length 5*numStages. */
+ } arm_biquad_cascade_df2T_instance_f64;
+
+
+ /**
+ * @brief Processing function for the floating-point transposed direct form II Biquad cascade filter.
+ * @param[in] S points to an instance of the filter data structure.
+ * @param[in] pSrc points to the block of input data.
+ * @param[out] pDst points to the block of output data
+ * @param[in] blockSize number of samples to process.
+ */
+ void arm_biquad_cascade_df2T_f32(
+ const arm_biquad_cascade_df2T_instance_f32 * S,
+ float32_t * pSrc,
+ float32_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Processing function for the floating-point transposed direct form II Biquad cascade filter. 2 channels
+ * @param[in] S points to an instance of the filter data structure.
+ * @param[in] pSrc points to the block of input data.
+ * @param[out] pDst points to the block of output data
+ * @param[in] blockSize number of samples to process.
+ */
+ void arm_biquad_cascade_stereo_df2T_f32(
+ const arm_biquad_cascade_stereo_df2T_instance_f32 * S,
+ float32_t * pSrc,
+ float32_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Processing function for the floating-point transposed direct form II Biquad cascade filter.
+ * @param[in] S points to an instance of the filter data structure.
+ * @param[in] pSrc points to the block of input data.
+ * @param[out] pDst points to the block of output data
+ * @param[in] blockSize number of samples to process.
+ */
+ void arm_biquad_cascade_df2T_f64(
+ const arm_biquad_cascade_df2T_instance_f64 * S,
+ float64_t * pSrc,
+ float64_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Initialization function for the floating-point transposed direct form II Biquad cascade filter.
+ * @param[in,out] S points to an instance of the filter data structure.
+ * @param[in] numStages number of 2nd order stages in the filter.
+ * @param[in] pCoeffs points to the filter coefficients.
+ * @param[in] pState points to the state buffer.
+ */
+ void arm_biquad_cascade_df2T_init_f32(
+ arm_biquad_cascade_df2T_instance_f32 * S,
+ uint8_t numStages,
+ float32_t * pCoeffs,
+ float32_t * pState);
+
+
+ /**
+ * @brief Initialization function for the floating-point transposed direct form II Biquad cascade filter.
+ * @param[in,out] S points to an instance of the filter data structure.
+ * @param[in] numStages number of 2nd order stages in the filter.
+ * @param[in] pCoeffs points to the filter coefficients.
+ * @param[in] pState points to the state buffer.
+ */
+ void arm_biquad_cascade_stereo_df2T_init_f32(
+ arm_biquad_cascade_stereo_df2T_instance_f32 * S,
+ uint8_t numStages,
+ float32_t * pCoeffs,
+ float32_t * pState);
+
+
+ /**
+ * @brief Initialization function for the floating-point transposed direct form II Biquad cascade filter.
+ * @param[in,out] S points to an instance of the filter data structure.
+ * @param[in] numStages number of 2nd order stages in the filter.
+ * @param[in] pCoeffs points to the filter coefficients.
+ * @param[in] pState points to the state buffer.
+ */
+ void arm_biquad_cascade_df2T_init_f64(
+ arm_biquad_cascade_df2T_instance_f64 * S,
+ uint8_t numStages,
+ float64_t * pCoeffs,
+ float64_t * pState);
+
+
+ /**
+ * @brief Instance structure for the Q15 FIR lattice filter.
+ */
+ typedef struct
+ {
+ uint16_t numStages; /**< number of filter stages. */
+ q15_t *pState; /**< points to the state variable array. The array is of length numStages. */
+ q15_t *pCoeffs; /**< points to the coefficient array. The array is of length numStages. */
+ } arm_fir_lattice_instance_q15;
+
+ /**
+ * @brief Instance structure for the Q31 FIR lattice filter.
+ */
+ typedef struct
+ {
+ uint16_t numStages; /**< number of filter stages. */
+ q31_t *pState; /**< points to the state variable array. The array is of length numStages. */
+ q31_t *pCoeffs; /**< points to the coefficient array. The array is of length numStages. */
+ } arm_fir_lattice_instance_q31;
+
+ /**
+ * @brief Instance structure for the floating-point FIR lattice filter.
+ */
+ typedef struct
+ {
+ uint16_t numStages; /**< number of filter stages. */
+ float32_t *pState; /**< points to the state variable array. The array is of length numStages. */
+ float32_t *pCoeffs; /**< points to the coefficient array. The array is of length numStages. */
+ } arm_fir_lattice_instance_f32;
+
+
+ /**
+ * @brief Initialization function for the Q15 FIR lattice filter.
+ * @param[in] S points to an instance of the Q15 FIR lattice structure.
+ * @param[in] numStages number of filter stages.
+ * @param[in] pCoeffs points to the coefficient buffer. The array is of length numStages.
+ * @param[in] pState points to the state buffer. The array is of length numStages.
+ */
+ void arm_fir_lattice_init_q15(
+ arm_fir_lattice_instance_q15 * S,
+ uint16_t numStages,
+ q15_t * pCoeffs,
+ q15_t * pState);
+
+
+ /**
+ * @brief Processing function for the Q15 FIR lattice filter.
+ * @param[in] S points to an instance of the Q15 FIR lattice structure.
+ * @param[in] pSrc points to the block of input data.
+ * @param[out] pDst points to the block of output data.
+ * @param[in] blockSize number of samples to process.
+ */
+ void arm_fir_lattice_q15(
+ const arm_fir_lattice_instance_q15 * S,
+ q15_t * pSrc,
+ q15_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Initialization function for the Q31 FIR lattice filter.
+ * @param[in] S points to an instance of the Q31 FIR lattice structure.
+ * @param[in] numStages number of filter stages.
+ * @param[in] pCoeffs points to the coefficient buffer. The array is of length numStages.
+ * @param[in] pState points to the state buffer. The array is of length numStages.
+ */
+ void arm_fir_lattice_init_q31(
+ arm_fir_lattice_instance_q31 * S,
+ uint16_t numStages,
+ q31_t * pCoeffs,
+ q31_t * pState);
+
+
+ /**
+ * @brief Processing function for the Q31 FIR lattice filter.
+ * @param[in] S points to an instance of the Q31 FIR lattice structure.
+ * @param[in] pSrc points to the block of input data.
+ * @param[out] pDst points to the block of output data
+ * @param[in] blockSize number of samples to process.
+ */
+ void arm_fir_lattice_q31(
+ const arm_fir_lattice_instance_q31 * S,
+ q31_t * pSrc,
+ q31_t * pDst,
+ uint32_t blockSize);
+
+
+/**
+ * @brief Initialization function for the floating-point FIR lattice filter.
+ * @param[in] S points to an instance of the floating-point FIR lattice structure.
+ * @param[in] numStages number of filter stages.
+ * @param[in] pCoeffs points to the coefficient buffer. The array is of length numStages.
+ * @param[in] pState points to the state buffer. The array is of length numStages.
+ */
+ void arm_fir_lattice_init_f32(
+ arm_fir_lattice_instance_f32 * S,
+ uint16_t numStages,
+ float32_t * pCoeffs,
+ float32_t * pState);
+
+
+ /**
+ * @brief Processing function for the floating-point FIR lattice filter.
+ * @param[in] S points to an instance of the floating-point FIR lattice structure.
+ * @param[in] pSrc points to the block of input data.
+ * @param[out] pDst points to the block of output data
+ * @param[in] blockSize number of samples to process.
+ */
+ void arm_fir_lattice_f32(
+ const arm_fir_lattice_instance_f32 * S,
+ float32_t * pSrc,
+ float32_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Instance structure for the Q15 IIR lattice filter.
+ */
+ typedef struct
+ {
+ uint16_t numStages; /**< number of stages in the filter. */
+ q15_t *pState; /**< points to the state variable array. The array is of length numStages+blockSize. */
+ q15_t *pkCoeffs; /**< points to the reflection coefficient array. The array is of length numStages. */
+ q15_t *pvCoeffs; /**< points to the ladder coefficient array. The array is of length numStages+1. */
+ } arm_iir_lattice_instance_q15;
+
+ /**
+ * @brief Instance structure for the Q31 IIR lattice filter.
+ */
+ typedef struct
+ {
+ uint16_t numStages; /**< number of stages in the filter. */
+ q31_t *pState; /**< points to the state variable array. The array is of length numStages+blockSize. */
+ q31_t *pkCoeffs; /**< points to the reflection coefficient array. The array is of length numStages. */
+ q31_t *pvCoeffs; /**< points to the ladder coefficient array. The array is of length numStages+1. */
+ } arm_iir_lattice_instance_q31;
+
+ /**
+ * @brief Instance structure for the floating-point IIR lattice filter.
+ */
+ typedef struct
+ {
+ uint16_t numStages; /**< number of stages in the filter. */
+ float32_t *pState; /**< points to the state variable array. The array is of length numStages+blockSize. */
+ float32_t *pkCoeffs; /**< points to the reflection coefficient array. The array is of length numStages. */
+ float32_t *pvCoeffs; /**< points to the ladder coefficient array. The array is of length numStages+1. */
+ } arm_iir_lattice_instance_f32;
+
+
+ /**
+ * @brief Processing function for the floating-point IIR lattice filter.
+ * @param[in] S points to an instance of the floating-point IIR lattice structure.
+ * @param[in] pSrc points to the block of input data.
+ * @param[out] pDst points to the block of output data.
+ * @param[in] blockSize number of samples to process.
+ */
+ void arm_iir_lattice_f32(
+ const arm_iir_lattice_instance_f32 * S,
+ float32_t * pSrc,
+ float32_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Initialization function for the floating-point IIR lattice filter.
+ * @param[in] S points to an instance of the floating-point IIR lattice structure.
+ * @param[in] numStages number of stages in the filter.
+ * @param[in] pkCoeffs points to the reflection coefficient buffer. The array is of length numStages.
+ * @param[in] pvCoeffs points to the ladder coefficient buffer. The array is of length numStages+1.
+ * @param[in] pState points to the state buffer. The array is of length numStages+blockSize-1.
+ * @param[in] blockSize number of samples to process.
+ */
+ void arm_iir_lattice_init_f32(
+ arm_iir_lattice_instance_f32 * S,
+ uint16_t numStages,
+ float32_t * pkCoeffs,
+ float32_t * pvCoeffs,
+ float32_t * pState,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Processing function for the Q31 IIR lattice filter.
+ * @param[in] S points to an instance of the Q31 IIR lattice structure.
+ * @param[in] pSrc points to the block of input data.
+ * @param[out] pDst points to the block of output data.
+ * @param[in] blockSize number of samples to process.
+ */
+ void arm_iir_lattice_q31(
+ const arm_iir_lattice_instance_q31 * S,
+ q31_t * pSrc,
+ q31_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Initialization function for the Q31 IIR lattice filter.
+ * @param[in] S points to an instance of the Q31 IIR lattice structure.
+ * @param[in] numStages number of stages in the filter.
+ * @param[in] pkCoeffs points to the reflection coefficient buffer. The array is of length numStages.
+ * @param[in] pvCoeffs points to the ladder coefficient buffer. The array is of length numStages+1.
+ * @param[in] pState points to the state buffer. The array is of length numStages+blockSize.
+ * @param[in] blockSize number of samples to process.
+ */
+ void arm_iir_lattice_init_q31(
+ arm_iir_lattice_instance_q31 * S,
+ uint16_t numStages,
+ q31_t * pkCoeffs,
+ q31_t * pvCoeffs,
+ q31_t * pState,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Processing function for the Q15 IIR lattice filter.
+ * @param[in] S points to an instance of the Q15 IIR lattice structure.
+ * @param[in] pSrc points to the block of input data.
+ * @param[out] pDst points to the block of output data.
+ * @param[in] blockSize number of samples to process.
+ */
+ void arm_iir_lattice_q15(
+ const arm_iir_lattice_instance_q15 * S,
+ q15_t * pSrc,
+ q15_t * pDst,
+ uint32_t blockSize);
+
+
+/**
+ * @brief Initialization function for the Q15 IIR lattice filter.
+ * @param[in] S points to an instance of the fixed-point Q15 IIR lattice structure.
+ * @param[in] numStages number of stages in the filter.
+ * @param[in] pkCoeffs points to reflection coefficient buffer. The array is of length numStages.
+ * @param[in] pvCoeffs points to ladder coefficient buffer. The array is of length numStages+1.
+ * @param[in] pState points to state buffer. The array is of length numStages+blockSize.
+ * @param[in] blockSize number of samples to process per call.
+ */
+ void arm_iir_lattice_init_q15(
+ arm_iir_lattice_instance_q15 * S,
+ uint16_t numStages,
+ q15_t * pkCoeffs,
+ q15_t * pvCoeffs,
+ q15_t * pState,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Instance structure for the floating-point LMS filter.
+ */
+ typedef struct
+ {
+ uint16_t numTaps; /**< number of coefficients in the filter. */
+ float32_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */
+ float32_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps. */
+ float32_t mu; /**< step size that controls filter coefficient updates. */
+ } arm_lms_instance_f32;
+
+
+ /**
+ * @brief Processing function for floating-point LMS filter.
+ * @param[in] S points to an instance of the floating-point LMS filter structure.
+ * @param[in] pSrc points to the block of input data.
+ * @param[in] pRef points to the block of reference data.
+ * @param[out] pOut points to the block of output data.
+ * @param[out] pErr points to the block of error data.
+ * @param[in] blockSize number of samples to process.
+ */
+ void arm_lms_f32(
+ const arm_lms_instance_f32 * S,
+ float32_t * pSrc,
+ float32_t * pRef,
+ float32_t * pOut,
+ float32_t * pErr,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Initialization function for floating-point LMS filter.
+ * @param[in] S points to an instance of the floating-point LMS filter structure.
+ * @param[in] numTaps number of filter coefficients.
+ * @param[in] pCoeffs points to the coefficient buffer.
+ * @param[in] pState points to state buffer.
+ * @param[in] mu step size that controls filter coefficient updates.
+ * @param[in] blockSize number of samples to process.
+ */
+ void arm_lms_init_f32(
+ arm_lms_instance_f32 * S,
+ uint16_t numTaps,
+ float32_t * pCoeffs,
+ float32_t * pState,
+ float32_t mu,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Instance structure for the Q15 LMS filter.
+ */
+ typedef struct
+ {
+ uint16_t numTaps; /**< number of coefficients in the filter. */
+ q15_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */
+ q15_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps. */
+ q15_t mu; /**< step size that controls filter coefficient updates. */
+ uint32_t postShift; /**< bit shift applied to coefficients. */
+ } arm_lms_instance_q15;
+
+
+ /**
+ * @brief Initialization function for the Q15 LMS filter.
+ * @param[in] S points to an instance of the Q15 LMS filter structure.
+ * @param[in] numTaps number of filter coefficients.
+ * @param[in] pCoeffs points to the coefficient buffer.
+ * @param[in] pState points to the state buffer.
+ * @param[in] mu step size that controls filter coefficient updates.
+ * @param[in] blockSize number of samples to process.
+ * @param[in] postShift bit shift applied to coefficients.
+ */
+ void arm_lms_init_q15(
+ arm_lms_instance_q15 * S,
+ uint16_t numTaps,
+ q15_t * pCoeffs,
+ q15_t * pState,
+ q15_t mu,
+ uint32_t blockSize,
+ uint32_t postShift);
+
+
+ /**
+ * @brief Processing function for Q15 LMS filter.
+ * @param[in] S points to an instance of the Q15 LMS filter structure.
+ * @param[in] pSrc points to the block of input data.
+ * @param[in] pRef points to the block of reference data.
+ * @param[out] pOut points to the block of output data.
+ * @param[out] pErr points to the block of error data.
+ * @param[in] blockSize number of samples to process.
+ */
+ void arm_lms_q15(
+ const arm_lms_instance_q15 * S,
+ q15_t * pSrc,
+ q15_t * pRef,
+ q15_t * pOut,
+ q15_t * pErr,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Instance structure for the Q31 LMS filter.
+ */
+ typedef struct
+ {
+ uint16_t numTaps; /**< number of coefficients in the filter. */
+ q31_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */
+ q31_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps. */
+ q31_t mu; /**< step size that controls filter coefficient updates. */
+ uint32_t postShift; /**< bit shift applied to coefficients. */
+ } arm_lms_instance_q31;
+
+
+ /**
+ * @brief Processing function for Q31 LMS filter.
+ * @param[in] S points to an instance of the Q15 LMS filter structure.
+ * @param[in] pSrc points to the block of input data.
+ * @param[in] pRef points to the block of reference data.
+ * @param[out] pOut points to the block of output data.
+ * @param[out] pErr points to the block of error data.
+ * @param[in] blockSize number of samples to process.
+ */
+ void arm_lms_q31(
+ const arm_lms_instance_q31 * S,
+ q31_t * pSrc,
+ q31_t * pRef,
+ q31_t * pOut,
+ q31_t * pErr,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Initialization function for Q31 LMS filter.
+ * @param[in] S points to an instance of the Q31 LMS filter structure.
+ * @param[in] numTaps number of filter coefficients.
+ * @param[in] pCoeffs points to coefficient buffer.
+ * @param[in] pState points to state buffer.
+ * @param[in] mu step size that controls filter coefficient updates.
+ * @param[in] blockSize number of samples to process.
+ * @param[in] postShift bit shift applied to coefficients.
+ */
+ void arm_lms_init_q31(
+ arm_lms_instance_q31 * S,
+ uint16_t numTaps,
+ q31_t * pCoeffs,
+ q31_t * pState,
+ q31_t mu,
+ uint32_t blockSize,
+ uint32_t postShift);
+
+
+ /**
+ * @brief Instance structure for the floating-point normalized LMS filter.
+ */
+ typedef struct
+ {
+ uint16_t numTaps; /**< number of coefficients in the filter. */
+ float32_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */
+ float32_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps. */
+ float32_t mu; /**< step size that control filter coefficient updates. */
+ float32_t energy; /**< saves previous frame energy. */
+ float32_t x0; /**< saves previous input sample. */
+ } arm_lms_norm_instance_f32;
+
+
+ /**
+ * @brief Processing function for floating-point normalized LMS filter.
+ * @param[in] S points to an instance of the floating-point normalized LMS filter structure.
+ * @param[in] pSrc points to the block of input data.
+ * @param[in] pRef points to the block of reference data.
+ * @param[out] pOut points to the block of output data.
+ * @param[out] pErr points to the block of error data.
+ * @param[in] blockSize number of samples to process.
+ */
+ void arm_lms_norm_f32(
+ arm_lms_norm_instance_f32 * S,
+ float32_t * pSrc,
+ float32_t * pRef,
+ float32_t * pOut,
+ float32_t * pErr,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Initialization function for floating-point normalized LMS filter.
+ * @param[in] S points to an instance of the floating-point LMS filter structure.
+ * @param[in] numTaps number of filter coefficients.
+ * @param[in] pCoeffs points to coefficient buffer.
+ * @param[in] pState points to state buffer.
+ * @param[in] mu step size that controls filter coefficient updates.
+ * @param[in] blockSize number of samples to process.
+ */
+ void arm_lms_norm_init_f32(
+ arm_lms_norm_instance_f32 * S,
+ uint16_t numTaps,
+ float32_t * pCoeffs,
+ float32_t * pState,
+ float32_t mu,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Instance structure for the Q31 normalized LMS filter.
+ */
+ typedef struct
+ {
+ uint16_t numTaps; /**< number of coefficients in the filter. */
+ q31_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */
+ q31_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps. */
+ q31_t mu; /**< step size that controls filter coefficient updates. */
+ uint8_t postShift; /**< bit shift applied to coefficients. */
+ q31_t *recipTable; /**< points to the reciprocal initial value table. */
+ q31_t energy; /**< saves previous frame energy. */
+ q31_t x0; /**< saves previous input sample. */
+ } arm_lms_norm_instance_q31;
+
+
+ /**
+ * @brief Processing function for Q31 normalized LMS filter.
+ * @param[in] S points to an instance of the Q31 normalized LMS filter structure.
+ * @param[in] pSrc points to the block of input data.
+ * @param[in] pRef points to the block of reference data.
+ * @param[out] pOut points to the block of output data.
+ * @param[out] pErr points to the block of error data.
+ * @param[in] blockSize number of samples to process.
+ */
+ void arm_lms_norm_q31(
+ arm_lms_norm_instance_q31 * S,
+ q31_t * pSrc,
+ q31_t * pRef,
+ q31_t * pOut,
+ q31_t * pErr,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Initialization function for Q31 normalized LMS filter.
+ * @param[in] S points to an instance of the Q31 normalized LMS filter structure.
+ * @param[in] numTaps number of filter coefficients.
+ * @param[in] pCoeffs points to coefficient buffer.
+ * @param[in] pState points to state buffer.
+ * @param[in] mu step size that controls filter coefficient updates.
+ * @param[in] blockSize number of samples to process.
+ * @param[in] postShift bit shift applied to coefficients.
+ */
+ void arm_lms_norm_init_q31(
+ arm_lms_norm_instance_q31 * S,
+ uint16_t numTaps,
+ q31_t * pCoeffs,
+ q31_t * pState,
+ q31_t mu,
+ uint32_t blockSize,
+ uint8_t postShift);
+
+
+ /**
+ * @brief Instance structure for the Q15 normalized LMS filter.
+ */
+ typedef struct
+ {
+ uint16_t numTaps; /**< Number of coefficients in the filter. */
+ q15_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */
+ q15_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps. */
+ q15_t mu; /**< step size that controls filter coefficient updates. */
+ uint8_t postShift; /**< bit shift applied to coefficients. */
+ q15_t *recipTable; /**< Points to the reciprocal initial value table. */
+ q15_t energy; /**< saves previous frame energy. */
+ q15_t x0; /**< saves previous input sample. */
+ } arm_lms_norm_instance_q15;
+
+
+ /**
+ * @brief Processing function for Q15 normalized LMS filter.
+ * @param[in] S points to an instance of the Q15 normalized LMS filter structure.
+ * @param[in] pSrc points to the block of input data.
+ * @param[in] pRef points to the block of reference data.
+ * @param[out] pOut points to the block of output data.
+ * @param[out] pErr points to the block of error data.
+ * @param[in] blockSize number of samples to process.
+ */
+ void arm_lms_norm_q15(
+ arm_lms_norm_instance_q15 * S,
+ q15_t * pSrc,
+ q15_t * pRef,
+ q15_t * pOut,
+ q15_t * pErr,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Initialization function for Q15 normalized LMS filter.
+ * @param[in] S points to an instance of the Q15 normalized LMS filter structure.
+ * @param[in] numTaps number of filter coefficients.
+ * @param[in] pCoeffs points to coefficient buffer.
+ * @param[in] pState points to state buffer.
+ * @param[in] mu step size that controls filter coefficient updates.
+ * @param[in] blockSize number of samples to process.
+ * @param[in] postShift bit shift applied to coefficients.
+ */
+ void arm_lms_norm_init_q15(
+ arm_lms_norm_instance_q15 * S,
+ uint16_t numTaps,
+ q15_t * pCoeffs,
+ q15_t * pState,
+ q15_t mu,
+ uint32_t blockSize,
+ uint8_t postShift);
+
+
+ /**
+ * @brief Correlation of floating-point sequences.
+ * @param[in] pSrcA points to the first input sequence.
+ * @param[in] srcALen length of the first input sequence.
+ * @param[in] pSrcB points to the second input sequence.
+ * @param[in] srcBLen length of the second input sequence.
+ * @param[out] pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1.
+ */
+ void arm_correlate_f32(
+ float32_t * pSrcA,
+ uint32_t srcALen,
+ float32_t * pSrcB,
+ uint32_t srcBLen,
+ float32_t * pDst);
+
+
+ /**
+ * @brief Correlation of Q15 sequences
+ * @param[in] pSrcA points to the first input sequence.
+ * @param[in] srcALen length of the first input sequence.
+ * @param[in] pSrcB points to the second input sequence.
+ * @param[in] srcBLen length of the second input sequence.
+ * @param[out] pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1.
+ * @param[in] pScratch points to scratch buffer of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2.
+ */
+ void arm_correlate_opt_q15(
+ q15_t * pSrcA,
+ uint32_t srcALen,
+ q15_t * pSrcB,
+ uint32_t srcBLen,
+ q15_t * pDst,
+ q15_t * pScratch);
+
+
+ /**
+ * @brief Correlation of Q15 sequences.
+ * @param[in] pSrcA points to the first input sequence.
+ * @param[in] srcALen length of the first input sequence.
+ * @param[in] pSrcB points to the second input sequence.
+ * @param[in] srcBLen length of the second input sequence.
+ * @param[out] pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1.
+ */
+
+ void arm_correlate_q15(
+ q15_t * pSrcA,
+ uint32_t srcALen,
+ q15_t * pSrcB,
+ uint32_t srcBLen,
+ q15_t * pDst);
+
+
+ /**
+ * @brief Correlation of Q15 sequences (fast version) for Cortex-M3 and Cortex-M4.
+ * @param[in] pSrcA points to the first input sequence.
+ * @param[in] srcALen length of the first input sequence.
+ * @param[in] pSrcB points to the second input sequence.
+ * @param[in] srcBLen length of the second input sequence.
+ * @param[out] pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1.
+ */
+
+ void arm_correlate_fast_q15(
+ q15_t * pSrcA,
+ uint32_t srcALen,
+ q15_t * pSrcB,
+ uint32_t srcBLen,
+ q15_t * pDst);
+
+
+ /**
+ * @brief Correlation of Q15 sequences (fast version) for Cortex-M3 and Cortex-M4.
+ * @param[in] pSrcA points to the first input sequence.
+ * @param[in] srcALen length of the first input sequence.
+ * @param[in] pSrcB points to the second input sequence.
+ * @param[in] srcBLen length of the second input sequence.
+ * @param[out] pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1.
+ * @param[in] pScratch points to scratch buffer of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2.
+ */
+ void arm_correlate_fast_opt_q15(
+ q15_t * pSrcA,
+ uint32_t srcALen,
+ q15_t * pSrcB,
+ uint32_t srcBLen,
+ q15_t * pDst,
+ q15_t * pScratch);
+
+
+ /**
+ * @brief Correlation of Q31 sequences.
+ * @param[in] pSrcA points to the first input sequence.
+ * @param[in] srcALen length of the first input sequence.
+ * @param[in] pSrcB points to the second input sequence.
+ * @param[in] srcBLen length of the second input sequence.
+ * @param[out] pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1.
+ */
+ void arm_correlate_q31(
+ q31_t * pSrcA,
+ uint32_t srcALen,
+ q31_t * pSrcB,
+ uint32_t srcBLen,
+ q31_t * pDst);
+
+
+ /**
+ * @brief Correlation of Q31 sequences (fast version) for Cortex-M3 and Cortex-M4
+ * @param[in] pSrcA points to the first input sequence.
+ * @param[in] srcALen length of the first input sequence.
+ * @param[in] pSrcB points to the second input sequence.
+ * @param[in] srcBLen length of the second input sequence.
+ * @param[out] pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1.
+ */
+ void arm_correlate_fast_q31(
+ q31_t * pSrcA,
+ uint32_t srcALen,
+ q31_t * pSrcB,
+ uint32_t srcBLen,
+ q31_t * pDst);
+
+
+ /**
+ * @brief Correlation of Q7 sequences.
+ * @param[in] pSrcA points to the first input sequence.
+ * @param[in] srcALen length of the first input sequence.
+ * @param[in] pSrcB points to the second input sequence.
+ * @param[in] srcBLen length of the second input sequence.
+ * @param[out] pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1.
+ * @param[in] pScratch1 points to scratch buffer(of type q15_t) of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2.
+ * @param[in] pScratch2 points to scratch buffer (of type q15_t) of size min(srcALen, srcBLen).
+ */
+ void arm_correlate_opt_q7(
+ q7_t * pSrcA,
+ uint32_t srcALen,
+ q7_t * pSrcB,
+ uint32_t srcBLen,
+ q7_t * pDst,
+ q15_t * pScratch1,
+ q15_t * pScratch2);
+
+
+ /**
+ * @brief Correlation of Q7 sequences.
+ * @param[in] pSrcA points to the first input sequence.
+ * @param[in] srcALen length of the first input sequence.
+ * @param[in] pSrcB points to the second input sequence.
+ * @param[in] srcBLen length of the second input sequence.
+ * @param[out] pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1.
+ */
+ void arm_correlate_q7(
+ q7_t * pSrcA,
+ uint32_t srcALen,
+ q7_t * pSrcB,
+ uint32_t srcBLen,
+ q7_t * pDst);
+
+
+ /**
+ * @brief Instance structure for the floating-point sparse FIR filter.
+ */
+ typedef struct
+ {
+ uint16_t numTaps; /**< number of coefficients in the filter. */
+ uint16_t stateIndex; /**< state buffer index. Points to the oldest sample in the state buffer. */
+ float32_t *pState; /**< points to the state buffer array. The array is of length maxDelay+blockSize-1. */
+ float32_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/
+ uint16_t maxDelay; /**< maximum offset specified by the pTapDelay array. */
+ int32_t *pTapDelay; /**< points to the array of delay values. The array is of length numTaps. */
+ } arm_fir_sparse_instance_f32;
+
+ /**
+ * @brief Instance structure for the Q31 sparse FIR filter.
+ */
+ typedef struct
+ {
+ uint16_t numTaps; /**< number of coefficients in the filter. */
+ uint16_t stateIndex; /**< state buffer index. Points to the oldest sample in the state buffer. */
+ q31_t *pState; /**< points to the state buffer array. The array is of length maxDelay+blockSize-1. */
+ q31_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/
+ uint16_t maxDelay; /**< maximum offset specified by the pTapDelay array. */
+ int32_t *pTapDelay; /**< points to the array of delay values. The array is of length numTaps. */
+ } arm_fir_sparse_instance_q31;
+
+ /**
+ * @brief Instance structure for the Q15 sparse FIR filter.
+ */
+ typedef struct
+ {
+ uint16_t numTaps; /**< number of coefficients in the filter. */
+ uint16_t stateIndex; /**< state buffer index. Points to the oldest sample in the state buffer. */
+ q15_t *pState; /**< points to the state buffer array. The array is of length maxDelay+blockSize-1. */
+ q15_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/
+ uint16_t maxDelay; /**< maximum offset specified by the pTapDelay array. */
+ int32_t *pTapDelay; /**< points to the array of delay values. The array is of length numTaps. */
+ } arm_fir_sparse_instance_q15;
+
+ /**
+ * @brief Instance structure for the Q7 sparse FIR filter.
+ */
+ typedef struct
+ {
+ uint16_t numTaps; /**< number of coefficients in the filter. */
+ uint16_t stateIndex; /**< state buffer index. Points to the oldest sample in the state buffer. */
+ q7_t *pState; /**< points to the state buffer array. The array is of length maxDelay+blockSize-1. */
+ q7_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/
+ uint16_t maxDelay; /**< maximum offset specified by the pTapDelay array. */
+ int32_t *pTapDelay; /**< points to the array of delay values. The array is of length numTaps. */
+ } arm_fir_sparse_instance_q7;
+
+
+ /**
+ * @brief Processing function for the floating-point sparse FIR filter.
+ * @param[in] S points to an instance of the floating-point sparse FIR structure.
+ * @param[in] pSrc points to the block of input data.
+ * @param[out] pDst points to the block of output data
+ * @param[in] pScratchIn points to a temporary buffer of size blockSize.
+ * @param[in] blockSize number of input samples to process per call.
+ */
+ void arm_fir_sparse_f32(
+ arm_fir_sparse_instance_f32 * S,
+ float32_t * pSrc,
+ float32_t * pDst,
+ float32_t * pScratchIn,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Initialization function for the floating-point sparse FIR filter.
+ * @param[in,out] S points to an instance of the floating-point sparse FIR structure.
+ * @param[in] numTaps number of nonzero coefficients in the filter.
+ * @param[in] pCoeffs points to the array of filter coefficients.
+ * @param[in] pState points to the state buffer.
+ * @param[in] pTapDelay points to the array of offset times.
+ * @param[in] maxDelay maximum offset time supported.
+ * @param[in] blockSize number of samples that will be processed per block.
+ */
+ void arm_fir_sparse_init_f32(
+ arm_fir_sparse_instance_f32 * S,
+ uint16_t numTaps,
+ float32_t * pCoeffs,
+ float32_t * pState,
+ int32_t * pTapDelay,
+ uint16_t maxDelay,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Processing function for the Q31 sparse FIR filter.
+ * @param[in] S points to an instance of the Q31 sparse FIR structure.
+ * @param[in] pSrc points to the block of input data.
+ * @param[out] pDst points to the block of output data
+ * @param[in] pScratchIn points to a temporary buffer of size blockSize.
+ * @param[in] blockSize number of input samples to process per call.
+ */
+ void arm_fir_sparse_q31(
+ arm_fir_sparse_instance_q31 * S,
+ q31_t * pSrc,
+ q31_t * pDst,
+ q31_t * pScratchIn,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Initialization function for the Q31 sparse FIR filter.
+ * @param[in,out] S points to an instance of the Q31 sparse FIR structure.
+ * @param[in] numTaps number of nonzero coefficients in the filter.
+ * @param[in] pCoeffs points to the array of filter coefficients.
+ * @param[in] pState points to the state buffer.
+ * @param[in] pTapDelay points to the array of offset times.
+ * @param[in] maxDelay maximum offset time supported.
+ * @param[in] blockSize number of samples that will be processed per block.
+ */
+ void arm_fir_sparse_init_q31(
+ arm_fir_sparse_instance_q31 * S,
+ uint16_t numTaps,
+ q31_t * pCoeffs,
+ q31_t * pState,
+ int32_t * pTapDelay,
+ uint16_t maxDelay,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Processing function for the Q15 sparse FIR filter.
+ * @param[in] S points to an instance of the Q15 sparse FIR structure.
+ * @param[in] pSrc points to the block of input data.
+ * @param[out] pDst points to the block of output data
+ * @param[in] pScratchIn points to a temporary buffer of size blockSize.
+ * @param[in] pScratchOut points to a temporary buffer of size blockSize.
+ * @param[in] blockSize number of input samples to process per call.
+ */
+ void arm_fir_sparse_q15(
+ arm_fir_sparse_instance_q15 * S,
+ q15_t * pSrc,
+ q15_t * pDst,
+ q15_t * pScratchIn,
+ q31_t * pScratchOut,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Initialization function for the Q15 sparse FIR filter.
+ * @param[in,out] S points to an instance of the Q15 sparse FIR structure.
+ * @param[in] numTaps number of nonzero coefficients in the filter.
+ * @param[in] pCoeffs points to the array of filter coefficients.
+ * @param[in] pState points to the state buffer.
+ * @param[in] pTapDelay points to the array of offset times.
+ * @param[in] maxDelay maximum offset time supported.
+ * @param[in] blockSize number of samples that will be processed per block.
+ */
+ void arm_fir_sparse_init_q15(
+ arm_fir_sparse_instance_q15 * S,
+ uint16_t numTaps,
+ q15_t * pCoeffs,
+ q15_t * pState,
+ int32_t * pTapDelay,
+ uint16_t maxDelay,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Processing function for the Q7 sparse FIR filter.
+ * @param[in] S points to an instance of the Q7 sparse FIR structure.
+ * @param[in] pSrc points to the block of input data.
+ * @param[out] pDst points to the block of output data
+ * @param[in] pScratchIn points to a temporary buffer of size blockSize.
+ * @param[in] pScratchOut points to a temporary buffer of size blockSize.
+ * @param[in] blockSize number of input samples to process per call.
+ */
+ void arm_fir_sparse_q7(
+ arm_fir_sparse_instance_q7 * S,
+ q7_t * pSrc,
+ q7_t * pDst,
+ q7_t * pScratchIn,
+ q31_t * pScratchOut,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Initialization function for the Q7 sparse FIR filter.
+ * @param[in,out] S points to an instance of the Q7 sparse FIR structure.
+ * @param[in] numTaps number of nonzero coefficients in the filter.
+ * @param[in] pCoeffs points to the array of filter coefficients.
+ * @param[in] pState points to the state buffer.
+ * @param[in] pTapDelay points to the array of offset times.
+ * @param[in] maxDelay maximum offset time supported.
+ * @param[in] blockSize number of samples that will be processed per block.
+ */
+ void arm_fir_sparse_init_q7(
+ arm_fir_sparse_instance_q7 * S,
+ uint16_t numTaps,
+ q7_t * pCoeffs,
+ q7_t * pState,
+ int32_t * pTapDelay,
+ uint16_t maxDelay,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Floating-point sin_cos function.
+ * @param[in] theta input value in degrees
+ * @param[out] pSinVal points to the processed sine output.
+ * @param[out] pCosVal points to the processed cos output.
+ */
+ void arm_sin_cos_f32(
+ float32_t theta,
+ float32_t * pSinVal,
+ float32_t * pCosVal);
+
+
+ /**
+ * @brief Q31 sin_cos function.
+ * @param[in] theta scaled input value in degrees
+ * @param[out] pSinVal points to the processed sine output.
+ * @param[out] pCosVal points to the processed cosine output.
+ */
+ void arm_sin_cos_q31(
+ q31_t theta,
+ q31_t * pSinVal,
+ q31_t * pCosVal);
+
+
+ /**
+ * @brief Floating-point complex conjugate.
+ * @param[in] pSrc points to the input vector
+ * @param[out] pDst points to the output vector
+ * @param[in] numSamples number of complex samples in each vector
+ */
+ void arm_cmplx_conj_f32(
+ float32_t * pSrc,
+ float32_t * pDst,
+ uint32_t numSamples);
+
+ /**
+ * @brief Q31 complex conjugate.
+ * @param[in] pSrc points to the input vector
+ * @param[out] pDst points to the output vector
+ * @param[in] numSamples number of complex samples in each vector
+ */
+ void arm_cmplx_conj_q31(
+ q31_t * pSrc,
+ q31_t * pDst,
+ uint32_t numSamples);
+
+
+ /**
+ * @brief Q15 complex conjugate.
+ * @param[in] pSrc points to the input vector
+ * @param[out] pDst points to the output vector
+ * @param[in] numSamples number of complex samples in each vector
+ */
+ void arm_cmplx_conj_q15(
+ q15_t * pSrc,
+ q15_t * pDst,
+ uint32_t numSamples);
+
+
+ /**
+ * @brief Floating-point complex magnitude squared
+ * @param[in] pSrc points to the complex input vector
+ * @param[out] pDst points to the real output vector
+ * @param[in] numSamples number of complex samples in the input vector
+ */
+ void arm_cmplx_mag_squared_f32(
+ float32_t * pSrc,
+ float32_t * pDst,
+ uint32_t numSamples);
+
+
+ /**
+ * @brief Q31 complex magnitude squared
+ * @param[in] pSrc points to the complex input vector
+ * @param[out] pDst points to the real output vector
+ * @param[in] numSamples number of complex samples in the input vector
+ */
+ void arm_cmplx_mag_squared_q31(
+ q31_t * pSrc,
+ q31_t * pDst,
+ uint32_t numSamples);
+
+
+ /**
+ * @brief Q15 complex magnitude squared
+ * @param[in] pSrc points to the complex input vector
+ * @param[out] pDst points to the real output vector
+ * @param[in] numSamples number of complex samples in the input vector
+ */
+ void arm_cmplx_mag_squared_q15(
+ q15_t * pSrc,
+ q15_t * pDst,
+ uint32_t numSamples);
+
+
+ /**
+ * @ingroup groupController
+ */
+
+ /**
+ * @defgroup PID PID Motor Control
+ *
+ * A Proportional Integral Derivative (PID) controller is a generic feedback control
+ * loop mechanism widely used in industrial control systems.
+ * A PID controller is the most commonly used type of feedback controller.
+ *
+ * This set of functions implements (PID) controllers
+ * for Q15, Q31, and floating-point data types. The functions operate on a single sample
+ * of data and each call to the function returns a single processed value.
+ * <code>S</code> points to an instance of the PID control data structure. <code>in</code>
+ * is the input sample value. The functions return the output value.
+ *
+ * \par Algorithm:
+ * <pre>
+ * y[n] = y[n-1] + A0 * x[n] + A1 * x[n-1] + A2 * x[n-2]
+ * A0 = Kp + Ki + Kd
+ * A1 = (-Kp ) - (2 * Kd )
+ * A2 = Kd </pre>
+ *
+ * \par
+ * where \c Kp is proportional constant, \c Ki is Integral constant and \c Kd is Derivative constant
+ *
+ * \par
+ * \image html PID.gif "Proportional Integral Derivative Controller"
+ *
+ * \par
+ * The PID controller calculates an "error" value as the difference between
+ * the measured output and the reference input.
+ * The controller attempts to minimize the error by adjusting the process control inputs.
+ * The proportional value determines the reaction to the current error,
+ * the integral value determines the reaction based on the sum of recent errors,
+ * and the derivative value determines the reaction based on the rate at which the error has been changing.
+ *
+ * \par Instance Structure
+ * The Gains A0, A1, A2 and state variables for a PID controller are stored together in an instance data structure.
+ * A separate instance structure must be defined for each PID Controller.
+ * There are separate instance structure declarations for each of the 3 supported data types.
+ *
+ * \par Reset Functions
+ * There is also an associated reset function for each data type which clears the state array.
+ *
+ * \par Initialization Functions
+ * There is also an associated initialization function for each data type.
+ * The initialization function performs the following operations:
+ * - Initializes the Gains A0, A1, A2 from Kp,Ki, Kd gains.
+ * - Zeros out the values in the state buffer.
+ *
+ * \par
+ * Instance structure cannot be placed into a const data section and it is recommended to use the initialization function.
+ *
+ * \par Fixed-Point Behavior
+ * Care must be taken when using the fixed-point versions of the PID Controller functions.
+ * In particular, the overflow and saturation behavior of the accumulator used in each function must be considered.
+ * Refer to the function specific documentation below for usage guidelines.
+ */
+
+ /**
+ * @addtogroup PID
+ * @{
+ */
+
+ /**
+ * @brief Process function for the floating-point PID Control.
+ * @param[in,out] S is an instance of the floating-point PID Control structure
+ * @param[in] in input sample to process
+ * @return out processed output sample.
+ */
+ CMSIS_INLINE __STATIC_INLINE float32_t arm_pid_f32(
+ arm_pid_instance_f32 * S,
+ float32_t in)
+ {
+ float32_t out;
+
+ /* y[n] = y[n-1] + A0 * x[n] + A1 * x[n-1] + A2 * x[n-2] */
+ out = (S->A0 * in) +
+ (S->A1 * S->state[0]) + (S->A2 * S->state[1]) + (S->state[2]);
+
+ /* Update state */
+ S->state[1] = S->state[0];
+ S->state[0] = in;
+ S->state[2] = out;
+
+ /* return to application */
+ return (out);
+
+ }
+
+ /**
+ * @brief Process function for the Q31 PID Control.
+ * @param[in,out] S points to an instance of the Q31 PID Control structure
+ * @param[in] in input sample to process
+ * @return out processed output sample.
+ *
+ * <b>Scaling and Overflow Behavior:</b>
+ * \par
+ * The function is implemented using an internal 64-bit accumulator.
+ * The accumulator has a 2.62 format and maintains full precision of the intermediate multiplication results but provides only a single guard bit.
+ * Thus, if the accumulator result overflows it wraps around rather than clip.
+ * In order to avoid overflows completely the input signal must be scaled down by 2 bits as there are four additions.
+ * After all multiply-accumulates are performed, the 2.62 accumulator is truncated to 1.32 format and then saturated to 1.31 format.
+ */
+ CMSIS_INLINE __STATIC_INLINE q31_t arm_pid_q31(
+ arm_pid_instance_q31 * S,
+ q31_t in)
+ {
+ q63_t acc;
+ q31_t out;
+
+ /* acc = A0 * x[n] */
+ acc = (q63_t) S->A0 * in;
+
+ /* acc += A1 * x[n-1] */
+ acc += (q63_t) S->A1 * S->state[0];
+
+ /* acc += A2 * x[n-2] */
+ acc += (q63_t) S->A2 * S->state[1];
+
+ /* convert output to 1.31 format to add y[n-1] */
+ out = (q31_t) (acc >> 31U);
+
+ /* out += y[n-1] */
+ out += S->state[2];
+
+ /* Update state */
+ S->state[1] = S->state[0];
+ S->state[0] = in;
+ S->state[2] = out;
+
+ /* return to application */
+ return (out);
+ }
+
+
+ /**
+ * @brief Process function for the Q15 PID Control.
+ * @param[in,out] S points to an instance of the Q15 PID Control structure
+ * @param[in] in input sample to process
+ * @return out processed output sample.
+ *
+ * <b>Scaling and Overflow Behavior:</b>
+ * \par
+ * The function is implemented using a 64-bit internal accumulator.
+ * Both Gains and state variables are represented in 1.15 format and multiplications yield a 2.30 result.
+ * The 2.30 intermediate results are accumulated in a 64-bit accumulator in 34.30 format.
+ * There is no risk of internal overflow with this approach and the full precision of intermediate multiplications is preserved.
+ * After all additions have been performed, the accumulator is truncated to 34.15 format by discarding low 15 bits.
+ * Lastly, the accumulator is saturated to yield a result in 1.15 format.
+ */
+ CMSIS_INLINE __STATIC_INLINE q15_t arm_pid_q15(
+ arm_pid_instance_q15 * S,
+ q15_t in)
+ {
+ q63_t acc;
+ q15_t out;
+
+#if defined (ARM_MATH_DSP)
+ __SIMD32_TYPE *vstate;
+
+ /* Implementation of PID controller */
+
+ /* acc = A0 * x[n] */
+ acc = (q31_t) __SMUAD((uint32_t)S->A0, (uint32_t)in);
+
+ /* acc += A1 * x[n-1] + A2 * x[n-2] */
+ vstate = __SIMD32_CONST(S->state);
+ acc = (q63_t)__SMLALD((uint32_t)S->A1, (uint32_t)*vstate, (uint64_t)acc);
+#else
+ /* acc = A0 * x[n] */
+ acc = ((q31_t) S->A0) * in;
+
+ /* acc += A1 * x[n-1] + A2 * x[n-2] */
+ acc += (q31_t) S->A1 * S->state[0];
+ acc += (q31_t) S->A2 * S->state[1];
+#endif
+
+ /* acc += y[n-1] */
+ acc += (q31_t) S->state[2] << 15;
+
+ /* saturate the output */
+ out = (q15_t) (__SSAT((acc >> 15), 16));
+
+ /* Update state */
+ S->state[1] = S->state[0];
+ S->state[0] = in;
+ S->state[2] = out;
+
+ /* return to application */
+ return (out);
+ }
+
+ /**
+ * @} end of PID group
+ */
+
+
+ /**
+ * @brief Floating-point matrix inverse.
+ * @param[in] src points to the instance of the input floating-point matrix structure.
+ * @param[out] dst points to the instance of the output floating-point matrix structure.
+ * @return The function returns ARM_MATH_SIZE_MISMATCH, if the dimensions do not match.
+ * If the input matrix is singular (does not have an inverse), then the algorithm terminates and returns error status ARM_MATH_SINGULAR.
+ */
+ arm_status arm_mat_inverse_f32(
+ const arm_matrix_instance_f32 * src,
+ arm_matrix_instance_f32 * dst);
+
+
+ /**
+ * @brief Floating-point matrix inverse.
+ * @param[in] src points to the instance of the input floating-point matrix structure.
+ * @param[out] dst points to the instance of the output floating-point matrix structure.
+ * @return The function returns ARM_MATH_SIZE_MISMATCH, if the dimensions do not match.
+ * If the input matrix is singular (does not have an inverse), then the algorithm terminates and returns error status ARM_MATH_SINGULAR.
+ */
+ arm_status arm_mat_inverse_f64(
+ const arm_matrix_instance_f64 * src,
+ arm_matrix_instance_f64 * dst);
+
+
+
+ /**
+ * @ingroup groupController
+ */
+
+ /**
+ * @defgroup clarke Vector Clarke Transform
+ * Forward Clarke transform converts the instantaneous stator phases into a two-coordinate time invariant vector.
+ * Generally the Clarke transform uses three-phase currents <code>Ia, Ib and Ic</code> to calculate currents
+ * in the two-phase orthogonal stator axis <code>Ialpha</code> and <code>Ibeta</code>.
+ * When <code>Ialpha</code> is superposed with <code>Ia</code> as shown in the figure below
+ * \image html clarke.gif Stator current space vector and its components in (a,b).
+ * and <code>Ia + Ib + Ic = 0</code>, in this condition <code>Ialpha</code> and <code>Ibeta</code>
+ * can be calculated using only <code>Ia</code> and <code>Ib</code>.
+ *
+ * The function operates on a single sample of data and each call to the function returns the processed output.
+ * The library provides separate functions for Q31 and floating-point data types.
+ * \par Algorithm
+ * \image html clarkeFormula.gif
+ * where <code>Ia</code> and <code>Ib</code> are the instantaneous stator phases and
+ * <code>pIalpha</code> and <code>pIbeta</code> are the two coordinates of time invariant vector.
+ * \par Fixed-Point Behavior
+ * Care must be taken when using the Q31 version of the Clarke transform.
+ * In particular, the overflow and saturation behavior of the accumulator used must be considered.
+ * Refer to the function specific documentation below for usage guidelines.
+ */
+
+ /**
+ * @addtogroup clarke
+ * @{
+ */
+
+ /**
+ *
+ * @brief Floating-point Clarke transform
+ * @param[in] Ia input three-phase coordinate <code>a</code>
+ * @param[in] Ib input three-phase coordinate <code>b</code>
+ * @param[out] pIalpha points to output two-phase orthogonal vector axis alpha
+ * @param[out] pIbeta points to output two-phase orthogonal vector axis beta
+ */
+ CMSIS_INLINE __STATIC_INLINE void arm_clarke_f32(
+ float32_t Ia,
+ float32_t Ib,
+ float32_t * pIalpha,
+ float32_t * pIbeta)
+ {
+ /* Calculate pIalpha using the equation, pIalpha = Ia */
+ *pIalpha = Ia;
+
+ /* Calculate pIbeta using the equation, pIbeta = (1/sqrt(3)) * Ia + (2/sqrt(3)) * Ib */
+ *pIbeta = ((float32_t) 0.57735026919 * Ia + (float32_t) 1.15470053838 * Ib);
+ }
+
+
+ /**
+ * @brief Clarke transform for Q31 version
+ * @param[in] Ia input three-phase coordinate <code>a</code>
+ * @param[in] Ib input three-phase coordinate <code>b</code>
+ * @param[out] pIalpha points to output two-phase orthogonal vector axis alpha
+ * @param[out] pIbeta points to output two-phase orthogonal vector axis beta
+ *
+ * <b>Scaling and Overflow Behavior:</b>
+ * \par
+ * The function is implemented using an internal 32-bit accumulator.
+ * The accumulator maintains 1.31 format by truncating lower 31 bits of the intermediate multiplication in 2.62 format.
+ * There is saturation on the addition, hence there is no risk of overflow.
+ */
+ CMSIS_INLINE __STATIC_INLINE void arm_clarke_q31(
+ q31_t Ia,
+ q31_t Ib,
+ q31_t * pIalpha,
+ q31_t * pIbeta)
+ {
+ q31_t product1, product2; /* Temporary variables used to store intermediate results */
+
+ /* Calculating pIalpha from Ia by equation pIalpha = Ia */
+ *pIalpha = Ia;
+
+ /* Intermediate product is calculated by (1/(sqrt(3)) * Ia) */
+ product1 = (q31_t) (((q63_t) Ia * 0x24F34E8B) >> 30);
+
+ /* Intermediate product is calculated by (2/sqrt(3) * Ib) */
+ product2 = (q31_t) (((q63_t) Ib * 0x49E69D16) >> 30);
+
+ /* pIbeta is calculated by adding the intermediate products */
+ *pIbeta = __QADD(product1, product2);
+ }
+
+ /**
+ * @} end of clarke group
+ */
+
+ /**
+ * @brief Converts the elements of the Q7 vector to Q31 vector.
+ * @param[in] pSrc input pointer
+ * @param[out] pDst output pointer
+ * @param[in] blockSize number of samples to process
+ */
+ void arm_q7_to_q31(
+ q7_t * pSrc,
+ q31_t * pDst,
+ uint32_t blockSize);
+
+
+
+ /**
+ * @ingroup groupController
+ */
+
+ /**
+ * @defgroup inv_clarke Vector Inverse Clarke Transform
+ * Inverse Clarke transform converts the two-coordinate time invariant vector into instantaneous stator phases.
+ *
+ * The function operates on a single sample of data and each call to the function returns the processed output.
+ * The library provides separate functions for Q31 and floating-point data types.
+ * \par Algorithm
+ * \image html clarkeInvFormula.gif
+ * where <code>pIa</code> and <code>pIb</code> are the instantaneous stator phases and
+ * <code>Ialpha</code> and <code>Ibeta</code> are the two coordinates of time invariant vector.
+ * \par Fixed-Point Behavior
+ * Care must be taken when using the Q31 version of the Clarke transform.
+ * In particular, the overflow and saturation behavior of the accumulator used must be considered.
+ * Refer to the function specific documentation below for usage guidelines.
+ */
+
+ /**
+ * @addtogroup inv_clarke
+ * @{
+ */
+
+ /**
+ * @brief Floating-point Inverse Clarke transform
+ * @param[in] Ialpha input two-phase orthogonal vector axis alpha
+ * @param[in] Ibeta input two-phase orthogonal vector axis beta
+ * @param[out] pIa points to output three-phase coordinate <code>a</code>
+ * @param[out] pIb points to output three-phase coordinate <code>b</code>
+ */
+ CMSIS_INLINE __STATIC_INLINE void arm_inv_clarke_f32(
+ float32_t Ialpha,
+ float32_t Ibeta,
+ float32_t * pIa,
+ float32_t * pIb)
+ {
+ /* Calculating pIa from Ialpha by equation pIa = Ialpha */
+ *pIa = Ialpha;
+
+ /* Calculating pIb from Ialpha and Ibeta by equation pIb = -(1/2) * Ialpha + (sqrt(3)/2) * Ibeta */
+ *pIb = -0.5f * Ialpha + 0.8660254039f * Ibeta;
+ }
+
+
+ /**
+ * @brief Inverse Clarke transform for Q31 version
+ * @param[in] Ialpha input two-phase orthogonal vector axis alpha
+ * @param[in] Ibeta input two-phase orthogonal vector axis beta
+ * @param[out] pIa points to output three-phase coordinate <code>a</code>
+ * @param[out] pIb points to output three-phase coordinate <code>b</code>
+ *
+ * <b>Scaling and Overflow Behavior:</b>
+ * \par
+ * The function is implemented using an internal 32-bit accumulator.
+ * The accumulator maintains 1.31 format by truncating lower 31 bits of the intermediate multiplication in 2.62 format.
+ * There is saturation on the subtraction, hence there is no risk of overflow.
+ */
+ CMSIS_INLINE __STATIC_INLINE void arm_inv_clarke_q31(
+ q31_t Ialpha,
+ q31_t Ibeta,
+ q31_t * pIa,
+ q31_t * pIb)
+ {
+ q31_t product1, product2; /* Temporary variables used to store intermediate results */
+
+ /* Calculating pIa from Ialpha by equation pIa = Ialpha */
+ *pIa = Ialpha;
+
+ /* Intermediate product is calculated by (1/(2*sqrt(3)) * Ia) */
+ product1 = (q31_t) (((q63_t) (Ialpha) * (0x40000000)) >> 31);
+
+ /* Intermediate product is calculated by (1/sqrt(3) * pIb) */
+ product2 = (q31_t) (((q63_t) (Ibeta) * (0x6ED9EBA1)) >> 31);
+
+ /* pIb is calculated by subtracting the products */
+ *pIb = __QSUB(product2, product1);
+ }
+
+ /**
+ * @} end of inv_clarke group
+ */
+
+ /**
+ * @brief Converts the elements of the Q7 vector to Q15 vector.
+ * @param[in] pSrc input pointer
+ * @param[out] pDst output pointer
+ * @param[in] blockSize number of samples to process
+ */
+ void arm_q7_to_q15(
+ q7_t * pSrc,
+ q15_t * pDst,
+ uint32_t blockSize);
+
+
+
+ /**
+ * @ingroup groupController
+ */
+
+ /**
+ * @defgroup park Vector Park Transform
+ *
+ * Forward Park transform converts the input two-coordinate vector to flux and torque components.
+ * The Park transform can be used to realize the transformation of the <code>Ialpha</code> and the <code>Ibeta</code> currents
+ * from the stationary to the moving reference frame and control the spatial relationship between
+ * the stator vector current and rotor flux vector.
+ * If we consider the d axis aligned with the rotor flux, the diagram below shows the
+ * current vector and the relationship from the two reference frames:
+ * \image html park.gif "Stator current space vector and its component in (a,b) and in the d,q rotating reference frame"
+ *
+ * The function operates on a single sample of data and each call to the function returns the processed output.
+ * The library provides separate functions for Q31 and floating-point data types.
+ * \par Algorithm
+ * \image html parkFormula.gif
+ * where <code>Ialpha</code> and <code>Ibeta</code> are the stator vector components,
+ * <code>pId</code> and <code>pIq</code> are rotor vector components and <code>cosVal</code> and <code>sinVal</code> are the
+ * cosine and sine values of theta (rotor flux position).
+ * \par Fixed-Point Behavior
+ * Care must be taken when using the Q31 version of the Park transform.
+ * In particular, the overflow and saturation behavior of the accumulator used must be considered.
+ * Refer to the function specific documentation below for usage guidelines.
+ */
+
+ /**
+ * @addtogroup park
+ * @{
+ */
+
+ /**
+ * @brief Floating-point Park transform
+ * @param[in] Ialpha input two-phase vector coordinate alpha
+ * @param[in] Ibeta input two-phase vector coordinate beta
+ * @param[out] pId points to output rotor reference frame d
+ * @param[out] pIq points to output rotor reference frame q
+ * @param[in] sinVal sine value of rotation angle theta
+ * @param[in] cosVal cosine value of rotation angle theta
+ *
+ * The function implements the forward Park transform.
+ *
+ */
+ CMSIS_INLINE __STATIC_INLINE void arm_park_f32(
+ float32_t Ialpha,
+ float32_t Ibeta,
+ float32_t * pId,
+ float32_t * pIq,
+ float32_t sinVal,
+ float32_t cosVal)
+ {
+ /* Calculate pId using the equation, pId = Ialpha * cosVal + Ibeta * sinVal */
+ *pId = Ialpha * cosVal + Ibeta * sinVal;
+
+ /* Calculate pIq using the equation, pIq = - Ialpha * sinVal + Ibeta * cosVal */
+ *pIq = -Ialpha * sinVal + Ibeta * cosVal;
+ }
+
+
+ /**
+ * @brief Park transform for Q31 version
+ * @param[in] Ialpha input two-phase vector coordinate alpha
+ * @param[in] Ibeta input two-phase vector coordinate beta
+ * @param[out] pId points to output rotor reference frame d
+ * @param[out] pIq points to output rotor reference frame q
+ * @param[in] sinVal sine value of rotation angle theta
+ * @param[in] cosVal cosine value of rotation angle theta
+ *
+ * <b>Scaling and Overflow Behavior:</b>
+ * \par
+ * The function is implemented using an internal 32-bit accumulator.
+ * The accumulator maintains 1.31 format by truncating lower 31 bits of the intermediate multiplication in 2.62 format.
+ * There is saturation on the addition and subtraction, hence there is no risk of overflow.
+ */
+ CMSIS_INLINE __STATIC_INLINE void arm_park_q31(
+ q31_t Ialpha,
+ q31_t Ibeta,
+ q31_t * pId,
+ q31_t * pIq,
+ q31_t sinVal,
+ q31_t cosVal)
+ {
+ q31_t product1, product2; /* Temporary variables used to store intermediate results */
+ q31_t product3, product4; /* Temporary variables used to store intermediate results */
+
+ /* Intermediate product is calculated by (Ialpha * cosVal) */
+ product1 = (q31_t) (((q63_t) (Ialpha) * (cosVal)) >> 31);
+
+ /* Intermediate product is calculated by (Ibeta * sinVal) */
+ product2 = (q31_t) (((q63_t) (Ibeta) * (sinVal)) >> 31);
+
+
+ /* Intermediate product is calculated by (Ialpha * sinVal) */
+ product3 = (q31_t) (((q63_t) (Ialpha) * (sinVal)) >> 31);
+
+ /* Intermediate product is calculated by (Ibeta * cosVal) */
+ product4 = (q31_t) (((q63_t) (Ibeta) * (cosVal)) >> 31);
+
+ /* Calculate pId by adding the two intermediate products 1 and 2 */
+ *pId = __QADD(product1, product2);
+
+ /* Calculate pIq by subtracting the two intermediate products 3 from 4 */
+ *pIq = __QSUB(product4, product3);
+ }
+
+ /**
+ * @} end of park group
+ */
+
+ /**
+ * @brief Converts the elements of the Q7 vector to floating-point vector.
+ * @param[in] pSrc is input pointer
+ * @param[out] pDst is output pointer
+ * @param[in] blockSize is the number of samples to process
+ */
+ void arm_q7_to_float(
+ q7_t * pSrc,
+ float32_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @ingroup groupController
+ */
+
+ /**
+ * @defgroup inv_park Vector Inverse Park transform
+ * Inverse Park transform converts the input flux and torque components to two-coordinate vector.
+ *
+ * The function operates on a single sample of data and each call to the function returns the processed output.
+ * The library provides separate functions for Q31 and floating-point data types.
+ * \par Algorithm
+ * \image html parkInvFormula.gif
+ * where <code>pIalpha</code> and <code>pIbeta</code> are the stator vector components,
+ * <code>Id</code> and <code>Iq</code> are rotor vector components and <code>cosVal</code> and <code>sinVal</code> are the
+ * cosine and sine values of theta (rotor flux position).
+ * \par Fixed-Point Behavior
+ * Care must be taken when using the Q31 version of the Park transform.
+ * In particular, the overflow and saturation behavior of the accumulator used must be considered.
+ * Refer to the function specific documentation below for usage guidelines.
+ */
+
+ /**
+ * @addtogroup inv_park
+ * @{
+ */
+
+ /**
+ * @brief Floating-point Inverse Park transform
+ * @param[in] Id input coordinate of rotor reference frame d
+ * @param[in] Iq input coordinate of rotor reference frame q
+ * @param[out] pIalpha points to output two-phase orthogonal vector axis alpha
+ * @param[out] pIbeta points to output two-phase orthogonal vector axis beta
+ * @param[in] sinVal sine value of rotation angle theta
+ * @param[in] cosVal cosine value of rotation angle theta
+ */
+ CMSIS_INLINE __STATIC_INLINE void arm_inv_park_f32(
+ float32_t Id,
+ float32_t Iq,
+ float32_t * pIalpha,
+ float32_t * pIbeta,
+ float32_t sinVal,
+ float32_t cosVal)
+ {
+ /* Calculate pIalpha using the equation, pIalpha = Id * cosVal - Iq * sinVal */
+ *pIalpha = Id * cosVal - Iq * sinVal;
+
+ /* Calculate pIbeta using the equation, pIbeta = Id * sinVal + Iq * cosVal */
+ *pIbeta = Id * sinVal + Iq * cosVal;
+ }
+
+
+ /**
+ * @brief Inverse Park transform for Q31 version
+ * @param[in] Id input coordinate of rotor reference frame d
+ * @param[in] Iq input coordinate of rotor reference frame q
+ * @param[out] pIalpha points to output two-phase orthogonal vector axis alpha
+ * @param[out] pIbeta points to output two-phase orthogonal vector axis beta
+ * @param[in] sinVal sine value of rotation angle theta
+ * @param[in] cosVal cosine value of rotation angle theta
+ *
+ * <b>Scaling and Overflow Behavior:</b>
+ * \par
+ * The function is implemented using an internal 32-bit accumulator.
+ * The accumulator maintains 1.31 format by truncating lower 31 bits of the intermediate multiplication in 2.62 format.
+ * There is saturation on the addition, hence there is no risk of overflow.
+ */
+ CMSIS_INLINE __STATIC_INLINE void arm_inv_park_q31(
+ q31_t Id,
+ q31_t Iq,
+ q31_t * pIalpha,
+ q31_t * pIbeta,
+ q31_t sinVal,
+ q31_t cosVal)
+ {
+ q31_t product1, product2; /* Temporary variables used to store intermediate results */
+ q31_t product3, product4; /* Temporary variables used to store intermediate results */
+
+ /* Intermediate product is calculated by (Id * cosVal) */
+ product1 = (q31_t) (((q63_t) (Id) * (cosVal)) >> 31);
+
+ /* Intermediate product is calculated by (Iq * sinVal) */
+ product2 = (q31_t) (((q63_t) (Iq) * (sinVal)) >> 31);
+
+
+ /* Intermediate product is calculated by (Id * sinVal) */
+ product3 = (q31_t) (((q63_t) (Id) * (sinVal)) >> 31);
+
+ /* Intermediate product is calculated by (Iq * cosVal) */
+ product4 = (q31_t) (((q63_t) (Iq) * (cosVal)) >> 31);
+
+ /* Calculate pIalpha by using the two intermediate products 1 and 2 */
+ *pIalpha = __QSUB(product1, product2);
+
+ /* Calculate pIbeta by using the two intermediate products 3 and 4 */
+ *pIbeta = __QADD(product4, product3);
+ }
+
+ /**
+ * @} end of Inverse park group
+ */
+
+
+ /**
+ * @brief Converts the elements of the Q31 vector to floating-point vector.
+ * @param[in] pSrc is input pointer
+ * @param[out] pDst is output pointer
+ * @param[in] blockSize is the number of samples to process
+ */
+ void arm_q31_to_float(
+ q31_t * pSrc,
+ float32_t * pDst,
+ uint32_t blockSize);
+
+ /**
+ * @ingroup groupInterpolation
+ */
+
+ /**
+ * @defgroup LinearInterpolate Linear Interpolation
+ *
+ * Linear interpolation is a method of curve fitting using linear polynomials.
+ * Linear interpolation works by effectively drawing a straight line between two neighboring samples and returning the appropriate point along that line
+ *
+ * \par
+ * \image html LinearInterp.gif "Linear interpolation"
+ *
+ * \par
+ * A Linear Interpolate function calculates an output value(y), for the input(x)
+ * using linear interpolation of the input values x0, x1( nearest input values) and the output values y0 and y1(nearest output values)
+ *
+ * \par Algorithm:
+ * <pre>
+ * y = y0 + (x - x0) * ((y1 - y0)/(x1-x0))
+ * where x0, x1 are nearest values of input x
+ * y0, y1 are nearest values to output y
+ * </pre>
+ *
+ * \par
+ * This set of functions implements Linear interpolation process
+ * for Q7, Q15, Q31, and floating-point data types. The functions operate on a single
+ * sample of data and each call to the function returns a single processed value.
+ * <code>S</code> points to an instance of the Linear Interpolate function data structure.
+ * <code>x</code> is the input sample value. The functions returns the output value.
+ *
+ * \par
+ * if x is outside of the table boundary, Linear interpolation returns first value of the table
+ * if x is below input range and returns last value of table if x is above range.
+ */
+
+ /**
+ * @addtogroup LinearInterpolate
+ * @{
+ */
+
+ /**
+ * @brief Process function for the floating-point Linear Interpolation Function.
+ * @param[in,out] S is an instance of the floating-point Linear Interpolation structure
+ * @param[in] x input sample to process
+ * @return y processed output sample.
+ *
+ */
+ CMSIS_INLINE __STATIC_INLINE float32_t arm_linear_interp_f32(
+ arm_linear_interp_instance_f32 * S,
+ float32_t x)
+ {
+ float32_t y;
+ float32_t x0, x1; /* Nearest input values */
+ float32_t y0, y1; /* Nearest output values */
+ float32_t xSpacing = S->xSpacing; /* spacing between input values */
+ int32_t i; /* Index variable */
+ float32_t *pYData = S->pYData; /* pointer to output table */
+
+ /* Calculation of index */
+ i = (int32_t) ((x - S->x1) / xSpacing);
+
+ if (i < 0)
+ {
+ /* Iniatilize output for below specified range as least output value of table */
+ y = pYData[0];
+ }
+ else if ((uint32_t)i >= S->nValues)
+ {
+ /* Iniatilize output for above specified range as last output value of table */
+ y = pYData[S->nValues - 1];
+ }
+ else
+ {
+ /* Calculation of nearest input values */
+ x0 = S->x1 + i * xSpacing;
+ x1 = S->x1 + (i + 1) * xSpacing;
+
+ /* Read of nearest output values */
+ y0 = pYData[i];
+ y1 = pYData[i + 1];
+
+ /* Calculation of output */
+ y = y0 + (x - x0) * ((y1 - y0) / (x1 - x0));
+
+ }
+
+ /* returns output value */
+ return (y);
+ }
+
+
+ /**
+ *
+ * @brief Process function for the Q31 Linear Interpolation Function.
+ * @param[in] pYData pointer to Q31 Linear Interpolation table
+ * @param[in] x input sample to process
+ * @param[in] nValues number of table values
+ * @return y processed output sample.
+ *
+ * \par
+ * Input sample <code>x</code> is in 12.20 format which contains 12 bits for table index and 20 bits for fractional part.
+ * This function can support maximum of table size 2^12.
+ *
+ */
+ CMSIS_INLINE __STATIC_INLINE q31_t arm_linear_interp_q31(
+ q31_t * pYData,
+ q31_t x,
+ uint32_t nValues)
+ {
+ q31_t y; /* output */
+ q31_t y0, y1; /* Nearest output values */
+ q31_t fract; /* fractional part */
+ int32_t index; /* Index to read nearest output values */
+
+ /* Input is in 12.20 format */
+ /* 12 bits for the table index */
+ /* Index value calculation */
+ index = ((x & (q31_t)0xFFF00000) >> 20);
+
+ if (index >= (int32_t)(nValues - 1))
+ {
+ return (pYData[nValues - 1]);
+ }
+ else if (index < 0)
+ {
+ return (pYData[0]);
+ }
+ else
+ {
+ /* 20 bits for the fractional part */
+ /* shift left by 11 to keep fract in 1.31 format */
+ fract = (x & 0x000FFFFF) << 11;
+
+ /* Read two nearest output values from the index in 1.31(q31) format */
+ y0 = pYData[index];
+ y1 = pYData[index + 1];
+
+ /* Calculation of y0 * (1-fract) and y is in 2.30 format */
+ y = ((q31_t) ((q63_t) y0 * (0x7FFFFFFF - fract) >> 32));
+
+ /* Calculation of y0 * (1-fract) + y1 *fract and y is in 2.30 format */
+ y += ((q31_t) (((q63_t) y1 * fract) >> 32));
+
+ /* Convert y to 1.31 format */
+ return (y << 1U);
+ }
+ }
+
+
+ /**
+ *
+ * @brief Process function for the Q15 Linear Interpolation Function.
+ * @param[in] pYData pointer to Q15 Linear Interpolation table
+ * @param[in] x input sample to process
+ * @param[in] nValues number of table values
+ * @return y processed output sample.
+ *
+ * \par
+ * Input sample <code>x</code> is in 12.20 format which contains 12 bits for table index and 20 bits for fractional part.
+ * This function can support maximum of table size 2^12.
+ *
+ */
+ CMSIS_INLINE __STATIC_INLINE q15_t arm_linear_interp_q15(
+ q15_t * pYData,
+ q31_t x,
+ uint32_t nValues)
+ {
+ q63_t y; /* output */
+ q15_t y0, y1; /* Nearest output values */
+ q31_t fract; /* fractional part */
+ int32_t index; /* Index to read nearest output values */
+
+ /* Input is in 12.20 format */
+ /* 12 bits for the table index */
+ /* Index value calculation */
+ index = ((x & (int32_t)0xFFF00000) >> 20);
+
+ if (index >= (int32_t)(nValues - 1))
+ {
+ return (pYData[nValues - 1]);
+ }
+ else if (index < 0)
+ {
+ return (pYData[0]);
+ }
+ else
+ {
+ /* 20 bits for the fractional part */
+ /* fract is in 12.20 format */
+ fract = (x & 0x000FFFFF);
+
+ /* Read two nearest output values from the index */
+ y0 = pYData[index];
+ y1 = pYData[index + 1];
+
+ /* Calculation of y0 * (1-fract) and y is in 13.35 format */
+ y = ((q63_t) y0 * (0xFFFFF - fract));
+
+ /* Calculation of (y0 * (1-fract) + y1 * fract) and y is in 13.35 format */
+ y += ((q63_t) y1 * (fract));
+
+ /* convert y to 1.15 format */
+ return (q15_t) (y >> 20);
+ }
+ }
+
+
+ /**
+ *
+ * @brief Process function for the Q7 Linear Interpolation Function.
+ * @param[in] pYData pointer to Q7 Linear Interpolation table
+ * @param[in] x input sample to process
+ * @param[in] nValues number of table values
+ * @return y processed output sample.
+ *
+ * \par
+ * Input sample <code>x</code> is in 12.20 format which contains 12 bits for table index and 20 bits for fractional part.
+ * This function can support maximum of table size 2^12.
+ */
+ CMSIS_INLINE __STATIC_INLINE q7_t arm_linear_interp_q7(
+ q7_t * pYData,
+ q31_t x,
+ uint32_t nValues)
+ {
+ q31_t y; /* output */
+ q7_t y0, y1; /* Nearest output values */
+ q31_t fract; /* fractional part */
+ uint32_t index; /* Index to read nearest output values */
+
+ /* Input is in 12.20 format */
+ /* 12 bits for the table index */
+ /* Index value calculation */
+ if (x < 0)
+ {
+ return (pYData[0]);
+ }
+ index = (x >> 20) & 0xfff;
+
+ if (index >= (nValues - 1))
+ {
+ return (pYData[nValues - 1]);
+ }
+ else
+ {
+ /* 20 bits for the fractional part */
+ /* fract is in 12.20 format */
+ fract = (x & 0x000FFFFF);
+
+ /* Read two nearest output values from the index and are in 1.7(q7) format */
+ y0 = pYData[index];
+ y1 = pYData[index + 1];
+
+ /* Calculation of y0 * (1-fract ) and y is in 13.27(q27) format */
+ y = ((y0 * (0xFFFFF - fract)));
+
+ /* Calculation of y1 * fract + y0 * (1-fract) and y is in 13.27(q27) format */
+ y += (y1 * fract);
+
+ /* convert y to 1.7(q7) format */
+ return (q7_t) (y >> 20);
+ }
+ }
+
+ /**
+ * @} end of LinearInterpolate group
+ */
+
+ /**
+ * @brief Fast approximation to the trigonometric sine function for floating-point data.
+ * @param[in] x input value in radians.
+ * @return sin(x).
+ */
+ float32_t arm_sin_f32(
+ float32_t x);
+
+
+ /**
+ * @brief Fast approximation to the trigonometric sine function for Q31 data.
+ * @param[in] x Scaled input value in radians.
+ * @return sin(x).
+ */
+ q31_t arm_sin_q31(
+ q31_t x);
+
+
+ /**
+ * @brief Fast approximation to the trigonometric sine function for Q15 data.
+ * @param[in] x Scaled input value in radians.
+ * @return sin(x).
+ */
+ q15_t arm_sin_q15(
+ q15_t x);
+
+
+ /**
+ * @brief Fast approximation to the trigonometric cosine function for floating-point data.
+ * @param[in] x input value in radians.
+ * @return cos(x).
+ */
+ float32_t arm_cos_f32(
+ float32_t x);
+
+
+ /**
+ * @brief Fast approximation to the trigonometric cosine function for Q31 data.
+ * @param[in] x Scaled input value in radians.
+ * @return cos(x).
+ */
+ q31_t arm_cos_q31(
+ q31_t x);
+
+
+ /**
+ * @brief Fast approximation to the trigonometric cosine function for Q15 data.
+ * @param[in] x Scaled input value in radians.
+ * @return cos(x).
+ */
+ q15_t arm_cos_q15(
+ q15_t x);
+
+
+ /**
+ * @ingroup groupFastMath
+ */
+
+
+ /**
+ * @defgroup SQRT Square Root
+ *
+ * Computes the square root of a number.
+ * There are separate functions for Q15, Q31, and floating-point data types.
+ * The square root function is computed using the Newton-Raphson algorithm.
+ * This is an iterative algorithm of the form:
+ * <pre>
+ * x1 = x0 - f(x0)/f'(x0)
+ * </pre>
+ * where <code>x1</code> is the current estimate,
+ * <code>x0</code> is the previous estimate, and
+ * <code>f'(x0)</code> is the derivative of <code>f()</code> evaluated at <code>x0</code>.
+ * For the square root function, the algorithm reduces to:
+ * <pre>
+ * x0 = in/2 [initial guess]
+ * x1 = 1/2 * ( x0 + in / x0) [each iteration]
+ * </pre>
+ */
+
+
+ /**
+ * @addtogroup SQRT
+ * @{
+ */
+
+ /**
+ * @brief Floating-point square root function.
+ * @param[in] in input value.
+ * @param[out] pOut square root of input value.
+ * @return The function returns ARM_MATH_SUCCESS if input value is positive value or ARM_MATH_ARGUMENT_ERROR if
+ * <code>in</code> is negative value and returns zero output for negative values.
+ */
+ CMSIS_INLINE __STATIC_INLINE arm_status arm_sqrt_f32(
+ float32_t in,
+ float32_t * pOut)
+ {
+ if (in >= 0.0f)
+ {
+
+#if (__FPU_USED == 1) && defined ( __CC_ARM )
+ *pOut = __sqrtf(in);
+#elif (__FPU_USED == 1) && (defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050))
+ *pOut = __builtin_sqrtf(in);
+#elif (__FPU_USED == 1) && defined(__GNUC__)
+ *pOut = __builtin_sqrtf(in);
+#elif (__FPU_USED == 1) && defined ( __ICCARM__ ) && (__VER__ >= 6040000)
+ __ASM("VSQRT.F32 %0,%1" : "=t"(*pOut) : "t"(in));
+#else
+ *pOut = sqrtf(in);
+#endif
+
+ return (ARM_MATH_SUCCESS);
+ }
+ else
+ {
+ *pOut = 0.0f;
+ return (ARM_MATH_ARGUMENT_ERROR);
+ }
+ }
+
+
+ /**
+ * @brief Q31 square root function.
+ * @param[in] in input value. The range of the input value is [0 +1) or 0x00000000 to 0x7FFFFFFF.
+ * @param[out] pOut square root of input value.
+ * @return The function returns ARM_MATH_SUCCESS if input value is positive value or ARM_MATH_ARGUMENT_ERROR if
+ * <code>in</code> is negative value and returns zero output for negative values.
+ */
+ arm_status arm_sqrt_q31(
+ q31_t in,
+ q31_t * pOut);
+
+
+ /**
+ * @brief Q15 square root function.
+ * @param[in] in input value. The range of the input value is [0 +1) or 0x0000 to 0x7FFF.
+ * @param[out] pOut square root of input value.
+ * @return The function returns ARM_MATH_SUCCESS if input value is positive value or ARM_MATH_ARGUMENT_ERROR if
+ * <code>in</code> is negative value and returns zero output for negative values.
+ */
+ arm_status arm_sqrt_q15(
+ q15_t in,
+ q15_t * pOut);
+
+ /**
+ * @} end of SQRT group
+ */
+
+
+ /**
+ * @brief floating-point Circular write function.
+ */
+ CMSIS_INLINE __STATIC_INLINE void arm_circularWrite_f32(
+ int32_t * circBuffer,
+ int32_t L,
+ uint16_t * writeOffset,
+ int32_t bufferInc,
+ const int32_t * src,
+ int32_t srcInc,
+ uint32_t blockSize)
+ {
+ uint32_t i = 0U;
+ int32_t wOffset;
+
+ /* Copy the value of Index pointer that points
+ * to the current location where the input samples to be copied */
+ wOffset = *writeOffset;
+
+ /* Loop over the blockSize */
+ i = blockSize;
+
+ while (i > 0U)
+ {
+ /* copy the input sample to the circular buffer */
+ circBuffer[wOffset] = *src;
+
+ /* Update the input pointer */
+ src += srcInc;
+
+ /* Circularly update wOffset. Watch out for positive and negative value */
+ wOffset += bufferInc;
+ if (wOffset >= L)
+ wOffset -= L;
+
+ /* Decrement the loop counter */
+ i--;
+ }
+
+ /* Update the index pointer */
+ *writeOffset = (uint16_t)wOffset;
+ }
+
+
+
+ /**
+ * @brief floating-point Circular Read function.
+ */
+ CMSIS_INLINE __STATIC_INLINE void arm_circularRead_f32(
+ int32_t * circBuffer,
+ int32_t L,
+ int32_t * readOffset,
+ int32_t bufferInc,
+ int32_t * dst,
+ int32_t * dst_base,
+ int32_t dst_length,
+ int32_t dstInc,
+ uint32_t blockSize)
+ {
+ uint32_t i = 0U;
+ int32_t rOffset, dst_end;
+
+ /* Copy the value of Index pointer that points
+ * to the current location from where the input samples to be read */
+ rOffset = *readOffset;
+ dst_end = (int32_t) (dst_base + dst_length);
+
+ /* Loop over the blockSize */
+ i = blockSize;
+
+ while (i > 0U)
+ {
+ /* copy the sample from the circular buffer to the destination buffer */
+ *dst = circBuffer[rOffset];
+
+ /* Update the input pointer */
+ dst += dstInc;
+
+ if (dst == (int32_t *) dst_end)
+ {
+ dst = dst_base;
+ }
+
+ /* Circularly update rOffset. Watch out for positive and negative value */
+ rOffset += bufferInc;
+
+ if (rOffset >= L)
+ {
+ rOffset -= L;
+ }
+
+ /* Decrement the loop counter */
+ i--;
+ }
+
+ /* Update the index pointer */
+ *readOffset = rOffset;
+ }
+
+
+ /**
+ * @brief Q15 Circular write function.
+ */
+ CMSIS_INLINE __STATIC_INLINE void arm_circularWrite_q15(
+ q15_t * circBuffer,
+ int32_t L,
+ uint16_t * writeOffset,
+ int32_t bufferInc,
+ const q15_t * src,
+ int32_t srcInc,
+ uint32_t blockSize)
+ {
+ uint32_t i = 0U;
+ int32_t wOffset;
+
+ /* Copy the value of Index pointer that points
+ * to the current location where the input samples to be copied */
+ wOffset = *writeOffset;
+
+ /* Loop over the blockSize */
+ i = blockSize;
+
+ while (i > 0U)
+ {
+ /* copy the input sample to the circular buffer */
+ circBuffer[wOffset] = *src;
+
+ /* Update the input pointer */
+ src += srcInc;
+
+ /* Circularly update wOffset. Watch out for positive and negative value */
+ wOffset += bufferInc;
+ if (wOffset >= L)
+ wOffset -= L;
+
+ /* Decrement the loop counter */
+ i--;
+ }
+
+ /* Update the index pointer */
+ *writeOffset = (uint16_t)wOffset;
+ }
+
+
+ /**
+ * @brief Q15 Circular Read function.
+ */
+ CMSIS_INLINE __STATIC_INLINE void arm_circularRead_q15(
+ q15_t * circBuffer,
+ int32_t L,
+ int32_t * readOffset,
+ int32_t bufferInc,
+ q15_t * dst,
+ q15_t * dst_base,
+ int32_t dst_length,
+ int32_t dstInc,
+ uint32_t blockSize)
+ {
+ uint32_t i = 0;
+ int32_t rOffset, dst_end;
+
+ /* Copy the value of Index pointer that points
+ * to the current location from where the input samples to be read */
+ rOffset = *readOffset;
+
+ dst_end = (int32_t) (dst_base + dst_length);
+
+ /* Loop over the blockSize */
+ i = blockSize;
+
+ while (i > 0U)
+ {
+ /* copy the sample from the circular buffer to the destination buffer */
+ *dst = circBuffer[rOffset];
+
+ /* Update the input pointer */
+ dst += dstInc;
+
+ if (dst == (q15_t *) dst_end)
+ {
+ dst = dst_base;
+ }
+
+ /* Circularly update wOffset. Watch out for positive and negative value */
+ rOffset += bufferInc;
+
+ if (rOffset >= L)
+ {
+ rOffset -= L;
+ }
+
+ /* Decrement the loop counter */
+ i--;
+ }
+
+ /* Update the index pointer */
+ *readOffset = rOffset;
+ }
+
+
+ /**
+ * @brief Q7 Circular write function.
+ */
+ CMSIS_INLINE __STATIC_INLINE void arm_circularWrite_q7(
+ q7_t * circBuffer,
+ int32_t L,
+ uint16_t * writeOffset,
+ int32_t bufferInc,
+ const q7_t * src,
+ int32_t srcInc,
+ uint32_t blockSize)
+ {
+ uint32_t i = 0U;
+ int32_t wOffset;
+
+ /* Copy the value of Index pointer that points
+ * to the current location where the input samples to be copied */
+ wOffset = *writeOffset;
+
+ /* Loop over the blockSize */
+ i = blockSize;
+
+ while (i > 0U)
+ {
+ /* copy the input sample to the circular buffer */
+ circBuffer[wOffset] = *src;
+
+ /* Update the input pointer */
+ src += srcInc;
+
+ /* Circularly update wOffset. Watch out for positive and negative value */
+ wOffset += bufferInc;
+ if (wOffset >= L)
+ wOffset -= L;
+
+ /* Decrement the loop counter */
+ i--;
+ }
+
+ /* Update the index pointer */
+ *writeOffset = (uint16_t)wOffset;
+ }
+
+
+ /**
+ * @brief Q7 Circular Read function.
+ */
+ CMSIS_INLINE __STATIC_INLINE void arm_circularRead_q7(
+ q7_t * circBuffer,
+ int32_t L,
+ int32_t * readOffset,
+ int32_t bufferInc,
+ q7_t * dst,
+ q7_t * dst_base,
+ int32_t dst_length,
+ int32_t dstInc,
+ uint32_t blockSize)
+ {
+ uint32_t i = 0;
+ int32_t rOffset, dst_end;
+
+ /* Copy the value of Index pointer that points
+ * to the current location from where the input samples to be read */
+ rOffset = *readOffset;
+
+ dst_end = (int32_t) (dst_base + dst_length);
+
+ /* Loop over the blockSize */
+ i = blockSize;
+
+ while (i > 0U)
+ {
+ /* copy the sample from the circular buffer to the destination buffer */
+ *dst = circBuffer[rOffset];
+
+ /* Update the input pointer */
+ dst += dstInc;
+
+ if (dst == (q7_t *) dst_end)
+ {
+ dst = dst_base;
+ }
+
+ /* Circularly update rOffset. Watch out for positive and negative value */
+ rOffset += bufferInc;
+
+ if (rOffset >= L)
+ {
+ rOffset -= L;
+ }
+
+ /* Decrement the loop counter */
+ i--;
+ }
+
+ /* Update the index pointer */
+ *readOffset = rOffset;
+ }
+
+
+ /**
+ * @brief Sum of the squares of the elements of a Q31 vector.
+ * @param[in] pSrc is input pointer
+ * @param[in] blockSize is the number of samples to process
+ * @param[out] pResult is output value.
+ */
+ void arm_power_q31(
+ q31_t * pSrc,
+ uint32_t blockSize,
+ q63_t * pResult);
+
+
+ /**
+ * @brief Sum of the squares of the elements of a floating-point vector.
+ * @param[in] pSrc is input pointer
+ * @param[in] blockSize is the number of samples to process
+ * @param[out] pResult is output value.
+ */
+ void arm_power_f32(
+ float32_t * pSrc,
+ uint32_t blockSize,
+ float32_t * pResult);
+
+
+ /**
+ * @brief Sum of the squares of the elements of a Q15 vector.
+ * @param[in] pSrc is input pointer
+ * @param[in] blockSize is the number of samples to process
+ * @param[out] pResult is output value.
+ */
+ void arm_power_q15(
+ q15_t * pSrc,
+ uint32_t blockSize,
+ q63_t * pResult);
+
+
+ /**
+ * @brief Sum of the squares of the elements of a Q7 vector.
+ * @param[in] pSrc is input pointer
+ * @param[in] blockSize is the number of samples to process
+ * @param[out] pResult is output value.
+ */
+ void arm_power_q7(
+ q7_t * pSrc,
+ uint32_t blockSize,
+ q31_t * pResult);
+
+
+ /**
+ * @brief Mean value of a Q7 vector.
+ * @param[in] pSrc is input pointer
+ * @param[in] blockSize is the number of samples to process
+ * @param[out] pResult is output value.
+ */
+ void arm_mean_q7(
+ q7_t * pSrc,
+ uint32_t blockSize,
+ q7_t * pResult);
+
+
+ /**
+ * @brief Mean value of a Q15 vector.
+ * @param[in] pSrc is input pointer
+ * @param[in] blockSize is the number of samples to process
+ * @param[out] pResult is output value.
+ */
+ void arm_mean_q15(
+ q15_t * pSrc,
+ uint32_t blockSize,
+ q15_t * pResult);
+
+
+ /**
+ * @brief Mean value of a Q31 vector.
+ * @param[in] pSrc is input pointer
+ * @param[in] blockSize is the number of samples to process
+ * @param[out] pResult is output value.
+ */
+ void arm_mean_q31(
+ q31_t * pSrc,
+ uint32_t blockSize,
+ q31_t * pResult);
+
+
+ /**
+ * @brief Mean value of a floating-point vector.
+ * @param[in] pSrc is input pointer
+ * @param[in] blockSize is the number of samples to process
+ * @param[out] pResult is output value.
+ */
+ void arm_mean_f32(
+ float32_t * pSrc,
+ uint32_t blockSize,
+ float32_t * pResult);
+
+
+ /**
+ * @brief Variance of the elements of a floating-point vector.
+ * @param[in] pSrc is input pointer
+ * @param[in] blockSize is the number of samples to process
+ * @param[out] pResult is output value.
+ */
+ void arm_var_f32(
+ float32_t * pSrc,
+ uint32_t blockSize,
+ float32_t * pResult);
+
+
+ /**
+ * @brief Variance of the elements of a Q31 vector.
+ * @param[in] pSrc is input pointer
+ * @param[in] blockSize is the number of samples to process
+ * @param[out] pResult is output value.
+ */
+ void arm_var_q31(
+ q31_t * pSrc,
+ uint32_t blockSize,
+ q31_t * pResult);
+
+
+ /**
+ * @brief Variance of the elements of a Q15 vector.
+ * @param[in] pSrc is input pointer
+ * @param[in] blockSize is the number of samples to process
+ * @param[out] pResult is output value.
+ */
+ void arm_var_q15(
+ q15_t * pSrc,
+ uint32_t blockSize,
+ q15_t * pResult);
+
+
+ /**
+ * @brief Root Mean Square of the elements of a floating-point vector.
+ * @param[in] pSrc is input pointer
+ * @param[in] blockSize is the number of samples to process
+ * @param[out] pResult is output value.
+ */
+ void arm_rms_f32(
+ float32_t * pSrc,
+ uint32_t blockSize,
+ float32_t * pResult);
+
+
+ /**
+ * @brief Root Mean Square of the elements of a Q31 vector.
+ * @param[in] pSrc is input pointer
+ * @param[in] blockSize is the number of samples to process
+ * @param[out] pResult is output value.
+ */
+ void arm_rms_q31(
+ q31_t * pSrc,
+ uint32_t blockSize,
+ q31_t * pResult);
+
+
+ /**
+ * @brief Root Mean Square of the elements of a Q15 vector.
+ * @param[in] pSrc is input pointer
+ * @param[in] blockSize is the number of samples to process
+ * @param[out] pResult is output value.
+ */
+ void arm_rms_q15(
+ q15_t * pSrc,
+ uint32_t blockSize,
+ q15_t * pResult);
+
+
+ /**
+ * @brief Standard deviation of the elements of a floating-point vector.
+ * @param[in] pSrc is input pointer
+ * @param[in] blockSize is the number of samples to process
+ * @param[out] pResult is output value.
+ */
+ void arm_std_f32(
+ float32_t * pSrc,
+ uint32_t blockSize,
+ float32_t * pResult);
+
+
+ /**
+ * @brief Standard deviation of the elements of a Q31 vector.
+ * @param[in] pSrc is input pointer
+ * @param[in] blockSize is the number of samples to process
+ * @param[out] pResult is output value.
+ */
+ void arm_std_q31(
+ q31_t * pSrc,
+ uint32_t blockSize,
+ q31_t * pResult);
+
+
+ /**
+ * @brief Standard deviation of the elements of a Q15 vector.
+ * @param[in] pSrc is input pointer
+ * @param[in] blockSize is the number of samples to process
+ * @param[out] pResult is output value.
+ */
+ void arm_std_q15(
+ q15_t * pSrc,
+ uint32_t blockSize,
+ q15_t * pResult);
+
+
+ /**
+ * @brief Floating-point complex magnitude
+ * @param[in] pSrc points to the complex input vector
+ * @param[out] pDst points to the real output vector
+ * @param[in] numSamples number of complex samples in the input vector
+ */
+ void arm_cmplx_mag_f32(
+ float32_t * pSrc,
+ float32_t * pDst,
+ uint32_t numSamples);
+
+
+ /**
+ * @brief Q31 complex magnitude
+ * @param[in] pSrc points to the complex input vector
+ * @param[out] pDst points to the real output vector
+ * @param[in] numSamples number of complex samples in the input vector
+ */
+ void arm_cmplx_mag_q31(
+ q31_t * pSrc,
+ q31_t * pDst,
+ uint32_t numSamples);
+
+
+ /**
+ * @brief Q15 complex magnitude
+ * @param[in] pSrc points to the complex input vector
+ * @param[out] pDst points to the real output vector
+ * @param[in] numSamples number of complex samples in the input vector
+ */
+ void arm_cmplx_mag_q15(
+ q15_t * pSrc,
+ q15_t * pDst,
+ uint32_t numSamples);
+
+
+ /**
+ * @brief Q15 complex dot product
+ * @param[in] pSrcA points to the first input vector
+ * @param[in] pSrcB points to the second input vector
+ * @param[in] numSamples number of complex samples in each vector
+ * @param[out] realResult real part of the result returned here
+ * @param[out] imagResult imaginary part of the result returned here
+ */
+ void arm_cmplx_dot_prod_q15(
+ q15_t * pSrcA,
+ q15_t * pSrcB,
+ uint32_t numSamples,
+ q31_t * realResult,
+ q31_t * imagResult);
+
+
+ /**
+ * @brief Q31 complex dot product
+ * @param[in] pSrcA points to the first input vector
+ * @param[in] pSrcB points to the second input vector
+ * @param[in] numSamples number of complex samples in each vector
+ * @param[out] realResult real part of the result returned here
+ * @param[out] imagResult imaginary part of the result returned here
+ */
+ void arm_cmplx_dot_prod_q31(
+ q31_t * pSrcA,
+ q31_t * pSrcB,
+ uint32_t numSamples,
+ q63_t * realResult,
+ q63_t * imagResult);
+
+
+ /**
+ * @brief Floating-point complex dot product
+ * @param[in] pSrcA points to the first input vector
+ * @param[in] pSrcB points to the second input vector
+ * @param[in] numSamples number of complex samples in each vector
+ * @param[out] realResult real part of the result returned here
+ * @param[out] imagResult imaginary part of the result returned here
+ */
+ void arm_cmplx_dot_prod_f32(
+ float32_t * pSrcA,
+ float32_t * pSrcB,
+ uint32_t numSamples,
+ float32_t * realResult,
+ float32_t * imagResult);
+
+
+ /**
+ * @brief Q15 complex-by-real multiplication
+ * @param[in] pSrcCmplx points to the complex input vector
+ * @param[in] pSrcReal points to the real input vector
+ * @param[out] pCmplxDst points to the complex output vector
+ * @param[in] numSamples number of samples in each vector
+ */
+ void arm_cmplx_mult_real_q15(
+ q15_t * pSrcCmplx,
+ q15_t * pSrcReal,
+ q15_t * pCmplxDst,
+ uint32_t numSamples);
+
+
+ /**
+ * @brief Q31 complex-by-real multiplication
+ * @param[in] pSrcCmplx points to the complex input vector
+ * @param[in] pSrcReal points to the real input vector
+ * @param[out] pCmplxDst points to the complex output vector
+ * @param[in] numSamples number of samples in each vector
+ */
+ void arm_cmplx_mult_real_q31(
+ q31_t * pSrcCmplx,
+ q31_t * pSrcReal,
+ q31_t * pCmplxDst,
+ uint32_t numSamples);
+
+
+ /**
+ * @brief Floating-point complex-by-real multiplication
+ * @param[in] pSrcCmplx points to the complex input vector
+ * @param[in] pSrcReal points to the real input vector
+ * @param[out] pCmplxDst points to the complex output vector
+ * @param[in] numSamples number of samples in each vector
+ */
+ void arm_cmplx_mult_real_f32(
+ float32_t * pSrcCmplx,
+ float32_t * pSrcReal,
+ float32_t * pCmplxDst,
+ uint32_t numSamples);
+
+
+ /**
+ * @brief Minimum value of a Q7 vector.
+ * @param[in] pSrc is input pointer
+ * @param[in] blockSize is the number of samples to process
+ * @param[out] result is output pointer
+ * @param[in] index is the array index of the minimum value in the input buffer.
+ */
+ void arm_min_q7(
+ q7_t * pSrc,
+ uint32_t blockSize,
+ q7_t * result,
+ uint32_t * index);
+
+
+ /**
+ * @brief Minimum value of a Q15 vector.
+ * @param[in] pSrc is input pointer
+ * @param[in] blockSize is the number of samples to process
+ * @param[out] pResult is output pointer
+ * @param[in] pIndex is the array index of the minimum value in the input buffer.
+ */
+ void arm_min_q15(
+ q15_t * pSrc,
+ uint32_t blockSize,
+ q15_t * pResult,
+ uint32_t * pIndex);
+
+
+ /**
+ * @brief Minimum value of a Q31 vector.
+ * @param[in] pSrc is input pointer
+ * @param[in] blockSize is the number of samples to process
+ * @param[out] pResult is output pointer
+ * @param[out] pIndex is the array index of the minimum value in the input buffer.
+ */
+ void arm_min_q31(
+ q31_t * pSrc,
+ uint32_t blockSize,
+ q31_t * pResult,
+ uint32_t * pIndex);
+
+
+ /**
+ * @brief Minimum value of a floating-point vector.
+ * @param[in] pSrc is input pointer
+ * @param[in] blockSize is the number of samples to process
+ * @param[out] pResult is output pointer
+ * @param[out] pIndex is the array index of the minimum value in the input buffer.
+ */
+ void arm_min_f32(
+ float32_t * pSrc,
+ uint32_t blockSize,
+ float32_t * pResult,
+ uint32_t * pIndex);
+
+
+/**
+ * @brief Maximum value of a Q7 vector.
+ * @param[in] pSrc points to the input buffer
+ * @param[in] blockSize length of the input vector
+ * @param[out] pResult maximum value returned here
+ * @param[out] pIndex index of maximum value returned here
+ */
+ void arm_max_q7(
+ q7_t * pSrc,
+ uint32_t blockSize,
+ q7_t * pResult,
+ uint32_t * pIndex);
+
+
+/**
+ * @brief Maximum value of a Q15 vector.
+ * @param[in] pSrc points to the input buffer
+ * @param[in] blockSize length of the input vector
+ * @param[out] pResult maximum value returned here
+ * @param[out] pIndex index of maximum value returned here
+ */
+ void arm_max_q15(
+ q15_t * pSrc,
+ uint32_t blockSize,
+ q15_t * pResult,
+ uint32_t * pIndex);
+
+
+/**
+ * @brief Maximum value of a Q31 vector.
+ * @param[in] pSrc points to the input buffer
+ * @param[in] blockSize length of the input vector
+ * @param[out] pResult maximum value returned here
+ * @param[out] pIndex index of maximum value returned here
+ */
+ void arm_max_q31(
+ q31_t * pSrc,
+ uint32_t blockSize,
+ q31_t * pResult,
+ uint32_t * pIndex);
+
+
+/**
+ * @brief Maximum value of a floating-point vector.
+ * @param[in] pSrc points to the input buffer
+ * @param[in] blockSize length of the input vector
+ * @param[out] pResult maximum value returned here
+ * @param[out] pIndex index of maximum value returned here
+ */
+ void arm_max_f32(
+ float32_t * pSrc,
+ uint32_t blockSize,
+ float32_t * pResult,
+ uint32_t * pIndex);
+
+
+ /**
+ * @brief Q15 complex-by-complex multiplication
+ * @param[in] pSrcA points to the first input vector
+ * @param[in] pSrcB points to the second input vector
+ * @param[out] pDst points to the output vector
+ * @param[in] numSamples number of complex samples in each vector
+ */
+ void arm_cmplx_mult_cmplx_q15(
+ q15_t * pSrcA,
+ q15_t * pSrcB,
+ q15_t * pDst,
+ uint32_t numSamples);
+
+
+ /**
+ * @brief Q31 complex-by-complex multiplication
+ * @param[in] pSrcA points to the first input vector
+ * @param[in] pSrcB points to the second input vector
+ * @param[out] pDst points to the output vector
+ * @param[in] numSamples number of complex samples in each vector
+ */
+ void arm_cmplx_mult_cmplx_q31(
+ q31_t * pSrcA,
+ q31_t * pSrcB,
+ q31_t * pDst,
+ uint32_t numSamples);
+
+
+ /**
+ * @brief Floating-point complex-by-complex multiplication
+ * @param[in] pSrcA points to the first input vector
+ * @param[in] pSrcB points to the second input vector
+ * @param[out] pDst points to the output vector
+ * @param[in] numSamples number of complex samples in each vector
+ */
+ void arm_cmplx_mult_cmplx_f32(
+ float32_t * pSrcA,
+ float32_t * pSrcB,
+ float32_t * pDst,
+ uint32_t numSamples);
+
+
+ /**
+ * @brief Converts the elements of the floating-point vector to Q31 vector.
+ * @param[in] pSrc points to the floating-point input vector
+ * @param[out] pDst points to the Q31 output vector
+ * @param[in] blockSize length of the input vector
+ */
+ void arm_float_to_q31(
+ float32_t * pSrc,
+ q31_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Converts the elements of the floating-point vector to Q15 vector.
+ * @param[in] pSrc points to the floating-point input vector
+ * @param[out] pDst points to the Q15 output vector
+ * @param[in] blockSize length of the input vector
+ */
+ void arm_float_to_q15(
+ float32_t * pSrc,
+ q15_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Converts the elements of the floating-point vector to Q7 vector.
+ * @param[in] pSrc points to the floating-point input vector
+ * @param[out] pDst points to the Q7 output vector
+ * @param[in] blockSize length of the input vector
+ */
+ void arm_float_to_q7(
+ float32_t * pSrc,
+ q7_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Converts the elements of the Q31 vector to Q15 vector.
+ * @param[in] pSrc is input pointer
+ * @param[out] pDst is output pointer
+ * @param[in] blockSize is the number of samples to process
+ */
+ void arm_q31_to_q15(
+ q31_t * pSrc,
+ q15_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Converts the elements of the Q31 vector to Q7 vector.
+ * @param[in] pSrc is input pointer
+ * @param[out] pDst is output pointer
+ * @param[in] blockSize is the number of samples to process
+ */
+ void arm_q31_to_q7(
+ q31_t * pSrc,
+ q7_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Converts the elements of the Q15 vector to floating-point vector.
+ * @param[in] pSrc is input pointer
+ * @param[out] pDst is output pointer
+ * @param[in] blockSize is the number of samples to process
+ */
+ void arm_q15_to_float(
+ q15_t * pSrc,
+ float32_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Converts the elements of the Q15 vector to Q31 vector.
+ * @param[in] pSrc is input pointer
+ * @param[out] pDst is output pointer
+ * @param[in] blockSize is the number of samples to process
+ */
+ void arm_q15_to_q31(
+ q15_t * pSrc,
+ q31_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Converts the elements of the Q15 vector to Q7 vector.
+ * @param[in] pSrc is input pointer
+ * @param[out] pDst is output pointer
+ * @param[in] blockSize is the number of samples to process
+ */
+ void arm_q15_to_q7(
+ q15_t * pSrc,
+ q7_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @ingroup groupInterpolation
+ */
+
+ /**
+ * @defgroup BilinearInterpolate Bilinear Interpolation
+ *
+ * Bilinear interpolation is an extension of linear interpolation applied to a two dimensional grid.
+ * The underlying function <code>f(x, y)</code> is sampled on a regular grid and the interpolation process
+ * determines values between the grid points.
+ * Bilinear interpolation is equivalent to two step linear interpolation, first in the x-dimension and then in the y-dimension.
+ * Bilinear interpolation is often used in image processing to rescale images.
+ * The CMSIS DSP library provides bilinear interpolation functions for Q7, Q15, Q31, and floating-point data types.
+ *
+ * <b>Algorithm</b>
+ * \par
+ * The instance structure used by the bilinear interpolation functions describes a two dimensional data table.
+ * For floating-point, the instance structure is defined as:
+ * <pre>
+ * typedef struct
+ * {
+ * uint16_t numRows;
+ * uint16_t numCols;
+ * float32_t *pData;
+ * } arm_bilinear_interp_instance_f32;
+ * </pre>
+ *
+ * \par
+ * where <code>numRows</code> specifies the number of rows in the table;
+ * <code>numCols</code> specifies the number of columns in the table;
+ * and <code>pData</code> points to an array of size <code>numRows*numCols</code> values.
+ * The data table <code>pTable</code> is organized in row order and the supplied data values fall on integer indexes.
+ * That is, table element (x,y) is located at <code>pTable[x + y*numCols]</code> where x and y are integers.
+ *
+ * \par
+ * Let <code>(x, y)</code> specify the desired interpolation point. Then define:
+ * <pre>
+ * XF = floor(x)
+ * YF = floor(y)
+ * </pre>
+ * \par
+ * The interpolated output point is computed as:
+ * <pre>
+ * f(x, y) = f(XF, YF) * (1-(x-XF)) * (1-(y-YF))
+ * + f(XF+1, YF) * (x-XF)*(1-(y-YF))
+ * + f(XF, YF+1) * (1-(x-XF))*(y-YF)
+ * + f(XF+1, YF+1) * (x-XF)*(y-YF)
+ * </pre>
+ * Note that the coordinates (x, y) contain integer and fractional components.
+ * The integer components specify which portion of the table to use while the
+ * fractional components control the interpolation processor.
+ *
+ * \par
+ * if (x,y) are outside of the table boundary, Bilinear interpolation returns zero output.
+ */
+
+ /**
+ * @addtogroup BilinearInterpolate
+ * @{
+ */
+
+
+ /**
+ *
+ * @brief Floating-point bilinear interpolation.
+ * @param[in,out] S points to an instance of the interpolation structure.
+ * @param[in] X interpolation coordinate.
+ * @param[in] Y interpolation coordinate.
+ * @return out interpolated value.
+ */
+ CMSIS_INLINE __STATIC_INLINE float32_t arm_bilinear_interp_f32(
+ const arm_bilinear_interp_instance_f32 * S,
+ float32_t X,
+ float32_t Y)
+ {
+ float32_t out;
+ float32_t f00, f01, f10, f11;
+ float32_t *pData = S->pData;
+ int32_t xIndex, yIndex, index;
+ float32_t xdiff, ydiff;
+ float32_t b1, b2, b3, b4;
+
+ xIndex = (int32_t) X;
+ yIndex = (int32_t) Y;
+
+ /* Care taken for table outside boundary */
+ /* Returns zero output when values are outside table boundary */
+ if (xIndex < 0 || xIndex > (S->numRows - 1) || yIndex < 0 || yIndex > (S->numCols - 1))
+ {
+ return (0);
+ }
+
+ /* Calculation of index for two nearest points in X-direction */
+ index = (xIndex - 1) + (yIndex - 1) * S->numCols;
+
+
+ /* Read two nearest points in X-direction */
+ f00 = pData[index];
+ f01 = pData[index + 1];
+
+ /* Calculation of index for two nearest points in Y-direction */
+ index = (xIndex - 1) + (yIndex) * S->numCols;
+
+
+ /* Read two nearest points in Y-direction */
+ f10 = pData[index];
+ f11 = pData[index + 1];
+
+ /* Calculation of intermediate values */
+ b1 = f00;
+ b2 = f01 - f00;
+ b3 = f10 - f00;
+ b4 = f00 - f01 - f10 + f11;
+
+ /* Calculation of fractional part in X */
+ xdiff = X - xIndex;
+
+ /* Calculation of fractional part in Y */
+ ydiff = Y - yIndex;
+
+ /* Calculation of bi-linear interpolated output */
+ out = b1 + b2 * xdiff + b3 * ydiff + b4 * xdiff * ydiff;
+
+ /* return to application */
+ return (out);
+ }
+
+
+ /**
+ *
+ * @brief Q31 bilinear interpolation.
+ * @param[in,out] S points to an instance of the interpolation structure.
+ * @param[in] X interpolation coordinate in 12.20 format.
+ * @param[in] Y interpolation coordinate in 12.20 format.
+ * @return out interpolated value.
+ */
+ CMSIS_INLINE __STATIC_INLINE q31_t arm_bilinear_interp_q31(
+ arm_bilinear_interp_instance_q31 * S,
+ q31_t X,
+ q31_t Y)
+ {
+ q31_t out; /* Temporary output */
+ q31_t acc = 0; /* output */
+ q31_t xfract, yfract; /* X, Y fractional parts */
+ q31_t x1, x2, y1, y2; /* Nearest output values */
+ int32_t rI, cI; /* Row and column indices */
+ q31_t *pYData = S->pData; /* pointer to output table values */
+ uint32_t nCols = S->numCols; /* num of rows */
+
+ /* Input is in 12.20 format */
+ /* 12 bits for the table index */
+ /* Index value calculation */
+ rI = ((X & (q31_t)0xFFF00000) >> 20);
+
+ /* Input is in 12.20 format */
+ /* 12 bits for the table index */
+ /* Index value calculation */
+ cI = ((Y & (q31_t)0xFFF00000) >> 20);
+
+ /* Care taken for table outside boundary */
+ /* Returns zero output when values are outside table boundary */
+ if (rI < 0 || rI > (S->numRows - 1) || cI < 0 || cI > (S->numCols - 1))
+ {
+ return (0);
+ }
+
+ /* 20 bits for the fractional part */
+ /* shift left xfract by 11 to keep 1.31 format */
+ xfract = (X & 0x000FFFFF) << 11U;
+
+ /* Read two nearest output values from the index */
+ x1 = pYData[(rI) + (int32_t)nCols * (cI) ];
+ x2 = pYData[(rI) + (int32_t)nCols * (cI) + 1];
+
+ /* 20 bits for the fractional part */
+ /* shift left yfract by 11 to keep 1.31 format */
+ yfract = (Y & 0x000FFFFF) << 11U;
+
+ /* Read two nearest output values from the index */
+ y1 = pYData[(rI) + (int32_t)nCols * (cI + 1) ];
+ y2 = pYData[(rI) + (int32_t)nCols * (cI + 1) + 1];
+
+ /* Calculation of x1 * (1-xfract ) * (1-yfract) and acc is in 3.29(q29) format */
+ out = ((q31_t) (((q63_t) x1 * (0x7FFFFFFF - xfract)) >> 32));
+ acc = ((q31_t) (((q63_t) out * (0x7FFFFFFF - yfract)) >> 32));
+
+ /* x2 * (xfract) * (1-yfract) in 3.29(q29) and adding to acc */
+ out = ((q31_t) ((q63_t) x2 * (0x7FFFFFFF - yfract) >> 32));
+ acc += ((q31_t) ((q63_t) out * (xfract) >> 32));
+
+ /* y1 * (1 - xfract) * (yfract) in 3.29(q29) and adding to acc */
+ out = ((q31_t) ((q63_t) y1 * (0x7FFFFFFF - xfract) >> 32));
+ acc += ((q31_t) ((q63_t) out * (yfract) >> 32));
+
+ /* y2 * (xfract) * (yfract) in 3.29(q29) and adding to acc */
+ out = ((q31_t) ((q63_t) y2 * (xfract) >> 32));
+ acc += ((q31_t) ((q63_t) out * (yfract) >> 32));
+
+ /* Convert acc to 1.31(q31) format */
+ return ((q31_t)(acc << 2));
+ }
+
+
+ /**
+ * @brief Q15 bilinear interpolation.
+ * @param[in,out] S points to an instance of the interpolation structure.
+ * @param[in] X interpolation coordinate in 12.20 format.
+ * @param[in] Y interpolation coordinate in 12.20 format.
+ * @return out interpolated value.
+ */
+ CMSIS_INLINE __STATIC_INLINE q15_t arm_bilinear_interp_q15(
+ arm_bilinear_interp_instance_q15 * S,
+ q31_t X,
+ q31_t Y)
+ {
+ q63_t acc = 0; /* output */
+ q31_t out; /* Temporary output */
+ q15_t x1, x2, y1, y2; /* Nearest output values */
+ q31_t xfract, yfract; /* X, Y fractional parts */
+ int32_t rI, cI; /* Row and column indices */
+ q15_t *pYData = S->pData; /* pointer to output table values */
+ uint32_t nCols = S->numCols; /* num of rows */
+
+ /* Input is in 12.20 format */
+ /* 12 bits for the table index */
+ /* Index value calculation */
+ rI = ((X & (q31_t)0xFFF00000) >> 20);
+
+ /* Input is in 12.20 format */
+ /* 12 bits for the table index */
+ /* Index value calculation */
+ cI = ((Y & (q31_t)0xFFF00000) >> 20);
+
+ /* Care taken for table outside boundary */
+ /* Returns zero output when values are outside table boundary */
+ if (rI < 0 || rI > (S->numRows - 1) || cI < 0 || cI > (S->numCols - 1))
+ {
+ return (0);
+ }
+
+ /* 20 bits for the fractional part */
+ /* xfract should be in 12.20 format */
+ xfract = (X & 0x000FFFFF);
+
+ /* Read two nearest output values from the index */
+ x1 = pYData[((uint32_t)rI) + nCols * ((uint32_t)cI) ];
+ x2 = pYData[((uint32_t)rI) + nCols * ((uint32_t)cI) + 1];
+
+ /* 20 bits for the fractional part */
+ /* yfract should be in 12.20 format */
+ yfract = (Y & 0x000FFFFF);
+
+ /* Read two nearest output values from the index */
+ y1 = pYData[((uint32_t)rI) + nCols * ((uint32_t)cI + 1) ];
+ y2 = pYData[((uint32_t)rI) + nCols * ((uint32_t)cI + 1) + 1];
+
+ /* Calculation of x1 * (1-xfract ) * (1-yfract) and acc is in 13.51 format */
+
+ /* x1 is in 1.15(q15), xfract in 12.20 format and out is in 13.35 format */
+ /* convert 13.35 to 13.31 by right shifting and out is in 1.31 */
+ out = (q31_t) (((q63_t) x1 * (0xFFFFF - xfract)) >> 4U);
+ acc = ((q63_t) out * (0xFFFFF - yfract));
+
+ /* x2 * (xfract) * (1-yfract) in 1.51 and adding to acc */
+ out = (q31_t) (((q63_t) x2 * (0xFFFFF - yfract)) >> 4U);
+ acc += ((q63_t) out * (xfract));
+
+ /* y1 * (1 - xfract) * (yfract) in 1.51 and adding to acc */
+ out = (q31_t) (((q63_t) y1 * (0xFFFFF - xfract)) >> 4U);
+ acc += ((q63_t) out * (yfract));
+
+ /* y2 * (xfract) * (yfract) in 1.51 and adding to acc */
+ out = (q31_t) (((q63_t) y2 * (xfract)) >> 4U);
+ acc += ((q63_t) out * (yfract));
+
+ /* acc is in 13.51 format and down shift acc by 36 times */
+ /* Convert out to 1.15 format */
+ return ((q15_t)(acc >> 36));
+ }
+
+
+ /**
+ * @brief Q7 bilinear interpolation.
+ * @param[in,out] S points to an instance of the interpolation structure.
+ * @param[in] X interpolation coordinate in 12.20 format.
+ * @param[in] Y interpolation coordinate in 12.20 format.
+ * @return out interpolated value.
+ */
+ CMSIS_INLINE __STATIC_INLINE q7_t arm_bilinear_interp_q7(
+ arm_bilinear_interp_instance_q7 * S,
+ q31_t X,
+ q31_t Y)
+ {
+ q63_t acc = 0; /* output */
+ q31_t out; /* Temporary output */
+ q31_t xfract, yfract; /* X, Y fractional parts */
+ q7_t x1, x2, y1, y2; /* Nearest output values */
+ int32_t rI, cI; /* Row and column indices */
+ q7_t *pYData = S->pData; /* pointer to output table values */
+ uint32_t nCols = S->numCols; /* num of rows */
+
+ /* Input is in 12.20 format */
+ /* 12 bits for the table index */
+ /* Index value calculation */
+ rI = ((X & (q31_t)0xFFF00000) >> 20);
+
+ /* Input is in 12.20 format */
+ /* 12 bits for the table index */
+ /* Index value calculation */
+ cI = ((Y & (q31_t)0xFFF00000) >> 20);
+
+ /* Care taken for table outside boundary */
+ /* Returns zero output when values are outside table boundary */
+ if (rI < 0 || rI > (S->numRows - 1) || cI < 0 || cI > (S->numCols - 1))
+ {
+ return (0);
+ }
+
+ /* 20 bits for the fractional part */
+ /* xfract should be in 12.20 format */
+ xfract = (X & (q31_t)0x000FFFFF);
+
+ /* Read two nearest output values from the index */
+ x1 = pYData[((uint32_t)rI) + nCols * ((uint32_t)cI) ];
+ x2 = pYData[((uint32_t)rI) + nCols * ((uint32_t)cI) + 1];
+
+ /* 20 bits for the fractional part */
+ /* yfract should be in 12.20 format */
+ yfract = (Y & (q31_t)0x000FFFFF);
+
+ /* Read two nearest output values from the index */
+ y1 = pYData[((uint32_t)rI) + nCols * ((uint32_t)cI + 1) ];
+ y2 = pYData[((uint32_t)rI) + nCols * ((uint32_t)cI + 1) + 1];
+
+ /* Calculation of x1 * (1-xfract ) * (1-yfract) and acc is in 16.47 format */
+ out = ((x1 * (0xFFFFF - xfract)));
+ acc = (((q63_t) out * (0xFFFFF - yfract)));
+
+ /* x2 * (xfract) * (1-yfract) in 2.22 and adding to acc */
+ out = ((x2 * (0xFFFFF - yfract)));
+ acc += (((q63_t) out * (xfract)));
+
+ /* y1 * (1 - xfract) * (yfract) in 2.22 and adding to acc */
+ out = ((y1 * (0xFFFFF - xfract)));
+ acc += (((q63_t) out * (yfract)));
+
+ /* y2 * (xfract) * (yfract) in 2.22 and adding to acc */
+ out = ((y2 * (yfract)));
+ acc += (((q63_t) out * (xfract)));
+
+ /* acc in 16.47 format and down shift by 40 to convert to 1.7 format */
+ return ((q7_t)(acc >> 40));
+ }
+
+ /**
+ * @} end of BilinearInterpolate group
+ */
+
+
+/* SMMLAR */
+#define multAcc_32x32_keep32_R(a, x, y) \
+ a = (q31_t) (((((q63_t) a) << 32) + ((q63_t) x * y) + 0x80000000LL ) >> 32)
+
+/* SMMLSR */
+#define multSub_32x32_keep32_R(a, x, y) \
+ a = (q31_t) (((((q63_t) a) << 32) - ((q63_t) x * y) + 0x80000000LL ) >> 32)
+
+/* SMMULR */
+#define mult_32x32_keep32_R(a, x, y) \
+ a = (q31_t) (((q63_t) x * y + 0x80000000LL ) >> 32)
+
+/* SMMLA */
+#define multAcc_32x32_keep32(a, x, y) \
+ a += (q31_t) (((q63_t) x * y) >> 32)
+
+/* SMMLS */
+#define multSub_32x32_keep32(a, x, y) \
+ a -= (q31_t) (((q63_t) x * y) >> 32)
+
+/* SMMUL */
+#define mult_32x32_keep32(a, x, y) \
+ a = (q31_t) (((q63_t) x * y ) >> 32)
+
+
+#if defined ( __CC_ARM )
+ /* Enter low optimization region - place directly above function definition */
+ #if defined( ARM_MATH_CM4 ) || defined( ARM_MATH_CM7)
+ #define LOW_OPTIMIZATION_ENTER \
+ _Pragma ("push") \
+ _Pragma ("O1")
+ #else
+ #define LOW_OPTIMIZATION_ENTER
+ #endif
+
+ /* Exit low optimization region - place directly after end of function definition */
+ #if defined ( ARM_MATH_CM4 ) || defined ( ARM_MATH_CM7 )
+ #define LOW_OPTIMIZATION_EXIT \
+ _Pragma ("pop")
+ #else
+ #define LOW_OPTIMIZATION_EXIT
+ #endif
+
+ /* Enter low optimization region - place directly above function definition */
+ #define IAR_ONLY_LOW_OPTIMIZATION_ENTER
+
+ /* Exit low optimization region - place directly after end of function definition */
+ #define IAR_ONLY_LOW_OPTIMIZATION_EXIT
+
+#elif defined (__ARMCC_VERSION ) && ( __ARMCC_VERSION >= 6010050 )
+ #define LOW_OPTIMIZATION_ENTER
+ #define LOW_OPTIMIZATION_EXIT
+ #define IAR_ONLY_LOW_OPTIMIZATION_ENTER
+ #define IAR_ONLY_LOW_OPTIMIZATION_EXIT
+
+#elif defined ( __GNUC__ )
+ #define LOW_OPTIMIZATION_ENTER \
+ __attribute__(( optimize("-O1") ))
+ #define LOW_OPTIMIZATION_EXIT
+ #define IAR_ONLY_LOW_OPTIMIZATION_ENTER
+ #define IAR_ONLY_LOW_OPTIMIZATION_EXIT
+
+#elif defined ( __ICCARM__ )
+ /* Enter low optimization region - place directly above function definition */
+ #if defined ( ARM_MATH_CM4 ) || defined ( ARM_MATH_CM7 )
+ #define LOW_OPTIMIZATION_ENTER \
+ _Pragma ("optimize=low")
+ #else
+ #define LOW_OPTIMIZATION_ENTER
+ #endif
+
+ /* Exit low optimization region - place directly after end of function definition */
+ #define LOW_OPTIMIZATION_EXIT
+
+ /* Enter low optimization region - place directly above function definition */
+ #if defined ( ARM_MATH_CM4 ) || defined ( ARM_MATH_CM7 )
+ #define IAR_ONLY_LOW_OPTIMIZATION_ENTER \
+ _Pragma ("optimize=low")
+ #else
+ #define IAR_ONLY_LOW_OPTIMIZATION_ENTER
+ #endif
+
+ /* Exit low optimization region - place directly after end of function definition */
+ #define IAR_ONLY_LOW_OPTIMIZATION_EXIT
+
+#elif defined ( __TI_ARM__ )
+ #define LOW_OPTIMIZATION_ENTER
+ #define LOW_OPTIMIZATION_EXIT
+ #define IAR_ONLY_LOW_OPTIMIZATION_ENTER
+ #define IAR_ONLY_LOW_OPTIMIZATION_EXIT
+
+#elif defined ( __CSMC__ )
+ #define LOW_OPTIMIZATION_ENTER
+ #define LOW_OPTIMIZATION_EXIT
+ #define IAR_ONLY_LOW_OPTIMIZATION_ENTER
+ #define IAR_ONLY_LOW_OPTIMIZATION_EXIT
+
+#elif defined ( __TASKING__ )
+ #define LOW_OPTIMIZATION_ENTER
+ #define LOW_OPTIMIZATION_EXIT
+ #define IAR_ONLY_LOW_OPTIMIZATION_ENTER
+ #define IAR_ONLY_LOW_OPTIMIZATION_EXIT
+
+#endif
+
+
+#ifdef __cplusplus
+}
+#endif
+
+/* Compiler specific diagnostic adjustment */
+#if defined ( __CC_ARM )
+
+#elif defined ( __ARMCC_VERSION ) && ( __ARMCC_VERSION >= 6010050 )
+
+#elif defined ( __GNUC__ )
+#pragma GCC diagnostic pop
+
+#elif defined ( __ICCARM__ )
+
+#elif defined ( __TI_ARM__ )
+
+#elif defined ( __CSMC__ )
+
+#elif defined ( __TASKING__ )
+
+#else
+ #error Unknown compiler
+#endif
+
+#endif /* _ARM_MATH_H */
+
+/**
+ *
+ * End of file.
+ */
diff --git a/CMSIS/cmsis_armcc.h b/CMSIS/cmsis_armcc.h
new file mode 100644
index 0000000..093d35b
--- /dev/null
+++ b/CMSIS/cmsis_armcc.h
@@ -0,0 +1,870 @@
+/**************************************************************************//**
+ * @file cmsis_armcc.h
+ * @brief CMSIS compiler ARMCC (Arm Compiler 5) 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_ARMCC_H
+#define __CMSIS_ARMCC_H
+
+
+#if defined(__ARMCC_VERSION) && (__ARMCC_VERSION < 400677)
+ #error "Please use Arm Compiler Toolchain V4.0.677 or later!"
+#endif
+
+/* CMSIS compiler control architecture macros */
+#if ((defined (__TARGET_ARCH_6_M ) && (__TARGET_ARCH_6_M == 1)) || \
+ (defined (__TARGET_ARCH_6S_M ) && (__TARGET_ARCH_6S_M == 1)) )
+ #define __ARM_ARCH_6M__ 1
+#endif
+
+#if (defined (__TARGET_ARCH_7_M ) && (__TARGET_ARCH_7_M == 1))
+ #define __ARM_ARCH_7M__ 1
+#endif
+
+#if (defined (__TARGET_ARCH_7E_M) && (__TARGET_ARCH_7E_M == 1))
+ #define __ARM_ARCH_7EM__ 1
+#endif
+
+ /* __ARM_ARCH_8M_BASE__ not applicable */
+ /* __ARM_ARCH_8M_MAIN__ not applicable */
+
+
+/* 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 static __forceinline
+#endif
+#ifndef __NO_RETURN
+ #define __NO_RETURN __declspec(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 __packed struct
+#endif
+#ifndef __PACKED_UNION
+ #define __PACKED_UNION __packed union
+#endif
+#ifndef __UNALIGNED_UINT32 /* deprecated */
+ #define __UNALIGNED_UINT32(x) (*((__packed uint32_t *)(x)))
+#endif
+#ifndef __UNALIGNED_UINT16_WRITE
+ #define __UNALIGNED_UINT16_WRITE(addr, val) ((*((__packed uint16_t *)(addr))) = (val))
+#endif
+#ifndef __UNALIGNED_UINT16_READ
+ #define __UNALIGNED_UINT16_READ(addr) (*((const __packed uint16_t *)(addr)))
+#endif
+#ifndef __UNALIGNED_UINT32_WRITE
+ #define __UNALIGNED_UINT32_WRITE(addr, val) ((*((__packed uint32_t *)(addr))) = (val))
+#endif
+#ifndef __UNALIGNED_UINT32_READ
+ #define __UNALIGNED_UINT32_READ(addr) (*((const __packed uint32_t *)(addr)))
+#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.
+ */
+/* intrinsic void __enable_irq(); */
+
+
+/**
+ \brief Disable IRQ Interrupts
+ \details Disables IRQ interrupts by setting the I-bit in the CPSR.
+ Can only be executed in Privileged modes.
+ */
+/* intrinsic void __disable_irq(); */
+
+/**
+ \brief Get Control Register
+ \details Returns the content of the Control Register.
+ \return Control Register value
+ */
+__STATIC_INLINE uint32_t __get_CONTROL(void)
+{
+ register uint32_t __regControl __ASM("control");
+ return(__regControl);
+}
+
+
+/**
+ \brief Set Control Register
+ \details Writes the given value to the Control Register.
+ \param [in] control Control Register value to set
+ */
+__STATIC_INLINE void __set_CONTROL(uint32_t control)
+{
+ register uint32_t __regControl __ASM("control");
+ __regControl = control;
+}
+
+
+/**
+ \brief Get IPSR Register
+ \details Returns the content of the IPSR Register.
+ \return IPSR Register value
+ */
+__STATIC_INLINE uint32_t __get_IPSR(void)
+{
+ register uint32_t __regIPSR __ASM("ipsr");
+ return(__regIPSR);
+}
+
+
+/**
+ \brief Get APSR Register
+ \details Returns the content of the APSR Register.
+ \return APSR Register value
+ */
+__STATIC_INLINE uint32_t __get_APSR(void)
+{
+ register uint32_t __regAPSR __ASM("apsr");
+ return(__regAPSR);
+}
+
+
+/**
+ \brief Get xPSR Register
+ \details Returns the content of the xPSR Register.
+ \return xPSR Register value
+ */
+__STATIC_INLINE uint32_t __get_xPSR(void)
+{
+ register uint32_t __regXPSR __ASM("xpsr");
+ return(__regXPSR);
+}
+
+
+/**
+ \brief Get Process Stack Pointer
+ \details Returns the current value of the Process Stack Pointer (PSP).
+ \return PSP Register value
+ */
+__STATIC_INLINE uint32_t __get_PSP(void)
+{
+ register uint32_t __regProcessStackPointer __ASM("psp");
+ return(__regProcessStackPointer);
+}
+
+
+/**
+ \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_INLINE void __set_PSP(uint32_t topOfProcStack)
+{
+ register uint32_t __regProcessStackPointer __ASM("psp");
+ __regProcessStackPointer = topOfProcStack;
+}
+
+
+/**
+ \brief Get Main Stack Pointer
+ \details Returns the current value of the Main Stack Pointer (MSP).
+ \return MSP Register value
+ */
+__STATIC_INLINE uint32_t __get_MSP(void)
+{
+ register uint32_t __regMainStackPointer __ASM("msp");
+ return(__regMainStackPointer);
+}
+
+
+/**
+ \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_INLINE void __set_MSP(uint32_t topOfMainStack)
+{
+ register uint32_t __regMainStackPointer __ASM("msp");
+ __regMainStackPointer = topOfMainStack;
+}
+
+
+/**
+ \brief Get Priority Mask
+ \details Returns the current state of the priority mask bit from the Priority Mask Register.
+ \return Priority Mask value
+ */
+__STATIC_INLINE uint32_t __get_PRIMASK(void)
+{
+ register uint32_t __regPriMask __ASM("primask");
+ return(__regPriMask);
+}
+
+
+/**
+ \brief Set Priority Mask
+ \details Assigns the given value to the Priority Mask Register.
+ \param [in] priMask Priority Mask
+ */
+__STATIC_INLINE void __set_PRIMASK(uint32_t priMask)
+{
+ register uint32_t __regPriMask __ASM("primask");
+ __regPriMask = (priMask);
+}
+
+
+#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \
+ (defined (__ARM_ARCH_7EM__) && (__ARM_ARCH_7EM__ == 1)) )
+
+/**
+ \brief Enable FIQ
+ \details Enables FIQ interrupts by clearing the F-bit in the CPSR.
+ Can only be executed in Privileged modes.
+ */
+#define __enable_fault_irq __enable_fiq
+
+
+/**
+ \brief Disable FIQ
+ \details Disables FIQ interrupts by setting the F-bit in the CPSR.
+ Can only be executed in Privileged modes.
+ */
+#define __disable_fault_irq __disable_fiq
+
+
+/**
+ \brief Get Base Priority
+ \details Returns the current value of the Base Priority register.
+ \return Base Priority register value
+ */
+__STATIC_INLINE uint32_t __get_BASEPRI(void)
+{
+ register uint32_t __regBasePri __ASM("basepri");
+ return(__regBasePri);
+}
+
+
+/**
+ \brief Set Base Priority
+ \details Assigns the given value to the Base Priority register.
+ \param [in] basePri Base Priority value to set
+ */
+__STATIC_INLINE void __set_BASEPRI(uint32_t basePri)
+{
+ register uint32_t __regBasePri __ASM("basepri");
+ __regBasePri = (basePri & 0xFFU);
+}
+
+
+/**
+ \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_INLINE void __set_BASEPRI_MAX(uint32_t basePri)
+{
+ register uint32_t __regBasePriMax __ASM("basepri_max");
+ __regBasePriMax = (basePri & 0xFFU);
+}
+
+
+/**
+ \brief Get Fault Mask
+ \details Returns the current value of the Fault Mask register.
+ \return Fault Mask register value
+ */
+__STATIC_INLINE uint32_t __get_FAULTMASK(void)
+{
+ register uint32_t __regFaultMask __ASM("faultmask");
+ return(__regFaultMask);
+}
+
+
+/**
+ \brief Set Fault Mask
+ \details Assigns the given value to the Fault Mask register.
+ \param [in] faultMask Fault Mask value to set
+ */
+__STATIC_INLINE void __set_FAULTMASK(uint32_t faultMask)
+{
+ register uint32_t __regFaultMask __ASM("faultmask");
+ __regFaultMask = (faultMask & (uint32_t)1U);
+}
+
+#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \
+ (defined (__ARM_ARCH_7EM__) && (__ARM_ARCH_7EM__ == 1)) ) */
+
+
+#if ((defined (__ARM_ARCH_7EM__) && (__ARM_ARCH_7EM__ == 1)) )
+
+/**
+ \brief Get FPSCR
+ \details Returns the current value of the Floating Point Status/Control register.
+ \return Floating Point Status/Control register value
+ */
+__STATIC_INLINE uint32_t __get_FPSCR(void)
+{
+#if ((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \
+ (defined (__FPU_USED ) && (__FPU_USED == 1U)) )
+ register uint32_t __regfpscr __ASM("fpscr");
+ return(__regfpscr);
+#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_INLINE void __set_FPSCR(uint32_t fpscr)
+{
+#if ((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \
+ (defined (__FPU_USED ) && (__FPU_USED == 1U)) )
+ register uint32_t __regfpscr __ASM("fpscr");
+ __regfpscr = (fpscr);
+#else
+ (void)fpscr;
+#endif
+}
+
+#endif /* ((defined (__ARM_ARCH_7EM__) && (__ARM_ARCH_7EM__ == 1)) ) */
+
+
+
+/*@} end of CMSIS_Core_RegAccFunctions */
+
+
+/* ########################## Core Instruction Access ######################### */
+/** \defgroup CMSIS_Core_InstructionInterface CMSIS Core Instruction Interface
+ Access to dedicated instructions
+ @{
+*/
+
+/**
+ \brief No Operation
+ \details No Operation does nothing. This instruction can be used for code alignment purposes.
+ */
+#define __NOP __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 __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 __wfe
+
+
+/**
+ \brief Send Event
+ \details Send Event is a hint instruction. It causes an event to be signaled to the CPU.
+ */
+#define __SEV __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.
+ */
+#define __ISB() do {\
+ __schedule_barrier();\
+ __isb(0xF);\
+ __schedule_barrier();\
+ } while (0U)
+
+/**
+ \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.
+ */
+#define __DSB() do {\
+ __schedule_barrier();\
+ __dsb(0xF);\
+ __schedule_barrier();\
+ } while (0U)
+
+/**
+ \brief Data Memory Barrier
+ \details Ensures the apparent order of the explicit memory operations before
+ and after the instruction, without ensuring their completion.
+ */
+#define __DMB() do {\
+ __schedule_barrier();\
+ __dmb(0xF);\
+ __schedule_barrier();\
+ } while (0U)
+
+
+/**
+ \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
+ */
+#define __REV __rev
+
+
+/**
+ \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
+ */
+#ifndef __NO_EMBEDDED_ASM
+__attribute__((section(".rev16_text"))) __STATIC_INLINE __ASM uint32_t __REV16(uint32_t value)
+{
+ rev16 r0, r0
+ bx lr
+}
+#endif
+
+
+/**
+ \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
+ */
+#ifndef __NO_EMBEDDED_ASM
+__attribute__((section(".revsh_text"))) __STATIC_INLINE __ASM int16_t __REVSH(int16_t value)
+{
+ revsh r0, r0
+ bx lr
+}
+#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
+ */
+#define __ROR __ror
+
+
+/**
+ \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) __breakpoint(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
+ */
+#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \
+ (defined (__ARM_ARCH_7EM__) && (__ARM_ARCH_7EM__ == 1)) )
+ #define __RBIT __rbit
+#else
+__attribute__((always_inline)) __STATIC_INLINE uint32_t __RBIT(uint32_t value)
+{
+ uint32_t result;
+ 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 */
+ return result;
+}
+#endif
+
+
+/**
+ \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 __clz
+
+
+#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \
+ (defined (__ARM_ARCH_7EM__) && (__ARM_ARCH_7EM__ == 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)
+ */
+#if defined(__ARMCC_VERSION) && (__ARMCC_VERSION < 5060020)
+ #define __LDREXB(ptr) ((uint8_t ) __ldrex(ptr))
+#else
+ #define __LDREXB(ptr) _Pragma("push") _Pragma("diag_suppress 3731") ((uint8_t ) __ldrex(ptr)) _Pragma("pop")
+#endif
+
+
+/**
+ \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)
+ */
+#if defined(__ARMCC_VERSION) && (__ARMCC_VERSION < 5060020)
+ #define __LDREXH(ptr) ((uint16_t) __ldrex(ptr))
+#else
+ #define __LDREXH(ptr) _Pragma("push") _Pragma("diag_suppress 3731") ((uint16_t) __ldrex(ptr)) _Pragma("pop")
+#endif
+
+
+/**
+ \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)
+ */
+#if defined(__ARMCC_VERSION) && (__ARMCC_VERSION < 5060020)
+ #define __LDREXW(ptr) ((uint32_t ) __ldrex(ptr))
+#else
+ #define __LDREXW(ptr) _Pragma("push") _Pragma("diag_suppress 3731") ((uint32_t ) __ldrex(ptr)) _Pragma("pop")
+#endif
+
+
+/**
+ \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
+ */
+#if defined(__ARMCC_VERSION) && (__ARMCC_VERSION < 5060020)
+ #define __STREXB(value, ptr) __strex(value, ptr)
+#else
+ #define __STREXB(value, ptr) _Pragma("push") _Pragma("diag_suppress 3731") __strex(value, ptr) _Pragma("pop")
+#endif
+
+
+/**
+ \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
+ */
+#if defined(__ARMCC_VERSION) && (__ARMCC_VERSION < 5060020)
+ #define __STREXH(value, ptr) __strex(value, ptr)
+#else
+ #define __STREXH(value, ptr) _Pragma("push") _Pragma("diag_suppress 3731") __strex(value, ptr) _Pragma("pop")
+#endif
+
+
+/**
+ \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
+ */
+#if defined(__ARMCC_VERSION) && (__ARMCC_VERSION < 5060020)
+ #define __STREXW(value, ptr) __strex(value, ptr)
+#else
+ #define __STREXW(value, ptr) _Pragma("push") _Pragma("diag_suppress 3731") __strex(value, ptr) _Pragma("pop")
+#endif
+
+
+/**
+ \brief Remove the exclusive lock
+ \details Removes the exclusive lock which is created by LDREX.
+ */
+#define __CLREX __clrex
+
+
+/**
+ \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
+ */
+#define __SSAT __ssat
+
+
+/**
+ \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
+ */
+#define __USAT __usat
+
+
+/**
+ \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
+ */
+#ifndef __NO_EMBEDDED_ASM
+__attribute__((section(".rrx_text"))) __STATIC_INLINE __ASM uint32_t __RRX(uint32_t value)
+{
+ rrx r0, r0
+ bx lr
+}
+#endif
+
+
+/**
+ \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)
+ */
+#define __LDRBT(ptr) ((uint8_t ) __ldrt(ptr))
+
+
+/**
+ \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)
+ */
+#define __LDRHT(ptr) ((uint16_t) __ldrt(ptr))
+
+
+/**
+ \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)
+ */
+#define __LDRT(ptr) ((uint32_t ) __ldrt(ptr))
+
+
+/**
+ \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
+ */
+#define __STRBT(value, ptr) __strt(value, ptr)
+
+
+/**
+ \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
+ */
+#define __STRHT(value, ptr) __strt(value, ptr)
+
+
+/**
+ \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
+ */
+#define __STRT(value, ptr) __strt(value, ptr)
+
+#else /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \
+ (defined (__ARM_ARCH_7EM__) && (__ARM_ARCH_7EM__ == 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
+ */
+__attribute__((always_inline)) __STATIC_INLINE 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
+ */
+__attribute__((always_inline)) __STATIC_INLINE 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)) ) */
+
+/*@}*/ /* end of group CMSIS_Core_InstructionInterface */
+
+
+/* ################### Compiler specific Intrinsics ########################### */
+/** \defgroup CMSIS_SIMD_intrinsics CMSIS SIMD Intrinsics
+ Access to dedicated SIMD instructions
+ @{
+*/
+
+#if ((defined (__ARM_ARCH_7EM__) && (__ARM_ARCH_7EM__ == 1)) )
+
+#define __SADD8 __sadd8
+#define __QADD8 __qadd8
+#define __SHADD8 __shadd8
+#define __UADD8 __uadd8
+#define __UQADD8 __uqadd8
+#define __UHADD8 __uhadd8
+#define __SSUB8 __ssub8
+#define __QSUB8 __qsub8
+#define __SHSUB8 __shsub8
+#define __USUB8 __usub8
+#define __UQSUB8 __uqsub8
+#define __UHSUB8 __uhsub8
+#define __SADD16 __sadd16
+#define __QADD16 __qadd16
+#define __SHADD16 __shadd16
+#define __UADD16 __uadd16
+#define __UQADD16 __uqadd16
+#define __UHADD16 __uhadd16
+#define __SSUB16 __ssub16
+#define __QSUB16 __qsub16
+#define __SHSUB16 __shsub16
+#define __USUB16 __usub16
+#define __UQSUB16 __uqsub16
+#define __UHSUB16 __uhsub16
+#define __SASX __sasx
+#define __QASX __qasx
+#define __SHASX __shasx
+#define __UASX __uasx
+#define __UQASX __uqasx
+#define __UHASX __uhasx
+#define __SSAX __ssax
+#define __QSAX __qsax
+#define __SHSAX __shsax
+#define __USAX __usax
+#define __UQSAX __uqsax
+#define __UHSAX __uhsax
+#define __USAD8 __usad8
+#define __USADA8 __usada8
+#define __SSAT16 __ssat16
+#define __USAT16 __usat16
+#define __UXTB16 __uxtb16
+#define __UXTAB16 __uxtab16
+#define __SXTB16 __sxtb16
+#define __SXTAB16 __sxtab16
+#define __SMUAD __smuad
+#define __SMUADX __smuadx
+#define __SMLAD __smlad
+#define __SMLADX __smladx
+#define __SMLALD __smlald
+#define __SMLALDX __smlaldx
+#define __SMUSD __smusd
+#define __SMUSDX __smusdx
+#define __SMLSD __smlsd
+#define __SMLSDX __smlsdx
+#define __SMLSLD __smlsld
+#define __SMLSLDX __smlsldx
+#define __SEL __sel
+#define __QADD __qadd
+#define __QSUB __qsub
+
+#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) )
+
+#define __SMMLA(ARG1,ARG2,ARG3) ( (int32_t)((((int64_t)(ARG1) * (ARG2)) + \
+ ((int64_t)(ARG3) << 32U) ) >> 32U))
+
+#endif /* ((defined (__ARM_ARCH_7EM__) && (__ARM_ARCH_7EM__ == 1)) ) */
+/*@} end of group CMSIS_SIMD_intrinsics */
+
+
+#endif /* __CMSIS_ARMCC_H */
diff --git a/CMSIS/cmsis_armclang.h b/CMSIS/cmsis_armclang.h
new file mode 100644
index 0000000..5c4c20e
--- /dev/null
+++ b/CMSIS/cmsis_armclang.h
@@ -0,0 +1,1877 @@
+/**************************************************************************//**
+ * @file cmsis_armclang.h
+ * @brief CMSIS compiler armclang (Arm Compiler 6) 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.
+ */
+
+/*lint -esym(9058, IRQn)*/ /* disable MISRA 2012 Rule 2.4 for IRQn */
+
+#ifndef __CMSIS_ARMCLANG_H
+#define __CMSIS_ARMCLANG_H
+
+#pragma clang system_header /* treat file as system include file */
+
+#ifndef __ARM_COMPAT_H
+#include <arm_compat.h> /* Compatibility header for Arm Compiler 5 intrinsics */
+#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 clang diagnostic push
+ #pragma clang diagnostic ignored "-Wpacked"
+/*lint -esym(9058, T_UINT32)*/ /* disable MISRA 2012 Rule 2.4 for T_UINT32 */
+ struct __attribute__((packed)) T_UINT32 { uint32_t v; };
+ #pragma clang diagnostic pop
+ #define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v)
+#endif
+#ifndef __UNALIGNED_UINT16_WRITE
+ #pragma clang diagnostic push
+ #pragma clang diagnostic ignored "-Wpacked"
+/*lint -esym(9058, T_UINT16_WRITE)*/ /* disable MISRA 2012 Rule 2.4 for T_UINT16_WRITE */
+ __PACKED_STRUCT T_UINT16_WRITE { uint16_t v; };
+ #pragma clang diagnostic pop
+ #define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void *)(addr))->v) = (val))
+#endif
+#ifndef __UNALIGNED_UINT16_READ
+ #pragma clang diagnostic push
+ #pragma clang diagnostic ignored "-Wpacked"
+/*lint -esym(9058, T_UINT16_READ)*/ /* disable MISRA 2012 Rule 2.4 for T_UINT16_READ */
+ __PACKED_STRUCT T_UINT16_READ { uint16_t v; };
+ #pragma clang diagnostic pop
+ #define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v)
+#endif
+#ifndef __UNALIGNED_UINT32_WRITE
+ #pragma clang diagnostic push
+ #pragma clang diagnostic ignored "-Wpacked"
+/*lint -esym(9058, T_UINT32_WRITE)*/ /* disable MISRA 2012 Rule 2.4 for T_UINT32_WRITE */
+ __PACKED_STRUCT T_UINT32_WRITE { uint32_t v; };
+ #pragma clang diagnostic pop
+ #define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val))
+#endif
+#ifndef __UNALIGNED_UINT32_READ
+ #pragma clang diagnostic push
+ #pragma clang diagnostic ignored "-Wpacked"
+/*lint -esym(9058, T_UINT32_READ)*/ /* disable MISRA 2012 Rule 2.4 for T_UINT32_READ */
+ __PACKED_STRUCT T_UINT32_READ { uint32_t v; };
+ #pragma clang 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.
+ */
+/* intrinsic void __enable_irq(); see arm_compat.h */
+
+
+/**
+ \brief Disable IRQ Interrupts
+ \details Disables IRQ interrupts by setting the I-bit in the CPSR.
+ Can only be executed in Privileged modes.
+ */
+/* intrinsic void __disable_irq(); see arm_compat.h */
+
+
+/**
+ \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)
+{
+ register 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)
+{
+ register 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)
+{
+ register 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)
+{
+ register 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)
+{
+ register 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) );
+ 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) );
+ 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.
+ */
+#define __enable_fault_irq __enable_fiq /* see arm_compat.h */
+
+
+/**
+ \brief Disable FIQ
+ \details Disables FIQ interrupts by setting the F-bit in the CPSR.
+ Can only be executed in Privileged modes.
+ */
+#define __disable_fault_irq __disable_fiq /* see arm_compat.h */
+
+
+/**
+ \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
+ register 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 in non-secure
+ mode.
+
+ \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
+ register 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 in non-secure
+ mode.
+
+ \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.
+
+ \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
+ register 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
+ register 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.
+
+ \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)) ) */
+
+
+#if ((defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \
+ (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) )
+
+/**
+ \brief Get FPSCR
+ \details Returns the current value of the Floating Point Status/Control register.
+ \return Floating Point Status/Control register value
+ */
+#if ((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \
+ (defined (__FPU_USED ) && (__FPU_USED == 1U)) )
+#define __get_FPSCR (uint32_t)__builtin_arm_get_fpscr
+#else
+#define __get_FPSCR() ((uint32_t)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
+ */
+#if ((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \
+ (defined (__FPU_USED ) && (__FPU_USED == 1U)) )
+#define __set_FPSCR __builtin_arm_set_fpscr
+#else
+#define __set_FPSCR(x) ((void)(x))
+#endif
+
+#endif /* ((defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \
+ (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) */
+
+
+
+/*@} 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_USE_REG(r) "l" (r)
+#else
+#define __CMSIS_GCC_OUT_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 __builtin_arm_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 __builtin_arm_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 __builtin_arm_wfe
+
+
+/**
+ \brief Send Event
+ \details Send Event is a hint instruction. It causes an event to be signaled to the CPU.
+ */
+#define __SEV __builtin_arm_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.
+ */
+#define __ISB() __builtin_arm_isb(0xF);
+
+/**
+ \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.
+ */
+#define __DSB() __builtin_arm_dsb(0xF);
+
+
+/**
+ \brief Data Memory Barrier
+ \details Ensures the apparent order of the explicit memory operations before
+ and after the instruction, without ensuring their completion.
+ */
+#define __DMB() __builtin_arm_dmb(0xF);
+
+
+/**
+ \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
+ */
+#define __REV(value) __builtin_bswap32(value)
+
+
+/**
+ \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
+ */
+#define __REV16(value) __ROR(__REV(value), 16)
+
+
+/**
+ \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
+ */
+#define __REVSH(value) (int16_t)__builtin_bswap16(value)
+
+
+/**
+ \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
+ */
+#define __RBIT __builtin_arm_rbit
+
+/**
+ \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)
+ */
+#define __LDREXB (uint8_t)__builtin_arm_ldrex
+
+
+/**
+ \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)
+ */
+#define __LDREXH (uint16_t)__builtin_arm_ldrex
+
+
+/**
+ \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)
+ */
+#define __LDREXW (uint32_t)__builtin_arm_ldrex
+
+
+/**
+ \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
+ */
+#define __STREXB (uint32_t)__builtin_arm_strex
+
+
+/**
+ \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
+ */
+#define __STREXH (uint32_t)__builtin_arm_strex
+
+
+/**
+ \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
+ */
+#define __STREXW (uint32_t)__builtin_arm_strex
+
+
+/**
+ \brief Remove the exclusive lock
+ \details Removes the exclusive lock which is created by LDREX.
+ */
+#define __CLREX __builtin_arm_clrex
+
+#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] value Value to be saturated
+ \param [in] sat Bit position to saturate to (1..32)
+ \return Saturated value
+ */
+#define __SSAT __builtin_arm_ssat
+
+
+/**
+ \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
+ */
+#define __USAT __builtin_arm_usat
+
+
+/**
+ \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;
+
+ __ASM volatile ("ldrbt %0, %1" : "=r" (result) : "Q" (*ptr) );
+ 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;
+
+ __ASM volatile ("ldrht %0, %1" : "=r" (result) : "Q" (*ptr) );
+ 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)
+ */
+#define __LDAEXB (uint8_t)__builtin_arm_ldaex
+
+
+/**
+ \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)
+ */
+#define __LDAEXH (uint16_t)__builtin_arm_ldaex
+
+
+/**
+ \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)
+ */
+#define __LDAEX (uint32_t)__builtin_arm_ldaex
+
+
+/**
+ \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
+ */
+#define __STLEXB (uint32_t)__builtin_arm_stlex
+
+
+/**
+ \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
+ */
+#define __STLEXH (uint32_t)__builtin_arm_stlex
+
+
+/**
+ \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
+ */
+#define __STLEX (uint32_t)__builtin_arm_stlex
+
+#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 */
+
+
+#endif /* __CMSIS_ARMCLANG_H */
diff --git a/CMSIS/cmsis_compiler.h b/CMSIS/cmsis_compiler.h
new file mode 100644
index 0000000..94212eb
--- /dev/null
+++ b/CMSIS/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 <stdint.h>
+
+/*
+ * 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 <cmsis_iccarm.h>
+
+
+/*
+ * TI Arm Compiler
+ */
+#elif defined ( __TI_ARM__ )
+ #include <cmsis_ccs.h>
+
+ #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 <cmsis_csm.h>
+
+ #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/CMSIS/cmsis_gcc.h b/CMSIS/cmsis_gcc.h
new file mode 100644
index 0000000..5d0f07e
--- /dev/null
+++ b/CMSIS/cmsis_gcc.h
@@ -0,0 +1,2088 @@
+/**************************************************************************//**
+ * @file cmsis_gcc.h
+ * @brief CMSIS compiler GCC header file
+ * @version V5.0.3
+ * @date 16. January 2018
+ ******************************************************************************/
+/*
+ * 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.
+ */
+
+#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)
+{
+ register 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)
+{
+ register 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)
+{
+ register 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)
+{
+ register 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)
+{
+ register 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
+ register 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
+ register 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
+ register 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
+ register 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)) ) */
+
+
+#if ((defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \
+ (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 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) || (__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) || (__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
+}
+
+#endif /* ((defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \
+ (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) */
+
+
+
+/*@} 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/CMSIS/cmsis_iccarm.h b/CMSIS/cmsis_iccarm.h
new file mode 100644
index 0000000..edcaee3
--- /dev/null
+++ b/CMSIS/cmsis_iccarm.h
@@ -0,0 +1,913 @@
+/**************************************************************************//**
+ * @file cmsis_iccarm.h
+ * @brief CMSIS compiler ICCARM (IAR Compiler for Arm) header file
+ * @version V5.0.5
+ * @date 10. January 2018
+ ******************************************************************************/
+
+//------------------------------------------------------------------------------
+//
+// Copyright (c) 2017-2018 IAR Systems
+//
+// 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.
+//
+//------------------------------------------------------------------------------
+
+
+#ifndef __CMSIS_ICCARM_H__
+#define __CMSIS_ICCARM_H__
+
+#ifndef __ICCARM__
+ #error This file should only be compiled by ICCARM
+#endif
+
+#pragma system_include
+
+#define __IAR_FT _Pragma("inline=forced") __intrinsic
+
+#if (__VER__ >= 8000000)
+ #define __ICCARM_V8 1
+#else
+ #define __ICCARM_V8 0
+#endif
+
+#ifndef __ALIGNED
+ #if __ICCARM_V8
+ #define __ALIGNED(x) __attribute__((aligned(x)))
+ #elif (__VER__ >= 7080000)
+ /* Needs IAR language extensions */
+ #define __ALIGNED(x) __attribute__((aligned(x)))
+ #else
+ #warning No compiler specific solution for __ALIGNED.__ALIGNED is ignored.
+ #define __ALIGNED(x)
+ #endif
+#endif
+
+
+/* Define compiler macros for CPU architecture, used in CMSIS 5.
+ */
+#if __ARM_ARCH_6M__ || __ARM_ARCH_7M__ || __ARM_ARCH_7EM__ || __ARM_ARCH_8M_BASE__ || __ARM_ARCH_8M_MAIN__
+/* Macros already defined */
+#else
+ #if defined(__ARM8M_MAINLINE__) || defined(__ARM8EM_MAINLINE__)
+ #define __ARM_ARCH_8M_MAIN__ 1
+ #elif defined(__ARM8M_BASELINE__)
+ #define __ARM_ARCH_8M_BASE__ 1
+ #elif defined(__ARM_ARCH_PROFILE) && __ARM_ARCH_PROFILE == 'M'
+ #if __ARM_ARCH == 6
+ #define __ARM_ARCH_6M__ 1
+ #elif __ARM_ARCH == 7
+ #if __ARM_FEATURE_DSP
+ #define __ARM_ARCH_7EM__ 1
+ #else
+ #define __ARM_ARCH_7M__ 1
+ #endif
+ #endif /* __ARM_ARCH */
+ #endif /* __ARM_ARCH_PROFILE == 'M' */
+#endif
+
+/* Alternativ core deduction for older ICCARM's */
+#if !defined(__ARM_ARCH_6M__) && !defined(__ARM_ARCH_7M__) && !defined(__ARM_ARCH_7EM__) && \
+ !defined(__ARM_ARCH_8M_BASE__) && !defined(__ARM_ARCH_8M_MAIN__)
+ #if defined(__ARM6M__) && (__CORE__ == __ARM6M__)
+ #define __ARM_ARCH_6M__ 1
+ #elif defined(__ARM7M__) && (__CORE__ == __ARM7M__)
+ #define __ARM_ARCH_7M__ 1
+ #elif defined(__ARM7EM__) && (__CORE__ == __ARM7EM__)
+ #define __ARM_ARCH_7EM__ 1
+ #elif defined(__ARM8M_BASELINE__) && (__CORE == __ARM8M_BASELINE__)
+ #define __ARM_ARCH_8M_BASE__ 1
+ #elif defined(__ARM8M_MAINLINE__) && (__CORE == __ARM8M_MAINLINE__)
+ #define __ARM_ARCH_8M_MAIN__ 1
+ #elif defined(__ARM8EM_MAINLINE__) && (__CORE == __ARM8EM_MAINLINE__)
+ #define __ARM_ARCH_8M_MAIN__ 1
+ #else
+ #error "Unknown target."
+ #endif
+#endif
+
+
+
+#if defined(__ARM_ARCH_6M__) && __ARM_ARCH_6M__==1
+ #define __IAR_M0_FAMILY 1
+#elif defined(__ARM_ARCH_8M_BASE__) && __ARM_ARCH_8M_BASE__==1
+ #define __IAR_M0_FAMILY 1
+#else
+ #define __IAR_M0_FAMILY 0
+#endif
+
+
+#ifndef __ASM
+ #define __ASM __asm
+#endif
+
+#ifndef __INLINE
+ #define __INLINE inline
+#endif
+
+#ifndef __NO_RETURN
+ #if __ICCARM_V8
+ #define __NO_RETURN __attribute__((__noreturn__))
+ #else
+ #define __NO_RETURN _Pragma("object_attribute=__noreturn")
+ #endif
+#endif
+
+#ifndef __PACKED
+ #if __ICCARM_V8
+ #define __PACKED __attribute__((packed, aligned(1)))
+ #else
+ /* Needs IAR language extensions */
+ #define __PACKED __packed
+ #endif
+#endif
+
+#ifndef __PACKED_STRUCT
+ #if __ICCARM_V8
+ #define __PACKED_STRUCT struct __attribute__((packed, aligned(1)))
+ #else
+ /* Needs IAR language extensions */
+ #define __PACKED_STRUCT __packed struct
+ #endif
+#endif
+
+#ifndef __PACKED_UNION
+ #if __ICCARM_V8
+ #define __PACKED_UNION union __attribute__((packed, aligned(1)))
+ #else
+ /* Needs IAR language extensions */
+ #define __PACKED_UNION __packed union
+ #endif
+#endif
+
+#ifndef __RESTRICT
+ #define __RESTRICT restrict
+#endif
+
+#ifndef __STATIC_INLINE
+ #define __STATIC_INLINE static inline
+#endif
+
+#ifndef __FORCEINLINE
+ #define __FORCEINLINE _Pragma("inline=forced")
+#endif
+
+#ifndef __STATIC_FORCEINLINE
+ #define __STATIC_FORCEINLINE __FORCEINLINE __STATIC_INLINE
+#endif
+
+#ifndef __UNALIGNED_UINT16_READ
+#pragma language=save
+#pragma language=extended
+__IAR_FT uint16_t __iar_uint16_read(void const *ptr)
+{
+ return *(__packed uint16_t*)(ptr);
+}
+#pragma language=restore
+#define __UNALIGNED_UINT16_READ(PTR) __iar_uint16_read(PTR)
+#endif
+
+
+#ifndef __UNALIGNED_UINT16_WRITE
+#pragma language=save
+#pragma language=extended
+__IAR_FT void __iar_uint16_write(void const *ptr, uint16_t val)
+{
+ *(__packed uint16_t*)(ptr) = val;;
+}
+#pragma language=restore
+#define __UNALIGNED_UINT16_WRITE(PTR,VAL) __iar_uint16_write(PTR,VAL)
+#endif
+
+#ifndef __UNALIGNED_UINT32_READ
+#pragma language=save
+#pragma language=extended
+__IAR_FT uint32_t __iar_uint32_read(void const *ptr)
+{
+ return *(__packed uint32_t*)(ptr);
+}
+#pragma language=restore
+#define __UNALIGNED_UINT32_READ(PTR) __iar_uint32_read(PTR)
+#endif
+
+#ifndef __UNALIGNED_UINT32_WRITE
+#pragma language=save
+#pragma language=extended
+__IAR_FT void __iar_uint32_write(void const *ptr, uint32_t val)
+{
+ *(__packed uint32_t*)(ptr) = val;;
+}
+#pragma language=restore
+#define __UNALIGNED_UINT32_WRITE(PTR,VAL) __iar_uint32_write(PTR,VAL)
+#endif
+
+#ifndef __UNALIGNED_UINT32 /* deprecated */
+#pragma language=save
+#pragma language=extended
+__packed struct __iar_u32 { uint32_t v; };
+#pragma language=restore
+#define __UNALIGNED_UINT32(PTR) (((struct __iar_u32 *)(PTR))->v)
+#endif
+
+#ifndef __USED
+ #if __ICCARM_V8
+ #define __USED __attribute__((used))
+ #else
+ #define __USED _Pragma("__root")
+ #endif
+#endif
+
+#ifndef __WEAK
+ #if __ICCARM_V8
+ #define __WEAK __attribute__((weak))
+ #else
+ #define __WEAK _Pragma("__weak")
+ #endif
+#endif
+
+
+#ifndef __ICCARM_INTRINSICS_VERSION__
+ #define __ICCARM_INTRINSICS_VERSION__ 0
+#endif
+
+#if __ICCARM_INTRINSICS_VERSION__ == 2
+
+ #if defined(__CLZ)
+ #undef __CLZ
+ #endif
+ #if defined(__REVSH)
+ #undef __REVSH
+ #endif
+ #if defined(__RBIT)
+ #undef __RBIT
+ #endif
+ #if defined(__SSAT)
+ #undef __SSAT
+ #endif
+ #if defined(__USAT)
+ #undef __USAT
+ #endif
+
+ #include "iccarm_builtin.h"
+
+ #define __disable_fault_irq __iar_builtin_disable_fiq
+ #define __disable_irq __iar_builtin_disable_interrupt
+ #define __enable_fault_irq __iar_builtin_enable_fiq
+ #define __enable_irq __iar_builtin_enable_interrupt
+ #define __arm_rsr __iar_builtin_rsr
+ #define __arm_wsr __iar_builtin_wsr
+
+
+ #define __get_APSR() (__arm_rsr("APSR"))
+ #define __get_BASEPRI() (__arm_rsr("BASEPRI"))
+ #define __get_CONTROL() (__arm_rsr("CONTROL"))
+ #define __get_FAULTMASK() (__arm_rsr("FAULTMASK"))
+
+ #if ((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \
+ (defined (__FPU_USED ) && (__FPU_USED == 1U)) )
+ #define __get_FPSCR() (__arm_rsr("FPSCR"))
+ #define __set_FPSCR(VALUE) (__arm_wsr("FPSCR", (VALUE)))
+ #else
+ #define __get_FPSCR() ( 0 )
+ #define __set_FPSCR(VALUE) ((void)VALUE)
+ #endif
+
+ #define __get_IPSR() (__arm_rsr("IPSR"))
+ #define __get_MSP() (__arm_rsr("MSP"))
+ #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
+ #define __get_MSPLIM() (0U)
+ #else
+ #define __get_MSPLIM() (__arm_rsr("MSPLIM"))
+ #endif
+ #define __get_PRIMASK() (__arm_rsr("PRIMASK"))
+ #define __get_PSP() (__arm_rsr("PSP"))
+
+ #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
+ #define __get_PSPLIM() (0U)
+ #else
+ #define __get_PSPLIM() (__arm_rsr("PSPLIM"))
+ #endif
+
+ #define __get_xPSR() (__arm_rsr("xPSR"))
+
+ #define __set_BASEPRI(VALUE) (__arm_wsr("BASEPRI", (VALUE)))
+ #define __set_BASEPRI_MAX(VALUE) (__arm_wsr("BASEPRI_MAX", (VALUE)))
+ #define __set_CONTROL(VALUE) (__arm_wsr("CONTROL", (VALUE)))
+ #define __set_FAULTMASK(VALUE) (__arm_wsr("FAULTMASK", (VALUE)))
+ #define __set_MSP(VALUE) (__arm_wsr("MSP", (VALUE)))
+
+ #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
+ #define __set_MSPLIM(VALUE) ((void)(VALUE))
+ #else
+ #define __set_MSPLIM(VALUE) (__arm_wsr("MSPLIM", (VALUE)))
+ #endif
+ #define __set_PRIMASK(VALUE) (__arm_wsr("PRIMASK", (VALUE)))
+ #define __set_PSP(VALUE) (__arm_wsr("PSP", (VALUE)))
+ #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
+ #define __set_PSPLIM(VALUE) ((void)(VALUE))
+ #else
+ #define __set_PSPLIM(VALUE) (__arm_wsr("PSPLIM", (VALUE)))
+ #endif
+
+ #define __TZ_get_CONTROL_NS() (__arm_rsr("CONTROL_NS"))
+ #define __TZ_set_CONTROL_NS(VALUE) (__arm_wsr("CONTROL_NS", (VALUE)))
+ #define __TZ_get_PSP_NS() (__arm_rsr("PSP_NS"))
+ #define __TZ_set_PSP_NS(VALUE) (__arm_wsr("PSP_NS", (VALUE)))
+ #define __TZ_get_MSP_NS() (__arm_rsr("MSP_NS"))
+ #define __TZ_set_MSP_NS(VALUE) (__arm_wsr("MSP_NS", (VALUE)))
+ #define __TZ_get_SP_NS() (__arm_rsr("SP_NS"))
+ #define __TZ_set_SP_NS(VALUE) (__arm_wsr("SP_NS", (VALUE)))
+ #define __TZ_get_PRIMASK_NS() (__arm_rsr("PRIMASK_NS"))
+ #define __TZ_set_PRIMASK_NS(VALUE) (__arm_wsr("PRIMASK_NS", (VALUE)))
+ #define __TZ_get_BASEPRI_NS() (__arm_rsr("BASEPRI_NS"))
+ #define __TZ_set_BASEPRI_NS(VALUE) (__arm_wsr("BASEPRI_NS", (VALUE)))
+ #define __TZ_get_FAULTMASK_NS() (__arm_rsr("FAULTMASK_NS"))
+ #define __TZ_set_FAULTMASK_NS(VALUE)(__arm_wsr("FAULTMASK_NS", (VALUE)))
+ #define __TZ_get_PSPLIM_NS() (__arm_rsr("PSPLIM_NS"))
+ #define __TZ_set_PSPLIM_NS(VALUE) (__arm_wsr("PSPLIM_NS", (VALUE)))
+ #define __TZ_get_MSPLIM_NS() (__arm_rsr("MSPLIM_NS"))
+ #define __TZ_set_MSPLIM_NS(VALUE) (__arm_wsr("MSPLIM_NS", (VALUE)))
+
+ #define __NOP __iar_builtin_no_operation
+
+ #define __CLZ __iar_builtin_CLZ
+ #define __CLREX __iar_builtin_CLREX
+
+ #define __DMB __iar_builtin_DMB
+ #define __DSB __iar_builtin_DSB
+ #define __ISB __iar_builtin_ISB
+
+ #define __LDREXB __iar_builtin_LDREXB
+ #define __LDREXH __iar_builtin_LDREXH
+ #define __LDREXW __iar_builtin_LDREX
+
+ #define __RBIT __iar_builtin_RBIT
+ #define __REV __iar_builtin_REV
+ #define __REV16 __iar_builtin_REV16
+
+ __IAR_FT int16_t __REVSH(int16_t val)
+ {
+ return (int16_t) __iar_builtin_REVSH(val);
+ }
+
+ #define __ROR __iar_builtin_ROR
+ #define __RRX __iar_builtin_RRX
+
+ #define __SEV __iar_builtin_SEV
+
+ #if !__IAR_M0_FAMILY
+ #define __SSAT __iar_builtin_SSAT
+ #endif
+
+ #define __STREXB __iar_builtin_STREXB
+ #define __STREXH __iar_builtin_STREXH
+ #define __STREXW __iar_builtin_STREX
+
+ #if !__IAR_M0_FAMILY
+ #define __USAT __iar_builtin_USAT
+ #endif
+
+ #define __WFE __iar_builtin_WFE
+ #define __WFI __iar_builtin_WFI
+
+ #if __ARM_MEDIA__
+ #define __SADD8 __iar_builtin_SADD8
+ #define __QADD8 __iar_builtin_QADD8
+ #define __SHADD8 __iar_builtin_SHADD8
+ #define __UADD8 __iar_builtin_UADD8
+ #define __UQADD8 __iar_builtin_UQADD8
+ #define __UHADD8 __iar_builtin_UHADD8
+ #define __SSUB8 __iar_builtin_SSUB8
+ #define __QSUB8 __iar_builtin_QSUB8
+ #define __SHSUB8 __iar_builtin_SHSUB8
+ #define __USUB8 __iar_builtin_USUB8
+ #define __UQSUB8 __iar_builtin_UQSUB8
+ #define __UHSUB8 __iar_builtin_UHSUB8
+ #define __SADD16 __iar_builtin_SADD16
+ #define __QADD16 __iar_builtin_QADD16
+ #define __SHADD16 __iar_builtin_SHADD16
+ #define __UADD16 __iar_builtin_UADD16
+ #define __UQADD16 __iar_builtin_UQADD16
+ #define __UHADD16 __iar_builtin_UHADD16
+ #define __SSUB16 __iar_builtin_SSUB16
+ #define __QSUB16 __iar_builtin_QSUB16
+ #define __SHSUB16 __iar_builtin_SHSUB16
+ #define __USUB16 __iar_builtin_USUB16
+ #define __UQSUB16 __iar_builtin_UQSUB16
+ #define __UHSUB16 __iar_builtin_UHSUB16
+ #define __SASX __iar_builtin_SASX
+ #define __QASX __iar_builtin_QASX
+ #define __SHASX __iar_builtin_SHASX
+ #define __UASX __iar_builtin_UASX
+ #define __UQASX __iar_builtin_UQASX
+ #define __UHASX __iar_builtin_UHASX
+ #define __SSAX __iar_builtin_SSAX
+ #define __QSAX __iar_builtin_QSAX
+ #define __SHSAX __iar_builtin_SHSAX
+ #define __USAX __iar_builtin_USAX
+ #define __UQSAX __iar_builtin_UQSAX
+ #define __UHSAX __iar_builtin_UHSAX
+ #define __USAD8 __iar_builtin_USAD8
+ #define __USADA8 __iar_builtin_USADA8
+ #define __SSAT16 __iar_builtin_SSAT16
+ #define __USAT16 __iar_builtin_USAT16
+ #define __UXTB16 __iar_builtin_UXTB16
+ #define __UXTAB16 __iar_builtin_UXTAB16
+ #define __SXTB16 __iar_builtin_SXTB16
+ #define __SXTAB16 __iar_builtin_SXTAB16
+ #define __SMUAD __iar_builtin_SMUAD
+ #define __SMUADX __iar_builtin_SMUADX
+ #define __SMMLA __iar_builtin_SMMLA
+ #define __SMLAD __iar_builtin_SMLAD
+ #define __SMLADX __iar_builtin_SMLADX
+ #define __SMLALD __iar_builtin_SMLALD
+ #define __SMLALDX __iar_builtin_SMLALDX
+ #define __SMUSD __iar_builtin_SMUSD
+ #define __SMUSDX __iar_builtin_SMUSDX
+ #define __SMLSD __iar_builtin_SMLSD
+ #define __SMLSDX __iar_builtin_SMLSDX
+ #define __SMLSLD __iar_builtin_SMLSLD
+ #define __SMLSLDX __iar_builtin_SMLSLDX
+ #define __SEL __iar_builtin_SEL
+ #define __QADD __iar_builtin_QADD
+ #define __QSUB __iar_builtin_QSUB
+ #define __PKHBT __iar_builtin_PKHBT
+ #define __PKHTB __iar_builtin_PKHTB
+ #endif
+
+#else /* __ICCARM_INTRINSICS_VERSION__ == 2 */
+
+ #if __IAR_M0_FAMILY
+ /* Avoid clash between intrinsics.h and arm_math.h when compiling for Cortex-M0. */
+ #define __CLZ __cmsis_iar_clz_not_active
+ #define __SSAT __cmsis_iar_ssat_not_active
+ #define __USAT __cmsis_iar_usat_not_active
+ #define __RBIT __cmsis_iar_rbit_not_active
+ #define __get_APSR __cmsis_iar_get_APSR_not_active
+ #endif
+
+
+ #if (!((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \
+ (defined (__FPU_USED ) && (__FPU_USED == 1U)) ))
+ #define __get_FPSCR __cmsis_iar_get_FPSR_not_active
+ #define __set_FPSCR __cmsis_iar_set_FPSR_not_active
+ #endif
+
+ #ifdef __INTRINSICS_INCLUDED
+ #error intrinsics.h is already included previously!
+ #endif
+
+ #include <intrinsics.h>
+
+ #if __IAR_M0_FAMILY
+ /* Avoid clash between intrinsics.h and arm_math.h when compiling for Cortex-M0. */
+ #undef __CLZ
+ #undef __SSAT
+ #undef __USAT
+ #undef __RBIT
+ #undef __get_APSR
+
+ __STATIC_INLINE uint8_t __CLZ(uint32_t data)
+ {
+ if (data == 0U) { return 32U; }
+
+ uint32_t count = 0U;
+ uint32_t mask = 0x80000000U;
+
+ while ((data & mask) == 0U)
+ {
+ count += 1U;
+ mask = mask >> 1U;
+ }
+ return count;
+ }
+
+ __STATIC_INLINE uint32_t __RBIT(uint32_t v)
+ {
+ uint8_t sc = 31U;
+ uint32_t r = v;
+ for (v >>= 1U; v; v >>= 1U)
+ {
+ r <<= 1U;
+ r |= v & 1U;
+ sc--;
+ }
+ return (r << sc);
+ }
+
+ __STATIC_INLINE uint32_t __get_APSR(void)
+ {
+ uint32_t res;
+ __asm("MRS %0,APSR" : "=r" (res));
+ return res;
+ }
+
+ #endif
+
+ #if (!((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \
+ (defined (__FPU_USED ) && (__FPU_USED == 1U)) ))
+ #undef __get_FPSCR
+ #undef __set_FPSCR
+ #define __get_FPSCR() (0)
+ #define __set_FPSCR(VALUE) ((void)VALUE)
+ #endif
+
+ #pragma diag_suppress=Pe940
+ #pragma diag_suppress=Pe177
+
+ #define __enable_irq __enable_interrupt
+ #define __disable_irq __disable_interrupt
+ #define __NOP __no_operation
+
+ #define __get_xPSR __get_PSR
+
+ #if (!defined(__ARM_ARCH_6M__) || __ARM_ARCH_6M__==0)
+
+ __IAR_FT uint32_t __LDREXW(uint32_t volatile *ptr)
+ {
+ return __LDREX((unsigned long *)ptr);
+ }
+
+ __IAR_FT uint32_t __STREXW(uint32_t value, uint32_t volatile *ptr)
+ {
+ return __STREX(value, (unsigned long *)ptr);
+ }
+ #endif
+
+
+ /* __CORTEX_M is defined in core_cm0.h, core_cm3.h and core_cm4.h. */
+ #if (__CORTEX_M >= 0x03)
+
+ __IAR_FT uint32_t __RRX(uint32_t value)
+ {
+ uint32_t result;
+ __ASM("RRX %0, %1" : "=r"(result) : "r" (value) : "cc");
+ return(result);
+ }
+
+ __IAR_FT void __set_BASEPRI_MAX(uint32_t value)
+ {
+ __asm volatile("MSR BASEPRI_MAX,%0"::"r" (value));
+ }
+
+
+ #define __enable_fault_irq __enable_fiq
+ #define __disable_fault_irq __disable_fiq
+
+
+ #endif /* (__CORTEX_M >= 0x03) */
+
+ __IAR_FT uint32_t __ROR(uint32_t op1, uint32_t op2)
+ {
+ return (op1 >> op2) | (op1 << ((sizeof(op1)*8)-op2));
+ }
+
+ #if ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \
+ (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) )
+
+ __IAR_FT uint32_t __get_MSPLIM(void)
+ {
+ uint32_t res;
+ #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
+ res = 0U;
+ #else
+ __asm volatile("MRS %0,MSPLIM" : "=r" (res));
+ #endif
+ return res;
+ }
+
+ __IAR_FT void __set_MSPLIM(uint32_t value)
+ {
+ #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)value;
+ #else
+ __asm volatile("MSR MSPLIM,%0" :: "r" (value));
+ #endif
+ }
+
+ __IAR_FT uint32_t __get_PSPLIM(void)
+ {
+ uint32_t res;
+ #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
+ res = 0U;
+ #else
+ __asm volatile("MRS %0,PSPLIM" : "=r" (res));
+ #endif
+ return res;
+ }
+
+ __IAR_FT void __set_PSPLIM(uint32_t value)
+ {
+ #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)value;
+ #else
+ __asm volatile("MSR PSPLIM,%0" :: "r" (value));
+ #endif
+ }
+
+ __IAR_FT uint32_t __TZ_get_CONTROL_NS(void)
+ {
+ uint32_t res;
+ __asm volatile("MRS %0,CONTROL_NS" : "=r" (res));
+ return res;
+ }
+
+ __IAR_FT void __TZ_set_CONTROL_NS(uint32_t value)
+ {
+ __asm volatile("MSR CONTROL_NS,%0" :: "r" (value));
+ }
+
+ __IAR_FT uint32_t __TZ_get_PSP_NS(void)
+ {
+ uint32_t res;
+ __asm volatile("MRS %0,PSP_NS" : "=r" (res));
+ return res;
+ }
+
+ __IAR_FT void __TZ_set_PSP_NS(uint32_t value)
+ {
+ __asm volatile("MSR PSP_NS,%0" :: "r" (value));
+ }
+
+ __IAR_FT uint32_t __TZ_get_MSP_NS(void)
+ {
+ uint32_t res;
+ __asm volatile("MRS %0,MSP_NS" : "=r" (res));
+ return res;
+ }
+
+ __IAR_FT void __TZ_set_MSP_NS(uint32_t value)
+ {
+ __asm volatile("MSR MSP_NS,%0" :: "r" (value));
+ }
+
+ __IAR_FT uint32_t __TZ_get_SP_NS(void)
+ {
+ uint32_t res;
+ __asm volatile("MRS %0,SP_NS" : "=r" (res));
+ return res;
+ }
+ __IAR_FT void __TZ_set_SP_NS(uint32_t value)
+ {
+ __asm volatile("MSR SP_NS,%0" :: "r" (value));
+ }
+
+ __IAR_FT uint32_t __TZ_get_PRIMASK_NS(void)
+ {
+ uint32_t res;
+ __asm volatile("MRS %0,PRIMASK_NS" : "=r" (res));
+ return res;
+ }
+
+ __IAR_FT void __TZ_set_PRIMASK_NS(uint32_t value)
+ {
+ __asm volatile("MSR PRIMASK_NS,%0" :: "r" (value));
+ }
+
+ __IAR_FT uint32_t __TZ_get_BASEPRI_NS(void)
+ {
+ uint32_t res;
+ __asm volatile("MRS %0,BASEPRI_NS" : "=r" (res));
+ return res;
+ }
+
+ __IAR_FT void __TZ_set_BASEPRI_NS(uint32_t value)
+ {
+ __asm volatile("MSR BASEPRI_NS,%0" :: "r" (value));
+ }
+
+ __IAR_FT uint32_t __TZ_get_FAULTMASK_NS(void)
+ {
+ uint32_t res;
+ __asm volatile("MRS %0,FAULTMASK_NS" : "=r" (res));
+ return res;
+ }
+
+ __IAR_FT void __TZ_set_FAULTMASK_NS(uint32_t value)
+ {
+ __asm volatile("MSR FAULTMASK_NS,%0" :: "r" (value));
+ }
+
+ __IAR_FT uint32_t __TZ_get_PSPLIM_NS(void)
+ {
+ uint32_t res;
+ __asm volatile("MRS %0,PSPLIM_NS" : "=r" (res));
+ return res;
+ }
+ __IAR_FT void __TZ_set_PSPLIM_NS(uint32_t value)
+ {
+ __asm volatile("MSR PSPLIM_NS,%0" :: "r" (value));
+ }
+
+ __IAR_FT uint32_t __TZ_get_MSPLIM_NS(void)
+ {
+ uint32_t res;
+ __asm volatile("MRS %0,MSPLIM_NS" : "=r" (res));
+ return res;
+ }
+
+ __IAR_FT void __TZ_set_MSPLIM_NS(uint32_t value)
+ {
+ __asm volatile("MSR MSPLIM_NS,%0" :: "r" (value));
+ }
+
+ #endif /* __ARM_ARCH_8M_MAIN__ or __ARM_ARCH_8M_BASE__ */
+
+#endif /* __ICCARM_INTRINSICS_VERSION__ == 2 */
+
+#define __BKPT(value) __asm volatile ("BKPT %0" : : "i"(value))
+
+#if __IAR_M0_FAMILY
+ __STATIC_INLINE 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;
+ }
+
+ __STATIC_INLINE 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
+
+#if (__CORTEX_M >= 0x03) /* __CORTEX_M is defined in core_cm0.h, core_cm3.h and core_cm4.h. */
+
+ __IAR_FT uint8_t __LDRBT(volatile uint8_t *addr)
+ {
+ uint32_t res;
+ __ASM("LDRBT %0, [%1]" : "=r" (res) : "r" (addr) : "memory");
+ return ((uint8_t)res);
+ }
+
+ __IAR_FT uint16_t __LDRHT(volatile uint16_t *addr)
+ {
+ uint32_t res;
+ __ASM("LDRHT %0, [%1]" : "=r" (res) : "r" (addr) : "memory");
+ return ((uint16_t)res);
+ }
+
+ __IAR_FT uint32_t __LDRT(volatile uint32_t *addr)
+ {
+ uint32_t res;
+ __ASM("LDRT %0, [%1]" : "=r" (res) : "r" (addr) : "memory");
+ return res;
+ }
+
+ __IAR_FT void __STRBT(uint8_t value, volatile uint8_t *addr)
+ {
+ __ASM("STRBT %1, [%0]" : : "r" (addr), "r" ((uint32_t)value) : "memory");
+ }
+
+ __IAR_FT void __STRHT(uint16_t value, volatile uint16_t *addr)
+ {
+ __ASM("STRHT %1, [%0]" : : "r" (addr), "r" ((uint32_t)value) : "memory");
+ }
+
+ __IAR_FT void __STRT(uint32_t value, volatile uint32_t *addr)
+ {
+ __ASM("STRT %1, [%0]" : : "r" (addr), "r" (value) : "memory");
+ }
+
+#endif /* (__CORTEX_M >= 0x03) */
+
+#if ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \
+ (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) )
+
+
+ __IAR_FT uint8_t __LDAB(volatile uint8_t *ptr)
+ {
+ uint32_t res;
+ __ASM volatile ("LDAB %0, [%1]" : "=r" (res) : "r" (*ptr) : "memory");
+ return ((uint8_t)res);
+ }
+
+ __IAR_FT uint16_t __LDAH(volatile uint16_t *ptr)
+ {
+ uint32_t res;
+ __ASM volatile ("LDAH %0, [%1]" : "=r" (res) : "r" (*ptr) : "memory");
+ return ((uint16_t)res);
+ }
+
+ __IAR_FT uint32_t __LDA(volatile uint32_t *ptr)
+ {
+ uint32_t res;
+ __ASM volatile ("LDA %0, [%1]" : "=r" (res) : "r" (*ptr) : "memory");
+ return res;
+ }
+
+ __IAR_FT void __STLB(uint8_t value, volatile uint8_t *ptr)
+ {
+ __ASM volatile ("STLB %1, [%0]" :: "r" (*ptr), "r" (value) : "memory");
+ }
+
+ __IAR_FT void __STLH(uint16_t value, volatile uint16_t *ptr)
+ {
+ __ASM volatile ("STLH %1, [%0]" :: "r" (*ptr), "r" (value) : "memory");
+ }
+
+ __IAR_FT void __STL(uint32_t value, volatile uint32_t *ptr)
+ {
+ __ASM volatile ("STL %1, [%0]" :: "r" (*ptr), "r" (value) : "memory");
+ }
+
+ __IAR_FT uint8_t __LDAEXB(volatile uint8_t *ptr)
+ {
+ uint32_t res;
+ __ASM volatile ("LDAEXB %0, [%1]" : "=r" (res) : "r" (*ptr) : "memory");
+ return ((uint8_t)res);
+ }
+
+ __IAR_FT uint16_t __LDAEXH(volatile uint16_t *ptr)
+ {
+ uint32_t res;
+ __ASM volatile ("LDAEXH %0, [%1]" : "=r" (res) : "r" (*ptr) : "memory");
+ return ((uint16_t)res);
+ }
+
+ __IAR_FT uint32_t __LDAEX(volatile uint32_t *ptr)
+ {
+ uint32_t res;
+ __ASM volatile ("LDAEX %0, [%1]" : "=r" (res) : "r" (*ptr) : "memory");
+ return res;
+ }
+
+ __IAR_FT uint32_t __STLEXB(uint8_t value, volatile uint8_t *ptr)
+ {
+ uint32_t res;
+ __ASM volatile ("STLEXB %0, %2, [%1]" : "=r" (res) : "r" (*ptr), "r" (value) : "memory");
+ return res;
+ }
+
+ __IAR_FT uint32_t __STLEXH(uint16_t value, volatile uint16_t *ptr)
+ {
+ uint32_t res;
+ __ASM volatile ("STLEXH %0, %2, [%1]" : "=r" (res) : "r" (*ptr), "r" (value) : "memory");
+ return res;
+ }
+
+ __IAR_FT uint32_t __STLEX(uint32_t value, volatile uint32_t *ptr)
+ {
+ uint32_t res;
+ __ASM volatile ("STLEX %0, %2, [%1]" : "=r" (res) : "r" (*ptr), "r" (value) : "memory");
+ return res;
+ }
+
+#endif /* __ARM_ARCH_8M_MAIN__ or __ARM_ARCH_8M_BASE__ */
+
+#undef __IAR_FT
+#undef __IAR_M0_FAMILY
+#undef __ICCARM_V8
+
+#pragma diag_default=Pe940
+#pragma diag_default=Pe177
+
+#endif /* __CMSIS_ICCARM_H__ */
diff --git a/CMSIS/cmsis_version.h b/CMSIS/cmsis_version.h
new file mode 100644
index 0000000..660f612
--- /dev/null
+++ b/CMSIS/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/CMSIS/core_armv8mbl.h b/CMSIS/core_armv8mbl.h
new file mode 100644
index 0000000..47a3989
--- /dev/null
+++ b/CMSIS/core_armv8mbl.h
@@ -0,0 +1,1896 @@
+/**************************************************************************//**
+ * @file core_armv8mbl.h
+ * @brief CMSIS Armv8-M Baseline Core Peripheral Access Layer 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.
+ */
+
+#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_ARMV8MBL_H_GENERIC
+#define __CORE_ARMV8MBL_H_GENERIC
+
+#include <stdint.h>
+
+#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.<br>
+ Function definitions in header files are used to allow 'inlining'.
+
+ \li Required Rule 18.4, declaration of union type or object of union type: '{...}'.<br>
+ Unions are used for effective representation of core registers.
+
+ \li Advisory Rule 19.7, Function-like macro defined.<br>
+ Function-like macros are used to allow more efficient code.
+ */
+
+
+/*******************************************************************************
+ * CMSIS definitions
+ ******************************************************************************/
+/**
+ \ingroup Cortex_ARMv8MBL
+ @{
+ */
+
+#include "cmsis_version.h"
+
+/* CMSIS definitions */
+#define __ARMv8MBL_CMSIS_VERSION_MAIN (__CM_CMSIS_VERSION_MAIN) /*!< \deprecated [31:16] CMSIS HAL main version */
+#define __ARMv8MBL_CMSIS_VERSION_SUB (__CM_CMSIS_VERSION_SUB) /*!< \deprecated [15:0] CMSIS HAL sub version */
+#define __ARMv8MBL_CMSIS_VERSION ((__ARMv8MBL_CMSIS_VERSION_MAIN << 16U) | \
+ __ARMv8MBL_CMSIS_VERSION_SUB ) /*!< \deprecated CMSIS HAL version number */
+
+#define __CORTEX_M ( 2U) /*!< 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_ARMV8MBL_H_GENERIC */
+
+#ifndef __CMSIS_GENERIC
+
+#ifndef __CORE_ARMV8MBL_H_DEPENDANT
+#define __CORE_ARMV8MBL_H_DEPENDANT
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* check device defines and use defaults */
+#if defined __CHECK_DEVICE_DEFINES
+ #ifndef __ARMv8MBL_REV
+ #define __ARMv8MBL_REV 0x0000U
+ #warning "__ARMv8MBL_REV not defined in device header file; using default!"
+ #endif
+
+ #ifndef __FPU_PRESENT
+ #define __FPU_PRESENT 0U
+ #warning "__FPU_PRESENT not defined in device header file; using default!"
+ #endif
+
+ #ifndef __MPU_PRESENT
+ #define __MPU_PRESENT 0U
+ #warning "__MPU_PRESENT not defined in device header file; using default!"
+ #endif
+
+ #ifndef __SAUREGION_PRESENT
+ #define __SAUREGION_PRESENT 0U
+ #warning "__SAUREGION_PRESENT not defined in device header file; using default!"
+ #endif
+
+ #ifndef __VTOR_PRESENT
+ #define __VTOR_PRESENT 0U
+ #warning "__VTOR_PRESENT 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
+
+ #ifndef __ETM_PRESENT
+ #define __ETM_PRESENT 0U
+ #warning "__ETM_PRESENT not defined in device header file; using default!"
+ #endif
+
+ #ifndef __MTB_PRESENT
+ #define __MTB_PRESENT 0U
+ #warning "__MTB_PRESENT not defined in device header file; using default!"
+ #endif
+
+#endif
+
+/* IO definitions (access restrictions to peripheral registers) */
+/**
+ \defgroup CMSIS_glob_defs CMSIS Global Defines
+
+ <strong>IO Type Qualifiers</strong> 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 ARMv8MBL */
+
+
+
+/*******************************************************************************
+ * Register Abstraction
+ Core Register contain:
+ - Core Register
+ - Core NVIC Register
+ - Core SCB Register
+ - Core SysTick Register
+ - Core Debug Register
+ - Core MPU Register
+ - Core SAU 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 nPRIV:1; /*!< bit: 0 Execution privilege in Thread mode */
+ uint32_t SPSEL:1; /*!< bit: 1 Stack-pointer select */
+ 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 */
+
+#define CONTROL_nPRIV_Pos 0U /*!< CONTROL: nPRIV Position */
+#define CONTROL_nPRIV_Msk (1UL /*<< CONTROL_nPRIV_Pos*/) /*!< CONTROL: nPRIV 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[16U]; /*!< Offset: 0x000 (R/W) Interrupt Set Enable Register */
+ uint32_t RESERVED0[16U];
+ __IOM uint32_t ICER[16U]; /*!< Offset: 0x080 (R/W) Interrupt Clear Enable Register */
+ uint32_t RSERVED1[16U];
+ __IOM uint32_t ISPR[16U]; /*!< Offset: 0x100 (R/W) Interrupt Set Pending Register */
+ uint32_t RESERVED2[16U];
+ __IOM uint32_t ICPR[16U]; /*!< Offset: 0x180 (R/W) Interrupt Clear Pending Register */
+ uint32_t RESERVED3[16U];
+ __IOM uint32_t IABR[16U]; /*!< Offset: 0x200 (R/W) Interrupt Active bit Register */
+ uint32_t RESERVED4[16U];
+ __IOM uint32_t ITNS[16U]; /*!< Offset: 0x280 (R/W) Interrupt Non-Secure State Register */
+ uint32_t RESERVED5[16U];
+ __IOM uint32_t IPR[124U]; /*!< 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 */
+#if defined (__VTOR_PRESENT) && (__VTOR_PRESENT == 1U)
+ __IOM uint32_t VTOR; /*!< Offset: 0x008 (R/W) Vector Table Offset Register */
+#else
+ uint32_t RESERVED0;
+#endif
+ __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 SHPR[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_PENDNMISET_Pos 31U /*!< SCB ICSR: PENDNMISET Position */
+#define SCB_ICSR_PENDNMISET_Msk (1UL << SCB_ICSR_PENDNMISET_Pos) /*!< SCB ICSR: PENDNMISET Mask */
+
+#define SCB_ICSR_PENDNMICLR_Pos 30U /*!< SCB ICSR: PENDNMICLR Position */
+#define SCB_ICSR_PENDNMICLR_Msk (1UL << SCB_ICSR_PENDNMICLR_Pos) /*!< SCB ICSR: PENDNMICLR 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_STTNS_Pos 24U /*!< SCB ICSR: STTNS Position (Security Extension) */
+#define SCB_ICSR_STTNS_Msk (1UL << SCB_ICSR_STTNS_Pos) /*!< SCB ICSR: STTNS Mask (Security Extension) */
+
+#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_RETTOBASE_Pos 11U /*!< SCB ICSR: RETTOBASE Position */
+#define SCB_ICSR_RETTOBASE_Msk (1UL << SCB_ICSR_RETTOBASE_Pos) /*!< SCB ICSR: RETTOBASE 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 */
+
+#if defined (__VTOR_PRESENT) && (__VTOR_PRESENT == 1U)
+/* SCB Vector Table Offset Register Definitions */
+#define SCB_VTOR_TBLOFF_Pos 7U /*!< SCB VTOR: TBLOFF Position */
+#define SCB_VTOR_TBLOFF_Msk (0x1FFFFFFUL << SCB_VTOR_TBLOFF_Pos) /*!< SCB VTOR: TBLOFF Mask */
+#endif
+
+/* 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_PRIS_Pos 14U /*!< SCB AIRCR: PRIS Position */
+#define SCB_AIRCR_PRIS_Msk (1UL << SCB_AIRCR_PRIS_Pos) /*!< SCB AIRCR: PRIS Mask */
+
+#define SCB_AIRCR_BFHFNMINS_Pos 13U /*!< SCB AIRCR: BFHFNMINS Position */
+#define SCB_AIRCR_BFHFNMINS_Msk (1UL << SCB_AIRCR_BFHFNMINS_Pos) /*!< SCB AIRCR: BFHFNMINS Mask */
+
+#define SCB_AIRCR_SYSRESETREQS_Pos 3U /*!< SCB AIRCR: SYSRESETREQS Position */
+#define SCB_AIRCR_SYSRESETREQS_Msk (1UL << SCB_AIRCR_SYSRESETREQS_Pos) /*!< SCB AIRCR: SYSRESETREQS 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_SLEEPDEEPS_Pos 3U /*!< SCB SCR: SLEEPDEEPS Position */
+#define SCB_SCR_SLEEPDEEPS_Msk (1UL << SCB_SCR_SLEEPDEEPS_Pos) /*!< SCB SCR: SLEEPDEEPS 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_BP_Pos 18U /*!< SCB CCR: BP Position */
+#define SCB_CCR_BP_Msk (1UL << SCB_CCR_BP_Pos) /*!< SCB CCR: BP Mask */
+
+#define SCB_CCR_IC_Pos 17U /*!< SCB CCR: IC Position */
+#define SCB_CCR_IC_Msk (1UL << SCB_CCR_IC_Pos) /*!< SCB CCR: IC Mask */
+
+#define SCB_CCR_DC_Pos 16U /*!< SCB CCR: DC Position */
+#define SCB_CCR_DC_Msk (1UL << SCB_CCR_DC_Pos) /*!< SCB CCR: DC Mask */
+
+#define SCB_CCR_STKOFHFNMIGN_Pos 10U /*!< SCB CCR: STKOFHFNMIGN Position */
+#define SCB_CCR_STKOFHFNMIGN_Msk (1UL << SCB_CCR_STKOFHFNMIGN_Pos) /*!< SCB CCR: STKOFHFNMIGN Mask */
+
+#define SCB_CCR_BFHFNMIGN_Pos 8U /*!< SCB CCR: BFHFNMIGN Position */
+#define SCB_CCR_BFHFNMIGN_Msk (1UL << SCB_CCR_BFHFNMIGN_Pos) /*!< SCB CCR: BFHFNMIGN Mask */
+
+#define SCB_CCR_DIV_0_TRP_Pos 4U /*!< SCB CCR: DIV_0_TRP Position */
+#define SCB_CCR_DIV_0_TRP_Msk (1UL << SCB_CCR_DIV_0_TRP_Pos) /*!< SCB CCR: DIV_0_TRP 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 */
+
+#define SCB_CCR_USERSETMPEND_Pos 1U /*!< SCB CCR: USERSETMPEND Position */
+#define SCB_CCR_USERSETMPEND_Msk (1UL << SCB_CCR_USERSETMPEND_Pos) /*!< SCB CCR: USERSETMPEND Mask */
+
+/* SCB System Handler Control and State Register Definitions */
+#define SCB_SHCSR_HARDFAULTPENDED_Pos 21U /*!< SCB SHCSR: HARDFAULTPENDED Position */
+#define SCB_SHCSR_HARDFAULTPENDED_Msk (1UL << SCB_SHCSR_HARDFAULTPENDED_Pos) /*!< SCB SHCSR: HARDFAULTPENDED Mask */
+
+#define SCB_SHCSR_SVCALLPENDED_Pos 15U /*!< SCB SHCSR: SVCALLPENDED Position */
+#define SCB_SHCSR_SVCALLPENDED_Msk (1UL << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SHCSR: SVCALLPENDED Mask */
+
+#define SCB_SHCSR_SYSTICKACT_Pos 11U /*!< SCB SHCSR: SYSTICKACT Position */
+#define SCB_SHCSR_SYSTICKACT_Msk (1UL << SCB_SHCSR_SYSTICKACT_Pos) /*!< SCB SHCSR: SYSTICKACT Mask */
+
+#define SCB_SHCSR_PENDSVACT_Pos 10U /*!< SCB SHCSR: PENDSVACT Position */
+#define SCB_SHCSR_PENDSVACT_Msk (1UL << SCB_SHCSR_PENDSVACT_Pos) /*!< SCB SHCSR: PENDSVACT Mask */
+
+#define SCB_SHCSR_SVCALLACT_Pos 7U /*!< SCB SHCSR: SVCALLACT Position */
+#define SCB_SHCSR_SVCALLACT_Msk (1UL << SCB_SHCSR_SVCALLACT_Pos) /*!< SCB SHCSR: SVCALLACT Mask */
+
+#define SCB_SHCSR_NMIACT_Pos 5U /*!< SCB SHCSR: NMIACT Position */
+#define SCB_SHCSR_NMIACT_Msk (1UL << SCB_SHCSR_NMIACT_Pos) /*!< SCB SHCSR: NMIACT Mask */
+
+#define SCB_SHCSR_HARDFAULTACT_Pos 2U /*!< SCB SHCSR: HARDFAULTACT Position */
+#define SCB_SHCSR_HARDFAULTACT_Msk (1UL << SCB_SHCSR_HARDFAULTACT_Pos) /*!< SCB SHCSR: HARDFAULTACT 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_DWT Data Watchpoint and Trace (DWT)
+ \brief Type definitions for the Data Watchpoint and Trace (DWT)
+ @{
+ */
+
+/**
+ \brief Structure type to access the Data Watchpoint and Trace Register (DWT).
+ */
+typedef struct
+{
+ __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) Control Register */
+ uint32_t RESERVED0[6U];
+ __IM uint32_t PCSR; /*!< Offset: 0x01C (R/ ) Program Counter Sample Register */
+ __IOM uint32_t COMP0; /*!< Offset: 0x020 (R/W) Comparator Register 0 */
+ uint32_t RESERVED1[1U];
+ __IOM uint32_t FUNCTION0; /*!< Offset: 0x028 (R/W) Function Register 0 */
+ uint32_t RESERVED2[1U];
+ __IOM uint32_t COMP1; /*!< Offset: 0x030 (R/W) Comparator Register 1 */
+ uint32_t RESERVED3[1U];
+ __IOM uint32_t FUNCTION1; /*!< Offset: 0x038 (R/W) Function Register 1 */
+ uint32_t RESERVED4[1U];
+ __IOM uint32_t COMP2; /*!< Offset: 0x040 (R/W) Comparator Register 2 */
+ uint32_t RESERVED5[1U];
+ __IOM uint32_t FUNCTION2; /*!< Offset: 0x048 (R/W) Function Register 2 */
+ uint32_t RESERVED6[1U];
+ __IOM uint32_t COMP3; /*!< Offset: 0x050 (R/W) Comparator Register 3 */
+ uint32_t RESERVED7[1U];
+ __IOM uint32_t FUNCTION3; /*!< Offset: 0x058 (R/W) Function Register 3 */
+ uint32_t RESERVED8[1U];
+ __IOM uint32_t COMP4; /*!< Offset: 0x060 (R/W) Comparator Register 4 */
+ uint32_t RESERVED9[1U];
+ __IOM uint32_t FUNCTION4; /*!< Offset: 0x068 (R/W) Function Register 4 */
+ uint32_t RESERVED10[1U];
+ __IOM uint32_t COMP5; /*!< Offset: 0x070 (R/W) Comparator Register 5 */
+ uint32_t RESERVED11[1U];
+ __IOM uint32_t FUNCTION5; /*!< Offset: 0x078 (R/W) Function Register 5 */
+ uint32_t RESERVED12[1U];
+ __IOM uint32_t COMP6; /*!< Offset: 0x080 (R/W) Comparator Register 6 */
+ uint32_t RESERVED13[1U];
+ __IOM uint32_t FUNCTION6; /*!< Offset: 0x088 (R/W) Function Register 6 */
+ uint32_t RESERVED14[1U];
+ __IOM uint32_t COMP7; /*!< Offset: 0x090 (R/W) Comparator Register 7 */
+ uint32_t RESERVED15[1U];
+ __IOM uint32_t FUNCTION7; /*!< Offset: 0x098 (R/W) Function Register 7 */
+ uint32_t RESERVED16[1U];
+ __IOM uint32_t COMP8; /*!< Offset: 0x0A0 (R/W) Comparator Register 8 */
+ uint32_t RESERVED17[1U];
+ __IOM uint32_t FUNCTION8; /*!< Offset: 0x0A8 (R/W) Function Register 8 */
+ uint32_t RESERVED18[1U];
+ __IOM uint32_t COMP9; /*!< Offset: 0x0B0 (R/W) Comparator Register 9 */
+ uint32_t RESERVED19[1U];
+ __IOM uint32_t FUNCTION9; /*!< Offset: 0x0B8 (R/W) Function Register 9 */
+ uint32_t RESERVED20[1U];
+ __IOM uint32_t COMP10; /*!< Offset: 0x0C0 (R/W) Comparator Register 10 */
+ uint32_t RESERVED21[1U];
+ __IOM uint32_t FUNCTION10; /*!< Offset: 0x0C8 (R/W) Function Register 10 */
+ uint32_t RESERVED22[1U];
+ __IOM uint32_t COMP11; /*!< Offset: 0x0D0 (R/W) Comparator Register 11 */
+ uint32_t RESERVED23[1U];
+ __IOM uint32_t FUNCTION11; /*!< Offset: 0x0D8 (R/W) Function Register 11 */
+ uint32_t RESERVED24[1U];
+ __IOM uint32_t COMP12; /*!< Offset: 0x0E0 (R/W) Comparator Register 12 */
+ uint32_t RESERVED25[1U];
+ __IOM uint32_t FUNCTION12; /*!< Offset: 0x0E8 (R/W) Function Register 12 */
+ uint32_t RESERVED26[1U];
+ __IOM uint32_t COMP13; /*!< Offset: 0x0F0 (R/W) Comparator Register 13 */
+ uint32_t RESERVED27[1U];
+ __IOM uint32_t FUNCTION13; /*!< Offset: 0x0F8 (R/W) Function Register 13 */
+ uint32_t RESERVED28[1U];
+ __IOM uint32_t COMP14; /*!< Offset: 0x100 (R/W) Comparator Register 14 */
+ uint32_t RESERVED29[1U];
+ __IOM uint32_t FUNCTION14; /*!< Offset: 0x108 (R/W) Function Register 14 */
+ uint32_t RESERVED30[1U];
+ __IOM uint32_t COMP15; /*!< Offset: 0x110 (R/W) Comparator Register 15 */
+ uint32_t RESERVED31[1U];
+ __IOM uint32_t FUNCTION15; /*!< Offset: 0x118 (R/W) Function Register 15 */
+} DWT_Type;
+
+/* DWT Control Register Definitions */
+#define DWT_CTRL_NUMCOMP_Pos 28U /*!< DWT CTRL: NUMCOMP Position */
+#define DWT_CTRL_NUMCOMP_Msk (0xFUL << DWT_CTRL_NUMCOMP_Pos) /*!< DWT CTRL: NUMCOMP Mask */
+
+#define DWT_CTRL_NOTRCPKT_Pos 27U /*!< DWT CTRL: NOTRCPKT Position */
+#define DWT_CTRL_NOTRCPKT_Msk (0x1UL << DWT_CTRL_NOTRCPKT_Pos) /*!< DWT CTRL: NOTRCPKT Mask */
+
+#define DWT_CTRL_NOEXTTRIG_Pos 26U /*!< DWT CTRL: NOEXTTRIG Position */
+#define DWT_CTRL_NOEXTTRIG_Msk (0x1UL << DWT_CTRL_NOEXTTRIG_Pos) /*!< DWT CTRL: NOEXTTRIG Mask */
+
+#define DWT_CTRL_NOCYCCNT_Pos 25U /*!< DWT CTRL: NOCYCCNT Position */
+#define DWT_CTRL_NOCYCCNT_Msk (0x1UL << DWT_CTRL_NOCYCCNT_Pos) /*!< DWT CTRL: NOCYCCNT Mask */
+
+#define DWT_CTRL_NOPRFCNT_Pos 24U /*!< DWT CTRL: NOPRFCNT Position */
+#define DWT_CTRL_NOPRFCNT_Msk (0x1UL << DWT_CTRL_NOPRFCNT_Pos) /*!< DWT CTRL: NOPRFCNT Mask */
+
+/* DWT Comparator Function Register Definitions */
+#define DWT_FUNCTION_ID_Pos 27U /*!< DWT FUNCTION: ID Position */
+#define DWT_FUNCTION_ID_Msk (0x1FUL << DWT_FUNCTION_ID_Pos) /*!< DWT FUNCTION: ID Mask */
+
+#define DWT_FUNCTION_MATCHED_Pos 24U /*!< DWT FUNCTION: MATCHED Position */
+#define DWT_FUNCTION_MATCHED_Msk (0x1UL << DWT_FUNCTION_MATCHED_Pos) /*!< DWT FUNCTION: MATCHED Mask */
+
+#define DWT_FUNCTION_DATAVSIZE_Pos 10U /*!< DWT FUNCTION: DATAVSIZE Position */
+#define DWT_FUNCTION_DATAVSIZE_Msk (0x3UL << DWT_FUNCTION_DATAVSIZE_Pos) /*!< DWT FUNCTION: DATAVSIZE Mask */
+
+#define DWT_FUNCTION_ACTION_Pos 4U /*!< DWT FUNCTION: ACTION Position */
+#define DWT_FUNCTION_ACTION_Msk (0x3UL << DWT_FUNCTION_ACTION_Pos) /*!< DWT FUNCTION: ACTION Mask */
+
+#define DWT_FUNCTION_MATCH_Pos 0U /*!< DWT FUNCTION: MATCH Position */
+#define DWT_FUNCTION_MATCH_Msk (0xFUL /*<< DWT_FUNCTION_MATCH_Pos*/) /*!< DWT FUNCTION: MATCH Mask */
+
+/*@}*/ /* end of group CMSIS_DWT */
+
+
+/**
+ \ingroup CMSIS_core_register
+ \defgroup CMSIS_TPI Trace Port Interface (TPI)
+ \brief Type definitions for the Trace Port Interface (TPI)
+ @{
+ */
+
+/**
+ \brief Structure type to access the Trace Port Interface Register (TPI).
+ */
+typedef struct
+{
+ __IOM uint32_t SSPSR; /*!< Offset: 0x000 (R/ ) Supported Parallel Port Size Register */
+ __IOM uint32_t CSPSR; /*!< Offset: 0x004 (R/W) Current Parallel Port Size Register */
+ uint32_t RESERVED0[2U];
+ __IOM uint32_t ACPR; /*!< Offset: 0x010 (R/W) Asynchronous Clock Prescaler Register */
+ uint32_t RESERVED1[55U];
+ __IOM uint32_t SPPR; /*!< Offset: 0x0F0 (R/W) Selected Pin Protocol Register */
+ uint32_t RESERVED2[131U];
+ __IM uint32_t FFSR; /*!< Offset: 0x300 (R/ ) Formatter and Flush Status Register */
+ __IOM uint32_t FFCR; /*!< Offset: 0x304 (R/W) Formatter and Flush Control Register */
+ __IM uint32_t FSCR; /*!< Offset: 0x308 (R/ ) Formatter Synchronization Counter Register */
+ uint32_t RESERVED3[759U];
+ __IM uint32_t TRIGGER; /*!< Offset: 0xEE8 (R/ ) TRIGGER */
+ __IM uint32_t FIFO0; /*!< Offset: 0xEEC (R/ ) Integration ETM Data */
+ __IM uint32_t ITATBCTR2; /*!< Offset: 0xEF0 (R/ ) ITATBCTR2 */
+ uint32_t RESERVED4[1U];
+ __IM uint32_t ITATBCTR0; /*!< Offset: 0xEF8 (R/ ) ITATBCTR0 */
+ __IM uint32_t FIFO1; /*!< Offset: 0xEFC (R/ ) Integration ITM Data */
+ __IOM uint32_t ITCTRL; /*!< Offset: 0xF00 (R/W) Integration Mode Control */
+ uint32_t RESERVED5[39U];
+ __IOM uint32_t CLAIMSET; /*!< Offset: 0xFA0 (R/W) Claim tag set */
+ __IOM uint32_t CLAIMCLR; /*!< Offset: 0xFA4 (R/W) Claim tag clear */
+ uint32_t RESERVED7[8U];
+ __IM uint32_t DEVID; /*!< Offset: 0xFC8 (R/ ) TPIU_DEVID */
+ __IM uint32_t DEVTYPE; /*!< Offset: 0xFCC (R/ ) TPIU_DEVTYPE */
+} TPI_Type;
+
+/* TPI Asynchronous Clock Prescaler Register Definitions */
+#define TPI_ACPR_PRESCALER_Pos 0U /*!< TPI ACPR: PRESCALER Position */
+#define TPI_ACPR_PRESCALER_Msk (0x1FFFUL /*<< TPI_ACPR_PRESCALER_Pos*/) /*!< TPI ACPR: PRESCALER Mask */
+
+/* TPI Selected Pin Protocol Register Definitions */
+#define TPI_SPPR_TXMODE_Pos 0U /*!< TPI SPPR: TXMODE Position */
+#define TPI_SPPR_TXMODE_Msk (0x3UL /*<< TPI_SPPR_TXMODE_Pos*/) /*!< TPI SPPR: TXMODE Mask */
+
+/* TPI Formatter and Flush Status Register Definitions */
+#define TPI_FFSR_FtNonStop_Pos 3U /*!< TPI FFSR: FtNonStop Position */
+#define TPI_FFSR_FtNonStop_Msk (0x1UL << TPI_FFSR_FtNonStop_Pos) /*!< TPI FFSR: FtNonStop Mask */
+
+#define TPI_FFSR_TCPresent_Pos 2U /*!< TPI FFSR: TCPresent Position */
+#define TPI_FFSR_TCPresent_Msk (0x1UL << TPI_FFSR_TCPresent_Pos) /*!< TPI FFSR: TCPresent Mask */
+
+#define TPI_FFSR_FtStopped_Pos 1U /*!< TPI FFSR: FtStopped Position */
+#define TPI_FFSR_FtStopped_Msk (0x1UL << TPI_FFSR_FtStopped_Pos) /*!< TPI FFSR: FtStopped Mask */
+
+#define TPI_FFSR_FlInProg_Pos 0U /*!< TPI FFSR: FlInProg Position */
+#define TPI_FFSR_FlInProg_Msk (0x1UL /*<< TPI_FFSR_FlInProg_Pos*/) /*!< TPI FFSR: FlInProg Mask */
+
+/* TPI Formatter and Flush Control Register Definitions */
+#define TPI_FFCR_TrigIn_Pos 8U /*!< TPI FFCR: TrigIn Position */
+#define TPI_FFCR_TrigIn_Msk (0x1UL << TPI_FFCR_TrigIn_Pos) /*!< TPI FFCR: TrigIn Mask */
+
+#define TPI_FFCR_EnFCont_Pos 1U /*!< TPI FFCR: EnFCont Position */
+#define TPI_FFCR_EnFCont_Msk (0x1UL << TPI_FFCR_EnFCont_Pos) /*!< TPI FFCR: EnFCont Mask */
+
+/* TPI TRIGGER Register Definitions */
+#define TPI_TRIGGER_TRIGGER_Pos 0U /*!< TPI TRIGGER: TRIGGER Position */
+#define TPI_TRIGGER_TRIGGER_Msk (0x1UL /*<< TPI_TRIGGER_TRIGGER_Pos*/) /*!< TPI TRIGGER: TRIGGER Mask */
+
+/* TPI Integration ETM Data Register Definitions (FIFO0) */
+#define TPI_FIFO0_ITM_ATVALID_Pos 29U /*!< TPI FIFO0: ITM_ATVALID Position */
+#define TPI_FIFO0_ITM_ATVALID_Msk (0x3UL << TPI_FIFO0_ITM_ATVALID_Pos) /*!< TPI FIFO0: ITM_ATVALID Mask */
+
+#define TPI_FIFO0_ITM_bytecount_Pos 27U /*!< TPI FIFO0: ITM_bytecount Position */
+#define TPI_FIFO0_ITM_bytecount_Msk (0x3UL << TPI_FIFO0_ITM_bytecount_Pos) /*!< TPI FIFO0: ITM_bytecount Mask */
+
+#define TPI_FIFO0_ETM_ATVALID_Pos 26U /*!< TPI FIFO0: ETM_ATVALID Position */
+#define TPI_FIFO0_ETM_ATVALID_Msk (0x3UL << TPI_FIFO0_ETM_ATVALID_Pos) /*!< TPI FIFO0: ETM_ATVALID Mask */
+
+#define TPI_FIFO0_ETM_bytecount_Pos 24U /*!< TPI FIFO0: ETM_bytecount Position */
+#define TPI_FIFO0_ETM_bytecount_Msk (0x3UL << TPI_FIFO0_ETM_bytecount_Pos) /*!< TPI FIFO0: ETM_bytecount Mask */
+
+#define TPI_FIFO0_ETM2_Pos 16U /*!< TPI FIFO0: ETM2 Position */
+#define TPI_FIFO0_ETM2_Msk (0xFFUL << TPI_FIFO0_ETM2_Pos) /*!< TPI FIFO0: ETM2 Mask */
+
+#define TPI_FIFO0_ETM1_Pos 8U /*!< TPI FIFO0: ETM1 Position */
+#define TPI_FIFO0_ETM1_Msk (0xFFUL << TPI_FIFO0_ETM1_Pos) /*!< TPI FIFO0: ETM1 Mask */
+
+#define TPI_FIFO0_ETM0_Pos 0U /*!< TPI FIFO0: ETM0 Position */
+#define TPI_FIFO0_ETM0_Msk (0xFFUL /*<< TPI_FIFO0_ETM0_Pos*/) /*!< TPI FIFO0: ETM0 Mask */
+
+/* TPI ITATBCTR2 Register Definitions */
+#define TPI_ITATBCTR2_ATREADY_Pos 0U /*!< TPI ITATBCTR2: ATREADY Position */
+#define TPI_ITATBCTR2_ATREADY_Msk (0x1UL /*<< TPI_ITATBCTR2_ATREADY_Pos*/) /*!< TPI ITATBCTR2: ATREADY Mask */
+
+/* TPI Integration ITM Data Register Definitions (FIFO1) */
+#define TPI_FIFO1_ITM_ATVALID_Pos 29U /*!< TPI FIFO1: ITM_ATVALID Position */
+#define TPI_FIFO1_ITM_ATVALID_Msk (0x3UL << TPI_FIFO1_ITM_ATVALID_Pos) /*!< TPI FIFO1: ITM_ATVALID Mask */
+
+#define TPI_FIFO1_ITM_bytecount_Pos 27U /*!< TPI FIFO1: ITM_bytecount Position */
+#define TPI_FIFO1_ITM_bytecount_Msk (0x3UL << TPI_FIFO1_ITM_bytecount_Pos) /*!< TPI FIFO1: ITM_bytecount Mask */
+
+#define TPI_FIFO1_ETM_ATVALID_Pos 26U /*!< TPI FIFO1: ETM_ATVALID Position */
+#define TPI_FIFO1_ETM_ATVALID_Msk (0x3UL << TPI_FIFO1_ETM_ATVALID_Pos) /*!< TPI FIFO1: ETM_ATVALID Mask */
+
+#define TPI_FIFO1_ETM_bytecount_Pos 24U /*!< TPI FIFO1: ETM_bytecount Position */
+#define TPI_FIFO1_ETM_bytecount_Msk (0x3UL << TPI_FIFO1_ETM_bytecount_Pos) /*!< TPI FIFO1: ETM_bytecount Mask */
+
+#define TPI_FIFO1_ITM2_Pos 16U /*!< TPI FIFO1: ITM2 Position */
+#define TPI_FIFO1_ITM2_Msk (0xFFUL << TPI_FIFO1_ITM2_Pos) /*!< TPI FIFO1: ITM2 Mask */
+
+#define TPI_FIFO1_ITM1_Pos 8U /*!< TPI FIFO1: ITM1 Position */
+#define TPI_FIFO1_ITM1_Msk (0xFFUL << TPI_FIFO1_ITM1_Pos) /*!< TPI FIFO1: ITM1 Mask */
+
+#define TPI_FIFO1_ITM0_Pos 0U /*!< TPI FIFO1: ITM0 Position */
+#define TPI_FIFO1_ITM0_Msk (0xFFUL /*<< TPI_FIFO1_ITM0_Pos*/) /*!< TPI FIFO1: ITM0 Mask */
+
+/* TPI ITATBCTR0 Register Definitions */
+#define TPI_ITATBCTR0_ATREADY_Pos 0U /*!< TPI ITATBCTR0: ATREADY Position */
+#define TPI_ITATBCTR0_ATREADY_Msk (0x1UL /*<< TPI_ITATBCTR0_ATREADY_Pos*/) /*!< TPI ITATBCTR0: ATREADY Mask */
+
+/* TPI Integration Mode Control Register Definitions */
+#define TPI_ITCTRL_Mode_Pos 0U /*!< TPI ITCTRL: Mode Position */
+#define TPI_ITCTRL_Mode_Msk (0x1UL /*<< TPI_ITCTRL_Mode_Pos*/) /*!< TPI ITCTRL: Mode Mask */
+
+/* TPI DEVID Register Definitions */
+#define TPI_DEVID_NRZVALID_Pos 11U /*!< TPI DEVID: NRZVALID Position */
+#define TPI_DEVID_NRZVALID_Msk (0x1UL << TPI_DEVID_NRZVALID_Pos) /*!< TPI DEVID: NRZVALID Mask */
+
+#define TPI_DEVID_MANCVALID_Pos 10U /*!< TPI DEVID: MANCVALID Position */
+#define TPI_DEVID_MANCVALID_Msk (0x1UL << TPI_DEVID_MANCVALID_Pos) /*!< TPI DEVID: MANCVALID Mask */
+
+#define TPI_DEVID_PTINVALID_Pos 9U /*!< TPI DEVID: PTINVALID Position */
+#define TPI_DEVID_PTINVALID_Msk (0x1UL << TPI_DEVID_PTINVALID_Pos) /*!< TPI DEVID: PTINVALID Mask */
+
+#define TPI_DEVID_MinBufSz_Pos 6U /*!< TPI DEVID: MinBufSz Position */
+#define TPI_DEVID_MinBufSz_Msk (0x7UL << TPI_DEVID_MinBufSz_Pos) /*!< TPI DEVID: MinBufSz Mask */
+
+#define TPI_DEVID_AsynClkIn_Pos 5U /*!< TPI DEVID: AsynClkIn Position */
+#define TPI_DEVID_AsynClkIn_Msk (0x1UL << TPI_DEVID_AsynClkIn_Pos) /*!< TPI DEVID: AsynClkIn Mask */
+
+#define TPI_DEVID_NrTraceInput_Pos 0U /*!< TPI DEVID: NrTraceInput Position */
+#define TPI_DEVID_NrTraceInput_Msk (0x1FUL /*<< TPI_DEVID_NrTraceInput_Pos*/) /*!< TPI DEVID: NrTraceInput Mask */
+
+/* TPI DEVTYPE Register Definitions */
+#define TPI_DEVTYPE_MajorType_Pos 4U /*!< TPI DEVTYPE: MajorType Position */
+#define TPI_DEVTYPE_MajorType_Msk (0xFUL << TPI_DEVTYPE_MajorType_Pos) /*!< TPI DEVTYPE: MajorType Mask */
+
+#define TPI_DEVTYPE_SubType_Pos 0U /*!< TPI DEVTYPE: SubType Position */
+#define TPI_DEVTYPE_SubType_Msk (0xFUL /*<< TPI_DEVTYPE_SubType_Pos*/) /*!< TPI DEVTYPE: SubType Mask */
+
+/*@}*/ /* end of group CMSIS_TPI */
+
+
+#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U)
+/**
+ \ingroup CMSIS_core_register
+ \defgroup CMSIS_MPU Memory Protection Unit (MPU)
+ \brief Type definitions for the Memory Protection Unit (MPU)
+ @{
+ */
+
+/**
+ \brief Structure type to access the Memory Protection Unit (MPU).
+ */
+typedef struct
+{
+ __IM uint32_t TYPE; /*!< Offset: 0x000 (R/ ) MPU Type Register */
+ __IOM uint32_t CTRL; /*!< Offset: 0x004 (R/W) MPU Control Register */
+ __IOM uint32_t RNR; /*!< Offset: 0x008 (R/W) MPU Region Number Register */
+ __IOM uint32_t RBAR; /*!< Offset: 0x00C (R/W) MPU Region Base Address Register */
+ __IOM uint32_t RLAR; /*!< Offset: 0x010 (R/W) MPU Region Limit Address Register */
+ uint32_t RESERVED0[7U];
+ union {
+ __IOM uint32_t MAIR[2];
+ struct {
+ __IOM uint32_t MAIR0; /*!< Offset: 0x030 (R/W) MPU Memory Attribute Indirection Register 0 */
+ __IOM uint32_t MAIR1; /*!< Offset: 0x034 (R/W) MPU Memory Attribute Indirection Register 1 */
+ };
+ };
+} MPU_Type;
+
+#define MPU_TYPE_RALIASES 1U
+
+/* MPU Type Register Definitions */
+#define MPU_TYPE_IREGION_Pos 16U /*!< MPU TYPE: IREGION Position */
+#define MPU_TYPE_IREGION_Msk (0xFFUL << MPU_TYPE_IREGION_Pos) /*!< MPU TYPE: IREGION Mask */
+
+#define MPU_TYPE_DREGION_Pos 8U /*!< MPU TYPE: DREGION Position */
+#define MPU_TYPE_DREGION_Msk (0xFFUL << MPU_TYPE_DREGION_Pos) /*!< MPU TYPE: DREGION Mask */
+
+#define MPU_TYPE_SEPARATE_Pos 0U /*!< MPU TYPE: SEPARATE Position */
+#define MPU_TYPE_SEPARATE_Msk (1UL /*<< MPU_TYPE_SEPARATE_Pos*/) /*!< MPU TYPE: SEPARATE Mask */
+
+/* MPU Control Register Definitions */
+#define MPU_CTRL_PRIVDEFENA_Pos 2U /*!< MPU CTRL: PRIVDEFENA Position */
+#define MPU_CTRL_PRIVDEFENA_Msk (1UL << MPU_CTRL_PRIVDEFENA_Pos) /*!< MPU CTRL: PRIVDEFENA Mask */
+
+#define MPU_CTRL_HFNMIENA_Pos 1U /*!< MPU CTRL: HFNMIENA Position */
+#define MPU_CTRL_HFNMIENA_Msk (1UL << MPU_CTRL_HFNMIENA_Pos) /*!< MPU CTRL: HFNMIENA Mask */
+
+#define MPU_CTRL_ENABLE_Pos 0U /*!< MPU CTRL: ENABLE Position */
+#define MPU_CTRL_ENABLE_Msk (1UL /*<< MPU_CTRL_ENABLE_Pos*/) /*!< MPU CTRL: ENABLE Mask */
+
+/* MPU Region Number Register Definitions */
+#define MPU_RNR_REGION_Pos 0U /*!< MPU RNR: REGION Position */
+#define MPU_RNR_REGION_Msk (0xFFUL /*<< MPU_RNR_REGION_Pos*/) /*!< MPU RNR: REGION Mask */
+
+/* MPU Region Base Address Register Definitions */
+#define MPU_RBAR_BASE_Pos 5U /*!< MPU RBAR: BASE Position */
+#define MPU_RBAR_BASE_Msk (0x7FFFFFFUL << MPU_RBAR_BASE_Pos) /*!< MPU RBAR: BASE Mask */
+
+#define MPU_RBAR_SH_Pos 3U /*!< MPU RBAR: SH Position */
+#define MPU_RBAR_SH_Msk (0x3UL << MPU_RBAR_SH_Pos) /*!< MPU RBAR: SH Mask */
+
+#define MPU_RBAR_AP_Pos 1U /*!< MPU RBAR: AP Position */
+#define MPU_RBAR_AP_Msk (0x3UL << MPU_RBAR_AP_Pos) /*!< MPU RBAR: AP Mask */
+
+#define MPU_RBAR_XN_Pos 0U /*!< MPU RBAR: XN Position */
+#define MPU_RBAR_XN_Msk (01UL /*<< MPU_RBAR_XN_Pos*/) /*!< MPU RBAR: XN Mask */
+
+/* MPU Region Limit Address Register Definitions */
+#define MPU_RLAR_LIMIT_Pos 5U /*!< MPU RLAR: LIMIT Position */
+#define MPU_RLAR_LIMIT_Msk (0x7FFFFFFUL << MPU_RLAR_LIMIT_Pos) /*!< MPU RLAR: LIMIT Mask */
+
+#define MPU_RLAR_AttrIndx_Pos 1U /*!< MPU RLAR: AttrIndx Position */
+#define MPU_RLAR_AttrIndx_Msk (0x7UL << MPU_RLAR_AttrIndx_Pos) /*!< MPU RLAR: AttrIndx Mask */
+
+#define MPU_RLAR_EN_Pos 0U /*!< MPU RLAR: EN Position */
+#define MPU_RLAR_EN_Msk (1UL /*<< MPU_RLAR_EN_Pos*/) /*!< MPU RLAR: EN Mask */
+
+/* MPU Memory Attribute Indirection Register 0 Definitions */
+#define MPU_MAIR0_Attr3_Pos 24U /*!< MPU MAIR0: Attr3 Position */
+#define MPU_MAIR0_Attr3_Msk (0xFFUL << MPU_MAIR0_Attr3_Pos) /*!< MPU MAIR0: Attr3 Mask */
+
+#define MPU_MAIR0_Attr2_Pos 16U /*!< MPU MAIR0: Attr2 Position */
+#define MPU_MAIR0_Attr2_Msk (0xFFUL << MPU_MAIR0_Attr2_Pos) /*!< MPU MAIR0: Attr2 Mask */
+
+#define MPU_MAIR0_Attr1_Pos 8U /*!< MPU MAIR0: Attr1 Position */
+#define MPU_MAIR0_Attr1_Msk (0xFFUL << MPU_MAIR0_Attr1_Pos) /*!< MPU MAIR0: Attr1 Mask */
+
+#define MPU_MAIR0_Attr0_Pos 0U /*!< MPU MAIR0: Attr0 Position */
+#define MPU_MAIR0_Attr0_Msk (0xFFUL /*<< MPU_MAIR0_Attr0_Pos*/) /*!< MPU MAIR0: Attr0 Mask */
+
+/* MPU Memory Attribute Indirection Register 1 Definitions */
+#define MPU_MAIR1_Attr7_Pos 24U /*!< MPU MAIR1: Attr7 Position */
+#define MPU_MAIR1_Attr7_Msk (0xFFUL << MPU_MAIR1_Attr7_Pos) /*!< MPU MAIR1: Attr7 Mask */
+
+#define MPU_MAIR1_Attr6_Pos 16U /*!< MPU MAIR1: Attr6 Position */
+#define MPU_MAIR1_Attr6_Msk (0xFFUL << MPU_MAIR1_Attr6_Pos) /*!< MPU MAIR1: Attr6 Mask */
+
+#define MPU_MAIR1_Attr5_Pos 8U /*!< MPU MAIR1: Attr5 Position */
+#define MPU_MAIR1_Attr5_Msk (0xFFUL << MPU_MAIR1_Attr5_Pos) /*!< MPU MAIR1: Attr5 Mask */
+
+#define MPU_MAIR1_Attr4_Pos 0U /*!< MPU MAIR1: Attr4 Position */
+#define MPU_MAIR1_Attr4_Msk (0xFFUL /*<< MPU_MAIR1_Attr4_Pos*/) /*!< MPU MAIR1: Attr4 Mask */
+
+/*@} end of group CMSIS_MPU */
+#endif
+
+
+#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U)
+/**
+ \ingroup CMSIS_core_register
+ \defgroup CMSIS_SAU Security Attribution Unit (SAU)
+ \brief Type definitions for the Security Attribution Unit (SAU)
+ @{
+ */
+
+/**
+ \brief Structure type to access the Security Attribution Unit (SAU).
+ */
+typedef struct
+{
+ __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) SAU Control Register */
+ __IM uint32_t TYPE; /*!< Offset: 0x004 (R/ ) SAU Type Register */
+#if defined (__SAUREGION_PRESENT) && (__SAUREGION_PRESENT == 1U)
+ __IOM uint32_t RNR; /*!< Offset: 0x008 (R/W) SAU Region Number Register */
+ __IOM uint32_t RBAR; /*!< Offset: 0x00C (R/W) SAU Region Base Address Register */
+ __IOM uint32_t RLAR; /*!< Offset: 0x010 (R/W) SAU Region Limit Address Register */
+#endif
+} SAU_Type;
+
+/* SAU Control Register Definitions */
+#define SAU_CTRL_ALLNS_Pos 1U /*!< SAU CTRL: ALLNS Position */
+#define SAU_CTRL_ALLNS_Msk (1UL << SAU_CTRL_ALLNS_Pos) /*!< SAU CTRL: ALLNS Mask */
+
+#define SAU_CTRL_ENABLE_Pos 0U /*!< SAU CTRL: ENABLE Position */
+#define SAU_CTRL_ENABLE_Msk (1UL /*<< SAU_CTRL_ENABLE_Pos*/) /*!< SAU CTRL: ENABLE Mask */
+
+/* SAU Type Register Definitions */
+#define SAU_TYPE_SREGION_Pos 0U /*!< SAU TYPE: SREGION Position */
+#define SAU_TYPE_SREGION_Msk (0xFFUL /*<< SAU_TYPE_SREGION_Pos*/) /*!< SAU TYPE: SREGION Mask */
+
+#if defined (__SAUREGION_PRESENT) && (__SAUREGION_PRESENT == 1U)
+/* SAU Region Number Register Definitions */
+#define SAU_RNR_REGION_Pos 0U /*!< SAU RNR: REGION Position */
+#define SAU_RNR_REGION_Msk (0xFFUL /*<< SAU_RNR_REGION_Pos*/) /*!< SAU RNR: REGION Mask */
+
+/* SAU Region Base Address Register Definitions */
+#define SAU_RBAR_BADDR_Pos 5U /*!< SAU RBAR: BADDR Position */
+#define SAU_RBAR_BADDR_Msk (0x7FFFFFFUL << SAU_RBAR_BADDR_Pos) /*!< SAU RBAR: BADDR Mask */
+
+/* SAU Region Limit Address Register Definitions */
+#define SAU_RLAR_LADDR_Pos 5U /*!< SAU RLAR: LADDR Position */
+#define SAU_RLAR_LADDR_Msk (0x7FFFFFFUL << SAU_RLAR_LADDR_Pos) /*!< SAU RLAR: LADDR Mask */
+
+#define SAU_RLAR_NSC_Pos 1U /*!< SAU RLAR: NSC Position */
+#define SAU_RLAR_NSC_Msk (1UL << SAU_RLAR_NSC_Pos) /*!< SAU RLAR: NSC Mask */
+
+#define SAU_RLAR_ENABLE_Pos 0U /*!< SAU RLAR: ENABLE Position */
+#define SAU_RLAR_ENABLE_Msk (1UL /*<< SAU_RLAR_ENABLE_Pos*/) /*!< SAU RLAR: ENABLE Mask */
+
+#endif /* defined (__SAUREGION_PRESENT) && (__SAUREGION_PRESENT == 1U) */
+
+/*@} end of group CMSIS_SAU */
+#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */
+
+
+/**
+ \ingroup CMSIS_core_register
+ \defgroup CMSIS_CoreDebug Core Debug Registers (CoreDebug)
+ \brief Type definitions for the Core Debug Registers
+ @{
+ */
+
+/**
+ \brief Structure type to access the Core Debug Register (CoreDebug).
+ */
+typedef struct
+{
+ __IOM uint32_t DHCSR; /*!< Offset: 0x000 (R/W) Debug Halting Control and Status Register */
+ __OM uint32_t DCRSR; /*!< Offset: 0x004 ( /W) Debug Core Register Selector Register */
+ __IOM uint32_t DCRDR; /*!< Offset: 0x008 (R/W) Debug Core Register Data Register */
+ __IOM uint32_t DEMCR; /*!< Offset: 0x00C (R/W) Debug Exception and Monitor Control Register */
+ uint32_t RESERVED4[1U];
+ __IOM uint32_t DAUTHCTRL; /*!< Offset: 0x014 (R/W) Debug Authentication Control Register */
+ __IOM uint32_t DSCSR; /*!< Offset: 0x018 (R/W) Debug Security Control and Status Register */
+} CoreDebug_Type;
+
+/* Debug Halting Control and Status Register Definitions */
+#define CoreDebug_DHCSR_DBGKEY_Pos 16U /*!< CoreDebug DHCSR: DBGKEY Position */
+#define CoreDebug_DHCSR_DBGKEY_Msk (0xFFFFUL << CoreDebug_DHCSR_DBGKEY_Pos) /*!< CoreDebug DHCSR: DBGKEY Mask */
+
+#define CoreDebug_DHCSR_S_RESTART_ST_Pos 26U /*!< CoreDebug DHCSR: S_RESTART_ST Position */
+#define CoreDebug_DHCSR_S_RESTART_ST_Msk (1UL << CoreDebug_DHCSR_S_RESTART_ST_Pos) /*!< CoreDebug DHCSR: S_RESTART_ST Mask */
+
+#define CoreDebug_DHCSR_S_RESET_ST_Pos 25U /*!< CoreDebug DHCSR: S_RESET_ST Position */
+#define CoreDebug_DHCSR_S_RESET_ST_Msk (1UL << CoreDebug_DHCSR_S_RESET_ST_Pos) /*!< CoreDebug DHCSR: S_RESET_ST Mask */
+
+#define CoreDebug_DHCSR_S_RETIRE_ST_Pos 24U /*!< CoreDebug DHCSR: S_RETIRE_ST Position */
+#define CoreDebug_DHCSR_S_RETIRE_ST_Msk (1UL << CoreDebug_DHCSR_S_RETIRE_ST_Pos) /*!< CoreDebug DHCSR: S_RETIRE_ST Mask */
+
+#define CoreDebug_DHCSR_S_LOCKUP_Pos 19U /*!< CoreDebug DHCSR: S_LOCKUP Position */
+#define CoreDebug_DHCSR_S_LOCKUP_Msk (1UL << CoreDebug_DHCSR_S_LOCKUP_Pos) /*!< CoreDebug DHCSR: S_LOCKUP Mask */
+
+#define CoreDebug_DHCSR_S_SLEEP_Pos 18U /*!< CoreDebug DHCSR: S_SLEEP Position */
+#define CoreDebug_DHCSR_S_SLEEP_Msk (1UL << CoreDebug_DHCSR_S_SLEEP_Pos) /*!< CoreDebug DHCSR: S_SLEEP Mask */
+
+#define CoreDebug_DHCSR_S_HALT_Pos 17U /*!< CoreDebug DHCSR: S_HALT Position */
+#define CoreDebug_DHCSR_S_HALT_Msk (1UL << CoreDebug_DHCSR_S_HALT_Pos) /*!< CoreDebug DHCSR: S_HALT Mask */
+
+#define CoreDebug_DHCSR_S_REGRDY_Pos 16U /*!< CoreDebug DHCSR: S_REGRDY Position */
+#define CoreDebug_DHCSR_S_REGRDY_Msk (1UL << CoreDebug_DHCSR_S_REGRDY_Pos) /*!< CoreDebug DHCSR: S_REGRDY Mask */
+
+#define CoreDebug_DHCSR_C_MASKINTS_Pos 3U /*!< CoreDebug DHCSR: C_MASKINTS Position */
+#define CoreDebug_DHCSR_C_MASKINTS_Msk (1UL << CoreDebug_DHCSR_C_MASKINTS_Pos) /*!< CoreDebug DHCSR: C_MASKINTS Mask */
+
+#define CoreDebug_DHCSR_C_STEP_Pos 2U /*!< CoreDebug DHCSR: C_STEP Position */
+#define CoreDebug_DHCSR_C_STEP_Msk (1UL << CoreDebug_DHCSR_C_STEP_Pos) /*!< CoreDebug DHCSR: C_STEP Mask */
+
+#define CoreDebug_DHCSR_C_HALT_Pos 1U /*!< CoreDebug DHCSR: C_HALT Position */
+#define CoreDebug_DHCSR_C_HALT_Msk (1UL << CoreDebug_DHCSR_C_HALT_Pos) /*!< CoreDebug DHCSR: C_HALT Mask */
+
+#define CoreDebug_DHCSR_C_DEBUGEN_Pos 0U /*!< CoreDebug DHCSR: C_DEBUGEN Position */
+#define CoreDebug_DHCSR_C_DEBUGEN_Msk (1UL /*<< CoreDebug_DHCSR_C_DEBUGEN_Pos*/) /*!< CoreDebug DHCSR: C_DEBUGEN Mask */
+
+/* Debug Core Register Selector Register Definitions */
+#define CoreDebug_DCRSR_REGWnR_Pos 16U /*!< CoreDebug DCRSR: REGWnR Position */
+#define CoreDebug_DCRSR_REGWnR_Msk (1UL << CoreDebug_DCRSR_REGWnR_Pos) /*!< CoreDebug DCRSR: REGWnR Mask */
+
+#define CoreDebug_DCRSR_REGSEL_Pos 0U /*!< CoreDebug DCRSR: REGSEL Position */
+#define CoreDebug_DCRSR_REGSEL_Msk (0x1FUL /*<< CoreDebug_DCRSR_REGSEL_Pos*/) /*!< CoreDebug DCRSR: REGSEL Mask */
+
+/* Debug Exception and Monitor Control Register */
+#define CoreDebug_DEMCR_DWTENA_Pos 24U /*!< CoreDebug DEMCR: DWTENA Position */
+#define CoreDebug_DEMCR_DWTENA_Msk (1UL << CoreDebug_DEMCR_DWTENA_Pos) /*!< CoreDebug DEMCR: DWTENA Mask */
+
+#define CoreDebug_DEMCR_VC_HARDERR_Pos 10U /*!< CoreDebug DEMCR: VC_HARDERR Position */
+#define CoreDebug_DEMCR_VC_HARDERR_Msk (1UL << CoreDebug_DEMCR_VC_HARDERR_Pos) /*!< CoreDebug DEMCR: VC_HARDERR Mask */
+
+#define CoreDebug_DEMCR_VC_CORERESET_Pos 0U /*!< CoreDebug DEMCR: VC_CORERESET Position */
+#define CoreDebug_DEMCR_VC_CORERESET_Msk (1UL /*<< CoreDebug_DEMCR_VC_CORERESET_Pos*/) /*!< CoreDebug DEMCR: VC_CORERESET Mask */
+
+/* Debug Authentication Control Register Definitions */
+#define CoreDebug_DAUTHCTRL_INTSPNIDEN_Pos 3U /*!< CoreDebug DAUTHCTRL: INTSPNIDEN, Position */
+#define CoreDebug_DAUTHCTRL_INTSPNIDEN_Msk (1UL << CoreDebug_DAUTHCTRL_INTSPNIDEN_Pos) /*!< CoreDebug DAUTHCTRL: INTSPNIDEN, Mask */
+
+#define CoreDebug_DAUTHCTRL_SPNIDENSEL_Pos 2U /*!< CoreDebug DAUTHCTRL: SPNIDENSEL Position */
+#define CoreDebug_DAUTHCTRL_SPNIDENSEL_Msk (1UL << CoreDebug_DAUTHCTRL_SPNIDENSEL_Pos) /*!< CoreDebug DAUTHCTRL: SPNIDENSEL Mask */
+
+#define CoreDebug_DAUTHCTRL_INTSPIDEN_Pos 1U /*!< CoreDebug DAUTHCTRL: INTSPIDEN Position */
+#define CoreDebug_DAUTHCTRL_INTSPIDEN_Msk (1UL << CoreDebug_DAUTHCTRL_INTSPIDEN_Pos) /*!< CoreDebug DAUTHCTRL: INTSPIDEN Mask */
+
+#define CoreDebug_DAUTHCTRL_SPIDENSEL_Pos 0U /*!< CoreDebug DAUTHCTRL: SPIDENSEL Position */
+#define CoreDebug_DAUTHCTRL_SPIDENSEL_Msk (1UL /*<< CoreDebug_DAUTHCTRL_SPIDENSEL_Pos*/) /*!< CoreDebug DAUTHCTRL: SPIDENSEL Mask */
+
+/* Debug Security Control and Status Register Definitions */
+#define CoreDebug_DSCSR_CDS_Pos 16U /*!< CoreDebug DSCSR: CDS Position */
+#define CoreDebug_DSCSR_CDS_Msk (1UL << CoreDebug_DSCSR_CDS_Pos) /*!< CoreDebug DSCSR: CDS Mask */
+
+#define CoreDebug_DSCSR_SBRSEL_Pos 1U /*!< CoreDebug DSCSR: SBRSEL Position */
+#define CoreDebug_DSCSR_SBRSEL_Msk (1UL << CoreDebug_DSCSR_SBRSEL_Pos) /*!< CoreDebug DSCSR: SBRSEL Mask */
+
+#define CoreDebug_DSCSR_SBRSELEN_Pos 0U /*!< CoreDebug DSCSR: SBRSELEN Position */
+#define CoreDebug_DSCSR_SBRSELEN_Msk (1UL /*<< CoreDebug_DSCSR_SBRSELEN_Pos*/) /*!< CoreDebug DSCSR: SBRSELEN Mask */
+
+/*@} 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 DWT_BASE (0xE0001000UL) /*!< DWT Base Address */
+ #define TPI_BASE (0xE0040000UL) /*!< TPI Base Address */
+ #define CoreDebug_BASE (0xE000EDF0UL) /*!< Core Debug 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 */
+ #define DWT ((DWT_Type *) DWT_BASE ) /*!< DWT configuration struct */
+ #define TPI ((TPI_Type *) TPI_BASE ) /*!< TPI configuration struct */
+ #define CoreDebug ((CoreDebug_Type *) CoreDebug_BASE ) /*!< Core Debug configuration struct */
+
+ #if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U)
+ #define MPU_BASE (SCS_BASE + 0x0D90UL) /*!< Memory Protection Unit */
+ #define MPU ((MPU_Type *) MPU_BASE ) /*!< Memory Protection Unit */
+ #endif
+
+ #if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U)
+ #define SAU_BASE (SCS_BASE + 0x0DD0UL) /*!< Security Attribution Unit */
+ #define SAU ((SAU_Type *) SAU_BASE ) /*!< Security Attribution Unit */
+ #endif
+
+#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U)
+ #define SCS_BASE_NS (0xE002E000UL) /*!< System Control Space Base Address (non-secure address space) */
+ #define CoreDebug_BASE_NS (0xE002EDF0UL) /*!< Core Debug Base Address (non-secure address space) */
+ #define SysTick_BASE_NS (SCS_BASE_NS + 0x0010UL) /*!< SysTick Base Address (non-secure address space) */
+ #define NVIC_BASE_NS (SCS_BASE_NS + 0x0100UL) /*!< NVIC Base Address (non-secure address space) */
+ #define SCB_BASE_NS (SCS_BASE_NS + 0x0D00UL) /*!< System Control Block Base Address (non-secure address space) */
+
+ #define SCB_NS ((SCB_Type *) SCB_BASE_NS ) /*!< SCB configuration struct (non-secure address space) */
+ #define SysTick_NS ((SysTick_Type *) SysTick_BASE_NS ) /*!< SysTick configuration struct (non-secure address space) */
+ #define NVIC_NS ((NVIC_Type *) NVIC_BASE_NS ) /*!< NVIC configuration struct (non-secure address space) */
+ #define CoreDebug_NS ((CoreDebug_Type *) CoreDebug_BASE_NS) /*!< Core Debug configuration struct (non-secure address space) */
+
+ #if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U)
+ #define MPU_BASE_NS (SCS_BASE_NS + 0x0D90UL) /*!< Memory Protection Unit (non-secure address space) */
+ #define MPU_NS ((MPU_Type *) MPU_BASE_NS ) /*!< Memory Protection Unit (non-secure address space) */
+ #endif
+
+#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */
+/*@} */
+
+
+
+/*******************************************************************************
+ * 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 not available for Armv8-M Baseline */
+/*#define NVIC_GetPriorityGrouping __NVIC_GetPriorityGrouping not available for Armv8-M Baseline */
+ #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
+ #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
+
+
+/* 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) )
+
+
+/**
+ \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[(((uint32_t)IRQn) >> 5UL)] = (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[(((uint32_t)IRQn) >> 5UL)] & (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[(((uint32_t)IRQn) >> 5UL)] = (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[(((uint32_t)IRQn) >> 5UL)] & (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[(((uint32_t)IRQn) >> 5UL)] = (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[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL));
+ }
+}
+
+
+/**
+ \brief Get Active Interrupt
+ \details Reads the active register in the NVIC and returns the active bit for the device specific interrupt.
+ \param [in] IRQn Device specific interrupt number.
+ \return 0 Interrupt status is not active.
+ \return 1 Interrupt status is active.
+ \note IRQn must not be negative.
+ */
+__STATIC_INLINE uint32_t __NVIC_GetActive(IRQn_Type IRQn)
+{
+ if ((int32_t)(IRQn) >= 0)
+ {
+ return((uint32_t)(((NVIC->IABR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL));
+ }
+ else
+ {
+ return(0U);
+ }
+}
+
+
+#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U)
+/**
+ \brief Get Interrupt Target State
+ \details Reads the interrupt target field in the NVIC and returns the interrupt target bit for the device specific interrupt.
+ \param [in] IRQn Device specific interrupt number.
+ \return 0 if interrupt is assigned to Secure
+ \return 1 if interrupt is assigned to Non Secure
+ \note IRQn must not be negative.
+ */
+__STATIC_INLINE uint32_t NVIC_GetTargetState(IRQn_Type IRQn)
+{
+ if ((int32_t)(IRQn) >= 0)
+ {
+ return((uint32_t)(((NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL));
+ }
+ else
+ {
+ return(0U);
+ }
+}
+
+
+/**
+ \brief Set Interrupt Target State
+ \details Sets the interrupt target field in the NVIC and returns the interrupt target bit for the device specific interrupt.
+ \param [in] IRQn Device specific interrupt number.
+ \return 0 if interrupt is assigned to Secure
+ 1 if interrupt is assigned to Non Secure
+ \note IRQn must not be negative.
+ */
+__STATIC_INLINE uint32_t NVIC_SetTargetState(IRQn_Type IRQn)
+{
+ if ((int32_t)(IRQn) >= 0)
+ {
+ NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] |= ((uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)));
+ return((uint32_t)(((NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL));
+ }
+ else
+ {
+ return(0U);
+ }
+}
+
+
+/**
+ \brief Clear Interrupt Target State
+ \details Clears the interrupt target field in the NVIC and returns the interrupt target bit for the device specific interrupt.
+ \param [in] IRQn Device specific interrupt number.
+ \return 0 if interrupt is assigned to Secure
+ 1 if interrupt is assigned to Non Secure
+ \note IRQn must not be negative.
+ */
+__STATIC_INLINE uint32_t NVIC_ClearTargetState(IRQn_Type IRQn)
+{
+ if ((int32_t)(IRQn) >= 0)
+ {
+ NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] &= ~((uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)));
+ return((uint32_t)(((NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL));
+ }
+ else
+ {
+ return(0U);
+ }
+}
+#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */
+
+
+/**
+ \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->IPR[_IP_IDX(IRQn)] = ((uint32_t)(NVIC->IPR[_IP_IDX(IRQn)] & ~(0xFFUL << _BIT_SHIFT(IRQn))) |
+ (((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL) << _BIT_SHIFT(IRQn)));
+ }
+ else
+ {
+ SCB->SHPR[_SHP_IDX(IRQn)] = ((uint32_t)(SCB->SHPR[_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->IPR[ _IP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & (uint32_t)0xFFUL) >> (8U - __NVIC_PRIO_BITS)));
+ }
+ else
+ {
+ return((uint32_t)(((SCB->SHPR[_SHP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & (uint32_t)0xFFUL) >> (8U - __NVIC_PRIO_BITS)));
+ }
+}
+
+
+/**
+ \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.
+ VTOR must been relocated to SRAM before.
+ If VTOR is not present 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)
+{
+#if defined (__VTOR_PRESENT) && (__VTOR_PRESENT == 1U)
+ uint32_t *vectors = (uint32_t *)SCB->VTOR;
+#else
+ uint32_t *vectors = (uint32_t *)0x0U;
+#endif
+ 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)
+{
+#if defined (__VTOR_PRESENT) && (__VTOR_PRESENT == 1U)
+ uint32_t *vectors = (uint32_t *)SCB->VTOR;
+#else
+ uint32_t *vectors = (uint32_t *)0x0U;
+#endif
+ return vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET];
+}
+
+
+/**
+ \brief System Reset
+ \details Initiates a system reset request to reset the MCU.
+ */
+__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();
+ }
+}
+
+#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U)
+/**
+ \brief Enable Interrupt (non-secure)
+ \details Enables a device specific interrupt in the non-secure NVIC interrupt controller when in secure state.
+ \param [in] IRQn Device specific interrupt number.
+ \note IRQn must not be negative.
+ */
+__STATIC_INLINE void TZ_NVIC_EnableIRQ_NS(IRQn_Type IRQn)
+{
+ if ((int32_t)(IRQn) >= 0)
+ {
+ NVIC_NS->ISER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL));
+ }
+}
+
+
+/**
+ \brief Get Interrupt Enable status (non-secure)
+ \details Returns a device specific interrupt enable status from the non-secure NVIC interrupt controller when in secure state.
+ \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 TZ_NVIC_GetEnableIRQ_NS(IRQn_Type IRQn)
+{
+ if ((int32_t)(IRQn) >= 0)
+ {
+ return((uint32_t)(((NVIC_NS->ISER[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL));
+ }
+ else
+ {
+ return(0U);
+ }
+}
+
+
+/**
+ \brief Disable Interrupt (non-secure)
+ \details Disables a device specific interrupt in the non-secure NVIC interrupt controller when in secure state.
+ \param [in] IRQn Device specific interrupt number.
+ \note IRQn must not be negative.
+ */
+__STATIC_INLINE void TZ_NVIC_DisableIRQ_NS(IRQn_Type IRQn)
+{
+ if ((int32_t)(IRQn) >= 0)
+ {
+ NVIC_NS->ICER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL));
+ }
+}
+
+
+/**
+ \brief Get Pending Interrupt (non-secure)
+ \details Reads the NVIC pending register in the non-secure NVIC when in secure state 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 TZ_NVIC_GetPendingIRQ_NS(IRQn_Type IRQn)
+{
+ if ((int32_t)(IRQn) >= 0)
+ {
+ return((uint32_t)(((NVIC_NS->ISPR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL));
+ }
+ else
+ {
+ return(0U);
+ }
+}
+
+
+/**
+ \brief Set Pending Interrupt (non-secure)
+ \details Sets the pending bit of a device specific interrupt in the non-secure NVIC pending register when in secure state.
+ \param [in] IRQn Device specific interrupt number.
+ \note IRQn must not be negative.
+ */
+__STATIC_INLINE void TZ_NVIC_SetPendingIRQ_NS(IRQn_Type IRQn)
+{
+ if ((int32_t)(IRQn) >= 0)
+ {
+ NVIC_NS->ISPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL));
+ }
+}
+
+
+/**
+ \brief Clear Pending Interrupt (non-secure)
+ \details Clears the pending bit of a device specific interrupt in the non-secure NVIC pending register when in secure state.
+ \param [in] IRQn Device specific interrupt number.
+ \note IRQn must not be negative.
+ */
+__STATIC_INLINE void TZ_NVIC_ClearPendingIRQ_NS(IRQn_Type IRQn)
+{
+ if ((int32_t)(IRQn) >= 0)
+ {
+ NVIC_NS->ICPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL));
+ }
+}
+
+
+/**
+ \brief Get Active Interrupt (non-secure)
+ \details Reads the active register in non-secure NVIC when in secure state and returns the active bit for the device specific interrupt.
+ \param [in] IRQn Device specific interrupt number.
+ \return 0 Interrupt status is not active.
+ \return 1 Interrupt status is active.
+ \note IRQn must not be negative.
+ */
+__STATIC_INLINE uint32_t TZ_NVIC_GetActive_NS(IRQn_Type IRQn)
+{
+ if ((int32_t)(IRQn) >= 0)
+ {
+ return((uint32_t)(((NVIC_NS->IABR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL));
+ }
+ else
+ {
+ return(0U);
+ }
+}
+
+
+/**
+ \brief Set Interrupt Priority (non-secure)
+ \details Sets the priority of a non-secure device specific interrupt or a non-secure processor exception when in secure state.
+ 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 non-secure processor exception.
+ */
+__STATIC_INLINE void TZ_NVIC_SetPriority_NS(IRQn_Type IRQn, uint32_t priority)
+{
+ if ((int32_t)(IRQn) >= 0)
+ {
+ NVIC_NS->IPR[_IP_IDX(IRQn)] = ((uint32_t)(NVIC_NS->IPR[_IP_IDX(IRQn)] & ~(0xFFUL << _BIT_SHIFT(IRQn))) |
+ (((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL) << _BIT_SHIFT(IRQn)));
+ }
+ else
+ {
+ SCB_NS->SHPR[_SHP_IDX(IRQn)] = ((uint32_t)(SCB_NS->SHPR[_SHP_IDX(IRQn)] & ~(0xFFUL << _BIT_SHIFT(IRQn))) |
+ (((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL) << _BIT_SHIFT(IRQn)));
+ }
+}
+
+
+/**
+ \brief Get Interrupt Priority (non-secure)
+ \details Reads the priority of a non-secure device specific interrupt or a non-secure processor exception when in secure state.
+ 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 TZ_NVIC_GetPriority_NS(IRQn_Type IRQn)
+{
+
+ if ((int32_t)(IRQn) >= 0)
+ {
+ return((uint32_t)(((NVIC_NS->IPR[ _IP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & (uint32_t)0xFFUL) >> (8U - __NVIC_PRIO_BITS)));
+ }
+ else
+ {
+ return((uint32_t)(((SCB_NS->SHPR[_SHP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & (uint32_t)0xFFUL) >> (8U - __NVIC_PRIO_BITS)));
+ }
+}
+#endif /* defined (__ARM_FEATURE_CMSE) &&(__ARM_FEATURE_CMSE == 3U) */
+
+/*@} end of CMSIS_Core_NVICFunctions */
+
+/* ########################## MPU functions #################################### */
+
+#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U)
+
+#include "mpu_armv8.h"
+
+#endif
+
+/* ########################## 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 */
+
+
+
+/* ########################## SAU functions #################################### */
+/**
+ \ingroup CMSIS_Core_FunctionInterface
+ \defgroup CMSIS_Core_SAUFunctions SAU Functions
+ \brief Functions that configure the SAU.
+ @{
+ */
+
+#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U)
+
+/**
+ \brief Enable SAU
+ \details Enables the Security Attribution Unit (SAU).
+ */
+__STATIC_INLINE void TZ_SAU_Enable(void)
+{
+ SAU->CTRL |= (SAU_CTRL_ENABLE_Msk);
+}
+
+
+
+/**
+ \brief Disable SAU
+ \details Disables the Security Attribution Unit (SAU).
+ */
+__STATIC_INLINE void TZ_SAU_Disable(void)
+{
+ SAU->CTRL &= ~(SAU_CTRL_ENABLE_Msk);
+}
+
+#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */
+
+/*@} end of CMSIS_Core_SAUFunctions */
+
+
+
+
+/* ################################## 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 <b>__Vendor_SysTickConfig</b> is set to 1, then the
+ function <b>SysTick_Config</b> is not included. In this case, the file <b><i>device</i>.h</b>
+ 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 */
+}
+
+#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U)
+/**
+ \brief System Tick Configuration (non-secure)
+ \details Initializes the non-secure System Timer and its interrupt when in secure state, 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 <b>__Vendor_SysTickConfig</b> is set to 1, then the
+ function <b>TZ_SysTick_Config_NS</b> is not included. In this case, the file <b><i>device</i>.h</b>
+ must contain a vendor-specific implementation of this function.
+
+ */
+__STATIC_INLINE uint32_t TZ_SysTick_Config_NS(uint32_t ticks)
+{
+ if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk)
+ {
+ return (1UL); /* Reload value impossible */
+ }
+
+ SysTick_NS->LOAD = (uint32_t)(ticks - 1UL); /* set reload register */
+ TZ_NVIC_SetPriority_NS (SysTick_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL); /* set Priority for Systick Interrupt */
+ SysTick_NS->VAL = 0UL; /* Load the SysTick Counter Value */
+ SysTick_NS->CTRL = SysTick_CTRL_CLKSOURCE_Msk |
+ SysTick_CTRL_TICKINT_Msk |
+ SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */
+ return (0UL); /* Function successful */
+}
+#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */
+
+#endif
+
+/*@} end of CMSIS_Core_SysTickFunctions */
+
+
+
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __CORE_ARMV8MBL_H_DEPENDANT */
+
+#endif /* __CMSIS_GENERIC */
diff --git a/CMSIS/core_armv8mml.h b/CMSIS/core_armv8mml.h
new file mode 100644
index 0000000..0951a1f
--- /dev/null
+++ b/CMSIS/core_armv8mml.h
@@ -0,0 +1,2960 @@
+/**************************************************************************//**
+ * @file core_armv8mml.h
+ * @brief CMSIS Armv8-M Mainline Core Peripheral Access Layer 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.
+ */
+
+#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_ARMV8MML_H_GENERIC
+#define __CORE_ARMV8MML_H_GENERIC
+
+#include <stdint.h>
+
+#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.<br>
+ Function definitions in header files are used to allow 'inlining'.
+
+ \li Required Rule 18.4, declaration of union type or object of union type: '{...}'.<br>
+ Unions are used for effective representation of core registers.
+
+ \li Advisory Rule 19.7, Function-like macro defined.<br>
+ Function-like macros are used to allow more efficient code.
+ */
+
+
+/*******************************************************************************
+ * CMSIS definitions
+ ******************************************************************************/
+/**
+ \ingroup Cortex_ARMv8MML
+ @{
+ */
+
+#include "cmsis_version.h"
+
+/* CMSIS Armv8MML definitions */
+#define __ARMv8MML_CMSIS_VERSION_MAIN (__CM_CMSIS_VERSION_MAIN) /*!< \deprecated [31:16] CMSIS HAL main version */
+#define __ARMv8MML_CMSIS_VERSION_SUB (__CM_CMSIS_VERSION_SUB) /*!< \deprecated [15:0] CMSIS HAL sub version */
+#define __ARMv8MML_CMSIS_VERSION ((__ARMv8MML_CMSIS_VERSION_MAIN << 16U) | \
+ __ARMv8MML_CMSIS_VERSION_SUB ) /*!< \deprecated CMSIS HAL version number */
+
+#define __CORTEX_M (81U) /*!< Cortex-M Core */
+
+/** __FPU_USED indicates whether an FPU is used or not.
+ For this, __FPU_PRESENT has to be checked prior to making use of FPU specific registers and functions.
+*/
+#if defined ( __CC_ARM )
+ #if defined __TARGET_FPU_VFP
+ #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)
+ #define __FPU_USED 1U
+ #else
+ #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)"
+ #define __FPU_USED 0U
+ #endif
+ #else
+ #define __FPU_USED 0U
+ #endif
+
+ #if defined(__ARM_FEATURE_DSP)
+ #if defined(__DSP_PRESENT) && (__DSP_PRESENT == 1U)
+ #define __DSP_USED 1U
+ #else
+ #error "Compiler generates DSP (SIMD) instructions for a devices without DSP extensions (check __DSP_PRESENT)"
+ #define __DSP_USED 0U
+ #endif
+ #else
+ #define __DSP_USED 0U
+ #endif
+
+#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
+ #if defined __ARM_PCS_VFP
+ #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)
+ #define __FPU_USED 1U
+ #else
+ #warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)"
+ #define __FPU_USED 0U
+ #endif
+ #else
+ #define __FPU_USED 0U
+ #endif
+
+ #if defined(__ARM_FEATURE_DSP)
+ #if defined(__DSP_PRESENT) && (__DSP_PRESENT == 1U)
+ #define __DSP_USED 1U
+ #else
+ #error "Compiler generates DSP (SIMD) instructions for a devices without DSP extensions (check __DSP_PRESENT)"
+ #define __DSP_USED 0U
+ #endif
+ #else
+ #define __DSP_USED 0U
+ #endif
+
+#elif defined ( __GNUC__ )
+ #if defined (__VFP_FP__) && !defined(__SOFTFP__)
+ #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)
+ #define __FPU_USED 1U
+ #else
+ #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)"
+ #define __FPU_USED 0U
+ #endif
+ #else
+ #define __FPU_USED 0U
+ #endif
+
+ #if defined(__ARM_FEATURE_DSP)
+ #if defined(__DSP_PRESENT) && (__DSP_PRESENT == 1U)
+ #define __DSP_USED 1U
+ #else
+ #error "Compiler generates DSP (SIMD) instructions for a devices without DSP extensions (check __DSP_PRESENT)"
+ #define __DSP_USED 0U
+ #endif
+ #else
+ #define __DSP_USED 0U
+ #endif
+
+#elif defined ( __ICCARM__ )
+ #if defined __ARMVFP__
+ #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)
+ #define __FPU_USED 1U
+ #else
+ #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)"
+ #define __FPU_USED 0U
+ #endif
+ #else
+ #define __FPU_USED 0U
+ #endif
+
+ #if defined(__ARM_FEATURE_DSP)
+ #if defined(__DSP_PRESENT) && (__DSP_PRESENT == 1U)
+ #define __DSP_USED 1U
+ #else
+ #error "Compiler generates DSP (SIMD) instructions for a devices without DSP extensions (check __DSP_PRESENT)"
+ #define __DSP_USED 0U
+ #endif
+ #else
+ #define __DSP_USED 0U
+ #endif
+
+#elif defined ( __TI_ARM__ )
+ #if defined __TI_VFP_SUPPORT__
+ #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)
+ #define __FPU_USED 1U
+ #else
+ #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)"
+ #define __FPU_USED 0U
+ #endif
+ #else
+ #define __FPU_USED 0U
+ #endif
+
+#elif defined ( __TASKING__ )
+ #if defined __FPU_VFP__
+ #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)
+ #define __FPU_USED 1U
+ #else
+ #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)"
+ #define __FPU_USED 0U
+ #endif
+ #else
+ #define __FPU_USED 0U
+ #endif
+
+#elif defined ( __CSMC__ )
+ #if ( __CSMC__ & 0x400U)
+ #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)
+ #define __FPU_USED 1U
+ #else
+ #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)"
+ #define __FPU_USED 0U
+ #endif
+ #else
+ #define __FPU_USED 0U
+ #endif
+
+#endif
+
+#include "cmsis_compiler.h" /* CMSIS compiler specific defines */
+
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __CORE_ARMV8MML_H_GENERIC */
+
+#ifndef __CMSIS_GENERIC
+
+#ifndef __CORE_ARMV8MML_H_DEPENDANT
+#define __CORE_ARMV8MML_H_DEPENDANT
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* check device defines and use defaults */
+#if defined __CHECK_DEVICE_DEFINES
+ #ifndef __ARMv8MML_REV
+ #define __ARMv8MML_REV 0x0000U
+ #warning "__ARMv8MML_REV not defined in device header file; using default!"
+ #endif
+
+ #ifndef __FPU_PRESENT
+ #define __FPU_PRESENT 0U
+ #warning "__FPU_PRESENT not defined in device header file; using default!"
+ #endif
+
+ #ifndef __MPU_PRESENT
+ #define __MPU_PRESENT 0U
+ #warning "__MPU_PRESENT not defined in device header file; using default!"
+ #endif
+
+ #ifndef __SAUREGION_PRESENT
+ #define __SAUREGION_PRESENT 0U
+ #warning "__SAUREGION_PRESENT not defined in device header file; using default!"
+ #endif
+
+ #ifndef __DSP_PRESENT
+ #define __DSP_PRESENT 0U
+ #warning "__DSP_PRESENT not defined in device header file; using default!"
+ #endif
+
+ #ifndef __NVIC_PRIO_BITS
+ #define __NVIC_PRIO_BITS 3U
+ #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
+
+ <strong>IO Type Qualifiers</strong> 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 ARMv8MML */
+
+
+
+/*******************************************************************************
+ * Register Abstraction
+ Core Register contain:
+ - Core Register
+ - Core NVIC Register
+ - Core SCB Register
+ - Core SysTick Register
+ - Core Debug Register
+ - Core MPU Register
+ - Core SAU Register
+ - Core FPU 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:16; /*!< bit: 0..15 Reserved */
+ uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */
+ uint32_t _reserved1:7; /*!< bit: 20..26 Reserved */
+ uint32_t Q:1; /*!< bit: 27 Saturation condition flag */
+ 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 */
+
+#define APSR_Q_Pos 27U /*!< APSR: Q Position */
+#define APSR_Q_Msk (1UL << APSR_Q_Pos) /*!< APSR: Q Mask */
+
+#define APSR_GE_Pos 16U /*!< APSR: GE Position */
+#define APSR_GE_Msk (0xFUL << APSR_GE_Pos) /*!< APSR: GE 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:7; /*!< bit: 9..15 Reserved */
+ uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */
+ uint32_t _reserved1:4; /*!< bit: 20..23 Reserved */
+ uint32_t T:1; /*!< bit: 24 Thumb bit (read 0) */
+ uint32_t IT:2; /*!< bit: 25..26 saved IT state (read 0) */
+ uint32_t Q:1; /*!< bit: 27 Saturation condition flag */
+ 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_Q_Pos 27U /*!< xPSR: Q Position */
+#define xPSR_Q_Msk (1UL << xPSR_Q_Pos) /*!< xPSR: Q Mask */
+
+#define xPSR_IT_Pos 25U /*!< xPSR: IT Position */
+#define xPSR_IT_Msk (3UL << xPSR_IT_Pos) /*!< xPSR: IT Mask */
+
+#define xPSR_T_Pos 24U /*!< xPSR: T Position */
+#define xPSR_T_Msk (1UL << xPSR_T_Pos) /*!< xPSR: T Mask */
+
+#define xPSR_GE_Pos 16U /*!< xPSR: GE Position */
+#define xPSR_GE_Msk (0xFUL << xPSR_GE_Pos) /*!< xPSR: GE 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 nPRIV:1; /*!< bit: 0 Execution privilege in Thread mode */
+ uint32_t SPSEL:1; /*!< bit: 1 Stack-pointer select */
+ uint32_t FPCA:1; /*!< bit: 2 Floating-point context active */
+ uint32_t SFPA:1; /*!< bit: 3 Secure floating-point active */
+ uint32_t _reserved1:28; /*!< bit: 4..31 Reserved */
+ } b; /*!< Structure used for bit access */
+ uint32_t w; /*!< Type used for word access */
+} CONTROL_Type;
+
+/* CONTROL Register Definitions */
+#define CONTROL_SFPA_Pos 3U /*!< CONTROL: SFPA Position */
+#define CONTROL_SFPA_Msk (1UL << CONTROL_SFPA_Pos) /*!< CONTROL: SFPA Mask */
+
+#define CONTROL_FPCA_Pos 2U /*!< CONTROL: FPCA Position */
+#define CONTROL_FPCA_Msk (1UL << CONTROL_FPCA_Pos) /*!< CONTROL: FPCA Mask */
+
+#define CONTROL_SPSEL_Pos 1U /*!< CONTROL: SPSEL Position */
+#define CONTROL_SPSEL_Msk (1UL << CONTROL_SPSEL_Pos) /*!< CONTROL: SPSEL Mask */
+
+#define CONTROL_nPRIV_Pos 0U /*!< CONTROL: nPRIV Position */
+#define CONTROL_nPRIV_Msk (1UL /*<< CONTROL_nPRIV_Pos*/) /*!< CONTROL: nPRIV 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[16U]; /*!< Offset: 0x000 (R/W) Interrupt Set Enable Register */
+ uint32_t RESERVED0[16U];
+ __IOM uint32_t ICER[16U]; /*!< Offset: 0x080 (R/W) Interrupt Clear Enable Register */
+ uint32_t RSERVED1[16U];
+ __IOM uint32_t ISPR[16U]; /*!< Offset: 0x100 (R/W) Interrupt Set Pending Register */
+ uint32_t RESERVED2[16U];
+ __IOM uint32_t ICPR[16U]; /*!< Offset: 0x180 (R/W) Interrupt Clear Pending Register */
+ uint32_t RESERVED3[16U];
+ __IOM uint32_t IABR[16U]; /*!< Offset: 0x200 (R/W) Interrupt Active bit Register */
+ uint32_t RESERVED4[16U];
+ __IOM uint32_t ITNS[16U]; /*!< Offset: 0x280 (R/W) Interrupt Non-Secure State Register */
+ uint32_t RESERVED5[16U];
+ __IOM uint8_t IPR[496U]; /*!< Offset: 0x300 (R/W) Interrupt Priority Register (8Bit wide) */
+ uint32_t RESERVED6[580U];
+ __OM uint32_t STIR; /*!< Offset: 0xE00 ( /W) Software Trigger Interrupt Register */
+} NVIC_Type;
+
+/* Software Triggered Interrupt Register Definitions */
+#define NVIC_STIR_INTID_Pos 0U /*!< STIR: INTLINESNUM Position */
+#define NVIC_STIR_INTID_Msk (0x1FFUL /*<< NVIC_STIR_INTID_Pos*/) /*!< STIR: INTLINESNUM Mask */
+
+/*@} 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 */
+ __IOM uint32_t VTOR; /*!< Offset: 0x008 (R/W) Vector Table Offset Register */
+ __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 */
+ __IOM uint8_t SHPR[12U]; /*!< Offset: 0x018 (R/W) System Handlers Priority Registers (4-7, 8-11, 12-15) */
+ __IOM uint32_t SHCSR; /*!< Offset: 0x024 (R/W) System Handler Control and State Register */
+ __IOM uint32_t CFSR; /*!< Offset: 0x028 (R/W) Configurable Fault Status Register */
+ __IOM uint32_t HFSR; /*!< Offset: 0x02C (R/W) HardFault Status Register */
+ __IOM uint32_t DFSR; /*!< Offset: 0x030 (R/W) Debug Fault Status Register */
+ __IOM uint32_t MMFAR; /*!< Offset: 0x034 (R/W) MemManage Fault Address Register */
+ __IOM uint32_t BFAR; /*!< Offset: 0x038 (R/W) BusFault Address Register */
+ __IOM uint32_t AFSR; /*!< Offset: 0x03C (R/W) Auxiliary Fault Status Register */
+ __IM uint32_t ID_PFR[2U]; /*!< Offset: 0x040 (R/ ) Processor Feature Register */
+ __IM uint32_t ID_DFR; /*!< Offset: 0x048 (R/ ) Debug Feature Register */
+ __IM uint32_t ID_ADR; /*!< Offset: 0x04C (R/ ) Auxiliary Feature Register */
+ __IM uint32_t ID_MMFR[4U]; /*!< Offset: 0x050 (R/ ) Memory Model Feature Register */
+ __IM uint32_t ID_ISAR[6U]; /*!< Offset: 0x060 (R/ ) Instruction Set Attributes Register */
+ __IM uint32_t CLIDR; /*!< Offset: 0x078 (R/ ) Cache Level ID register */
+ __IM uint32_t CTR; /*!< Offset: 0x07C (R/ ) Cache Type register */
+ __IM uint32_t CCSIDR; /*!< Offset: 0x080 (R/ ) Cache Size ID Register */
+ __IOM uint32_t CSSELR; /*!< Offset: 0x084 (R/W) Cache Size Selection Register */
+ __IOM uint32_t CPACR; /*!< Offset: 0x088 (R/W) Coprocessor Access Control Register */
+ __IOM uint32_t NSACR; /*!< Offset: 0x08C (R/W) Non-Secure Access Control Register */
+ uint32_t RESERVED3[92U];
+ __OM uint32_t STIR; /*!< Offset: 0x200 ( /W) Software Triggered Interrupt Register */
+ uint32_t RESERVED4[15U];
+ __IM uint32_t MVFR0; /*!< Offset: 0x240 (R/ ) Media and VFP Feature Register 0 */
+ __IM uint32_t MVFR1; /*!< Offset: 0x244 (R/ ) Media and VFP Feature Register 1 */
+ __IM uint32_t MVFR2; /*!< Offset: 0x248 (R/ ) Media and VFP Feature Register 2 */
+ uint32_t RESERVED5[1U];
+ __OM uint32_t ICIALLU; /*!< Offset: 0x250 ( /W) I-Cache Invalidate All to PoU */
+ uint32_t RESERVED6[1U];
+ __OM uint32_t ICIMVAU; /*!< Offset: 0x258 ( /W) I-Cache Invalidate by MVA to PoU */
+ __OM uint32_t DCIMVAC; /*!< Offset: 0x25C ( /W) D-Cache Invalidate by MVA to PoC */
+ __OM uint32_t DCISW; /*!< Offset: 0x260 ( /W) D-Cache Invalidate by Set-way */
+ __OM uint32_t DCCMVAU; /*!< Offset: 0x264 ( /W) D-Cache Clean by MVA to PoU */
+ __OM uint32_t DCCMVAC; /*!< Offset: 0x268 ( /W) D-Cache Clean by MVA to PoC */
+ __OM uint32_t DCCSW; /*!< Offset: 0x26C ( /W) D-Cache Clean by Set-way */
+ __OM uint32_t DCCIMVAC; /*!< Offset: 0x270 ( /W) D-Cache Clean and Invalidate by MVA to PoC */
+ __OM uint32_t DCCISW; /*!< Offset: 0x274 ( /W) D-Cache Clean and Invalidate by Set-way */
+ uint32_t RESERVED7[6U];
+ __IOM uint32_t ITCMCR; /*!< Offset: 0x290 (R/W) Instruction Tightly-Coupled Memory Control Register */
+ __IOM uint32_t DTCMCR; /*!< Offset: 0x294 (R/W) Data Tightly-Coupled Memory Control Registers */
+ __IOM uint32_t AHBPCR; /*!< Offset: 0x298 (R/W) AHBP Control Register */
+ __IOM uint32_t CACR; /*!< Offset: 0x29C (R/W) L1 Cache Control Register */
+ __IOM uint32_t AHBSCR; /*!< Offset: 0x2A0 (R/W) AHB Slave Control Register */
+ uint32_t RESERVED8[1U];
+ __IOM uint32_t ABFSR; /*!< Offset: 0x2A8 (R/W) Auxiliary Bus Fault Status 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_PENDNMISET_Pos 31U /*!< SCB ICSR: PENDNMISET Position */
+#define SCB_ICSR_PENDNMISET_Msk (1UL << SCB_ICSR_PENDNMISET_Pos) /*!< SCB ICSR: PENDNMISET Mask */
+
+#define SCB_ICSR_PENDNMICLR_Pos 30U /*!< SCB ICSR: PENDNMICLR Position */
+#define SCB_ICSR_PENDNMICLR_Msk (1UL << SCB_ICSR_PENDNMICLR_Pos) /*!< SCB ICSR: PENDNMICLR 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_STTNS_Pos 24U /*!< SCB ICSR: STTNS Position (Security Extension) */
+#define SCB_ICSR_STTNS_Msk (1UL << SCB_ICSR_STTNS_Pos) /*!< SCB ICSR: STTNS Mask (Security Extension) */
+
+#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_RETTOBASE_Pos 11U /*!< SCB ICSR: RETTOBASE Position */
+#define SCB_ICSR_RETTOBASE_Msk (1UL << SCB_ICSR_RETTOBASE_Pos) /*!< SCB ICSR: RETTOBASE 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 Vector Table Offset Register Definitions */
+#define SCB_VTOR_TBLOFF_Pos 7U /*!< SCB VTOR: TBLOFF Position */
+#define SCB_VTOR_TBLOFF_Msk (0x1FFFFFFUL << SCB_VTOR_TBLOFF_Pos) /*!< SCB VTOR: TBLOFF 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_PRIS_Pos 14U /*!< SCB AIRCR: PRIS Position */
+#define SCB_AIRCR_PRIS_Msk (1UL << SCB_AIRCR_PRIS_Pos) /*!< SCB AIRCR: PRIS Mask */
+
+#define SCB_AIRCR_BFHFNMINS_Pos 13U /*!< SCB AIRCR: BFHFNMINS Position */
+#define SCB_AIRCR_BFHFNMINS_Msk (1UL << SCB_AIRCR_BFHFNMINS_Pos) /*!< SCB AIRCR: BFHFNMINS Mask */
+
+#define SCB_AIRCR_PRIGROUP_Pos 8U /*!< SCB AIRCR: PRIGROUP Position */
+#define SCB_AIRCR_PRIGROUP_Msk (7UL << SCB_AIRCR_PRIGROUP_Pos) /*!< SCB AIRCR: PRIGROUP Mask */
+
+#define SCB_AIRCR_SYSRESETREQS_Pos 3U /*!< SCB AIRCR: SYSRESETREQS Position */
+#define SCB_AIRCR_SYSRESETREQS_Msk (1UL << SCB_AIRCR_SYSRESETREQS_Pos) /*!< SCB AIRCR: SYSRESETREQS 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_SLEEPDEEPS_Pos 3U /*!< SCB SCR: SLEEPDEEPS Position */
+#define SCB_SCR_SLEEPDEEPS_Msk (1UL << SCB_SCR_SLEEPDEEPS_Pos) /*!< SCB SCR: SLEEPDEEPS 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_BP_Pos 18U /*!< SCB CCR: BP Position */
+#define SCB_CCR_BP_Msk (1UL << SCB_CCR_BP_Pos) /*!< SCB CCR: BP Mask */
+
+#define SCB_CCR_IC_Pos 17U /*!< SCB CCR: IC Position */
+#define SCB_CCR_IC_Msk (1UL << SCB_CCR_IC_Pos) /*!< SCB CCR: IC Mask */
+
+#define SCB_CCR_DC_Pos 16U /*!< SCB CCR: DC Position */
+#define SCB_CCR_DC_Msk (1UL << SCB_CCR_DC_Pos) /*!< SCB CCR: DC Mask */
+
+#define SCB_CCR_STKOFHFNMIGN_Pos 10U /*!< SCB CCR: STKOFHFNMIGN Position */
+#define SCB_CCR_STKOFHFNMIGN_Msk (1UL << SCB_CCR_STKOFHFNMIGN_Pos) /*!< SCB CCR: STKOFHFNMIGN Mask */
+
+#define SCB_CCR_BFHFNMIGN_Pos 8U /*!< SCB CCR: BFHFNMIGN Position */
+#define SCB_CCR_BFHFNMIGN_Msk (1UL << SCB_CCR_BFHFNMIGN_Pos) /*!< SCB CCR: BFHFNMIGN Mask */
+
+#define SCB_CCR_DIV_0_TRP_Pos 4U /*!< SCB CCR: DIV_0_TRP Position */
+#define SCB_CCR_DIV_0_TRP_Msk (1UL << SCB_CCR_DIV_0_TRP_Pos) /*!< SCB CCR: DIV_0_TRP 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 */
+
+#define SCB_CCR_USERSETMPEND_Pos 1U /*!< SCB CCR: USERSETMPEND Position */
+#define SCB_CCR_USERSETMPEND_Msk (1UL << SCB_CCR_USERSETMPEND_Pos) /*!< SCB CCR: USERSETMPEND Mask */
+
+/* SCB System Handler Control and State Register Definitions */
+#define SCB_SHCSR_HARDFAULTPENDED_Pos 21U /*!< SCB SHCSR: HARDFAULTPENDED Position */
+#define SCB_SHCSR_HARDFAULTPENDED_Msk (1UL << SCB_SHCSR_HARDFAULTPENDED_Pos) /*!< SCB SHCSR: HARDFAULTPENDED Mask */
+
+#define SCB_SHCSR_SECUREFAULTPENDED_Pos 20U /*!< SCB SHCSR: SECUREFAULTPENDED Position */
+#define SCB_SHCSR_SECUREFAULTPENDED_Msk (1UL << SCB_SHCSR_SECUREFAULTPENDED_Pos) /*!< SCB SHCSR: SECUREFAULTPENDED Mask */
+
+#define SCB_SHCSR_SECUREFAULTENA_Pos 19U /*!< SCB SHCSR: SECUREFAULTENA Position */
+#define SCB_SHCSR_SECUREFAULTENA_Msk (1UL << SCB_SHCSR_SECUREFAULTENA_Pos) /*!< SCB SHCSR: SECUREFAULTENA Mask */
+
+#define SCB_SHCSR_USGFAULTENA_Pos 18U /*!< SCB SHCSR: USGFAULTENA Position */
+#define SCB_SHCSR_USGFAULTENA_Msk (1UL << SCB_SHCSR_USGFAULTENA_Pos) /*!< SCB SHCSR: USGFAULTENA Mask */
+
+#define SCB_SHCSR_BUSFAULTENA_Pos 17U /*!< SCB SHCSR: BUSFAULTENA Position */
+#define SCB_SHCSR_BUSFAULTENA_Msk (1UL << SCB_SHCSR_BUSFAULTENA_Pos) /*!< SCB SHCSR: BUSFAULTENA Mask */
+
+#define SCB_SHCSR_MEMFAULTENA_Pos 16U /*!< SCB SHCSR: MEMFAULTENA Position */
+#define SCB_SHCSR_MEMFAULTENA_Msk (1UL << SCB_SHCSR_MEMFAULTENA_Pos) /*!< SCB SHCSR: MEMFAULTENA Mask */
+
+#define SCB_SHCSR_SVCALLPENDED_Pos 15U /*!< SCB SHCSR: SVCALLPENDED Position */
+#define SCB_SHCSR_SVCALLPENDED_Msk (1UL << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SHCSR: SVCALLPENDED Mask */
+
+#define SCB_SHCSR_BUSFAULTPENDED_Pos 14U /*!< SCB SHCSR: BUSFAULTPENDED Position */
+#define SCB_SHCSR_BUSFAULTPENDED_Msk (1UL << SCB_SHCSR_BUSFAULTPENDED_Pos) /*!< SCB SHCSR: BUSFAULTPENDED Mask */
+
+#define SCB_SHCSR_MEMFAULTPENDED_Pos 13U /*!< SCB SHCSR: MEMFAULTPENDED Position */
+#define SCB_SHCSR_MEMFAULTPENDED_Msk (1UL << SCB_SHCSR_MEMFAULTPENDED_Pos) /*!< SCB SHCSR: MEMFAULTPENDED Mask */
+
+#define SCB_SHCSR_USGFAULTPENDED_Pos 12U /*!< SCB SHCSR: USGFAULTPENDED Position */
+#define SCB_SHCSR_USGFAULTPENDED_Msk (1UL << SCB_SHCSR_USGFAULTPENDED_Pos) /*!< SCB SHCSR: USGFAULTPENDED Mask */
+
+#define SCB_SHCSR_SYSTICKACT_Pos 11U /*!< SCB SHCSR: SYSTICKACT Position */
+#define SCB_SHCSR_SYSTICKACT_Msk (1UL << SCB_SHCSR_SYSTICKACT_Pos) /*!< SCB SHCSR: SYSTICKACT Mask */
+
+#define SCB_SHCSR_PENDSVACT_Pos 10U /*!< SCB SHCSR: PENDSVACT Position */
+#define SCB_SHCSR_PENDSVACT_Msk (1UL << SCB_SHCSR_PENDSVACT_Pos) /*!< SCB SHCSR: PENDSVACT Mask */
+
+#define SCB_SHCSR_MONITORACT_Pos 8U /*!< SCB SHCSR: MONITORACT Position */
+#define SCB_SHCSR_MONITORACT_Msk (1UL << SCB_SHCSR_MONITORACT_Pos) /*!< SCB SHCSR: MONITORACT Mask */
+
+#define SCB_SHCSR_SVCALLACT_Pos 7U /*!< SCB SHCSR: SVCALLACT Position */
+#define SCB_SHCSR_SVCALLACT_Msk (1UL << SCB_SHCSR_SVCALLACT_Pos) /*!< SCB SHCSR: SVCALLACT Mask */
+
+#define SCB_SHCSR_NMIACT_Pos 5U /*!< SCB SHCSR: NMIACT Position */
+#define SCB_SHCSR_NMIACT_Msk (1UL << SCB_SHCSR_NMIACT_Pos) /*!< SCB SHCSR: NMIACT Mask */
+
+#define SCB_SHCSR_SECUREFAULTACT_Pos 4U /*!< SCB SHCSR: SECUREFAULTACT Position */
+#define SCB_SHCSR_SECUREFAULTACT_Msk (1UL << SCB_SHCSR_SECUREFAULTACT_Pos) /*!< SCB SHCSR: SECUREFAULTACT Mask */
+
+#define SCB_SHCSR_USGFAULTACT_Pos 3U /*!< SCB SHCSR: USGFAULTACT Position */
+#define SCB_SHCSR_USGFAULTACT_Msk (1UL << SCB_SHCSR_USGFAULTACT_Pos) /*!< SCB SHCSR: USGFAULTACT Mask */
+
+#define SCB_SHCSR_HARDFAULTACT_Pos 2U /*!< SCB SHCSR: HARDFAULTACT Position */
+#define SCB_SHCSR_HARDFAULTACT_Msk (1UL << SCB_SHCSR_HARDFAULTACT_Pos) /*!< SCB SHCSR: HARDFAULTACT Mask */
+
+#define SCB_SHCSR_BUSFAULTACT_Pos 1U /*!< SCB SHCSR: BUSFAULTACT Position */
+#define SCB_SHCSR_BUSFAULTACT_Msk (1UL << SCB_SHCSR_BUSFAULTACT_Pos) /*!< SCB SHCSR: BUSFAULTACT Mask */
+
+#define SCB_SHCSR_MEMFAULTACT_Pos 0U /*!< SCB SHCSR: MEMFAULTACT Position */
+#define SCB_SHCSR_MEMFAULTACT_Msk (1UL /*<< SCB_SHCSR_MEMFAULTACT_Pos*/) /*!< SCB SHCSR: MEMFAULTACT Mask */
+
+/* SCB Configurable Fault Status Register Definitions */
+#define SCB_CFSR_USGFAULTSR_Pos 16U /*!< SCB CFSR: Usage Fault Status Register Position */
+#define SCB_CFSR_USGFAULTSR_Msk (0xFFFFUL << SCB_CFSR_USGFAULTSR_Pos) /*!< SCB CFSR: Usage Fault Status Register Mask */
+
+#define SCB_CFSR_BUSFAULTSR_Pos 8U /*!< SCB CFSR: Bus Fault Status Register Position */
+#define SCB_CFSR_BUSFAULTSR_Msk (0xFFUL << SCB_CFSR_BUSFAULTSR_Pos) /*!< SCB CFSR: Bus Fault Status Register Mask */
+
+#define SCB_CFSR_MEMFAULTSR_Pos 0U /*!< SCB CFSR: Memory Manage Fault Status Register Position */
+#define SCB_CFSR_MEMFAULTSR_Msk (0xFFUL /*<< SCB_CFSR_MEMFAULTSR_Pos*/) /*!< SCB CFSR: Memory Manage Fault Status Register Mask */
+
+/* MemManage Fault Status Register (part of SCB Configurable Fault Status Register) */
+#define SCB_CFSR_MMARVALID_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 7U) /*!< SCB CFSR (MMFSR): MMARVALID Position */
+#define SCB_CFSR_MMARVALID_Msk (1UL << SCB_CFSR_MMARVALID_Pos) /*!< SCB CFSR (MMFSR): MMARVALID Mask */
+
+#define SCB_CFSR_MLSPERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 5U) /*!< SCB CFSR (MMFSR): MLSPERR Position */
+#define SCB_CFSR_MLSPERR_Msk (1UL << SCB_CFSR_MLSPERR_Pos) /*!< SCB CFSR (MMFSR): MLSPERR Mask */
+
+#define SCB_CFSR_MSTKERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 4U) /*!< SCB CFSR (MMFSR): MSTKERR Position */
+#define SCB_CFSR_MSTKERR_Msk (1UL << SCB_CFSR_MSTKERR_Pos) /*!< SCB CFSR (MMFSR): MSTKERR Mask */
+
+#define SCB_CFSR_MUNSTKERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 3U) /*!< SCB CFSR (MMFSR): MUNSTKERR Position */
+#define SCB_CFSR_MUNSTKERR_Msk (1UL << SCB_CFSR_MUNSTKERR_Pos) /*!< SCB CFSR (MMFSR): MUNSTKERR Mask */
+
+#define SCB_CFSR_DACCVIOL_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 1U) /*!< SCB CFSR (MMFSR): DACCVIOL Position */
+#define SCB_CFSR_DACCVIOL_Msk (1UL << SCB_CFSR_DACCVIOL_Pos) /*!< SCB CFSR (MMFSR): DACCVIOL Mask */
+
+#define SCB_CFSR_IACCVIOL_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 0U) /*!< SCB CFSR (MMFSR): IACCVIOL Position */
+#define SCB_CFSR_IACCVIOL_Msk (1UL /*<< SCB_CFSR_IACCVIOL_Pos*/) /*!< SCB CFSR (MMFSR): IACCVIOL Mask */
+
+/* BusFault Status Register (part of SCB Configurable Fault Status Register) */
+#define SCB_CFSR_BFARVALID_Pos (SCB_CFSR_BUSFAULTSR_Pos + 7U) /*!< SCB CFSR (BFSR): BFARVALID Position */
+#define SCB_CFSR_BFARVALID_Msk (1UL << SCB_CFSR_BFARVALID_Pos) /*!< SCB CFSR (BFSR): BFARVALID Mask */
+
+#define SCB_CFSR_LSPERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 5U) /*!< SCB CFSR (BFSR): LSPERR Position */
+#define SCB_CFSR_LSPERR_Msk (1UL << SCB_CFSR_LSPERR_Pos) /*!< SCB CFSR (BFSR): LSPERR Mask */
+
+#define SCB_CFSR_STKERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 4U) /*!< SCB CFSR (BFSR): STKERR Position */
+#define SCB_CFSR_STKERR_Msk (1UL << SCB_CFSR_STKERR_Pos) /*!< SCB CFSR (BFSR): STKERR Mask */
+
+#define SCB_CFSR_UNSTKERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 3U) /*!< SCB CFSR (BFSR): UNSTKERR Position */
+#define SCB_CFSR_UNSTKERR_Msk (1UL << SCB_CFSR_UNSTKERR_Pos) /*!< SCB CFSR (BFSR): UNSTKERR Mask */
+
+#define SCB_CFSR_IMPRECISERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 2U) /*!< SCB CFSR (BFSR): IMPRECISERR Position */
+#define SCB_CFSR_IMPRECISERR_Msk (1UL << SCB_CFSR_IMPRECISERR_Pos) /*!< SCB CFSR (BFSR): IMPRECISERR Mask */
+
+#define SCB_CFSR_PRECISERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 1U) /*!< SCB CFSR (BFSR): PRECISERR Position */
+#define SCB_CFSR_PRECISERR_Msk (1UL << SCB_CFSR_PRECISERR_Pos) /*!< SCB CFSR (BFSR): PRECISERR Mask */
+
+#define SCB_CFSR_IBUSERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 0U) /*!< SCB CFSR (BFSR): IBUSERR Position */
+#define SCB_CFSR_IBUSERR_Msk (1UL << SCB_CFSR_IBUSERR_Pos) /*!< SCB CFSR (BFSR): IBUSERR Mask */
+
+/* UsageFault Status Register (part of SCB Configurable Fault Status Register) */
+#define SCB_CFSR_DIVBYZERO_Pos (SCB_CFSR_USGFAULTSR_Pos + 9U) /*!< SCB CFSR (UFSR): DIVBYZERO Position */
+#define SCB_CFSR_DIVBYZERO_Msk (1UL << SCB_CFSR_DIVBYZERO_Pos) /*!< SCB CFSR (UFSR): DIVBYZERO Mask */
+
+#define SCB_CFSR_UNALIGNED_Pos (SCB_CFSR_USGFAULTSR_Pos + 8U) /*!< SCB CFSR (UFSR): UNALIGNED Position */
+#define SCB_CFSR_UNALIGNED_Msk (1UL << SCB_CFSR_UNALIGNED_Pos) /*!< SCB CFSR (UFSR): UNALIGNED Mask */
+
+#define SCB_CFSR_STKOF_Pos (SCB_CFSR_USGFAULTSR_Pos + 4U) /*!< SCB CFSR (UFSR): STKOF Position */
+#define SCB_CFSR_STKOF_Msk (1UL << SCB_CFSR_STKOF_Pos) /*!< SCB CFSR (UFSR): STKOF Mask */
+
+#define SCB_CFSR_NOCP_Pos (SCB_CFSR_USGFAULTSR_Pos + 3U) /*!< SCB CFSR (UFSR): NOCP Position */
+#define SCB_CFSR_NOCP_Msk (1UL << SCB_CFSR_NOCP_Pos) /*!< SCB CFSR (UFSR): NOCP Mask */
+
+#define SCB_CFSR_INVPC_Pos (SCB_CFSR_USGFAULTSR_Pos + 2U) /*!< SCB CFSR (UFSR): INVPC Position */
+#define SCB_CFSR_INVPC_Msk (1UL << SCB_CFSR_INVPC_Pos) /*!< SCB CFSR (UFSR): INVPC Mask */
+
+#define SCB_CFSR_INVSTATE_Pos (SCB_CFSR_USGFAULTSR_Pos + 1U) /*!< SCB CFSR (UFSR): INVSTATE Position */
+#define SCB_CFSR_INVSTATE_Msk (1UL << SCB_CFSR_INVSTATE_Pos) /*!< SCB CFSR (UFSR): INVSTATE Mask */
+
+#define SCB_CFSR_UNDEFINSTR_Pos (SCB_CFSR_USGFAULTSR_Pos + 0U) /*!< SCB CFSR (UFSR): UNDEFINSTR Position */
+#define SCB_CFSR_UNDEFINSTR_Msk (1UL << SCB_CFSR_UNDEFINSTR_Pos) /*!< SCB CFSR (UFSR): UNDEFINSTR Mask */
+
+/* SCB Hard Fault Status Register Definitions */
+#define SCB_HFSR_DEBUGEVT_Pos 31U /*!< SCB HFSR: DEBUGEVT Position */
+#define SCB_HFSR_DEBUGEVT_Msk (1UL << SCB_HFSR_DEBUGEVT_Pos) /*!< SCB HFSR: DEBUGEVT Mask */
+
+#define SCB_HFSR_FORCED_Pos 30U /*!< SCB HFSR: FORCED Position */
+#define SCB_HFSR_FORCED_Msk (1UL << SCB_HFSR_FORCED_Pos) /*!< SCB HFSR: FORCED Mask */
+
+#define SCB_HFSR_VECTTBL_Pos 1U /*!< SCB HFSR: VECTTBL Position */
+#define SCB_HFSR_VECTTBL_Msk (1UL << SCB_HFSR_VECTTBL_Pos) /*!< SCB HFSR: VECTTBL Mask */
+
+/* SCB Debug Fault Status Register Definitions */
+#define SCB_DFSR_EXTERNAL_Pos 4U /*!< SCB DFSR: EXTERNAL Position */
+#define SCB_DFSR_EXTERNAL_Msk (1UL << SCB_DFSR_EXTERNAL_Pos) /*!< SCB DFSR: EXTERNAL Mask */
+
+#define SCB_DFSR_VCATCH_Pos 3U /*!< SCB DFSR: VCATCH Position */
+#define SCB_DFSR_VCATCH_Msk (1UL << SCB_DFSR_VCATCH_Pos) /*!< SCB DFSR: VCATCH Mask */
+
+#define SCB_DFSR_DWTTRAP_Pos 2U /*!< SCB DFSR: DWTTRAP Position */
+#define SCB_DFSR_DWTTRAP_Msk (1UL << SCB_DFSR_DWTTRAP_Pos) /*!< SCB DFSR: DWTTRAP Mask */
+
+#define SCB_DFSR_BKPT_Pos 1U /*!< SCB DFSR: BKPT Position */
+#define SCB_DFSR_BKPT_Msk (1UL << SCB_DFSR_BKPT_Pos) /*!< SCB DFSR: BKPT Mask */
+
+#define SCB_DFSR_HALTED_Pos 0U /*!< SCB DFSR: HALTED Position */
+#define SCB_DFSR_HALTED_Msk (1UL /*<< SCB_DFSR_HALTED_Pos*/) /*!< SCB DFSR: HALTED Mask */
+
+/* SCB Non-Secure Access Control Register Definitions */
+#define SCB_NSACR_CP11_Pos 11U /*!< SCB NSACR: CP11 Position */
+#define SCB_NSACR_CP11_Msk (1UL << SCB_NSACR_CP11_Pos) /*!< SCB NSACR: CP11 Mask */
+
+#define SCB_NSACR_CP10_Pos 10U /*!< SCB NSACR: CP10 Position */
+#define SCB_NSACR_CP10_Msk (1UL << SCB_NSACR_CP10_Pos) /*!< SCB NSACR: CP10 Mask */
+
+#define SCB_NSACR_CPn_Pos 0U /*!< SCB NSACR: CPn Position */
+#define SCB_NSACR_CPn_Msk (1UL /*<< SCB_NSACR_CPn_Pos*/) /*!< SCB NSACR: CPn Mask */
+
+/* SCB Cache Level ID Register Definitions */
+#define SCB_CLIDR_LOUU_Pos 27U /*!< SCB CLIDR: LoUU Position */
+#define SCB_CLIDR_LOUU_Msk (7UL << SCB_CLIDR_LOUU_Pos) /*!< SCB CLIDR: LoUU Mask */
+
+#define SCB_CLIDR_LOC_Pos 24U /*!< SCB CLIDR: LoC Position */
+#define SCB_CLIDR_LOC_Msk (7UL << SCB_CLIDR_LOC_Pos) /*!< SCB CLIDR: LoC Mask */
+
+/* SCB Cache Type Register Definitions */
+#define SCB_CTR_FORMAT_Pos 29U /*!< SCB CTR: Format Position */
+#define SCB_CTR_FORMAT_Msk (7UL << SCB_CTR_FORMAT_Pos) /*!< SCB CTR: Format Mask */
+
+#define SCB_CTR_CWG_Pos 24U /*!< SCB CTR: CWG Position */
+#define SCB_CTR_CWG_Msk (0xFUL << SCB_CTR_CWG_Pos) /*!< SCB CTR: CWG Mask */
+
+#define SCB_CTR_ERG_Pos 20U /*!< SCB CTR: ERG Position */
+#define SCB_CTR_ERG_Msk (0xFUL << SCB_CTR_ERG_Pos) /*!< SCB CTR: ERG Mask */
+
+#define SCB_CTR_DMINLINE_Pos 16U /*!< SCB CTR: DminLine Position */
+#define SCB_CTR_DMINLINE_Msk (0xFUL << SCB_CTR_DMINLINE_Pos) /*!< SCB CTR: DminLine Mask */
+
+#define SCB_CTR_IMINLINE_Pos 0U /*!< SCB CTR: ImInLine Position */
+#define SCB_CTR_IMINLINE_Msk (0xFUL /*<< SCB_CTR_IMINLINE_Pos*/) /*!< SCB CTR: ImInLine Mask */
+
+/* SCB Cache Size ID Register Definitions */
+#define SCB_CCSIDR_WT_Pos 31U /*!< SCB CCSIDR: WT Position */
+#define SCB_CCSIDR_WT_Msk (1UL << SCB_CCSIDR_WT_Pos) /*!< SCB CCSIDR: WT Mask */
+
+#define SCB_CCSIDR_WB_Pos 30U /*!< SCB CCSIDR: WB Position */
+#define SCB_CCSIDR_WB_Msk (1UL << SCB_CCSIDR_WB_Pos) /*!< SCB CCSIDR: WB Mask */
+
+#define SCB_CCSIDR_RA_Pos 29U /*!< SCB CCSIDR: RA Position */
+#define SCB_CCSIDR_RA_Msk (1UL << SCB_CCSIDR_RA_Pos) /*!< SCB CCSIDR: RA Mask */
+
+#define SCB_CCSIDR_WA_Pos 28U /*!< SCB CCSIDR: WA Position */
+#define SCB_CCSIDR_WA_Msk (1UL << SCB_CCSIDR_WA_Pos) /*!< SCB CCSIDR: WA Mask */
+
+#define SCB_CCSIDR_NUMSETS_Pos 13U /*!< SCB CCSIDR: NumSets Position */
+#define SCB_CCSIDR_NUMSETS_Msk (0x7FFFUL << SCB_CCSIDR_NUMSETS_Pos) /*!< SCB CCSIDR: NumSets Mask */
+
+#define SCB_CCSIDR_ASSOCIATIVITY_Pos 3U /*!< SCB CCSIDR: Associativity Position */
+#define SCB_CCSIDR_ASSOCIATIVITY_Msk (0x3FFUL << SCB_CCSIDR_ASSOCIATIVITY_Pos) /*!< SCB CCSIDR: Associativity Mask */
+
+#define SCB_CCSIDR_LINESIZE_Pos 0U /*!< SCB CCSIDR: LineSize Position */
+#define SCB_CCSIDR_LINESIZE_Msk (7UL /*<< SCB_CCSIDR_LINESIZE_Pos*/) /*!< SCB CCSIDR: LineSize Mask */
+
+/* SCB Cache Size Selection Register Definitions */
+#define SCB_CSSELR_LEVEL_Pos 1U /*!< SCB CSSELR: Level Position */
+#define SCB_CSSELR_LEVEL_Msk (7UL << SCB_CSSELR_LEVEL_Pos) /*!< SCB CSSELR: Level Mask */
+
+#define SCB_CSSELR_IND_Pos 0U /*!< SCB CSSELR: InD Position */
+#define SCB_CSSELR_IND_Msk (1UL /*<< SCB_CSSELR_IND_Pos*/) /*!< SCB CSSELR: InD Mask */
+
+/* SCB Software Triggered Interrupt Register Definitions */
+#define SCB_STIR_INTID_Pos 0U /*!< SCB STIR: INTID Position */
+#define SCB_STIR_INTID_Msk (0x1FFUL /*<< SCB_STIR_INTID_Pos*/) /*!< SCB STIR: INTID Mask */
+
+/* SCB D-Cache Invalidate by Set-way Register Definitions */
+#define SCB_DCISW_WAY_Pos 30U /*!< SCB DCISW: Way Position */
+#define SCB_DCISW_WAY_Msk (3UL << SCB_DCISW_WAY_Pos) /*!< SCB DCISW: Way Mask */
+
+#define SCB_DCISW_SET_Pos 5U /*!< SCB DCISW: Set Position */
+#define SCB_DCISW_SET_Msk (0x1FFUL << SCB_DCISW_SET_Pos) /*!< SCB DCISW: Set Mask */
+
+/* SCB D-Cache Clean by Set-way Register Definitions */
+#define SCB_DCCSW_WAY_Pos 30U /*!< SCB DCCSW: Way Position */
+#define SCB_DCCSW_WAY_Msk (3UL << SCB_DCCSW_WAY_Pos) /*!< SCB DCCSW: Way Mask */
+
+#define SCB_DCCSW_SET_Pos 5U /*!< SCB DCCSW: Set Position */
+#define SCB_DCCSW_SET_Msk (0x1FFUL << SCB_DCCSW_SET_Pos) /*!< SCB DCCSW: Set Mask */
+
+/* SCB D-Cache Clean and Invalidate by Set-way Register Definitions */
+#define SCB_DCCISW_WAY_Pos 30U /*!< SCB DCCISW: Way Position */
+#define SCB_DCCISW_WAY_Msk (3UL << SCB_DCCISW_WAY_Pos) /*!< SCB DCCISW: Way Mask */
+
+#define SCB_DCCISW_SET_Pos 5U /*!< SCB DCCISW: Set Position */
+#define SCB_DCCISW_SET_Msk (0x1FFUL << SCB_DCCISW_SET_Pos) /*!< SCB DCCISW: Set Mask */
+
+/* Instruction Tightly-Coupled Memory Control Register Definitions */
+#define SCB_ITCMCR_SZ_Pos 3U /*!< SCB ITCMCR: SZ Position */
+#define SCB_ITCMCR_SZ_Msk (0xFUL << SCB_ITCMCR_SZ_Pos) /*!< SCB ITCMCR: SZ Mask */
+
+#define SCB_ITCMCR_RETEN_Pos 2U /*!< SCB ITCMCR: RETEN Position */
+#define SCB_ITCMCR_RETEN_Msk (1UL << SCB_ITCMCR_RETEN_Pos) /*!< SCB ITCMCR: RETEN Mask */
+
+#define SCB_ITCMCR_RMW_Pos 1U /*!< SCB ITCMCR: RMW Position */
+#define SCB_ITCMCR_RMW_Msk (1UL << SCB_ITCMCR_RMW_Pos) /*!< SCB ITCMCR: RMW Mask */
+
+#define SCB_ITCMCR_EN_Pos 0U /*!< SCB ITCMCR: EN Position */
+#define SCB_ITCMCR_EN_Msk (1UL /*<< SCB_ITCMCR_EN_Pos*/) /*!< SCB ITCMCR: EN Mask */
+
+/* Data Tightly-Coupled Memory Control Register Definitions */
+#define SCB_DTCMCR_SZ_Pos 3U /*!< SCB DTCMCR: SZ Position */
+#define SCB_DTCMCR_SZ_Msk (0xFUL << SCB_DTCMCR_SZ_Pos) /*!< SCB DTCMCR: SZ Mask */
+
+#define SCB_DTCMCR_RETEN_Pos 2U /*!< SCB DTCMCR: RETEN Position */
+#define SCB_DTCMCR_RETEN_Msk (1UL << SCB_DTCMCR_RETEN_Pos) /*!< SCB DTCMCR: RETEN Mask */
+
+#define SCB_DTCMCR_RMW_Pos 1U /*!< SCB DTCMCR: RMW Position */
+#define SCB_DTCMCR_RMW_Msk (1UL << SCB_DTCMCR_RMW_Pos) /*!< SCB DTCMCR: RMW Mask */
+
+#define SCB_DTCMCR_EN_Pos 0U /*!< SCB DTCMCR: EN Position */
+#define SCB_DTCMCR_EN_Msk (1UL /*<< SCB_DTCMCR_EN_Pos*/) /*!< SCB DTCMCR: EN Mask */
+
+/* AHBP Control Register Definitions */
+#define SCB_AHBPCR_SZ_Pos 1U /*!< SCB AHBPCR: SZ Position */
+#define SCB_AHBPCR_SZ_Msk (7UL << SCB_AHBPCR_SZ_Pos) /*!< SCB AHBPCR: SZ Mask */
+
+#define SCB_AHBPCR_EN_Pos 0U /*!< SCB AHBPCR: EN Position */
+#define SCB_AHBPCR_EN_Msk (1UL /*<< SCB_AHBPCR_EN_Pos*/) /*!< SCB AHBPCR: EN Mask */
+
+/* L1 Cache Control Register Definitions */
+#define SCB_CACR_FORCEWT_Pos 2U /*!< SCB CACR: FORCEWT Position */
+#define SCB_CACR_FORCEWT_Msk (1UL << SCB_CACR_FORCEWT_Pos) /*!< SCB CACR: FORCEWT Mask */
+
+#define SCB_CACR_ECCEN_Pos 1U /*!< SCB CACR: ECCEN Position */
+#define SCB_CACR_ECCEN_Msk (1UL << SCB_CACR_ECCEN_Pos) /*!< SCB CACR: ECCEN Mask */
+
+#define SCB_CACR_SIWT_Pos 0U /*!< SCB CACR: SIWT Position */
+#define SCB_CACR_SIWT_Msk (1UL /*<< SCB_CACR_SIWT_Pos*/) /*!< SCB CACR: SIWT Mask */
+
+/* AHBS Control Register Definitions */
+#define SCB_AHBSCR_INITCOUNT_Pos 11U /*!< SCB AHBSCR: INITCOUNT Position */
+#define SCB_AHBSCR_INITCOUNT_Msk (0x1FUL << SCB_AHBPCR_INITCOUNT_Pos) /*!< SCB AHBSCR: INITCOUNT Mask */
+
+#define SCB_AHBSCR_TPRI_Pos 2U /*!< SCB AHBSCR: TPRI Position */
+#define SCB_AHBSCR_TPRI_Msk (0x1FFUL << SCB_AHBPCR_TPRI_Pos) /*!< SCB AHBSCR: TPRI Mask */
+
+#define SCB_AHBSCR_CTL_Pos 0U /*!< SCB AHBSCR: CTL Position*/
+#define SCB_AHBSCR_CTL_Msk (3UL /*<< SCB_AHBPCR_CTL_Pos*/) /*!< SCB AHBSCR: CTL Mask */
+
+/* Auxiliary Bus Fault Status Register Definitions */
+#define SCB_ABFSR_AXIMTYPE_Pos 8U /*!< SCB ABFSR: AXIMTYPE Position*/
+#define SCB_ABFSR_AXIMTYPE_Msk (3UL << SCB_ABFSR_AXIMTYPE_Pos) /*!< SCB ABFSR: AXIMTYPE Mask */
+
+#define SCB_ABFSR_EPPB_Pos 4U /*!< SCB ABFSR: EPPB Position*/
+#define SCB_ABFSR_EPPB_Msk (1UL << SCB_ABFSR_EPPB_Pos) /*!< SCB ABFSR: EPPB Mask */
+
+#define SCB_ABFSR_AXIM_Pos 3U /*!< SCB ABFSR: AXIM Position*/
+#define SCB_ABFSR_AXIM_Msk (1UL << SCB_ABFSR_AXIM_Pos) /*!< SCB ABFSR: AXIM Mask */
+
+#define SCB_ABFSR_AHBP_Pos 2U /*!< SCB ABFSR: AHBP Position*/
+#define SCB_ABFSR_AHBP_Msk (1UL << SCB_ABFSR_AHBP_Pos) /*!< SCB ABFSR: AHBP Mask */
+
+#define SCB_ABFSR_DTCM_Pos 1U /*!< SCB ABFSR: DTCM Position*/
+#define SCB_ABFSR_DTCM_Msk (1UL << SCB_ABFSR_DTCM_Pos) /*!< SCB ABFSR: DTCM Mask */
+
+#define SCB_ABFSR_ITCM_Pos 0U /*!< SCB ABFSR: ITCM Position*/
+#define SCB_ABFSR_ITCM_Msk (1UL /*<< SCB_ABFSR_ITCM_Pos*/) /*!< SCB ABFSR: ITCM Mask */
+
+/*@} end of group CMSIS_SCB */
+
+
+/**
+ \ingroup CMSIS_core_register
+ \defgroup CMSIS_SCnSCB System Controls not in SCB (SCnSCB)
+ \brief Type definitions for the System Control and ID Register not in the SCB
+ @{
+ */
+
+/**
+ \brief Structure type to access the System Control and ID Register not in the SCB.
+ */
+typedef struct
+{
+ uint32_t RESERVED0[1U];
+ __IM uint32_t ICTR; /*!< Offset: 0x004 (R/ ) Interrupt Controller Type Register */
+ __IOM uint32_t ACTLR; /*!< Offset: 0x008 (R/W) Auxiliary Control Register */
+ __IOM uint32_t CPPWR; /*!< Offset: 0x00C (R/W) Coprocessor Power Control Register */
+} SCnSCB_Type;
+
+/* Interrupt Controller Type Register Definitions */
+#define SCnSCB_ICTR_INTLINESNUM_Pos 0U /*!< ICTR: INTLINESNUM Position */
+#define SCnSCB_ICTR_INTLINESNUM_Msk (0xFUL /*<< SCnSCB_ICTR_INTLINESNUM_Pos*/) /*!< ICTR: INTLINESNUM Mask */
+
+/*@} end of group CMSIS_SCnotSCB */
+
+
+/**
+ \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_ITM Instrumentation Trace Macrocell (ITM)
+ \brief Type definitions for the Instrumentation Trace Macrocell (ITM)
+ @{
+ */
+
+/**
+ \brief Structure type to access the Instrumentation Trace Macrocell Register (ITM).
+ */
+typedef struct
+{
+ __OM union
+ {
+ __OM uint8_t u8; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 8-bit */
+ __OM uint16_t u16; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 16-bit */
+ __OM uint32_t u32; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 32-bit */
+ } PORT [32U]; /*!< Offset: 0x000 ( /W) ITM Stimulus Port Registers */
+ uint32_t RESERVED0[864U];
+ __IOM uint32_t TER; /*!< Offset: 0xE00 (R/W) ITM Trace Enable Register */
+ uint32_t RESERVED1[15U];
+ __IOM uint32_t TPR; /*!< Offset: 0xE40 (R/W) ITM Trace Privilege Register */
+ uint32_t RESERVED2[15U];
+ __IOM uint32_t TCR; /*!< Offset: 0xE80 (R/W) ITM Trace Control Register */
+ uint32_t RESERVED3[29U];
+ __OM uint32_t IWR; /*!< Offset: 0xEF8 ( /W) ITM Integration Write Register */
+ __IM uint32_t IRR; /*!< Offset: 0xEFC (R/ ) ITM Integration Read Register */
+ __IOM uint32_t IMCR; /*!< Offset: 0xF00 (R/W) ITM Integration Mode Control Register */
+ uint32_t RESERVED4[43U];
+ __OM uint32_t LAR; /*!< Offset: 0xFB0 ( /W) ITM Lock Access Register */
+ __IM uint32_t LSR; /*!< Offset: 0xFB4 (R/ ) ITM Lock Status Register */
+ uint32_t RESERVED5[1U];
+ __IM uint32_t DEVARCH; /*!< Offset: 0xFBC (R/ ) ITM Device Architecture Register */
+ uint32_t RESERVED6[4U];
+ __IM uint32_t PID4; /*!< Offset: 0xFD0 (R/ ) ITM Peripheral Identification Register #4 */
+ __IM uint32_t PID5; /*!< Offset: 0xFD4 (R/ ) ITM Peripheral Identification Register #5 */
+ __IM uint32_t PID6; /*!< Offset: 0xFD8 (R/ ) ITM Peripheral Identification Register #6 */
+ __IM uint32_t PID7; /*!< Offset: 0xFDC (R/ ) ITM Peripheral Identification Register #7 */
+ __IM uint32_t PID0; /*!< Offset: 0xFE0 (R/ ) ITM Peripheral Identification Register #0 */
+ __IM uint32_t PID1; /*!< Offset: 0xFE4 (R/ ) ITM Peripheral Identification Register #1 */
+ __IM uint32_t PID2; /*!< Offset: 0xFE8 (R/ ) ITM Peripheral Identification Register #2 */
+ __IM uint32_t PID3; /*!< Offset: 0xFEC (R/ ) ITM Peripheral Identification Register #3 */
+ __IM uint32_t CID0; /*!< Offset: 0xFF0 (R/ ) ITM Component Identification Register #0 */
+ __IM uint32_t CID1; /*!< Offset: 0xFF4 (R/ ) ITM Component Identification Register #1 */
+ __IM uint32_t CID2; /*!< Offset: 0xFF8 (R/ ) ITM Component Identification Register #2 */
+ __IM uint32_t CID3; /*!< Offset: 0xFFC (R/ ) ITM Component Identification Register #3 */
+} ITM_Type;
+
+/* ITM Stimulus Port Register Definitions */
+#define ITM_STIM_DISABLED_Pos 1U /*!< ITM STIM: DISABLED Position */
+#define ITM_STIM_DISABLED_Msk (0x1UL << ITM_STIM_DISABLED_Pos) /*!< ITM STIM: DISABLED Mask */
+
+#define ITM_STIM_FIFOREADY_Pos 0U /*!< ITM STIM: FIFOREADY Position */
+#define ITM_STIM_FIFOREADY_Msk (0x1UL /*<< ITM_STIM_FIFOREADY_Pos*/) /*!< ITM STIM: FIFOREADY Mask */
+
+/* ITM Trace Privilege Register Definitions */
+#define ITM_TPR_PRIVMASK_Pos 0U /*!< ITM TPR: PRIVMASK Position */
+#define ITM_TPR_PRIVMASK_Msk (0xFUL /*<< ITM_TPR_PRIVMASK_Pos*/) /*!< ITM TPR: PRIVMASK Mask */
+
+/* ITM Trace Control Register Definitions */
+#define ITM_TCR_BUSY_Pos 23U /*!< ITM TCR: BUSY Position */
+#define ITM_TCR_BUSY_Msk (1UL << ITM_TCR_BUSY_Pos) /*!< ITM TCR: BUSY Mask */
+
+#define ITM_TCR_TRACEBUSID_Pos 16U /*!< ITM TCR: ATBID Position */
+#define ITM_TCR_TRACEBUSID_Msk (0x7FUL << ITM_TCR_TRACEBUSID_Pos) /*!< ITM TCR: ATBID Mask */
+
+#define ITM_TCR_GTSFREQ_Pos 10U /*!< ITM TCR: Global timestamp frequency Position */
+#define ITM_TCR_GTSFREQ_Msk (3UL << ITM_TCR_GTSFREQ_Pos) /*!< ITM TCR: Global timestamp frequency Mask */
+
+#define ITM_TCR_TSPRESCALE_Pos 8U /*!< ITM TCR: TSPRESCALE Position */
+#define ITM_TCR_TSPRESCALE_Msk (3UL << ITM_TCR_TSPRESCALE_Pos) /*!< ITM TCR: TSPRESCALE Mask */
+
+#define ITM_TCR_STALLENA_Pos 5U /*!< ITM TCR: STALLENA Position */
+#define ITM_TCR_STALLENA_Msk (1UL << ITM_TCR_STALLENA_Pos) /*!< ITM TCR: STALLENA Mask */
+
+#define ITM_TCR_SWOENA_Pos 4U /*!< ITM TCR: SWOENA Position */
+#define ITM_TCR_SWOENA_Msk (1UL << ITM_TCR_SWOENA_Pos) /*!< ITM TCR: SWOENA Mask */
+
+#define ITM_TCR_DWTENA_Pos 3U /*!< ITM TCR: DWTENA Position */
+#define ITM_TCR_DWTENA_Msk (1UL << ITM_TCR_DWTENA_Pos) /*!< ITM TCR: DWTENA Mask */
+
+#define ITM_TCR_SYNCENA_Pos 2U /*!< ITM TCR: SYNCENA Position */
+#define ITM_TCR_SYNCENA_Msk (1UL << ITM_TCR_SYNCENA_Pos) /*!< ITM TCR: SYNCENA Mask */
+
+#define ITM_TCR_TSENA_Pos 1U /*!< ITM TCR: TSENA Position */
+#define ITM_TCR_TSENA_Msk (1UL << ITM_TCR_TSENA_Pos) /*!< ITM TCR: TSENA Mask */
+
+#define ITM_TCR_ITMENA_Pos 0U /*!< ITM TCR: ITM Enable bit Position */
+#define ITM_TCR_ITMENA_Msk (1UL /*<< ITM_TCR_ITMENA_Pos*/) /*!< ITM TCR: ITM Enable bit Mask */
+
+/* ITM Integration Write Register Definitions */
+#define ITM_IWR_ATVALIDM_Pos 0U /*!< ITM IWR: ATVALIDM Position */
+#define ITM_IWR_ATVALIDM_Msk (1UL /*<< ITM_IWR_ATVALIDM_Pos*/) /*!< ITM IWR: ATVALIDM Mask */
+
+/* ITM Integration Read Register Definitions */
+#define ITM_IRR_ATREADYM_Pos 0U /*!< ITM IRR: ATREADYM Position */
+#define ITM_IRR_ATREADYM_Msk (1UL /*<< ITM_IRR_ATREADYM_Pos*/) /*!< ITM IRR: ATREADYM Mask */
+
+/* ITM Integration Mode Control Register Definitions */
+#define ITM_IMCR_INTEGRATION_Pos 0U /*!< ITM IMCR: INTEGRATION Position */
+#define ITM_IMCR_INTEGRATION_Msk (1UL /*<< ITM_IMCR_INTEGRATION_Pos*/) /*!< ITM IMCR: INTEGRATION Mask */
+
+/* ITM Lock Status Register Definitions */
+#define ITM_LSR_ByteAcc_Pos 2U /*!< ITM LSR: ByteAcc Position */
+#define ITM_LSR_ByteAcc_Msk (1UL << ITM_LSR_ByteAcc_Pos) /*!< ITM LSR: ByteAcc Mask */
+
+#define ITM_LSR_Access_Pos 1U /*!< ITM LSR: Access Position */
+#define ITM_LSR_Access_Msk (1UL << ITM_LSR_Access_Pos) /*!< ITM LSR: Access Mask */
+
+#define ITM_LSR_Present_Pos 0U /*!< ITM LSR: Present Position */
+#define ITM_LSR_Present_Msk (1UL /*<< ITM_LSR_Present_Pos*/) /*!< ITM LSR: Present Mask */
+
+/*@}*/ /* end of group CMSIS_ITM */
+
+
+/**
+ \ingroup CMSIS_core_register
+ \defgroup CMSIS_DWT Data Watchpoint and Trace (DWT)
+ \brief Type definitions for the Data Watchpoint and Trace (DWT)
+ @{
+ */
+
+/**
+ \brief Structure type to access the Data Watchpoint and Trace Register (DWT).
+ */
+typedef struct
+{
+ __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) Control Register */
+ __IOM uint32_t CYCCNT; /*!< Offset: 0x004 (R/W) Cycle Count Register */
+ __IOM uint32_t CPICNT; /*!< Offset: 0x008 (R/W) CPI Count Register */
+ __IOM uint32_t EXCCNT; /*!< Offset: 0x00C (R/W) Exception Overhead Count Register */
+ __IOM uint32_t SLEEPCNT; /*!< Offset: 0x010 (R/W) Sleep Count Register */
+ __IOM uint32_t LSUCNT; /*!< Offset: 0x014 (R/W) LSU Count Register */
+ __IOM uint32_t FOLDCNT; /*!< Offset: 0x018 (R/W) Folded-instruction Count Register */
+ __IM uint32_t PCSR; /*!< Offset: 0x01C (R/ ) Program Counter Sample Register */
+ __IOM uint32_t COMP0; /*!< Offset: 0x020 (R/W) Comparator Register 0 */
+ uint32_t RESERVED1[1U];
+ __IOM uint32_t FUNCTION0; /*!< Offset: 0x028 (R/W) Function Register 0 */
+ uint32_t RESERVED2[1U];
+ __IOM uint32_t COMP1; /*!< Offset: 0x030 (R/W) Comparator Register 1 */
+ uint32_t RESERVED3[1U];
+ __IOM uint32_t FUNCTION1; /*!< Offset: 0x038 (R/W) Function Register 1 */
+ uint32_t RESERVED4[1U];
+ __IOM uint32_t COMP2; /*!< Offset: 0x040 (R/W) Comparator Register 2 */
+ uint32_t RESERVED5[1U];
+ __IOM uint32_t FUNCTION2; /*!< Offset: 0x048 (R/W) Function Register 2 */
+ uint32_t RESERVED6[1U];
+ __IOM uint32_t COMP3; /*!< Offset: 0x050 (R/W) Comparator Register 3 */
+ uint32_t RESERVED7[1U];
+ __IOM uint32_t FUNCTION3; /*!< Offset: 0x058 (R/W) Function Register 3 */
+ uint32_t RESERVED8[1U];
+ __IOM uint32_t COMP4; /*!< Offset: 0x060 (R/W) Comparator Register 4 */
+ uint32_t RESERVED9[1U];
+ __IOM uint32_t FUNCTION4; /*!< Offset: 0x068 (R/W) Function Register 4 */
+ uint32_t RESERVED10[1U];
+ __IOM uint32_t COMP5; /*!< Offset: 0x070 (R/W) Comparator Register 5 */
+ uint32_t RESERVED11[1U];
+ __IOM uint32_t FUNCTION5; /*!< Offset: 0x078 (R/W) Function Register 5 */
+ uint32_t RESERVED12[1U];
+ __IOM uint32_t COMP6; /*!< Offset: 0x080 (R/W) Comparator Register 6 */
+ uint32_t RESERVED13[1U];
+ __IOM uint32_t FUNCTION6; /*!< Offset: 0x088 (R/W) Function Register 6 */
+ uint32_t RESERVED14[1U];
+ __IOM uint32_t COMP7; /*!< Offset: 0x090 (R/W) Comparator Register 7 */
+ uint32_t RESERVED15[1U];
+ __IOM uint32_t FUNCTION7; /*!< Offset: 0x098 (R/W) Function Register 7 */
+ uint32_t RESERVED16[1U];
+ __IOM uint32_t COMP8; /*!< Offset: 0x0A0 (R/W) Comparator Register 8 */
+ uint32_t RESERVED17[1U];
+ __IOM uint32_t FUNCTION8; /*!< Offset: 0x0A8 (R/W) Function Register 8 */
+ uint32_t RESERVED18[1U];
+ __IOM uint32_t COMP9; /*!< Offset: 0x0B0 (R/W) Comparator Register 9 */
+ uint32_t RESERVED19[1U];
+ __IOM uint32_t FUNCTION9; /*!< Offset: 0x0B8 (R/W) Function Register 9 */
+ uint32_t RESERVED20[1U];
+ __IOM uint32_t COMP10; /*!< Offset: 0x0C0 (R/W) Comparator Register 10 */
+ uint32_t RESERVED21[1U];
+ __IOM uint32_t FUNCTION10; /*!< Offset: 0x0C8 (R/W) Function Register 10 */
+ uint32_t RESERVED22[1U];
+ __IOM uint32_t COMP11; /*!< Offset: 0x0D0 (R/W) Comparator Register 11 */
+ uint32_t RESERVED23[1U];
+ __IOM uint32_t FUNCTION11; /*!< Offset: 0x0D8 (R/W) Function Register 11 */
+ uint32_t RESERVED24[1U];
+ __IOM uint32_t COMP12; /*!< Offset: 0x0E0 (R/W) Comparator Register 12 */
+ uint32_t RESERVED25[1U];
+ __IOM uint32_t FUNCTION12; /*!< Offset: 0x0E8 (R/W) Function Register 12 */
+ uint32_t RESERVED26[1U];
+ __IOM uint32_t COMP13; /*!< Offset: 0x0F0 (R/W) Comparator Register 13 */
+ uint32_t RESERVED27[1U];
+ __IOM uint32_t FUNCTION13; /*!< Offset: 0x0F8 (R/W) Function Register 13 */
+ uint32_t RESERVED28[1U];
+ __IOM uint32_t COMP14; /*!< Offset: 0x100 (R/W) Comparator Register 14 */
+ uint32_t RESERVED29[1U];
+ __IOM uint32_t FUNCTION14; /*!< Offset: 0x108 (R/W) Function Register 14 */
+ uint32_t RESERVED30[1U];
+ __IOM uint32_t COMP15; /*!< Offset: 0x110 (R/W) Comparator Register 15 */
+ uint32_t RESERVED31[1U];
+ __IOM uint32_t FUNCTION15; /*!< Offset: 0x118 (R/W) Function Register 15 */
+ uint32_t RESERVED32[934U];
+ __IM uint32_t LSR; /*!< Offset: 0xFB4 (R ) Lock Status Register */
+ uint32_t RESERVED33[1U];
+ __IM uint32_t DEVARCH; /*!< Offset: 0xFBC (R/ ) Device Architecture Register */
+} DWT_Type;
+
+/* DWT Control Register Definitions */
+#define DWT_CTRL_NUMCOMP_Pos 28U /*!< DWT CTRL: NUMCOMP Position */
+#define DWT_CTRL_NUMCOMP_Msk (0xFUL << DWT_CTRL_NUMCOMP_Pos) /*!< DWT CTRL: NUMCOMP Mask */
+
+#define DWT_CTRL_NOTRCPKT_Pos 27U /*!< DWT CTRL: NOTRCPKT Position */
+#define DWT_CTRL_NOTRCPKT_Msk (0x1UL << DWT_CTRL_NOTRCPKT_Pos) /*!< DWT CTRL: NOTRCPKT Mask */
+
+#define DWT_CTRL_NOEXTTRIG_Pos 26U /*!< DWT CTRL: NOEXTTRIG Position */
+#define DWT_CTRL_NOEXTTRIG_Msk (0x1UL << DWT_CTRL_NOEXTTRIG_Pos) /*!< DWT CTRL: NOEXTTRIG Mask */
+
+#define DWT_CTRL_NOCYCCNT_Pos 25U /*!< DWT CTRL: NOCYCCNT Position */
+#define DWT_CTRL_NOCYCCNT_Msk (0x1UL << DWT_CTRL_NOCYCCNT_Pos) /*!< DWT CTRL: NOCYCCNT Mask */
+
+#define DWT_CTRL_NOPRFCNT_Pos 24U /*!< DWT CTRL: NOPRFCNT Position */
+#define DWT_CTRL_NOPRFCNT_Msk (0x1UL << DWT_CTRL_NOPRFCNT_Pos) /*!< DWT CTRL: NOPRFCNT Mask */
+
+#define DWT_CTRL_CYCDISS_Pos 23U /*!< DWT CTRL: CYCDISS Position */
+#define DWT_CTRL_CYCDISS_Msk (0x1UL << DWT_CTRL_CYCDISS_Pos) /*!< DWT CTRL: CYCDISS Mask */
+
+#define DWT_CTRL_CYCEVTENA_Pos 22U /*!< DWT CTRL: CYCEVTENA Position */
+#define DWT_CTRL_CYCEVTENA_Msk (0x1UL << DWT_CTRL_CYCEVTENA_Pos) /*!< DWT CTRL: CYCEVTENA Mask */
+
+#define DWT_CTRL_FOLDEVTENA_Pos 21U /*!< DWT CTRL: FOLDEVTENA Position */
+#define DWT_CTRL_FOLDEVTENA_Msk (0x1UL << DWT_CTRL_FOLDEVTENA_Pos) /*!< DWT CTRL: FOLDEVTENA Mask */
+
+#define DWT_CTRL_LSUEVTENA_Pos 20U /*!< DWT CTRL: LSUEVTENA Position */
+#define DWT_CTRL_LSUEVTENA_Msk (0x1UL << DWT_CTRL_LSUEVTENA_Pos) /*!< DWT CTRL: LSUEVTENA Mask */
+
+#define DWT_CTRL_SLEEPEVTENA_Pos 19U /*!< DWT CTRL: SLEEPEVTENA Position */
+#define DWT_CTRL_SLEEPEVTENA_Msk (0x1UL << DWT_CTRL_SLEEPEVTENA_Pos) /*!< DWT CTRL: SLEEPEVTENA Mask */
+
+#define DWT_CTRL_EXCEVTENA_Pos 18U /*!< DWT CTRL: EXCEVTENA Position */
+#define DWT_CTRL_EXCEVTENA_Msk (0x1UL << DWT_CTRL_EXCEVTENA_Pos) /*!< DWT CTRL: EXCEVTENA Mask */
+
+#define DWT_CTRL_CPIEVTENA_Pos 17U /*!< DWT CTRL: CPIEVTENA Position */
+#define DWT_CTRL_CPIEVTENA_Msk (0x1UL << DWT_CTRL_CPIEVTENA_Pos) /*!< DWT CTRL: CPIEVTENA Mask */
+
+#define DWT_CTRL_EXCTRCENA_Pos 16U /*!< DWT CTRL: EXCTRCENA Position */
+#define DWT_CTRL_EXCTRCENA_Msk (0x1UL << DWT_CTRL_EXCTRCENA_Pos) /*!< DWT CTRL: EXCTRCENA Mask */
+
+#define DWT_CTRL_PCSAMPLENA_Pos 12U /*!< DWT CTRL: PCSAMPLENA Position */
+#define DWT_CTRL_PCSAMPLENA_Msk (0x1UL << DWT_CTRL_PCSAMPLENA_Pos) /*!< DWT CTRL: PCSAMPLENA Mask */
+
+#define DWT_CTRL_SYNCTAP_Pos 10U /*!< DWT CTRL: SYNCTAP Position */
+#define DWT_CTRL_SYNCTAP_Msk (0x3UL << DWT_CTRL_SYNCTAP_Pos) /*!< DWT CTRL: SYNCTAP Mask */
+
+#define DWT_CTRL_CYCTAP_Pos 9U /*!< DWT CTRL: CYCTAP Position */
+#define DWT_CTRL_CYCTAP_Msk (0x1UL << DWT_CTRL_CYCTAP_Pos) /*!< DWT CTRL: CYCTAP Mask */
+
+#define DWT_CTRL_POSTINIT_Pos 5U /*!< DWT CTRL: POSTINIT Position */
+#define DWT_CTRL_POSTINIT_Msk (0xFUL << DWT_CTRL_POSTINIT_Pos) /*!< DWT CTRL: POSTINIT Mask */
+
+#define DWT_CTRL_POSTPRESET_Pos 1U /*!< DWT CTRL: POSTPRESET Position */
+#define DWT_CTRL_POSTPRESET_Msk (0xFUL << DWT_CTRL_POSTPRESET_Pos) /*!< DWT CTRL: POSTPRESET Mask */
+
+#define DWT_CTRL_CYCCNTENA_Pos 0U /*!< DWT CTRL: CYCCNTENA Position */
+#define DWT_CTRL_CYCCNTENA_Msk (0x1UL /*<< DWT_CTRL_CYCCNTENA_Pos*/) /*!< DWT CTRL: CYCCNTENA Mask */
+
+/* DWT CPI Count Register Definitions */
+#define DWT_CPICNT_CPICNT_Pos 0U /*!< DWT CPICNT: CPICNT Position */
+#define DWT_CPICNT_CPICNT_Msk (0xFFUL /*<< DWT_CPICNT_CPICNT_Pos*/) /*!< DWT CPICNT: CPICNT Mask */
+
+/* DWT Exception Overhead Count Register Definitions */
+#define DWT_EXCCNT_EXCCNT_Pos 0U /*!< DWT EXCCNT: EXCCNT Position */
+#define DWT_EXCCNT_EXCCNT_Msk (0xFFUL /*<< DWT_EXCCNT_EXCCNT_Pos*/) /*!< DWT EXCCNT: EXCCNT Mask */
+
+/* DWT Sleep Count Register Definitions */
+#define DWT_SLEEPCNT_SLEEPCNT_Pos 0U /*!< DWT SLEEPCNT: SLEEPCNT Position */
+#define DWT_SLEEPCNT_SLEEPCNT_Msk (0xFFUL /*<< DWT_SLEEPCNT_SLEEPCNT_Pos*/) /*!< DWT SLEEPCNT: SLEEPCNT Mask */
+
+/* DWT LSU Count Register Definitions */
+#define DWT_LSUCNT_LSUCNT_Pos 0U /*!< DWT LSUCNT: LSUCNT Position */
+#define DWT_LSUCNT_LSUCNT_Msk (0xFFUL /*<< DWT_LSUCNT_LSUCNT_Pos*/) /*!< DWT LSUCNT: LSUCNT Mask */
+
+/* DWT Folded-instruction Count Register Definitions */
+#define DWT_FOLDCNT_FOLDCNT_Pos 0U /*!< DWT FOLDCNT: FOLDCNT Position */
+#define DWT_FOLDCNT_FOLDCNT_Msk (0xFFUL /*<< DWT_FOLDCNT_FOLDCNT_Pos*/) /*!< DWT FOLDCNT: FOLDCNT Mask */
+
+/* DWT Comparator Function Register Definitions */
+#define DWT_FUNCTION_ID_Pos 27U /*!< DWT FUNCTION: ID Position */
+#define DWT_FUNCTION_ID_Msk (0x1FUL << DWT_FUNCTION_ID_Pos) /*!< DWT FUNCTION: ID Mask */
+
+#define DWT_FUNCTION_MATCHED_Pos 24U /*!< DWT FUNCTION: MATCHED Position */
+#define DWT_FUNCTION_MATCHED_Msk (0x1UL << DWT_FUNCTION_MATCHED_Pos) /*!< DWT FUNCTION: MATCHED Mask */
+
+#define DWT_FUNCTION_DATAVSIZE_Pos 10U /*!< DWT FUNCTION: DATAVSIZE Position */
+#define DWT_FUNCTION_DATAVSIZE_Msk (0x3UL << DWT_FUNCTION_DATAVSIZE_Pos) /*!< DWT FUNCTION: DATAVSIZE Mask */
+
+#define DWT_FUNCTION_ACTION_Pos 4U /*!< DWT FUNCTION: ACTION Position */
+#define DWT_FUNCTION_ACTION_Msk (0x1UL << DWT_FUNCTION_ACTION_Pos) /*!< DWT FUNCTION: ACTION Mask */
+
+#define DWT_FUNCTION_MATCH_Pos 0U /*!< DWT FUNCTION: MATCH Position */
+#define DWT_FUNCTION_MATCH_Msk (0xFUL /*<< DWT_FUNCTION_MATCH_Pos*/) /*!< DWT FUNCTION: MATCH Mask */
+
+/*@}*/ /* end of group CMSIS_DWT */
+
+
+/**
+ \ingroup CMSIS_core_register
+ \defgroup CMSIS_TPI Trace Port Interface (TPI)
+ \brief Type definitions for the Trace Port Interface (TPI)
+ @{
+ */
+
+/**
+ \brief Structure type to access the Trace Port Interface Register (TPI).
+ */
+typedef struct
+{
+ __IOM uint32_t SSPSR; /*!< Offset: 0x000 (R/ ) Supported Parallel Port Size Register */
+ __IOM uint32_t CSPSR; /*!< Offset: 0x004 (R/W) Current Parallel Port Size Register */
+ uint32_t RESERVED0[2U];
+ __IOM uint32_t ACPR; /*!< Offset: 0x010 (R/W) Asynchronous Clock Prescaler Register */
+ uint32_t RESERVED1[55U];
+ __IOM uint32_t SPPR; /*!< Offset: 0x0F0 (R/W) Selected Pin Protocol Register */
+ uint32_t RESERVED2[131U];
+ __IM uint32_t FFSR; /*!< Offset: 0x300 (R/ ) Formatter and Flush Status Register */
+ __IOM uint32_t FFCR; /*!< Offset: 0x304 (R/W) Formatter and Flush Control Register */
+ __IM uint32_t FSCR; /*!< Offset: 0x308 (R/ ) Formatter Synchronization Counter Register */
+ uint32_t RESERVED3[759U];
+ __IM uint32_t TRIGGER; /*!< Offset: 0xEE8 (R/ ) TRIGGER */
+ __IM uint32_t FIFO0; /*!< Offset: 0xEEC (R/ ) Integration ETM Data */
+ __IM uint32_t ITATBCTR2; /*!< Offset: 0xEF0 (R/ ) ITATBCTR2 */
+ uint32_t RESERVED4[1U];
+ __IM uint32_t ITATBCTR0; /*!< Offset: 0xEF8 (R/ ) ITATBCTR0 */
+ __IM uint32_t FIFO1; /*!< Offset: 0xEFC (R/ ) Integration ITM Data */
+ __IOM uint32_t ITCTRL; /*!< Offset: 0xF00 (R/W) Integration Mode Control */
+ uint32_t RESERVED5[39U];
+ __IOM uint32_t CLAIMSET; /*!< Offset: 0xFA0 (R/W) Claim tag set */
+ __IOM uint32_t CLAIMCLR; /*!< Offset: 0xFA4 (R/W) Claim tag clear */
+ uint32_t RESERVED7[8U];
+ __IM uint32_t DEVID; /*!< Offset: 0xFC8 (R/ ) TPIU_DEVID */
+ __IM uint32_t DEVTYPE; /*!< Offset: 0xFCC (R/ ) TPIU_DEVTYPE */
+} TPI_Type;
+
+/* TPI Asynchronous Clock Prescaler Register Definitions */
+#define TPI_ACPR_PRESCALER_Pos 0U /*!< TPI ACPR: PRESCALER Position */
+#define TPI_ACPR_PRESCALER_Msk (0x1FFFUL /*<< TPI_ACPR_PRESCALER_Pos*/) /*!< TPI ACPR: PRESCALER Mask */
+
+/* TPI Selected Pin Protocol Register Definitions */
+#define TPI_SPPR_TXMODE_Pos 0U /*!< TPI SPPR: TXMODE Position */
+#define TPI_SPPR_TXMODE_Msk (0x3UL /*<< TPI_SPPR_TXMODE_Pos*/) /*!< TPI SPPR: TXMODE Mask */
+
+/* TPI Formatter and Flush Status Register Definitions */
+#define TPI_FFSR_FtNonStop_Pos 3U /*!< TPI FFSR: FtNonStop Position */
+#define TPI_FFSR_FtNonStop_Msk (0x1UL << TPI_FFSR_FtNonStop_Pos) /*!< TPI FFSR: FtNonStop Mask */
+
+#define TPI_FFSR_TCPresent_Pos 2U /*!< TPI FFSR: TCPresent Position */
+#define TPI_FFSR_TCPresent_Msk (0x1UL << TPI_FFSR_TCPresent_Pos) /*!< TPI FFSR: TCPresent Mask */
+
+#define TPI_FFSR_FtStopped_Pos 1U /*!< TPI FFSR: FtStopped Position */
+#define TPI_FFSR_FtStopped_Msk (0x1UL << TPI_FFSR_FtStopped_Pos) /*!< TPI FFSR: FtStopped Mask */
+
+#define TPI_FFSR_FlInProg_Pos 0U /*!< TPI FFSR: FlInProg Position */
+#define TPI_FFSR_FlInProg_Msk (0x1UL /*<< TPI_FFSR_FlInProg_Pos*/) /*!< TPI FFSR: FlInProg Mask */
+
+/* TPI Formatter and Flush Control Register Definitions */
+#define TPI_FFCR_TrigIn_Pos 8U /*!< TPI FFCR: TrigIn Position */
+#define TPI_FFCR_TrigIn_Msk (0x1UL << TPI_FFCR_TrigIn_Pos) /*!< TPI FFCR: TrigIn Mask */
+
+#define TPI_FFCR_EnFCont_Pos 1U /*!< TPI FFCR: EnFCont Position */
+#define TPI_FFCR_EnFCont_Msk (0x1UL << TPI_FFCR_EnFCont_Pos) /*!< TPI FFCR: EnFCont Mask */
+
+/* TPI TRIGGER Register Definitions */
+#define TPI_TRIGGER_TRIGGER_Pos 0U /*!< TPI TRIGGER: TRIGGER Position */
+#define TPI_TRIGGER_TRIGGER_Msk (0x1UL /*<< TPI_TRIGGER_TRIGGER_Pos*/) /*!< TPI TRIGGER: TRIGGER Mask */
+
+/* TPI Integration ETM Data Register Definitions (FIFO0) */
+#define TPI_FIFO0_ITM_ATVALID_Pos 29U /*!< TPI FIFO0: ITM_ATVALID Position */
+#define TPI_FIFO0_ITM_ATVALID_Msk (0x3UL << TPI_FIFO0_ITM_ATVALID_Pos) /*!< TPI FIFO0: ITM_ATVALID Mask */
+
+#define TPI_FIFO0_ITM_bytecount_Pos 27U /*!< TPI FIFO0: ITM_bytecount Position */
+#define TPI_FIFO0_ITM_bytecount_Msk (0x3UL << TPI_FIFO0_ITM_bytecount_Pos) /*!< TPI FIFO0: ITM_bytecount Mask */
+
+#define TPI_FIFO0_ETM_ATVALID_Pos 26U /*!< TPI FIFO0: ETM_ATVALID Position */
+#define TPI_FIFO0_ETM_ATVALID_Msk (0x3UL << TPI_FIFO0_ETM_ATVALID_Pos) /*!< TPI FIFO0: ETM_ATVALID Mask */
+
+#define TPI_FIFO0_ETM_bytecount_Pos 24U /*!< TPI FIFO0: ETM_bytecount Position */
+#define TPI_FIFO0_ETM_bytecount_Msk (0x3UL << TPI_FIFO0_ETM_bytecount_Pos) /*!< TPI FIFO0: ETM_bytecount Mask */
+
+#define TPI_FIFO0_ETM2_Pos 16U /*!< TPI FIFO0: ETM2 Position */
+#define TPI_FIFO0_ETM2_Msk (0xFFUL << TPI_FIFO0_ETM2_Pos) /*!< TPI FIFO0: ETM2 Mask */
+
+#define TPI_FIFO0_ETM1_Pos 8U /*!< TPI FIFO0: ETM1 Position */
+#define TPI_FIFO0_ETM1_Msk (0xFFUL << TPI_FIFO0_ETM1_Pos) /*!< TPI FIFO0: ETM1 Mask */
+
+#define TPI_FIFO0_ETM0_Pos 0U /*!< TPI FIFO0: ETM0 Position */
+#define TPI_FIFO0_ETM0_Msk (0xFFUL /*<< TPI_FIFO0_ETM0_Pos*/) /*!< TPI FIFO0: ETM0 Mask */
+
+/* TPI ITATBCTR2 Register Definitions */
+#define TPI_ITATBCTR2_ATREADY_Pos 0U /*!< TPI ITATBCTR2: ATREADY Position */
+#define TPI_ITATBCTR2_ATREADY_Msk (0x1UL /*<< TPI_ITATBCTR2_ATREADY_Pos*/) /*!< TPI ITATBCTR2: ATREADY Mask */
+
+/* TPI Integration ITM Data Register Definitions (FIFO1) */
+#define TPI_FIFO1_ITM_ATVALID_Pos 29U /*!< TPI FIFO1: ITM_ATVALID Position */
+#define TPI_FIFO1_ITM_ATVALID_Msk (0x3UL << TPI_FIFO1_ITM_ATVALID_Pos) /*!< TPI FIFO1: ITM_ATVALID Mask */
+
+#define TPI_FIFO1_ITM_bytecount_Pos 27U /*!< TPI FIFO1: ITM_bytecount Position */
+#define TPI_FIFO1_ITM_bytecount_Msk (0x3UL << TPI_FIFO1_ITM_bytecount_Pos) /*!< TPI FIFO1: ITM_bytecount Mask */
+
+#define TPI_FIFO1_ETM_ATVALID_Pos 26U /*!< TPI FIFO1: ETM_ATVALID Position */
+#define TPI_FIFO1_ETM_ATVALID_Msk (0x3UL << TPI_FIFO1_ETM_ATVALID_Pos) /*!< TPI FIFO1: ETM_ATVALID Mask */
+
+#define TPI_FIFO1_ETM_bytecount_Pos 24U /*!< TPI FIFO1: ETM_bytecount Position */
+#define TPI_FIFO1_ETM_bytecount_Msk (0x3UL << TPI_FIFO1_ETM_bytecount_Pos) /*!< TPI FIFO1: ETM_bytecount Mask */
+
+#define TPI_FIFO1_ITM2_Pos 16U /*!< TPI FIFO1: ITM2 Position */
+#define TPI_FIFO1_ITM2_Msk (0xFFUL << TPI_FIFO1_ITM2_Pos) /*!< TPI FIFO1: ITM2 Mask */
+
+#define TPI_FIFO1_ITM1_Pos 8U /*!< TPI FIFO1: ITM1 Position */
+#define TPI_FIFO1_ITM1_Msk (0xFFUL << TPI_FIFO1_ITM1_Pos) /*!< TPI FIFO1: ITM1 Mask */
+
+#define TPI_FIFO1_ITM0_Pos 0U /*!< TPI FIFO1: ITM0 Position */
+#define TPI_FIFO1_ITM0_Msk (0xFFUL /*<< TPI_FIFO1_ITM0_Pos*/) /*!< TPI FIFO1: ITM0 Mask */
+
+/* TPI ITATBCTR0 Register Definitions */
+#define TPI_ITATBCTR0_ATREADY_Pos 0U /*!< TPI ITATBCTR0: ATREADY Position */
+#define TPI_ITATBCTR0_ATREADY_Msk (0x1UL /*<< TPI_ITATBCTR0_ATREADY_Pos*/) /*!< TPI ITATBCTR0: ATREADY Mask */
+
+/* TPI Integration Mode Control Register Definitions */
+#define TPI_ITCTRL_Mode_Pos 0U /*!< TPI ITCTRL: Mode Position */
+#define TPI_ITCTRL_Mode_Msk (0x1UL /*<< TPI_ITCTRL_Mode_Pos*/) /*!< TPI ITCTRL: Mode Mask */
+
+/* TPI DEVID Register Definitions */
+#define TPI_DEVID_NRZVALID_Pos 11U /*!< TPI DEVID: NRZVALID Position */
+#define TPI_DEVID_NRZVALID_Msk (0x1UL << TPI_DEVID_NRZVALID_Pos) /*!< TPI DEVID: NRZVALID Mask */
+
+#define TPI_DEVID_MANCVALID_Pos 10U /*!< TPI DEVID: MANCVALID Position */
+#define TPI_DEVID_MANCVALID_Msk (0x1UL << TPI_DEVID_MANCVALID_Pos) /*!< TPI DEVID: MANCVALID Mask */
+
+#define TPI_DEVID_PTINVALID_Pos 9U /*!< TPI DEVID: PTINVALID Position */
+#define TPI_DEVID_PTINVALID_Msk (0x1UL << TPI_DEVID_PTINVALID_Pos) /*!< TPI DEVID: PTINVALID Mask */
+
+#define TPI_DEVID_MinBufSz_Pos 6U /*!< TPI DEVID: MinBufSz Position */
+#define TPI_DEVID_MinBufSz_Msk (0x7UL << TPI_DEVID_MinBufSz_Pos) /*!< TPI DEVID: MinBufSz Mask */
+
+#define TPI_DEVID_AsynClkIn_Pos 5U /*!< TPI DEVID: AsynClkIn Position */
+#define TPI_DEVID_AsynClkIn_Msk (0x1UL << TPI_DEVID_AsynClkIn_Pos) /*!< TPI DEVID: AsynClkIn Mask */
+
+#define TPI_DEVID_NrTraceInput_Pos 0U /*!< TPI DEVID: NrTraceInput Position */
+#define TPI_DEVID_NrTraceInput_Msk (0x1FUL /*<< TPI_DEVID_NrTraceInput_Pos*/) /*!< TPI DEVID: NrTraceInput Mask */
+
+/* TPI DEVTYPE Register Definitions */
+#define TPI_DEVTYPE_MajorType_Pos 4U /*!< TPI DEVTYPE: MajorType Position */
+#define TPI_DEVTYPE_MajorType_Msk (0xFUL << TPI_DEVTYPE_MajorType_Pos) /*!< TPI DEVTYPE: MajorType Mask */
+
+#define TPI_DEVTYPE_SubType_Pos 0U /*!< TPI DEVTYPE: SubType Position */
+#define TPI_DEVTYPE_SubType_Msk (0xFUL /*<< TPI_DEVTYPE_SubType_Pos*/) /*!< TPI DEVTYPE: SubType Mask */
+
+/*@}*/ /* end of group CMSIS_TPI */
+
+
+#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U)
+/**
+ \ingroup CMSIS_core_register
+ \defgroup CMSIS_MPU Memory Protection Unit (MPU)
+ \brief Type definitions for the Memory Protection Unit (MPU)
+ @{
+ */
+
+/**
+ \brief Structure type to access the Memory Protection Unit (MPU).
+ */
+typedef struct
+{
+ __IM uint32_t TYPE; /*!< Offset: 0x000 (R/ ) MPU Type Register */
+ __IOM uint32_t CTRL; /*!< Offset: 0x004 (R/W) MPU Control Register */
+ __IOM uint32_t RNR; /*!< Offset: 0x008 (R/W) MPU Region Number Register */
+ __IOM uint32_t RBAR; /*!< Offset: 0x00C (R/W) MPU Region Base Address Register */
+ __IOM uint32_t RLAR; /*!< Offset: 0x010 (R/W) MPU Region Limit Address Register */
+ __IOM uint32_t RBAR_A1; /*!< Offset: 0x014 (R/W) MPU Region Base Address Register Alias 1 */
+ __IOM uint32_t RLAR_A1; /*!< Offset: 0x018 (R/W) MPU Region Limit Address Register Alias 1 */
+ __IOM uint32_t RBAR_A2; /*!< Offset: 0x01C (R/W) MPU Region Base Address Register Alias 2 */
+ __IOM uint32_t RLAR_A2; /*!< Offset: 0x020 (R/W) MPU Region Limit Address Register Alias 2 */
+ __IOM uint32_t RBAR_A3; /*!< Offset: 0x024 (R/W) MPU Region Base Address Register Alias 3 */
+ __IOM uint32_t RLAR_A3; /*!< Offset: 0x028 (R/W) MPU Region Limit Address Register Alias 3 */
+ uint32_t RESERVED0[1];
+ union {
+ __IOM uint32_t MAIR[2];
+ struct {
+ __IOM uint32_t MAIR0; /*!< Offset: 0x030 (R/W) MPU Memory Attribute Indirection Register 0 */
+ __IOM uint32_t MAIR1; /*!< Offset: 0x034 (R/W) MPU Memory Attribute Indirection Register 1 */
+ };
+ };
+} MPU_Type;
+
+#define MPU_TYPE_RALIASES 4U
+
+/* MPU Type Register Definitions */
+#define MPU_TYPE_IREGION_Pos 16U /*!< MPU TYPE: IREGION Position */
+#define MPU_TYPE_IREGION_Msk (0xFFUL << MPU_TYPE_IREGION_Pos) /*!< MPU TYPE: IREGION Mask */
+
+#define MPU_TYPE_DREGION_Pos 8U /*!< MPU TYPE: DREGION Position */
+#define MPU_TYPE_DREGION_Msk (0xFFUL << MPU_TYPE_DREGION_Pos) /*!< MPU TYPE: DREGION Mask */
+
+#define MPU_TYPE_SEPARATE_Pos 0U /*!< MPU TYPE: SEPARATE Position */
+#define MPU_TYPE_SEPARATE_Msk (1UL /*<< MPU_TYPE_SEPARATE_Pos*/) /*!< MPU TYPE: SEPARATE Mask */
+
+/* MPU Control Register Definitions */
+#define MPU_CTRL_PRIVDEFENA_Pos 2U /*!< MPU CTRL: PRIVDEFENA Position */
+#define MPU_CTRL_PRIVDEFENA_Msk (1UL << MPU_CTRL_PRIVDEFENA_Pos) /*!< MPU CTRL: PRIVDEFENA Mask */
+
+#define MPU_CTRL_HFNMIENA_Pos 1U /*!< MPU CTRL: HFNMIENA Position */
+#define MPU_CTRL_HFNMIENA_Msk (1UL << MPU_CTRL_HFNMIENA_Pos) /*!< MPU CTRL: HFNMIENA Mask */
+
+#define MPU_CTRL_ENABLE_Pos 0U /*!< MPU CTRL: ENABLE Position */
+#define MPU_CTRL_ENABLE_Msk (1UL /*<< MPU_CTRL_ENABLE_Pos*/) /*!< MPU CTRL: ENABLE Mask */
+
+/* MPU Region Number Register Definitions */
+#define MPU_RNR_REGION_Pos 0U /*!< MPU RNR: REGION Position */
+#define MPU_RNR_REGION_Msk (0xFFUL /*<< MPU_RNR_REGION_Pos*/) /*!< MPU RNR: REGION Mask */
+
+/* MPU Region Base Address Register Definitions */
+#define MPU_RBAR_ADDR_Pos 5U /*!< MPU RBAR: ADDR Position */
+#define MPU_RBAR_ADDR_Msk (0x7FFFFFFUL << MPU_RBAR_ADDR_Pos) /*!< MPU RBAR: ADDR Mask */
+
+#define MPU_RBAR_SH_Pos 3U /*!< MPU RBAR: SH Position */
+#define MPU_RBAR_SH_Msk (0x3UL << MPU_RBAR_SH_Pos) /*!< MPU RBAR: SH Mask */
+
+#define MPU_RBAR_AP_Pos 1U /*!< MPU RBAR: AP Position */
+#define MPU_RBAR_AP_Msk (0x3UL << MPU_RBAR_AP_Pos) /*!< MPU RBAR: AP Mask */
+
+#define MPU_RBAR_XN_Pos 0U /*!< MPU RBAR: XN Position */
+#define MPU_RBAR_XN_Msk (01UL /*<< MPU_RBAR_XN_Pos*/) /*!< MPU RBAR: XN Mask */
+
+/* MPU Region Limit Address Register Definitions */
+#define MPU_RLAR_LIMIT_Pos 5U /*!< MPU RLAR: LIMIT Position */
+#define MPU_RLAR_LIMIT_Msk (0x7FFFFFFUL << MPU_RLAR_LIMIT_Pos) /*!< MPU RLAR: LIMIT Mask */
+
+#define MPU_RLAR_AttrIndx_Pos 1U /*!< MPU RLAR: AttrIndx Position */
+#define MPU_RLAR_AttrIndx_Msk (0x7UL << MPU_RLAR_AttrIndx_Pos) /*!< MPU RLAR: AttrIndx Mask */
+
+#define MPU_RLAR_EN_Pos 0U /*!< MPU RLAR: Region enable bit Position */
+#define MPU_RLAR_EN_Msk (1UL /*<< MPU_RLAR_EN_Pos*/) /*!< MPU RLAR: Region enable bit Disable Mask */
+
+/* MPU Memory Attribute Indirection Register 0 Definitions */
+#define MPU_MAIR0_Attr3_Pos 24U /*!< MPU MAIR0: Attr3 Position */
+#define MPU_MAIR0_Attr3_Msk (0xFFUL << MPU_MAIR0_Attr3_Pos) /*!< MPU MAIR0: Attr3 Mask */
+
+#define MPU_MAIR0_Attr2_Pos 16U /*!< MPU MAIR0: Attr2 Position */
+#define MPU_MAIR0_Attr2_Msk (0xFFUL << MPU_MAIR0_Attr2_Pos) /*!< MPU MAIR0: Attr2 Mask */
+
+#define MPU_MAIR0_Attr1_Pos 8U /*!< MPU MAIR0: Attr1 Position */
+#define MPU_MAIR0_Attr1_Msk (0xFFUL << MPU_MAIR0_Attr1_Pos) /*!< MPU MAIR0: Attr1 Mask */
+
+#define MPU_MAIR0_Attr0_Pos 0U /*!< MPU MAIR0: Attr0 Position */
+#define MPU_MAIR0_Attr0_Msk (0xFFUL /*<< MPU_MAIR0_Attr0_Pos*/) /*!< MPU MAIR0: Attr0 Mask */
+
+/* MPU Memory Attribute Indirection Register 1 Definitions */
+#define MPU_MAIR1_Attr7_Pos 24U /*!< MPU MAIR1: Attr7 Position */
+#define MPU_MAIR1_Attr7_Msk (0xFFUL << MPU_MAIR1_Attr7_Pos) /*!< MPU MAIR1: Attr7 Mask */
+
+#define MPU_MAIR1_Attr6_Pos 16U /*!< MPU MAIR1: Attr6 Position */
+#define MPU_MAIR1_Attr6_Msk (0xFFUL << MPU_MAIR1_Attr6_Pos) /*!< MPU MAIR1: Attr6 Mask */
+
+#define MPU_MAIR1_Attr5_Pos 8U /*!< MPU MAIR1: Attr5 Position */
+#define MPU_MAIR1_Attr5_Msk (0xFFUL << MPU_MAIR1_Attr5_Pos) /*!< MPU MAIR1: Attr5 Mask */
+
+#define MPU_MAIR1_Attr4_Pos 0U /*!< MPU MAIR1: Attr4 Position */
+#define MPU_MAIR1_Attr4_Msk (0xFFUL /*<< MPU_MAIR1_Attr4_Pos*/) /*!< MPU MAIR1: Attr4 Mask */
+
+/*@} end of group CMSIS_MPU */
+#endif
+
+
+#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U)
+/**
+ \ingroup CMSIS_core_register
+ \defgroup CMSIS_SAU Security Attribution Unit (SAU)
+ \brief Type definitions for the Security Attribution Unit (SAU)
+ @{
+ */
+
+/**
+ \brief Structure type to access the Security Attribution Unit (SAU).
+ */
+typedef struct
+{
+ __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) SAU Control Register */
+ __IM uint32_t TYPE; /*!< Offset: 0x004 (R/ ) SAU Type Register */
+#if defined (__SAUREGION_PRESENT) && (__SAUREGION_PRESENT == 1U)
+ __IOM uint32_t RNR; /*!< Offset: 0x008 (R/W) SAU Region Number Register */
+ __IOM uint32_t RBAR; /*!< Offset: 0x00C (R/W) SAU Region Base Address Register */
+ __IOM uint32_t RLAR; /*!< Offset: 0x010 (R/W) SAU Region Limit Address Register */
+#else
+ uint32_t RESERVED0[3];
+#endif
+ __IOM uint32_t SFSR; /*!< Offset: 0x014 (R/W) Secure Fault Status Register */
+ __IOM uint32_t SFAR; /*!< Offset: 0x018 (R/W) Secure Fault Address Register */
+} SAU_Type;
+
+/* SAU Control Register Definitions */
+#define SAU_CTRL_ALLNS_Pos 1U /*!< SAU CTRL: ALLNS Position */
+#define SAU_CTRL_ALLNS_Msk (1UL << SAU_CTRL_ALLNS_Pos) /*!< SAU CTRL: ALLNS Mask */
+
+#define SAU_CTRL_ENABLE_Pos 0U /*!< SAU CTRL: ENABLE Position */
+#define SAU_CTRL_ENABLE_Msk (1UL /*<< SAU_CTRL_ENABLE_Pos*/) /*!< SAU CTRL: ENABLE Mask */
+
+/* SAU Type Register Definitions */
+#define SAU_TYPE_SREGION_Pos 0U /*!< SAU TYPE: SREGION Position */
+#define SAU_TYPE_SREGION_Msk (0xFFUL /*<< SAU_TYPE_SREGION_Pos*/) /*!< SAU TYPE: SREGION Mask */
+
+#if defined (__SAUREGION_PRESENT) && (__SAUREGION_PRESENT == 1U)
+/* SAU Region Number Register Definitions */
+#define SAU_RNR_REGION_Pos 0U /*!< SAU RNR: REGION Position */
+#define SAU_RNR_REGION_Msk (0xFFUL /*<< SAU_RNR_REGION_Pos*/) /*!< SAU RNR: REGION Mask */
+
+/* SAU Region Base Address Register Definitions */
+#define SAU_RBAR_BADDR_Pos 5U /*!< SAU RBAR: BADDR Position */
+#define SAU_RBAR_BADDR_Msk (0x7FFFFFFUL << SAU_RBAR_BADDR_Pos) /*!< SAU RBAR: BADDR Mask */
+
+/* SAU Region Limit Address Register Definitions */
+#define SAU_RLAR_LADDR_Pos 5U /*!< SAU RLAR: LADDR Position */
+#define SAU_RLAR_LADDR_Msk (0x7FFFFFFUL << SAU_RLAR_LADDR_Pos) /*!< SAU RLAR: LADDR Mask */
+
+#define SAU_RLAR_NSC_Pos 1U /*!< SAU RLAR: NSC Position */
+#define SAU_RLAR_NSC_Msk (1UL << SAU_RLAR_NSC_Pos) /*!< SAU RLAR: NSC Mask */
+
+#define SAU_RLAR_ENABLE_Pos 0U /*!< SAU RLAR: ENABLE Position */
+#define SAU_RLAR_ENABLE_Msk (1UL /*<< SAU_RLAR_ENABLE_Pos*/) /*!< SAU RLAR: ENABLE Mask */
+
+#endif /* defined (__SAUREGION_PRESENT) && (__SAUREGION_PRESENT == 1U) */
+
+/* Secure Fault Status Register Definitions */
+#define SAU_SFSR_LSERR_Pos 7U /*!< SAU SFSR: LSERR Position */
+#define SAU_SFSR_LSERR_Msk (1UL << SAU_SFSR_LSERR_Pos) /*!< SAU SFSR: LSERR Mask */
+
+#define SAU_SFSR_SFARVALID_Pos 6U /*!< SAU SFSR: SFARVALID Position */
+#define SAU_SFSR_SFARVALID_Msk (1UL << SAU_SFSR_SFARVALID_Pos) /*!< SAU SFSR: SFARVALID Mask */
+
+#define SAU_SFSR_LSPERR_Pos 5U /*!< SAU SFSR: LSPERR Position */
+#define SAU_SFSR_LSPERR_Msk (1UL << SAU_SFSR_LSPERR_Pos) /*!< SAU SFSR: LSPERR Mask */
+
+#define SAU_SFSR_INVTRAN_Pos 4U /*!< SAU SFSR: INVTRAN Position */
+#define SAU_SFSR_INVTRAN_Msk (1UL << SAU_SFSR_INVTRAN_Pos) /*!< SAU SFSR: INVTRAN Mask */
+
+#define SAU_SFSR_AUVIOL_Pos 3U /*!< SAU SFSR: AUVIOL Position */
+#define SAU_SFSR_AUVIOL_Msk (1UL << SAU_SFSR_AUVIOL_Pos) /*!< SAU SFSR: AUVIOL Mask */
+
+#define SAU_SFSR_INVER_Pos 2U /*!< SAU SFSR: INVER Position */
+#define SAU_SFSR_INVER_Msk (1UL << SAU_SFSR_INVER_Pos) /*!< SAU SFSR: INVER Mask */
+
+#define SAU_SFSR_INVIS_Pos 1U /*!< SAU SFSR: INVIS Position */
+#define SAU_SFSR_INVIS_Msk (1UL << SAU_SFSR_INVIS_Pos) /*!< SAU SFSR: INVIS Mask */
+
+#define SAU_SFSR_INVEP_Pos 0U /*!< SAU SFSR: INVEP Position */
+#define SAU_SFSR_INVEP_Msk (1UL /*<< SAU_SFSR_INVEP_Pos*/) /*!< SAU SFSR: INVEP Mask */
+
+/*@} end of group CMSIS_SAU */
+#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */
+
+
+/**
+ \ingroup CMSIS_core_register
+ \defgroup CMSIS_FPU Floating Point Unit (FPU)
+ \brief Type definitions for the Floating Point Unit (FPU)
+ @{
+ */
+
+/**
+ \brief Structure type to access the Floating Point Unit (FPU).
+ */
+typedef struct
+{
+ uint32_t RESERVED0[1U];
+ __IOM uint32_t FPCCR; /*!< Offset: 0x004 (R/W) Floating-Point Context Control Register */
+ __IOM uint32_t FPCAR; /*!< Offset: 0x008 (R/W) Floating-Point Context Address Register */
+ __IOM uint32_t FPDSCR; /*!< Offset: 0x00C (R/W) Floating-Point Default Status Control Register */
+ __IM uint32_t MVFR0; /*!< Offset: 0x010 (R/ ) Media and FP Feature Register 0 */
+ __IM uint32_t MVFR1; /*!< Offset: 0x014 (R/ ) Media and FP Feature Register 1 */
+} FPU_Type;
+
+/* Floating-Point Context Control Register Definitions */
+#define FPU_FPCCR_ASPEN_Pos 31U /*!< FPCCR: ASPEN bit Position */
+#define FPU_FPCCR_ASPEN_Msk (1UL << FPU_FPCCR_ASPEN_Pos) /*!< FPCCR: ASPEN bit Mask */
+
+#define FPU_FPCCR_LSPEN_Pos 30U /*!< FPCCR: LSPEN Position */
+#define FPU_FPCCR_LSPEN_Msk (1UL << FPU_FPCCR_LSPEN_Pos) /*!< FPCCR: LSPEN bit Mask */
+
+#define FPU_FPCCR_LSPENS_Pos 29U /*!< FPCCR: LSPENS Position */
+#define FPU_FPCCR_LSPENS_Msk (1UL << FPU_FPCCR_LSPENS_Pos) /*!< FPCCR: LSPENS bit Mask */
+
+#define FPU_FPCCR_CLRONRET_Pos 28U /*!< FPCCR: CLRONRET Position */
+#define FPU_FPCCR_CLRONRET_Msk (1UL << FPU_FPCCR_CLRONRET_Pos) /*!< FPCCR: CLRONRET bit Mask */
+
+#define FPU_FPCCR_CLRONRETS_Pos 27U /*!< FPCCR: CLRONRETS Position */
+#define FPU_FPCCR_CLRONRETS_Msk (1UL << FPU_FPCCR_CLRONRETS_Pos) /*!< FPCCR: CLRONRETS bit Mask */
+
+#define FPU_FPCCR_TS_Pos 26U /*!< FPCCR: TS Position */
+#define FPU_FPCCR_TS_Msk (1UL << FPU_FPCCR_TS_Pos) /*!< FPCCR: TS bit Mask */
+
+#define FPU_FPCCR_UFRDY_Pos 10U /*!< FPCCR: UFRDY Position */
+#define FPU_FPCCR_UFRDY_Msk (1UL << FPU_FPCCR_UFRDY_Pos) /*!< FPCCR: UFRDY bit Mask */
+
+#define FPU_FPCCR_SPLIMVIOL_Pos 9U /*!< FPCCR: SPLIMVIOL Position */
+#define FPU_FPCCR_SPLIMVIOL_Msk (1UL << FPU_FPCCR_SPLIMVIOL_Pos) /*!< FPCCR: SPLIMVIOL bit Mask */
+
+#define FPU_FPCCR_MONRDY_Pos 8U /*!< FPCCR: MONRDY Position */
+#define FPU_FPCCR_MONRDY_Msk (1UL << FPU_FPCCR_MONRDY_Pos) /*!< FPCCR: MONRDY bit Mask */
+
+#define FPU_FPCCR_SFRDY_Pos 7U /*!< FPCCR: SFRDY Position */
+#define FPU_FPCCR_SFRDY_Msk (1UL << FPU_FPCCR_SFRDY_Pos) /*!< FPCCR: SFRDY bit Mask */
+
+#define FPU_FPCCR_BFRDY_Pos 6U /*!< FPCCR: BFRDY Position */
+#define FPU_FPCCR_BFRDY_Msk (1UL << FPU_FPCCR_BFRDY_Pos) /*!< FPCCR: BFRDY bit Mask */
+
+#define FPU_FPCCR_MMRDY_Pos 5U /*!< FPCCR: MMRDY Position */
+#define FPU_FPCCR_MMRDY_Msk (1UL << FPU_FPCCR_MMRDY_Pos) /*!< FPCCR: MMRDY bit Mask */
+
+#define FPU_FPCCR_HFRDY_Pos 4U /*!< FPCCR: HFRDY Position */
+#define FPU_FPCCR_HFRDY_Msk (1UL << FPU_FPCCR_HFRDY_Pos) /*!< FPCCR: HFRDY bit Mask */
+
+#define FPU_FPCCR_THREAD_Pos 3U /*!< FPCCR: processor mode bit Position */
+#define FPU_FPCCR_THREAD_Msk (1UL << FPU_FPCCR_THREAD_Pos) /*!< FPCCR: processor mode active bit Mask */
+
+#define FPU_FPCCR_S_Pos 2U /*!< FPCCR: Security status of the FP context bit Position */
+#define FPU_FPCCR_S_Msk (1UL << FPU_FPCCR_S_Pos) /*!< FPCCR: Security status of the FP context bit Mask */
+
+#define FPU_FPCCR_USER_Pos 1U /*!< FPCCR: privilege level bit Position */
+#define FPU_FPCCR_USER_Msk (1UL << FPU_FPCCR_USER_Pos) /*!< FPCCR: privilege level bit Mask */
+
+#define FPU_FPCCR_LSPACT_Pos 0U /*!< FPCCR: Lazy state preservation active bit Position */
+#define FPU_FPCCR_LSPACT_Msk (1UL /*<< FPU_FPCCR_LSPACT_Pos*/) /*!< FPCCR: Lazy state preservation active bit Mask */
+
+/* Floating-Point Context Address Register Definitions */
+#define FPU_FPCAR_ADDRESS_Pos 3U /*!< FPCAR: ADDRESS bit Position */
+#define FPU_FPCAR_ADDRESS_Msk (0x1FFFFFFFUL << FPU_FPCAR_ADDRESS_Pos) /*!< FPCAR: ADDRESS bit Mask */
+
+/* Floating-Point Default Status Control Register Definitions */
+#define FPU_FPDSCR_AHP_Pos 26U /*!< FPDSCR: AHP bit Position */
+#define FPU_FPDSCR_AHP_Msk (1UL << FPU_FPDSCR_AHP_Pos) /*!< FPDSCR: AHP bit Mask */
+
+#define FPU_FPDSCR_DN_Pos 25U /*!< FPDSCR: DN bit Position */
+#define FPU_FPDSCR_DN_Msk (1UL << FPU_FPDSCR_DN_Pos) /*!< FPDSCR: DN bit Mask */
+
+#define FPU_FPDSCR_FZ_Pos 24U /*!< FPDSCR: FZ bit Position */
+#define FPU_FPDSCR_FZ_Msk (1UL << FPU_FPDSCR_FZ_Pos) /*!< FPDSCR: FZ bit Mask */
+
+#define FPU_FPDSCR_RMode_Pos 22U /*!< FPDSCR: RMode bit Position */
+#define FPU_FPDSCR_RMode_Msk (3UL << FPU_FPDSCR_RMode_Pos) /*!< FPDSCR: RMode bit Mask */
+
+/* Media and FP Feature Register 0 Definitions */
+#define FPU_MVFR0_FP_rounding_modes_Pos 28U /*!< MVFR0: FP rounding modes bits Position */
+#define FPU_MVFR0_FP_rounding_modes_Msk (0xFUL << FPU_MVFR0_FP_rounding_modes_Pos) /*!< MVFR0: FP rounding modes bits Mask */
+
+#define FPU_MVFR0_Short_vectors_Pos 24U /*!< MVFR0: Short vectors bits Position */
+#define FPU_MVFR0_Short_vectors_Msk (0xFUL << FPU_MVFR0_Short_vectors_Pos) /*!< MVFR0: Short vectors bits Mask */
+
+#define FPU_MVFR0_Square_root_Pos 20U /*!< MVFR0: Square root bits Position */
+#define FPU_MVFR0_Square_root_Msk (0xFUL << FPU_MVFR0_Square_root_Pos) /*!< MVFR0: Square root bits Mask */
+
+#define FPU_MVFR0_Divide_Pos 16U /*!< MVFR0: Divide bits Position */
+#define FPU_MVFR0_Divide_Msk (0xFUL << FPU_MVFR0_Divide_Pos) /*!< MVFR0: Divide bits Mask */
+
+#define FPU_MVFR0_FP_excep_trapping_Pos 12U /*!< MVFR0: FP exception trapping bits Position */
+#define FPU_MVFR0_FP_excep_trapping_Msk (0xFUL << FPU_MVFR0_FP_excep_trapping_Pos) /*!< MVFR0: FP exception trapping bits Mask */
+
+#define FPU_MVFR0_Double_precision_Pos 8U /*!< MVFR0: Double-precision bits Position */
+#define FPU_MVFR0_Double_precision_Msk (0xFUL << FPU_MVFR0_Double_precision_Pos) /*!< MVFR0: Double-precision bits Mask */
+
+#define FPU_MVFR0_Single_precision_Pos 4U /*!< MVFR0: Single-precision bits Position */
+#define FPU_MVFR0_Single_precision_Msk (0xFUL << FPU_MVFR0_Single_precision_Pos) /*!< MVFR0: Single-precision bits Mask */
+
+#define FPU_MVFR0_A_SIMD_registers_Pos 0U /*!< MVFR0: A_SIMD registers bits Position */
+#define FPU_MVFR0_A_SIMD_registers_Msk (0xFUL /*<< FPU_MVFR0_A_SIMD_registers_Pos*/) /*!< MVFR0: A_SIMD registers bits Mask */
+
+/* Media and FP Feature Register 1 Definitions */
+#define FPU_MVFR1_FP_fused_MAC_Pos 28U /*!< MVFR1: FP fused MAC bits Position */
+#define FPU_MVFR1_FP_fused_MAC_Msk (0xFUL << FPU_MVFR1_FP_fused_MAC_Pos) /*!< MVFR1: FP fused MAC bits Mask */
+
+#define FPU_MVFR1_FP_HPFP_Pos 24U /*!< MVFR1: FP HPFP bits Position */
+#define FPU_MVFR1_FP_HPFP_Msk (0xFUL << FPU_MVFR1_FP_HPFP_Pos) /*!< MVFR1: FP HPFP bits Mask */
+
+#define FPU_MVFR1_D_NaN_mode_Pos 4U /*!< MVFR1: D_NaN mode bits Position */
+#define FPU_MVFR1_D_NaN_mode_Msk (0xFUL << FPU_MVFR1_D_NaN_mode_Pos) /*!< MVFR1: D_NaN mode bits Mask */
+
+#define FPU_MVFR1_FtZ_mode_Pos 0U /*!< MVFR1: FtZ mode bits Position */
+#define FPU_MVFR1_FtZ_mode_Msk (0xFUL /*<< FPU_MVFR1_FtZ_mode_Pos*/) /*!< MVFR1: FtZ mode bits Mask */
+
+/*@} end of group CMSIS_FPU */
+
+
+/**
+ \ingroup CMSIS_core_register
+ \defgroup CMSIS_CoreDebug Core Debug Registers (CoreDebug)
+ \brief Type definitions for the Core Debug Registers
+ @{
+ */
+
+/**
+ \brief Structure type to access the Core Debug Register (CoreDebug).
+ */
+typedef struct
+{
+ __IOM uint32_t DHCSR; /*!< Offset: 0x000 (R/W) Debug Halting Control and Status Register */
+ __OM uint32_t DCRSR; /*!< Offset: 0x004 ( /W) Debug Core Register Selector Register */
+ __IOM uint32_t DCRDR; /*!< Offset: 0x008 (R/W) Debug Core Register Data Register */
+ __IOM uint32_t DEMCR; /*!< Offset: 0x00C (R/W) Debug Exception and Monitor Control Register */
+ uint32_t RESERVED4[1U];
+ __IOM uint32_t DAUTHCTRL; /*!< Offset: 0x014 (R/W) Debug Authentication Control Register */
+ __IOM uint32_t DSCSR; /*!< Offset: 0x018 (R/W) Debug Security Control and Status Register */
+} CoreDebug_Type;
+
+/* Debug Halting Control and Status Register Definitions */
+#define CoreDebug_DHCSR_DBGKEY_Pos 16U /*!< CoreDebug DHCSR: DBGKEY Position */
+#define CoreDebug_DHCSR_DBGKEY_Msk (0xFFFFUL << CoreDebug_DHCSR_DBGKEY_Pos) /*!< CoreDebug DHCSR: DBGKEY Mask */
+
+#define CoreDebug_DHCSR_S_RESTART_ST_Pos 26U /*!< CoreDebug DHCSR: S_RESTART_ST Position */
+#define CoreDebug_DHCSR_S_RESTART_ST_Msk (1UL << CoreDebug_DHCSR_S_RESTART_ST_Pos) /*!< CoreDebug DHCSR: S_RESTART_ST Mask */
+
+#define CoreDebug_DHCSR_S_RESET_ST_Pos 25U /*!< CoreDebug DHCSR: S_RESET_ST Position */
+#define CoreDebug_DHCSR_S_RESET_ST_Msk (1UL << CoreDebug_DHCSR_S_RESET_ST_Pos) /*!< CoreDebug DHCSR: S_RESET_ST Mask */
+
+#define CoreDebug_DHCSR_S_RETIRE_ST_Pos 24U /*!< CoreDebug DHCSR: S_RETIRE_ST Position */
+#define CoreDebug_DHCSR_S_RETIRE_ST_Msk (1UL << CoreDebug_DHCSR_S_RETIRE_ST_Pos) /*!< CoreDebug DHCSR: S_RETIRE_ST Mask */
+
+#define CoreDebug_DHCSR_S_LOCKUP_Pos 19U /*!< CoreDebug DHCSR: S_LOCKUP Position */
+#define CoreDebug_DHCSR_S_LOCKUP_Msk (1UL << CoreDebug_DHCSR_S_LOCKUP_Pos) /*!< CoreDebug DHCSR: S_LOCKUP Mask */
+
+#define CoreDebug_DHCSR_S_SLEEP_Pos 18U /*!< CoreDebug DHCSR: S_SLEEP Position */
+#define CoreDebug_DHCSR_S_SLEEP_Msk (1UL << CoreDebug_DHCSR_S_SLEEP_Pos) /*!< CoreDebug DHCSR: S_SLEEP Mask */
+
+#define CoreDebug_DHCSR_S_HALT_Pos 17U /*!< CoreDebug DHCSR: S_HALT Position */
+#define CoreDebug_DHCSR_S_HALT_Msk (1UL << CoreDebug_DHCSR_S_HALT_Pos) /*!< CoreDebug DHCSR: S_HALT Mask */
+
+#define CoreDebug_DHCSR_S_REGRDY_Pos 16U /*!< CoreDebug DHCSR: S_REGRDY Position */
+#define CoreDebug_DHCSR_S_REGRDY_Msk (1UL << CoreDebug_DHCSR_S_REGRDY_Pos) /*!< CoreDebug DHCSR: S_REGRDY Mask */
+
+#define CoreDebug_DHCSR_C_SNAPSTALL_Pos 5U /*!< CoreDebug DHCSR: C_SNAPSTALL Position */
+#define CoreDebug_DHCSR_C_SNAPSTALL_Msk (1UL << CoreDebug_DHCSR_C_SNAPSTALL_Pos) /*!< CoreDebug DHCSR: C_SNAPSTALL Mask */
+
+#define CoreDebug_DHCSR_C_MASKINTS_Pos 3U /*!< CoreDebug DHCSR: C_MASKINTS Position */
+#define CoreDebug_DHCSR_C_MASKINTS_Msk (1UL << CoreDebug_DHCSR_C_MASKINTS_Pos) /*!< CoreDebug DHCSR: C_MASKINTS Mask */
+
+#define CoreDebug_DHCSR_C_STEP_Pos 2U /*!< CoreDebug DHCSR: C_STEP Position */
+#define CoreDebug_DHCSR_C_STEP_Msk (1UL << CoreDebug_DHCSR_C_STEP_Pos) /*!< CoreDebug DHCSR: C_STEP Mask */
+
+#define CoreDebug_DHCSR_C_HALT_Pos 1U /*!< CoreDebug DHCSR: C_HALT Position */
+#define CoreDebug_DHCSR_C_HALT_Msk (1UL << CoreDebug_DHCSR_C_HALT_Pos) /*!< CoreDebug DHCSR: C_HALT Mask */
+
+#define CoreDebug_DHCSR_C_DEBUGEN_Pos 0U /*!< CoreDebug DHCSR: C_DEBUGEN Position */
+#define CoreDebug_DHCSR_C_DEBUGEN_Msk (1UL /*<< CoreDebug_DHCSR_C_DEBUGEN_Pos*/) /*!< CoreDebug DHCSR: C_DEBUGEN Mask */
+
+/* Debug Core Register Selector Register Definitions */
+#define CoreDebug_DCRSR_REGWnR_Pos 16U /*!< CoreDebug DCRSR: REGWnR Position */
+#define CoreDebug_DCRSR_REGWnR_Msk (1UL << CoreDebug_DCRSR_REGWnR_Pos) /*!< CoreDebug DCRSR: REGWnR Mask */
+
+#define CoreDebug_DCRSR_REGSEL_Pos 0U /*!< CoreDebug DCRSR: REGSEL Position */
+#define CoreDebug_DCRSR_REGSEL_Msk (0x1FUL /*<< CoreDebug_DCRSR_REGSEL_Pos*/) /*!< CoreDebug DCRSR: REGSEL Mask */
+
+/* Debug Exception and Monitor Control Register Definitions */
+#define CoreDebug_DEMCR_TRCENA_Pos 24U /*!< CoreDebug DEMCR: TRCENA Position */
+#define CoreDebug_DEMCR_TRCENA_Msk (1UL << CoreDebug_DEMCR_TRCENA_Pos) /*!< CoreDebug DEMCR: TRCENA Mask */
+
+#define CoreDebug_DEMCR_MON_REQ_Pos 19U /*!< CoreDebug DEMCR: MON_REQ Position */
+#define CoreDebug_DEMCR_MON_REQ_Msk (1UL << CoreDebug_DEMCR_MON_REQ_Pos) /*!< CoreDebug DEMCR: MON_REQ Mask */
+
+#define CoreDebug_DEMCR_MON_STEP_Pos 18U /*!< CoreDebug DEMCR: MON_STEP Position */
+#define CoreDebug_DEMCR_MON_STEP_Msk (1UL << CoreDebug_DEMCR_MON_STEP_Pos) /*!< CoreDebug DEMCR: MON_STEP Mask */
+
+#define CoreDebug_DEMCR_MON_PEND_Pos 17U /*!< CoreDebug DEMCR: MON_PEND Position */
+#define CoreDebug_DEMCR_MON_PEND_Msk (1UL << CoreDebug_DEMCR_MON_PEND_Pos) /*!< CoreDebug DEMCR: MON_PEND Mask */
+
+#define CoreDebug_DEMCR_MON_EN_Pos 16U /*!< CoreDebug DEMCR: MON_EN Position */
+#define CoreDebug_DEMCR_MON_EN_Msk (1UL << CoreDebug_DEMCR_MON_EN_Pos) /*!< CoreDebug DEMCR: MON_EN Mask */
+
+#define CoreDebug_DEMCR_VC_HARDERR_Pos 10U /*!< CoreDebug DEMCR: VC_HARDERR Position */
+#define CoreDebug_DEMCR_VC_HARDERR_Msk (1UL << CoreDebug_DEMCR_VC_HARDERR_Pos) /*!< CoreDebug DEMCR: VC_HARDERR Mask */
+
+#define CoreDebug_DEMCR_VC_INTERR_Pos 9U /*!< CoreDebug DEMCR: VC_INTERR Position */
+#define CoreDebug_DEMCR_VC_INTERR_Msk (1UL << CoreDebug_DEMCR_VC_INTERR_Pos) /*!< CoreDebug DEMCR: VC_INTERR Mask */
+
+#define CoreDebug_DEMCR_VC_BUSERR_Pos 8U /*!< CoreDebug DEMCR: VC_BUSERR Position */
+#define CoreDebug_DEMCR_VC_BUSERR_Msk (1UL << CoreDebug_DEMCR_VC_BUSERR_Pos) /*!< CoreDebug DEMCR: VC_BUSERR Mask */
+
+#define CoreDebug_DEMCR_VC_STATERR_Pos 7U /*!< CoreDebug DEMCR: VC_STATERR Position */
+#define CoreDebug_DEMCR_VC_STATERR_Msk (1UL << CoreDebug_DEMCR_VC_STATERR_Pos) /*!< CoreDebug DEMCR: VC_STATERR Mask */
+
+#define CoreDebug_DEMCR_VC_CHKERR_Pos 6U /*!< CoreDebug DEMCR: VC_CHKERR Position */
+#define CoreDebug_DEMCR_VC_CHKERR_Msk (1UL << CoreDebug_DEMCR_VC_CHKERR_Pos) /*!< CoreDebug DEMCR: VC_CHKERR Mask */
+
+#define CoreDebug_DEMCR_VC_NOCPERR_Pos 5U /*!< CoreDebug DEMCR: VC_NOCPERR Position */
+#define CoreDebug_DEMCR_VC_NOCPERR_Msk (1UL << CoreDebug_DEMCR_VC_NOCPERR_Pos) /*!< CoreDebug DEMCR: VC_NOCPERR Mask */
+
+#define CoreDebug_DEMCR_VC_MMERR_Pos 4U /*!< CoreDebug DEMCR: VC_MMERR Position */
+#define CoreDebug_DEMCR_VC_MMERR_Msk (1UL << CoreDebug_DEMCR_VC_MMERR_Pos) /*!< CoreDebug DEMCR: VC_MMERR Mask */
+
+#define CoreDebug_DEMCR_VC_CORERESET_Pos 0U /*!< CoreDebug DEMCR: VC_CORERESET Position */
+#define CoreDebug_DEMCR_VC_CORERESET_Msk (1UL /*<< CoreDebug_DEMCR_VC_CORERESET_Pos*/) /*!< CoreDebug DEMCR: VC_CORERESET Mask */
+
+/* Debug Authentication Control Register Definitions */
+#define CoreDebug_DAUTHCTRL_INTSPNIDEN_Pos 3U /*!< CoreDebug DAUTHCTRL: INTSPNIDEN, Position */
+#define CoreDebug_DAUTHCTRL_INTSPNIDEN_Msk (1UL << CoreDebug_DAUTHCTRL_INTSPNIDEN_Pos) /*!< CoreDebug DAUTHCTRL: INTSPNIDEN, Mask */
+
+#define CoreDebug_DAUTHCTRL_SPNIDENSEL_Pos 2U /*!< CoreDebug DAUTHCTRL: SPNIDENSEL Position */
+#define CoreDebug_DAUTHCTRL_SPNIDENSEL_Msk (1UL << CoreDebug_DAUTHCTRL_SPNIDENSEL_Pos) /*!< CoreDebug DAUTHCTRL: SPNIDENSEL Mask */
+
+#define CoreDebug_DAUTHCTRL_INTSPIDEN_Pos 1U /*!< CoreDebug DAUTHCTRL: INTSPIDEN Position */
+#define CoreDebug_DAUTHCTRL_INTSPIDEN_Msk (1UL << CoreDebug_DAUTHCTRL_INTSPIDEN_Pos) /*!< CoreDebug DAUTHCTRL: INTSPIDEN Mask */
+
+#define CoreDebug_DAUTHCTRL_SPIDENSEL_Pos 0U /*!< CoreDebug DAUTHCTRL: SPIDENSEL Position */
+#define CoreDebug_DAUTHCTRL_SPIDENSEL_Msk (1UL /*<< CoreDebug_DAUTHCTRL_SPIDENSEL_Pos*/) /*!< CoreDebug DAUTHCTRL: SPIDENSEL Mask */
+
+/* Debug Security Control and Status Register Definitions */
+#define CoreDebug_DSCSR_CDS_Pos 16U /*!< CoreDebug DSCSR: CDS Position */
+#define CoreDebug_DSCSR_CDS_Msk (1UL << CoreDebug_DSCSR_CDS_Pos) /*!< CoreDebug DSCSR: CDS Mask */
+
+#define CoreDebug_DSCSR_SBRSEL_Pos 1U /*!< CoreDebug DSCSR: SBRSEL Position */
+#define CoreDebug_DSCSR_SBRSEL_Msk (1UL << CoreDebug_DSCSR_SBRSEL_Pos) /*!< CoreDebug DSCSR: SBRSEL Mask */
+
+#define CoreDebug_DSCSR_SBRSELEN_Pos 0U /*!< CoreDebug DSCSR: SBRSELEN Position */
+#define CoreDebug_DSCSR_SBRSELEN_Msk (1UL /*<< CoreDebug_DSCSR_SBRSELEN_Pos*/) /*!< CoreDebug DSCSR: SBRSELEN Mask */
+
+/*@} 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 ITM_BASE (0xE0000000UL) /*!< ITM Base Address */
+ #define DWT_BASE (0xE0001000UL) /*!< DWT Base Address */
+ #define TPI_BASE (0xE0040000UL) /*!< TPI Base Address */
+ #define CoreDebug_BASE (0xE000EDF0UL) /*!< Core Debug 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 SCnSCB ((SCnSCB_Type *) SCS_BASE ) /*!< System control Register not in SCB */
+ #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 */
+ #define ITM ((ITM_Type *) ITM_BASE ) /*!< ITM configuration struct */
+ #define DWT ((DWT_Type *) DWT_BASE ) /*!< DWT configuration struct */
+ #define TPI ((TPI_Type *) TPI_BASE ) /*!< TPI configuration struct */
+ #define CoreDebug ((CoreDebug_Type *) CoreDebug_BASE ) /*!< Core Debug configuration struct */
+
+ #if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U)
+ #define MPU_BASE (SCS_BASE + 0x0D90UL) /*!< Memory Protection Unit */
+ #define MPU ((MPU_Type *) MPU_BASE ) /*!< Memory Protection Unit */
+ #endif
+
+ #if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U)
+ #define SAU_BASE (SCS_BASE + 0x0DD0UL) /*!< Security Attribution Unit */
+ #define SAU ((SAU_Type *) SAU_BASE ) /*!< Security Attribution Unit */
+ #endif
+
+ #define FPU_BASE (SCS_BASE + 0x0F30UL) /*!< Floating Point Unit */
+ #define FPU ((FPU_Type *) FPU_BASE ) /*!< Floating Point Unit */
+
+#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U)
+ #define SCS_BASE_NS (0xE002E000UL) /*!< System Control Space Base Address (non-secure address space) */
+ #define CoreDebug_BASE_NS (0xE002EDF0UL) /*!< Core Debug Base Address (non-secure address space) */
+ #define SysTick_BASE_NS (SCS_BASE_NS + 0x0010UL) /*!< SysTick Base Address (non-secure address space) */
+ #define NVIC_BASE_NS (SCS_BASE_NS + 0x0100UL) /*!< NVIC Base Address (non-secure address space) */
+ #define SCB_BASE_NS (SCS_BASE_NS + 0x0D00UL) /*!< System Control Block Base Address (non-secure address space) */
+
+ #define SCnSCB_NS ((SCnSCB_Type *) SCS_BASE_NS ) /*!< System control Register not in SCB(non-secure address space) */
+ #define SCB_NS ((SCB_Type *) SCB_BASE_NS ) /*!< SCB configuration struct (non-secure address space) */
+ #define SysTick_NS ((SysTick_Type *) SysTick_BASE_NS ) /*!< SysTick configuration struct (non-secure address space) */
+ #define NVIC_NS ((NVIC_Type *) NVIC_BASE_NS ) /*!< NVIC configuration struct (non-secure address space) */
+ #define CoreDebug_NS ((CoreDebug_Type *) CoreDebug_BASE_NS) /*!< Core Debug configuration struct (non-secure address space) */
+
+ #if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U)
+ #define MPU_BASE_NS (SCS_BASE_NS + 0x0D90UL) /*!< Memory Protection Unit (non-secure address space) */
+ #define MPU_NS ((MPU_Type *) MPU_BASE_NS ) /*!< Memory Protection Unit (non-secure address space) */
+ #endif
+
+ #define FPU_BASE_NS (SCS_BASE_NS + 0x0F30UL) /*!< Floating Point Unit (non-secure address space) */
+ #define FPU_NS ((FPU_Type *) FPU_BASE_NS ) /*!< Floating Point Unit (non-secure address space) */
+
+#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */
+/*@} */
+
+
+
+/*******************************************************************************
+ * Hardware Abstraction Layer
+ Core Function Interface contains:
+ - Core NVIC Functions
+ - Core SysTick Functions
+ - Core Debug 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
+ #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
+
+
+
+/**
+ \brief Set Priority Grouping
+ \details Sets the priority grouping field using the required unlock sequence.
+ The parameter PriorityGroup is assigned to the field SCB->AIRCR [10:8] PRIGROUP field.
+ Only values from 0..7 are used.
+ 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 Priority grouping field.
+ */
+__STATIC_INLINE void __NVIC_SetPriorityGrouping(uint32_t PriorityGroup)
+{
+ uint32_t reg_value;
+ uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */
+
+ reg_value = SCB->AIRCR; /* read old register configuration */
+ reg_value &= ~((uint32_t)(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk)); /* clear bits to change */
+ reg_value = (reg_value |
+ ((uint32_t)0x5FAUL << SCB_AIRCR_VECTKEY_Pos) |
+ (PriorityGroupTmp << 8U) ); /* Insert write key and priorty group */
+ SCB->AIRCR = reg_value;
+}
+
+
+/**
+ \brief Get Priority Grouping
+ \details Reads the priority grouping field from the NVIC Interrupt Controller.
+ \return Priority grouping field (SCB->AIRCR [10:8] PRIGROUP field).
+ */
+__STATIC_INLINE uint32_t __NVIC_GetPriorityGrouping(void)
+{
+ return ((uint32_t)((SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) >> SCB_AIRCR_PRIGROUP_Pos));
+}
+
+
+/**
+ \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[(((uint32_t)IRQn) >> 5UL)] = (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[(((uint32_t)IRQn) >> 5UL)] & (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[(((uint32_t)IRQn) >> 5UL)] = (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[(((uint32_t)IRQn) >> 5UL)] & (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[(((uint32_t)IRQn) >> 5UL)] = (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[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL));
+ }
+}
+
+
+/**
+ \brief Get Active Interrupt
+ \details Reads the active register in the NVIC and returns the active bit for the device specific interrupt.
+ \param [in] IRQn Device specific interrupt number.
+ \return 0 Interrupt status is not active.
+ \return 1 Interrupt status is active.
+ \note IRQn must not be negative.
+ */
+__STATIC_INLINE uint32_t __NVIC_GetActive(IRQn_Type IRQn)
+{
+ if ((int32_t)(IRQn) >= 0)
+ {
+ return((uint32_t)(((NVIC->IABR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL));
+ }
+ else
+ {
+ return(0U);
+ }
+}
+
+
+#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U)
+/**
+ \brief Get Interrupt Target State
+ \details Reads the interrupt target field in the NVIC and returns the interrupt target bit for the device specific interrupt.
+ \param [in] IRQn Device specific interrupt number.
+ \return 0 if interrupt is assigned to Secure
+ \return 1 if interrupt is assigned to Non Secure
+ \note IRQn must not be negative.
+ */
+__STATIC_INLINE uint32_t NVIC_GetTargetState(IRQn_Type IRQn)
+{
+ if ((int32_t)(IRQn) >= 0)
+ {
+ return((uint32_t)(((NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL));
+ }
+ else
+ {
+ return(0U);
+ }
+}
+
+
+/**
+ \brief Set Interrupt Target State
+ \details Sets the interrupt target field in the NVIC and returns the interrupt target bit for the device specific interrupt.
+ \param [in] IRQn Device specific interrupt number.
+ \return 0 if interrupt is assigned to Secure
+ 1 if interrupt is assigned to Non Secure
+ \note IRQn must not be negative.
+ */
+__STATIC_INLINE uint32_t NVIC_SetTargetState(IRQn_Type IRQn)
+{
+ if ((int32_t)(IRQn) >= 0)
+ {
+ NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] |= ((uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)));
+ return((uint32_t)(((NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL));
+ }
+ else
+ {
+ return(0U);
+ }
+}
+
+
+/**
+ \brief Clear Interrupt Target State
+ \details Clears the interrupt target field in the NVIC and returns the interrupt target bit for the device specific interrupt.
+ \param [in] IRQn Device specific interrupt number.
+ \return 0 if interrupt is assigned to Secure
+ 1 if interrupt is assigned to Non Secure
+ \note IRQn must not be negative.
+ */
+__STATIC_INLINE uint32_t NVIC_ClearTargetState(IRQn_Type IRQn)
+{
+ if ((int32_t)(IRQn) >= 0)
+ {
+ NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] &= ~((uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)));
+ return((uint32_t)(((NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL));
+ }
+ else
+ {
+ return(0U);
+ }
+}
+#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */
+
+
+/**
+ \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->IPR[((uint32_t)IRQn)] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL);
+ }
+ else
+ {
+ SCB->SHPR[(((uint32_t)IRQn) & 0xFUL)-4UL] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL);
+ }
+}
+
+
+/**
+ \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->IPR[((uint32_t)IRQn)] >> (8U - __NVIC_PRIO_BITS)));
+ }
+ else
+ {
+ return(((uint32_t)SCB->SHPR[(((uint32_t)IRQn) & 0xFUL)-4UL] >> (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.
+ VTOR must been relocated to SRAM before.
+ \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 *)SCB->VTOR;
+ 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 *)SCB->VTOR;
+ return vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET];
+}
+
+
+/**
+ \brief System Reset
+ \details Initiates a system reset request to reset the MCU.
+ */
+__STATIC_INLINE void __NVIC_SystemReset(void)
+{
+ __DSB(); /* Ensure all outstanding memory accesses included
+ buffered write are completed before reset */
+ SCB->AIRCR = (uint32_t)((0x5FAUL << SCB_AIRCR_VECTKEY_Pos) |
+ (SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) |
+ SCB_AIRCR_SYSRESETREQ_Msk ); /* Keep priority group unchanged */
+ __DSB(); /* Ensure completion of memory access */
+
+ for(;;) /* wait until reset */
+ {
+ __NOP();
+ }
+}
+
+#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U)
+/**
+ \brief Set Priority Grouping (non-secure)
+ \details Sets the non-secure priority grouping field when in secure state using the required unlock sequence.
+ The parameter PriorityGroup is assigned to the field SCB->AIRCR [10:8] PRIGROUP field.
+ Only values from 0..7 are used.
+ 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 Priority grouping field.
+ */
+__STATIC_INLINE void TZ_NVIC_SetPriorityGrouping_NS(uint32_t PriorityGroup)
+{
+ uint32_t reg_value;
+ uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */
+
+ reg_value = SCB_NS->AIRCR; /* read old register configuration */
+ reg_value &= ~((uint32_t)(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk)); /* clear bits to change */
+ reg_value = (reg_value |
+ ((uint32_t)0x5FAUL << SCB_AIRCR_VECTKEY_Pos) |
+ (PriorityGroupTmp << 8U) ); /* Insert write key and priorty group */
+ SCB_NS->AIRCR = reg_value;
+}
+
+
+/**
+ \brief Get Priority Grouping (non-secure)
+ \details Reads the priority grouping field from the non-secure NVIC when in secure state.
+ \return Priority grouping field (SCB->AIRCR [10:8] PRIGROUP field).
+ */
+__STATIC_INLINE uint32_t TZ_NVIC_GetPriorityGrouping_NS(void)
+{
+ return ((uint32_t)((SCB_NS->AIRCR & SCB_AIRCR_PRIGROUP_Msk) >> SCB_AIRCR_PRIGROUP_Pos));
+}
+
+
+/**
+ \brief Enable Interrupt (non-secure)
+ \details Enables a device specific interrupt in the non-secure NVIC interrupt controller when in secure state.
+ \param [in] IRQn Device specific interrupt number.
+ \note IRQn must not be negative.
+ */
+__STATIC_INLINE void TZ_NVIC_EnableIRQ_NS(IRQn_Type IRQn)
+{
+ if ((int32_t)(IRQn) >= 0)
+ {
+ NVIC_NS->ISER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL));
+ }
+}
+
+
+/**
+ \brief Get Interrupt Enable status (non-secure)
+ \details Returns a device specific interrupt enable status from the non-secure NVIC interrupt controller when in secure state.
+ \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 TZ_NVIC_GetEnableIRQ_NS(IRQn_Type IRQn)
+{
+ if ((int32_t)(IRQn) >= 0)
+ {
+ return((uint32_t)(((NVIC_NS->ISER[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL));
+ }
+ else
+ {
+ return(0U);
+ }
+}
+
+
+/**
+ \brief Disable Interrupt (non-secure)
+ \details Disables a device specific interrupt in the non-secure NVIC interrupt controller when in secure state.
+ \param [in] IRQn Device specific interrupt number.
+ \note IRQn must not be negative.
+ */
+__STATIC_INLINE void TZ_NVIC_DisableIRQ_NS(IRQn_Type IRQn)
+{
+ if ((int32_t)(IRQn) >= 0)
+ {
+ NVIC_NS->ICER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL));
+ }
+}
+
+
+/**
+ \brief Get Pending Interrupt (non-secure)
+ \details Reads the NVIC pending register in the non-secure NVIC when in secure state 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 TZ_NVIC_GetPendingIRQ_NS(IRQn_Type IRQn)
+{
+ if ((int32_t)(IRQn) >= 0)
+ {
+ return((uint32_t)(((NVIC_NS->ISPR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL));
+ }
+ else
+ {
+ return(0U);
+ }
+}
+
+
+/**
+ \brief Set Pending Interrupt (non-secure)
+ \details Sets the pending bit of a device specific interrupt in the non-secure NVIC pending register when in secure state.
+ \param [in] IRQn Device specific interrupt number.
+ \note IRQn must not be negative.
+ */
+__STATIC_INLINE void TZ_NVIC_SetPendingIRQ_NS(IRQn_Type IRQn)
+{
+ if ((int32_t)(IRQn) >= 0)
+ {
+ NVIC_NS->ISPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL));
+ }
+}
+
+
+/**
+ \brief Clear Pending Interrupt (non-secure)
+ \details Clears the pending bit of a device specific interrupt in the non-secure NVIC pending register when in secure state.
+ \param [in] IRQn Device specific interrupt number.
+ \note IRQn must not be negative.
+ */
+__STATIC_INLINE void TZ_NVIC_ClearPendingIRQ_NS(IRQn_Type IRQn)
+{
+ if ((int32_t)(IRQn) >= 0)
+ {
+ NVIC_NS->ICPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL));
+ }
+}
+
+
+/**
+ \brief Get Active Interrupt (non-secure)
+ \details Reads the active register in non-secure NVIC when in secure state and returns the active bit for the device specific interrupt.
+ \param [in] IRQn Device specific interrupt number.
+ \return 0 Interrupt status is not active.
+ \return 1 Interrupt status is active.
+ \note IRQn must not be negative.
+ */
+__STATIC_INLINE uint32_t TZ_NVIC_GetActive_NS(IRQn_Type IRQn)
+{
+ if ((int32_t)(IRQn) >= 0)
+ {
+ return((uint32_t)(((NVIC_NS->IABR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL));
+ }
+ else
+ {
+ return(0U);
+ }
+}
+
+
+/**
+ \brief Set Interrupt Priority (non-secure)
+ \details Sets the priority of a non-secure device specific interrupt or a non-secure processor exception when in secure state.
+ 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 non-secure processor exception.
+ */
+__STATIC_INLINE void TZ_NVIC_SetPriority_NS(IRQn_Type IRQn, uint32_t priority)
+{
+ if ((int32_t)(IRQn) >= 0)
+ {
+ NVIC_NS->IPR[((uint32_t)IRQn)] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL);
+ }
+ else
+ {
+ SCB_NS->SHPR[(((uint32_t)IRQn) & 0xFUL)-4UL] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL);
+ }
+}
+
+
+/**
+ \brief Get Interrupt Priority (non-secure)
+ \details Reads the priority of a non-secure device specific interrupt or a non-secure processor exception when in secure state.
+ 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 TZ_NVIC_GetPriority_NS(IRQn_Type IRQn)
+{
+
+ if ((int32_t)(IRQn) >= 0)
+ {
+ return(((uint32_t)NVIC_NS->IPR[((uint32_t)IRQn)] >> (8U - __NVIC_PRIO_BITS)));
+ }
+ else
+ {
+ return(((uint32_t)SCB_NS->SHPR[(((uint32_t)IRQn) & 0xFUL)-4UL] >> (8U - __NVIC_PRIO_BITS)));
+ }
+}
+#endif /* defined (__ARM_FEATURE_CMSE) &&(__ARM_FEATURE_CMSE == 3U) */
+
+/*@} end of CMSIS_Core_NVICFunctions */
+
+/* ########################## MPU functions #################################### */
+
+#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U)
+
+#include "mpu_armv8.h"
+
+#endif
+
+/* ########################## 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)
+{
+ uint32_t mvfr0;
+
+ mvfr0 = FPU->MVFR0;
+ if ((mvfr0 & (FPU_MVFR0_Single_precision_Msk | FPU_MVFR0_Double_precision_Msk)) == 0x220U)
+ {
+ return 2U; /* Double + Single precision FPU */
+ }
+ else if ((mvfr0 & (FPU_MVFR0_Single_precision_Msk | FPU_MVFR0_Double_precision_Msk)) == 0x020U)
+ {
+ return 1U; /* Single precision FPU */
+ }
+ else
+ {
+ return 0U; /* No FPU */
+ }
+}
+
+
+/*@} end of CMSIS_Core_FpuFunctions */
+
+
+
+/* ########################## SAU functions #################################### */
+/**
+ \ingroup CMSIS_Core_FunctionInterface
+ \defgroup CMSIS_Core_SAUFunctions SAU Functions
+ \brief Functions that configure the SAU.
+ @{
+ */
+
+#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U)
+
+/**
+ \brief Enable SAU
+ \details Enables the Security Attribution Unit (SAU).
+ */
+__STATIC_INLINE void TZ_SAU_Enable(void)
+{
+ SAU->CTRL |= (SAU_CTRL_ENABLE_Msk);
+}
+
+
+
+/**
+ \brief Disable SAU
+ \details Disables the Security Attribution Unit (SAU).
+ */
+__STATIC_INLINE void TZ_SAU_Disable(void)
+{
+ SAU->CTRL &= ~(SAU_CTRL_ENABLE_Msk);
+}
+
+#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */
+
+/*@} end of CMSIS_Core_SAUFunctions */
+
+
+
+
+/* ################################## 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 <b>__Vendor_SysTickConfig</b> is set to 1, then the
+ function <b>SysTick_Config</b> is not included. In this case, the file <b><i>device</i>.h</b>
+ 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 */
+}
+
+#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U)
+/**
+ \brief System Tick Configuration (non-secure)
+ \details Initializes the non-secure System Timer and its interrupt when in secure state, 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 <b>__Vendor_SysTickConfig</b> is set to 1, then the
+ function <b>TZ_SysTick_Config_NS</b> is not included. In this case, the file <b><i>device</i>.h</b>
+ must contain a vendor-specific implementation of this function.
+
+ */
+__STATIC_INLINE uint32_t TZ_SysTick_Config_NS(uint32_t ticks)
+{
+ if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk)
+ {
+ return (1UL); /* Reload value impossible */
+ }
+
+ SysTick_NS->LOAD = (uint32_t)(ticks - 1UL); /* set reload register */
+ TZ_NVIC_SetPriority_NS (SysTick_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL); /* set Priority for Systick Interrupt */
+ SysTick_NS->VAL = 0UL; /* Load the SysTick Counter Value */
+ SysTick_NS->CTRL = SysTick_CTRL_CLKSOURCE_Msk |
+ SysTick_CTRL_TICKINT_Msk |
+ SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */
+ return (0UL); /* Function successful */
+}
+#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */
+
+#endif
+
+/*@} end of CMSIS_Core_SysTickFunctions */
+
+
+
+/* ##################################### Debug In/Output function ########################################### */
+/**
+ \ingroup CMSIS_Core_FunctionInterface
+ \defgroup CMSIS_core_DebugFunctions ITM Functions
+ \brief Functions that access the ITM debug interface.
+ @{
+ */
+
+extern volatile int32_t ITM_RxBuffer; /*!< External variable to receive characters. */
+#define ITM_RXBUFFER_EMPTY ((int32_t)0x5AA55AA5U) /*!< Value identifying \ref ITM_RxBuffer is ready for next character. */
+
+
+/**
+ \brief ITM Send Character
+ \details Transmits a character via the ITM channel 0, and
+ \li Just returns when no debugger is connected that has booked the output.
+ \li Is blocking when a debugger is connected, but the previous character sent has not been transmitted.
+ \param [in] ch Character to transmit.
+ \returns Character to transmit.
+ */
+__STATIC_INLINE uint32_t ITM_SendChar (uint32_t ch)
+{
+ if (((ITM->TCR & ITM_TCR_ITMENA_Msk) != 0UL) && /* ITM enabled */
+ ((ITM->TER & 1UL ) != 0UL) ) /* ITM Port #0 enabled */
+ {
+ while (ITM->PORT[0U].u32 == 0UL)
+ {
+ __NOP();
+ }
+ ITM->PORT[0U].u8 = (uint8_t)ch;
+ }
+ return (ch);
+}
+
+
+/**
+ \brief ITM Receive Character
+ \details Inputs a character via the external variable \ref ITM_RxBuffer.
+ \return Received character.
+ \return -1 No character pending.
+ */
+__STATIC_INLINE int32_t ITM_ReceiveChar (void)
+{
+ int32_t ch = -1; /* no character available */
+
+ if (ITM_RxBuffer != ITM_RXBUFFER_EMPTY)
+ {
+ ch = ITM_RxBuffer;
+ ITM_RxBuffer = ITM_RXBUFFER_EMPTY; /* ready for next character */
+ }
+
+ return (ch);
+}
+
+
+/**
+ \brief ITM Check Character
+ \details Checks whether a character is pending for reading in the variable \ref ITM_RxBuffer.
+ \return 0 No character available.
+ \return 1 Character available.
+ */
+__STATIC_INLINE int32_t ITM_CheckChar (void)
+{
+
+ if (ITM_RxBuffer == ITM_RXBUFFER_EMPTY)
+ {
+ return (0); /* no character available */
+ }
+ else
+ {
+ return (1); /* character available */
+ }
+}
+
+/*@} end of CMSIS_core_DebugFunctions */
+
+
+
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __CORE_ARMV8MML_H_DEPENDANT */
+
+#endif /* __CMSIS_GENERIC */
diff --git a/CMSIS/core_cm4.h b/CMSIS/core_cm4.h
new file mode 100644
index 0000000..a11a381
--- /dev/null
+++ b/CMSIS/core_cm4.h
@@ -0,0 +1,2118 @@
+/**************************************************************************//**
+ * @file core_cm4.h
+ * @brief CMSIS Cortex-M4 Core Peripheral Access Layer Header File
+ * @version V5.0.5
+ * @date 08. January 2018
+ ******************************************************************************/
+/*
+ * 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 __CORE_CM4_H_GENERIC
+#define __CORE_CM4_H_GENERIC
+
+#include <stdint.h>
+
+#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.<br>
+ Function definitions in header files are used to allow 'inlining'.
+
+ \li Required Rule 18.4, declaration of union type or object of union type: '{...}'.<br>
+ Unions are used for effective representation of core registers.
+
+ \li Advisory Rule 19.7, Function-like macro defined.<br>
+ Function-like macros are used to allow more efficient code.
+ */
+
+
+/*******************************************************************************
+ * CMSIS definitions
+ ******************************************************************************/
+/**
+ \ingroup Cortex_M4
+ @{
+ */
+
+#include "cmsis_version.h"
+
+/* CMSIS CM4 definitions */
+#define __CM4_CMSIS_VERSION_MAIN (__CM_CMSIS_VERSION_MAIN) /*!< \deprecated [31:16] CMSIS HAL main version */
+#define __CM4_CMSIS_VERSION_SUB (__CM_CMSIS_VERSION_SUB) /*!< \deprecated [15:0] CMSIS HAL sub version */
+#define __CM4_CMSIS_VERSION ((__CM4_CMSIS_VERSION_MAIN << 16U) | \
+ __CM4_CMSIS_VERSION_SUB ) /*!< \deprecated CMSIS HAL version number */
+
+#define __CORTEX_M (4U) /*!< Cortex-M Core */
+
+/** __FPU_USED indicates whether an FPU is used or not.
+ For this, __FPU_PRESENT has to be checked prior to making use of FPU specific registers and functions.
+*/
+#if defined ( __CC_ARM )
+ #if defined __TARGET_FPU_VFP
+ #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)
+ #define __FPU_USED 1U
+ #else
+ #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)"
+ #define __FPU_USED 0U
+ #endif
+ #else
+ #define __FPU_USED 0U
+ #endif
+
+#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
+ #if defined __ARM_PCS_VFP
+ #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)
+ #define __FPU_USED 1U
+ #else
+ #warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)"
+ #define __FPU_USED 0U
+ #endif
+ #else
+ #define __FPU_USED 0U
+ #endif
+
+#elif defined ( __GNUC__ )
+ #if defined (__VFP_FP__) && !defined(__SOFTFP__)
+ #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)
+ #define __FPU_USED 1U
+ #else
+ #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)"
+ #define __FPU_USED 0U
+ #endif
+ #else
+ #define __FPU_USED 0U
+ #endif
+
+#elif defined ( __ICCARM__ )
+ #if defined __ARMVFP__
+ #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)
+ #define __FPU_USED 1U
+ #else
+ #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)"
+ #define __FPU_USED 0U
+ #endif
+ #else
+ #define __FPU_USED 0U
+ #endif
+
+#elif defined ( __TI_ARM__ )
+ #if defined __TI_VFP_SUPPORT__
+ #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)
+ #define __FPU_USED 1U
+ #else
+ #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)"
+ #define __FPU_USED 0U
+ #endif
+ #else
+ #define __FPU_USED 0U
+ #endif
+
+#elif defined ( __TASKING__ )
+ #if defined __FPU_VFP__
+ #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)
+ #define __FPU_USED 1U
+ #else
+ #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)"
+ #define __FPU_USED 0U
+ #endif
+ #else
+ #define __FPU_USED 0U
+ #endif
+
+#elif defined ( __CSMC__ )
+ #if ( __CSMC__ & 0x400U)
+ #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)
+ #define __FPU_USED 1U
+ #else
+ #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)"
+ #define __FPU_USED 0U
+ #endif
+ #else
+ #define __FPU_USED 0U
+ #endif
+
+#endif
+
+#include "cmsis_compiler.h" /* CMSIS compiler specific defines */
+
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __CORE_CM4_H_GENERIC */
+
+#ifndef __CMSIS_GENERIC
+
+#ifndef __CORE_CM4_H_DEPENDANT
+#define __CORE_CM4_H_DEPENDANT
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* check device defines and use defaults */
+#if defined __CHECK_DEVICE_DEFINES
+ #ifndef __CM4_REV
+ #define __CM4_REV 0x0000U
+ #warning "__CM4_REV not defined in device header file; using default!"
+ #endif
+
+ #ifndef __FPU_PRESENT
+ #define __FPU_PRESENT 0U
+ #warning "__FPU_PRESENT not defined in device header file; using default!"
+ #endif
+
+ #ifndef __MPU_PRESENT
+ #define __MPU_PRESENT 0U
+ #warning "__MPU_PRESENT not defined in device header file; using default!"
+ #endif
+
+ #ifndef __NVIC_PRIO_BITS
+ #define __NVIC_PRIO_BITS 3U
+ #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
+
+ <strong>IO Type Qualifiers</strong> 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_M4 */
+
+
+
+/*******************************************************************************
+ * Register Abstraction
+ Core Register contain:
+ - Core Register
+ - Core NVIC Register
+ - Core SCB Register
+ - Core SysTick Register
+ - Core Debug Register
+ - Core MPU Register
+ - Core FPU 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:16; /*!< bit: 0..15 Reserved */
+ uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */
+ uint32_t _reserved1:7; /*!< bit: 20..26 Reserved */
+ uint32_t Q:1; /*!< bit: 27 Saturation condition flag */
+ 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 */
+
+#define APSR_Q_Pos 27U /*!< APSR: Q Position */
+#define APSR_Q_Msk (1UL << APSR_Q_Pos) /*!< APSR: Q Mask */
+
+#define APSR_GE_Pos 16U /*!< APSR: GE Position */
+#define APSR_GE_Msk (0xFUL << APSR_GE_Pos) /*!< APSR: GE 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:1; /*!< bit: 9 Reserved */
+ uint32_t ICI_IT_1:6; /*!< bit: 10..15 ICI/IT part 1 */
+ uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */
+ uint32_t _reserved1:4; /*!< bit: 20..23 Reserved */
+ uint32_t T:1; /*!< bit: 24 Thumb bit */
+ uint32_t ICI_IT_2:2; /*!< bit: 25..26 ICI/IT part 2 */
+ uint32_t Q:1; /*!< bit: 27 Saturation condition flag */
+ 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_Q_Pos 27U /*!< xPSR: Q Position */
+#define xPSR_Q_Msk (1UL << xPSR_Q_Pos) /*!< xPSR: Q Mask */
+
+#define xPSR_ICI_IT_2_Pos 25U /*!< xPSR: ICI/IT part 2 Position */
+#define xPSR_ICI_IT_2_Msk (3UL << xPSR_ICI_IT_2_Pos) /*!< xPSR: ICI/IT part 2 Mask */
+
+#define xPSR_T_Pos 24U /*!< xPSR: T Position */
+#define xPSR_T_Msk (1UL << xPSR_T_Pos) /*!< xPSR: T Mask */
+
+#define xPSR_GE_Pos 16U /*!< xPSR: GE Position */
+#define xPSR_GE_Msk (0xFUL << xPSR_GE_Pos) /*!< xPSR: GE Mask */
+
+#define xPSR_ICI_IT_1_Pos 10U /*!< xPSR: ICI/IT part 1 Position */
+#define xPSR_ICI_IT_1_Msk (0x3FUL << xPSR_ICI_IT_1_Pos) /*!< xPSR: ICI/IT part 1 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 nPRIV:1; /*!< bit: 0 Execution privilege in Thread mode */
+ uint32_t SPSEL:1; /*!< bit: 1 Stack to be used */
+ uint32_t FPCA:1; /*!< bit: 2 FP extension active flag */
+ uint32_t _reserved0:29; /*!< bit: 3..31 Reserved */
+ } b; /*!< Structure used for bit access */
+ uint32_t w; /*!< Type used for word access */
+} CONTROL_Type;
+
+/* CONTROL Register Definitions */
+#define CONTROL_FPCA_Pos 2U /*!< CONTROL: FPCA Position */
+#define CONTROL_FPCA_Msk (1UL << CONTROL_FPCA_Pos) /*!< CONTROL: FPCA Mask */
+
+#define CONTROL_SPSEL_Pos 1U /*!< CONTROL: SPSEL Position */
+#define CONTROL_SPSEL_Msk (1UL << CONTROL_SPSEL_Pos) /*!< CONTROL: SPSEL Mask */
+
+#define CONTROL_nPRIV_Pos 0U /*!< CONTROL: nPRIV Position */
+#define CONTROL_nPRIV_Msk (1UL /*<< CONTROL_nPRIV_Pos*/) /*!< CONTROL: nPRIV 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[8U]; /*!< Offset: 0x000 (R/W) Interrupt Set Enable Register */
+ uint32_t RESERVED0[24U];
+ __IOM uint32_t ICER[8U]; /*!< Offset: 0x080 (R/W) Interrupt Clear Enable Register */
+ uint32_t RSERVED1[24U];
+ __IOM uint32_t ISPR[8U]; /*!< Offset: 0x100 (R/W) Interrupt Set Pending Register */
+ uint32_t RESERVED2[24U];
+ __IOM uint32_t ICPR[8U]; /*!< Offset: 0x180 (R/W) Interrupt Clear Pending Register */
+ uint32_t RESERVED3[24U];
+ __IOM uint32_t IABR[8U]; /*!< Offset: 0x200 (R/W) Interrupt Active bit Register */
+ uint32_t RESERVED4[56U];
+ __IOM uint8_t IP[240U]; /*!< Offset: 0x300 (R/W) Interrupt Priority Register (8Bit wide) */
+ uint32_t RESERVED5[644U];
+ __OM uint32_t STIR; /*!< Offset: 0xE00 ( /W) Software Trigger Interrupt Register */
+} NVIC_Type;
+
+/* Software Triggered Interrupt Register Definitions */
+#define NVIC_STIR_INTID_Pos 0U /*!< STIR: INTLINESNUM Position */
+#define NVIC_STIR_INTID_Msk (0x1FFUL /*<< NVIC_STIR_INTID_Pos*/) /*!< STIR: INTLINESNUM Mask */
+
+/*@} 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 */
+ __IOM uint32_t VTOR; /*!< Offset: 0x008 (R/W) Vector Table Offset Register */
+ __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 */
+ __IOM uint8_t SHP[12U]; /*!< Offset: 0x018 (R/W) System Handlers Priority Registers (4-7, 8-11, 12-15) */
+ __IOM uint32_t SHCSR; /*!< Offset: 0x024 (R/W) System Handler Control and State Register */
+ __IOM uint32_t CFSR; /*!< Offset: 0x028 (R/W) Configurable Fault Status Register */
+ __IOM uint32_t HFSR; /*!< Offset: 0x02C (R/W) HardFault Status Register */
+ __IOM uint32_t DFSR; /*!< Offset: 0x030 (R/W) Debug Fault Status Register */
+ __IOM uint32_t MMFAR; /*!< Offset: 0x034 (R/W) MemManage Fault Address Register */
+ __IOM uint32_t BFAR; /*!< Offset: 0x038 (R/W) BusFault Address Register */
+ __IOM uint32_t AFSR; /*!< Offset: 0x03C (R/W) Auxiliary Fault Status Register */
+ __IM uint32_t PFR[2U]; /*!< Offset: 0x040 (R/ ) Processor Feature Register */
+ __IM uint32_t DFR; /*!< Offset: 0x048 (R/ ) Debug Feature Register */
+ __IM uint32_t ADR; /*!< Offset: 0x04C (R/ ) Auxiliary Feature Register */
+ __IM uint32_t MMFR[4U]; /*!< Offset: 0x050 (R/ ) Memory Model Feature Register */
+ __IM uint32_t ISAR[5U]; /*!< Offset: 0x060 (R/ ) Instruction Set Attributes Register */
+ uint32_t RESERVED0[5U];
+ __IOM uint32_t CPACR; /*!< Offset: 0x088 (R/W) Coprocessor Access Control 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_RETTOBASE_Pos 11U /*!< SCB ICSR: RETTOBASE Position */
+#define SCB_ICSR_RETTOBASE_Msk (1UL << SCB_ICSR_RETTOBASE_Pos) /*!< SCB ICSR: RETTOBASE 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 Vector Table Offset Register Definitions */
+#define SCB_VTOR_TBLOFF_Pos 7U /*!< SCB VTOR: TBLOFF Position */
+#define SCB_VTOR_TBLOFF_Msk (0x1FFFFFFUL << SCB_VTOR_TBLOFF_Pos) /*!< SCB VTOR: TBLOFF 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_PRIGROUP_Pos 8U /*!< SCB AIRCR: PRIGROUP Position */
+#define SCB_AIRCR_PRIGROUP_Msk (7UL << SCB_AIRCR_PRIGROUP_Pos) /*!< SCB AIRCR: PRIGROUP 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 */
+
+#define SCB_AIRCR_VECTRESET_Pos 0U /*!< SCB AIRCR: VECTRESET Position */
+#define SCB_AIRCR_VECTRESET_Msk (1UL /*<< SCB_AIRCR_VECTRESET_Pos*/) /*!< SCB AIRCR: VECTRESET 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_BFHFNMIGN_Pos 8U /*!< SCB CCR: BFHFNMIGN Position */
+#define SCB_CCR_BFHFNMIGN_Msk (1UL << SCB_CCR_BFHFNMIGN_Pos) /*!< SCB CCR: BFHFNMIGN Mask */
+
+#define SCB_CCR_DIV_0_TRP_Pos 4U /*!< SCB CCR: DIV_0_TRP Position */
+#define SCB_CCR_DIV_0_TRP_Msk (1UL << SCB_CCR_DIV_0_TRP_Pos) /*!< SCB CCR: DIV_0_TRP 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 */
+
+#define SCB_CCR_USERSETMPEND_Pos 1U /*!< SCB CCR: USERSETMPEND Position */
+#define SCB_CCR_USERSETMPEND_Msk (1UL << SCB_CCR_USERSETMPEND_Pos) /*!< SCB CCR: USERSETMPEND Mask */
+
+#define SCB_CCR_NONBASETHRDENA_Pos 0U /*!< SCB CCR: NONBASETHRDENA Position */
+#define SCB_CCR_NONBASETHRDENA_Msk (1UL /*<< SCB_CCR_NONBASETHRDENA_Pos*/) /*!< SCB CCR: NONBASETHRDENA Mask */
+
+/* SCB System Handler Control and State Register Definitions */
+#define SCB_SHCSR_USGFAULTENA_Pos 18U /*!< SCB SHCSR: USGFAULTENA Position */
+#define SCB_SHCSR_USGFAULTENA_Msk (1UL << SCB_SHCSR_USGFAULTENA_Pos) /*!< SCB SHCSR: USGFAULTENA Mask */
+
+#define SCB_SHCSR_BUSFAULTENA_Pos 17U /*!< SCB SHCSR: BUSFAULTENA Position */
+#define SCB_SHCSR_BUSFAULTENA_Msk (1UL << SCB_SHCSR_BUSFAULTENA_Pos) /*!< SCB SHCSR: BUSFAULTENA Mask */
+
+#define SCB_SHCSR_MEMFAULTENA_Pos 16U /*!< SCB SHCSR: MEMFAULTENA Position */
+#define SCB_SHCSR_MEMFAULTENA_Msk (1UL << SCB_SHCSR_MEMFAULTENA_Pos) /*!< SCB SHCSR: MEMFAULTENA Mask */
+
+#define SCB_SHCSR_SVCALLPENDED_Pos 15U /*!< SCB SHCSR: SVCALLPENDED Position */
+#define SCB_SHCSR_SVCALLPENDED_Msk (1UL << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SHCSR: SVCALLPENDED Mask */
+
+#define SCB_SHCSR_BUSFAULTPENDED_Pos 14U /*!< SCB SHCSR: BUSFAULTPENDED Position */
+#define SCB_SHCSR_BUSFAULTPENDED_Msk (1UL << SCB_SHCSR_BUSFAULTPENDED_Pos) /*!< SCB SHCSR: BUSFAULTPENDED Mask */
+
+#define SCB_SHCSR_MEMFAULTPENDED_Pos 13U /*!< SCB SHCSR: MEMFAULTPENDED Position */
+#define SCB_SHCSR_MEMFAULTPENDED_Msk (1UL << SCB_SHCSR_MEMFAULTPENDED_Pos) /*!< SCB SHCSR: MEMFAULTPENDED Mask */
+
+#define SCB_SHCSR_USGFAULTPENDED_Pos 12U /*!< SCB SHCSR: USGFAULTPENDED Position */
+#define SCB_SHCSR_USGFAULTPENDED_Msk (1UL << SCB_SHCSR_USGFAULTPENDED_Pos) /*!< SCB SHCSR: USGFAULTPENDED Mask */
+
+#define SCB_SHCSR_SYSTICKACT_Pos 11U /*!< SCB SHCSR: SYSTICKACT Position */
+#define SCB_SHCSR_SYSTICKACT_Msk (1UL << SCB_SHCSR_SYSTICKACT_Pos) /*!< SCB SHCSR: SYSTICKACT Mask */
+
+#define SCB_SHCSR_PENDSVACT_Pos 10U /*!< SCB SHCSR: PENDSVACT Position */
+#define SCB_SHCSR_PENDSVACT_Msk (1UL << SCB_SHCSR_PENDSVACT_Pos) /*!< SCB SHCSR: PENDSVACT Mask */
+
+#define SCB_SHCSR_MONITORACT_Pos 8U /*!< SCB SHCSR: MONITORACT Position */
+#define SCB_SHCSR_MONITORACT_Msk (1UL << SCB_SHCSR_MONITORACT_Pos) /*!< SCB SHCSR: MONITORACT Mask */
+
+#define SCB_SHCSR_SVCALLACT_Pos 7U /*!< SCB SHCSR: SVCALLACT Position */
+#define SCB_SHCSR_SVCALLACT_Msk (1UL << SCB_SHCSR_SVCALLACT_Pos) /*!< SCB SHCSR: SVCALLACT Mask */
+
+#define SCB_SHCSR_USGFAULTACT_Pos 3U /*!< SCB SHCSR: USGFAULTACT Position */
+#define SCB_SHCSR_USGFAULTACT_Msk (1UL << SCB_SHCSR_USGFAULTACT_Pos) /*!< SCB SHCSR: USGFAULTACT Mask */
+
+#define SCB_SHCSR_BUSFAULTACT_Pos 1U /*!< SCB SHCSR: BUSFAULTACT Position */
+#define SCB_SHCSR_BUSFAULTACT_Msk (1UL << SCB_SHCSR_BUSFAULTACT_Pos) /*!< SCB SHCSR: BUSFAULTACT Mask */
+
+#define SCB_SHCSR_MEMFAULTACT_Pos 0U /*!< SCB SHCSR: MEMFAULTACT Position */
+#define SCB_SHCSR_MEMFAULTACT_Msk (1UL /*<< SCB_SHCSR_MEMFAULTACT_Pos*/) /*!< SCB SHCSR: MEMFAULTACT Mask */
+
+/* SCB Configurable Fault Status Register Definitions */
+#define SCB_CFSR_USGFAULTSR_Pos 16U /*!< SCB CFSR: Usage Fault Status Register Position */
+#define SCB_CFSR_USGFAULTSR_Msk (0xFFFFUL << SCB_CFSR_USGFAULTSR_Pos) /*!< SCB CFSR: Usage Fault Status Register Mask */
+
+#define SCB_CFSR_BUSFAULTSR_Pos 8U /*!< SCB CFSR: Bus Fault Status Register Position */
+#define SCB_CFSR_BUSFAULTSR_Msk (0xFFUL << SCB_CFSR_BUSFAULTSR_Pos) /*!< SCB CFSR: Bus Fault Status Register Mask */
+
+#define SCB_CFSR_MEMFAULTSR_Pos 0U /*!< SCB CFSR: Memory Manage Fault Status Register Position */
+#define SCB_CFSR_MEMFAULTSR_Msk (0xFFUL /*<< SCB_CFSR_MEMFAULTSR_Pos*/) /*!< SCB CFSR: Memory Manage Fault Status Register Mask */
+
+/* MemManage Fault Status Register (part of SCB Configurable Fault Status Register) */
+#define SCB_CFSR_MMARVALID_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 7U) /*!< SCB CFSR (MMFSR): MMARVALID Position */
+#define SCB_CFSR_MMARVALID_Msk (1UL << SCB_CFSR_MMARVALID_Pos) /*!< SCB CFSR (MMFSR): MMARVALID Mask */
+
+#define SCB_CFSR_MLSPERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 5U) /*!< SCB CFSR (MMFSR): MLSPERR Position */
+#define SCB_CFSR_MLSPERR_Msk (1UL << SCB_CFSR_MLSPERR_Pos) /*!< SCB CFSR (MMFSR): MLSPERR Mask */
+
+#define SCB_CFSR_MSTKERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 4U) /*!< SCB CFSR (MMFSR): MSTKERR Position */
+#define SCB_CFSR_MSTKERR_Msk (1UL << SCB_CFSR_MSTKERR_Pos) /*!< SCB CFSR (MMFSR): MSTKERR Mask */
+
+#define SCB_CFSR_MUNSTKERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 3U) /*!< SCB CFSR (MMFSR): MUNSTKERR Position */
+#define SCB_CFSR_MUNSTKERR_Msk (1UL << SCB_CFSR_MUNSTKERR_Pos) /*!< SCB CFSR (MMFSR): MUNSTKERR Mask */
+
+#define SCB_CFSR_DACCVIOL_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 1U) /*!< SCB CFSR (MMFSR): DACCVIOL Position */
+#define SCB_CFSR_DACCVIOL_Msk (1UL << SCB_CFSR_DACCVIOL_Pos) /*!< SCB CFSR (MMFSR): DACCVIOL Mask */
+
+#define SCB_CFSR_IACCVIOL_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 0U) /*!< SCB CFSR (MMFSR): IACCVIOL Position */
+#define SCB_CFSR_IACCVIOL_Msk (1UL /*<< SCB_CFSR_IACCVIOL_Pos*/) /*!< SCB CFSR (MMFSR): IACCVIOL Mask */
+
+/* BusFault Status Register (part of SCB Configurable Fault Status Register) */
+#define SCB_CFSR_BFARVALID_Pos (SCB_CFSR_BUSFAULTSR_Pos + 7U) /*!< SCB CFSR (BFSR): BFARVALID Position */
+#define SCB_CFSR_BFARVALID_Msk (1UL << SCB_CFSR_BFARVALID_Pos) /*!< SCB CFSR (BFSR): BFARVALID Mask */
+
+#define SCB_CFSR_LSPERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 5U) /*!< SCB CFSR (BFSR): LSPERR Position */
+#define SCB_CFSR_LSPERR_Msk (1UL << SCB_CFSR_LSPERR_Pos) /*!< SCB CFSR (BFSR): LSPERR Mask */
+
+#define SCB_CFSR_STKERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 4U) /*!< SCB CFSR (BFSR): STKERR Position */
+#define SCB_CFSR_STKERR_Msk (1UL << SCB_CFSR_STKERR_Pos) /*!< SCB CFSR (BFSR): STKERR Mask */
+
+#define SCB_CFSR_UNSTKERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 3U) /*!< SCB CFSR (BFSR): UNSTKERR Position */
+#define SCB_CFSR_UNSTKERR_Msk (1UL << SCB_CFSR_UNSTKERR_Pos) /*!< SCB CFSR (BFSR): UNSTKERR Mask */
+
+#define SCB_CFSR_IMPRECISERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 2U) /*!< SCB CFSR (BFSR): IMPRECISERR Position */
+#define SCB_CFSR_IMPRECISERR_Msk (1UL << SCB_CFSR_IMPRECISERR_Pos) /*!< SCB CFSR (BFSR): IMPRECISERR Mask */
+
+#define SCB_CFSR_PRECISERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 1U) /*!< SCB CFSR (BFSR): PRECISERR Position */
+#define SCB_CFSR_PRECISERR_Msk (1UL << SCB_CFSR_PRECISERR_Pos) /*!< SCB CFSR (BFSR): PRECISERR Mask */
+
+#define SCB_CFSR_IBUSERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 0U) /*!< SCB CFSR (BFSR): IBUSERR Position */
+#define SCB_CFSR_IBUSERR_Msk (1UL << SCB_CFSR_IBUSERR_Pos) /*!< SCB CFSR (BFSR): IBUSERR Mask */
+
+/* UsageFault Status Register (part of SCB Configurable Fault Status Register) */
+#define SCB_CFSR_DIVBYZERO_Pos (SCB_CFSR_USGFAULTSR_Pos + 9U) /*!< SCB CFSR (UFSR): DIVBYZERO Position */
+#define SCB_CFSR_DIVBYZERO_Msk (1UL << SCB_CFSR_DIVBYZERO_Pos) /*!< SCB CFSR (UFSR): DIVBYZERO Mask */
+
+#define SCB_CFSR_UNALIGNED_Pos (SCB_CFSR_USGFAULTSR_Pos + 8U) /*!< SCB CFSR (UFSR): UNALIGNED Position */
+#define SCB_CFSR_UNALIGNED_Msk (1UL << SCB_CFSR_UNALIGNED_Pos) /*!< SCB CFSR (UFSR): UNALIGNED Mask */
+
+#define SCB_CFSR_NOCP_Pos (SCB_CFSR_USGFAULTSR_Pos + 3U) /*!< SCB CFSR (UFSR): NOCP Position */
+#define SCB_CFSR_NOCP_Msk (1UL << SCB_CFSR_NOCP_Pos) /*!< SCB CFSR (UFSR): NOCP Mask */
+
+#define SCB_CFSR_INVPC_Pos (SCB_CFSR_USGFAULTSR_Pos + 2U) /*!< SCB CFSR (UFSR): INVPC Position */
+#define SCB_CFSR_INVPC_Msk (1UL << SCB_CFSR_INVPC_Pos) /*!< SCB CFSR (UFSR): INVPC Mask */
+
+#define SCB_CFSR_INVSTATE_Pos (SCB_CFSR_USGFAULTSR_Pos + 1U) /*!< SCB CFSR (UFSR): INVSTATE Position */
+#define SCB_CFSR_INVSTATE_Msk (1UL << SCB_CFSR_INVSTATE_Pos) /*!< SCB CFSR (UFSR): INVSTATE Mask */
+
+#define SCB_CFSR_UNDEFINSTR_Pos (SCB_CFSR_USGFAULTSR_Pos + 0U) /*!< SCB CFSR (UFSR): UNDEFINSTR Position */
+#define SCB_CFSR_UNDEFINSTR_Msk (1UL << SCB_CFSR_UNDEFINSTR_Pos) /*!< SCB CFSR (UFSR): UNDEFINSTR Mask */
+
+/* SCB Hard Fault Status Register Definitions */
+#define SCB_HFSR_DEBUGEVT_Pos 31U /*!< SCB HFSR: DEBUGEVT Position */
+#define SCB_HFSR_DEBUGEVT_Msk (1UL << SCB_HFSR_DEBUGEVT_Pos) /*!< SCB HFSR: DEBUGEVT Mask */
+
+#define SCB_HFSR_FORCED_Pos 30U /*!< SCB HFSR: FORCED Position */
+#define SCB_HFSR_FORCED_Msk (1UL << SCB_HFSR_FORCED_Pos) /*!< SCB HFSR: FORCED Mask */
+
+#define SCB_HFSR_VECTTBL_Pos 1U /*!< SCB HFSR: VECTTBL Position */
+#define SCB_HFSR_VECTTBL_Msk (1UL << SCB_HFSR_VECTTBL_Pos) /*!< SCB HFSR: VECTTBL Mask */
+
+/* SCB Debug Fault Status Register Definitions */
+#define SCB_DFSR_EXTERNAL_Pos 4U /*!< SCB DFSR: EXTERNAL Position */
+#define SCB_DFSR_EXTERNAL_Msk (1UL << SCB_DFSR_EXTERNAL_Pos) /*!< SCB DFSR: EXTERNAL Mask */
+
+#define SCB_DFSR_VCATCH_Pos 3U /*!< SCB DFSR: VCATCH Position */
+#define SCB_DFSR_VCATCH_Msk (1UL << SCB_DFSR_VCATCH_Pos) /*!< SCB DFSR: VCATCH Mask */
+
+#define SCB_DFSR_DWTTRAP_Pos 2U /*!< SCB DFSR: DWTTRAP Position */
+#define SCB_DFSR_DWTTRAP_Msk (1UL << SCB_DFSR_DWTTRAP_Pos) /*!< SCB DFSR: DWTTRAP Mask */
+
+#define SCB_DFSR_BKPT_Pos 1U /*!< SCB DFSR: BKPT Position */
+#define SCB_DFSR_BKPT_Msk (1UL << SCB_DFSR_BKPT_Pos) /*!< SCB DFSR: BKPT Mask */
+
+#define SCB_DFSR_HALTED_Pos 0U /*!< SCB DFSR: HALTED Position */
+#define SCB_DFSR_HALTED_Msk (1UL /*<< SCB_DFSR_HALTED_Pos*/) /*!< SCB DFSR: HALTED Mask */
+
+/*@} end of group CMSIS_SCB */
+
+
+/**
+ \ingroup CMSIS_core_register
+ \defgroup CMSIS_SCnSCB System Controls not in SCB (SCnSCB)
+ \brief Type definitions for the System Control and ID Register not in the SCB
+ @{
+ */
+
+/**
+ \brief Structure type to access the System Control and ID Register not in the SCB.
+ */
+typedef struct
+{
+ uint32_t RESERVED0[1U];
+ __IM uint32_t ICTR; /*!< Offset: 0x004 (R/ ) Interrupt Controller Type Register */
+ __IOM uint32_t ACTLR; /*!< Offset: 0x008 (R/W) Auxiliary Control Register */
+} SCnSCB_Type;
+
+/* Interrupt Controller Type Register Definitions */
+#define SCnSCB_ICTR_INTLINESNUM_Pos 0U /*!< ICTR: INTLINESNUM Position */
+#define SCnSCB_ICTR_INTLINESNUM_Msk (0xFUL /*<< SCnSCB_ICTR_INTLINESNUM_Pos*/) /*!< ICTR: INTLINESNUM Mask */
+
+/* Auxiliary Control Register Definitions */
+#define SCnSCB_ACTLR_DISOOFP_Pos 9U /*!< ACTLR: DISOOFP Position */
+#define SCnSCB_ACTLR_DISOOFP_Msk (1UL << SCnSCB_ACTLR_DISOOFP_Pos) /*!< ACTLR: DISOOFP Mask */
+
+#define SCnSCB_ACTLR_DISFPCA_Pos 8U /*!< ACTLR: DISFPCA Position */
+#define SCnSCB_ACTLR_DISFPCA_Msk (1UL << SCnSCB_ACTLR_DISFPCA_Pos) /*!< ACTLR: DISFPCA Mask */
+
+#define SCnSCB_ACTLR_DISFOLD_Pos 2U /*!< ACTLR: DISFOLD Position */
+#define SCnSCB_ACTLR_DISFOLD_Msk (1UL << SCnSCB_ACTLR_DISFOLD_Pos) /*!< ACTLR: DISFOLD Mask */
+
+#define SCnSCB_ACTLR_DISDEFWBUF_Pos 1U /*!< ACTLR: DISDEFWBUF Position */
+#define SCnSCB_ACTLR_DISDEFWBUF_Msk (1UL << SCnSCB_ACTLR_DISDEFWBUF_Pos) /*!< ACTLR: DISDEFWBUF Mask */
+
+#define SCnSCB_ACTLR_DISMCYCINT_Pos 0U /*!< ACTLR: DISMCYCINT Position */
+#define SCnSCB_ACTLR_DISMCYCINT_Msk (1UL /*<< SCnSCB_ACTLR_DISMCYCINT_Pos*/) /*!< ACTLR: DISMCYCINT Mask */
+
+/*@} end of group CMSIS_SCnotSCB */
+
+
+/**
+ \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_ITM Instrumentation Trace Macrocell (ITM)
+ \brief Type definitions for the Instrumentation Trace Macrocell (ITM)
+ @{
+ */
+
+/**
+ \brief Structure type to access the Instrumentation Trace Macrocell Register (ITM).
+ */
+typedef struct
+{
+ __OM union
+ {
+ __OM uint8_t u8; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 8-bit */
+ __OM uint16_t u16; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 16-bit */
+ __OM uint32_t u32; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 32-bit */
+ } PORT [32U]; /*!< Offset: 0x000 ( /W) ITM Stimulus Port Registers */
+ uint32_t RESERVED0[864U];
+ __IOM uint32_t TER; /*!< Offset: 0xE00 (R/W) ITM Trace Enable Register */
+ uint32_t RESERVED1[15U];
+ __IOM uint32_t TPR; /*!< Offset: 0xE40 (R/W) ITM Trace Privilege Register */
+ uint32_t RESERVED2[15U];
+ __IOM uint32_t TCR; /*!< Offset: 0xE80 (R/W) ITM Trace Control Register */
+ uint32_t RESERVED3[29U];
+ __OM uint32_t IWR; /*!< Offset: 0xEF8 ( /W) ITM Integration Write Register */
+ __IM uint32_t IRR; /*!< Offset: 0xEFC (R/ ) ITM Integration Read Register */
+ __IOM uint32_t IMCR; /*!< Offset: 0xF00 (R/W) ITM Integration Mode Control Register */
+ uint32_t RESERVED4[43U];
+ __OM uint32_t LAR; /*!< Offset: 0xFB0 ( /W) ITM Lock Access Register */
+ __IM uint32_t LSR; /*!< Offset: 0xFB4 (R/ ) ITM Lock Status Register */
+ uint32_t RESERVED5[6U];
+ __IM uint32_t PID4; /*!< Offset: 0xFD0 (R/ ) ITM Peripheral Identification Register #4 */
+ __IM uint32_t PID5; /*!< Offset: 0xFD4 (R/ ) ITM Peripheral Identification Register #5 */
+ __IM uint32_t PID6; /*!< Offset: 0xFD8 (R/ ) ITM Peripheral Identification Register #6 */
+ __IM uint32_t PID7; /*!< Offset: 0xFDC (R/ ) ITM Peripheral Identification Register #7 */
+ __IM uint32_t PID0; /*!< Offset: 0xFE0 (R/ ) ITM Peripheral Identification Register #0 */
+ __IM uint32_t PID1; /*!< Offset: 0xFE4 (R/ ) ITM Peripheral Identification Register #1 */
+ __IM uint32_t PID2; /*!< Offset: 0xFE8 (R/ ) ITM Peripheral Identification Register #2 */
+ __IM uint32_t PID3; /*!< Offset: 0xFEC (R/ ) ITM Peripheral Identification Register #3 */
+ __IM uint32_t CID0; /*!< Offset: 0xFF0 (R/ ) ITM Component Identification Register #0 */
+ __IM uint32_t CID1; /*!< Offset: 0xFF4 (R/ ) ITM Component Identification Register #1 */
+ __IM uint32_t CID2; /*!< Offset: 0xFF8 (R/ ) ITM Component Identification Register #2 */
+ __IM uint32_t CID3; /*!< Offset: 0xFFC (R/ ) ITM Component Identification Register #3 */
+} ITM_Type;
+
+/* ITM Trace Privilege Register Definitions */
+#define ITM_TPR_PRIVMASK_Pos 0U /*!< ITM TPR: PRIVMASK Position */
+#define ITM_TPR_PRIVMASK_Msk (0xFFFFFFFFUL /*<< ITM_TPR_PRIVMASK_Pos*/) /*!< ITM TPR: PRIVMASK Mask */
+
+/* ITM Trace Control Register Definitions */
+#define ITM_TCR_BUSY_Pos 23U /*!< ITM TCR: BUSY Position */
+#define ITM_TCR_BUSY_Msk (1UL << ITM_TCR_BUSY_Pos) /*!< ITM TCR: BUSY Mask */
+
+#define ITM_TCR_TraceBusID_Pos 16U /*!< ITM TCR: ATBID Position */
+#define ITM_TCR_TraceBusID_Msk (0x7FUL << ITM_TCR_TraceBusID_Pos) /*!< ITM TCR: ATBID Mask */
+
+#define ITM_TCR_GTSFREQ_Pos 10U /*!< ITM TCR: Global timestamp frequency Position */
+#define ITM_TCR_GTSFREQ_Msk (3UL << ITM_TCR_GTSFREQ_Pos) /*!< ITM TCR: Global timestamp frequency Mask */
+
+#define ITM_TCR_TSPrescale_Pos 8U /*!< ITM TCR: TSPrescale Position */
+#define ITM_TCR_TSPrescale_Msk (3UL << ITM_TCR_TSPrescale_Pos) /*!< ITM TCR: TSPrescale Mask */
+
+#define ITM_TCR_SWOENA_Pos 4U /*!< ITM TCR: SWOENA Position */
+#define ITM_TCR_SWOENA_Msk (1UL << ITM_TCR_SWOENA_Pos) /*!< ITM TCR: SWOENA Mask */
+
+#define ITM_TCR_DWTENA_Pos 3U /*!< ITM TCR: DWTENA Position */
+#define ITM_TCR_DWTENA_Msk (1UL << ITM_TCR_DWTENA_Pos) /*!< ITM TCR: DWTENA Mask */
+
+#define ITM_TCR_SYNCENA_Pos 2U /*!< ITM TCR: SYNCENA Position */
+#define ITM_TCR_SYNCENA_Msk (1UL << ITM_TCR_SYNCENA_Pos) /*!< ITM TCR: SYNCENA Mask */
+
+#define ITM_TCR_TSENA_Pos 1U /*!< ITM TCR: TSENA Position */
+#define ITM_TCR_TSENA_Msk (1UL << ITM_TCR_TSENA_Pos) /*!< ITM TCR: TSENA Mask */
+
+#define ITM_TCR_ITMENA_Pos 0U /*!< ITM TCR: ITM Enable bit Position */
+#define ITM_TCR_ITMENA_Msk (1UL /*<< ITM_TCR_ITMENA_Pos*/) /*!< ITM TCR: ITM Enable bit Mask */
+
+/* ITM Integration Write Register Definitions */
+#define ITM_IWR_ATVALIDM_Pos 0U /*!< ITM IWR: ATVALIDM Position */
+#define ITM_IWR_ATVALIDM_Msk (1UL /*<< ITM_IWR_ATVALIDM_Pos*/) /*!< ITM IWR: ATVALIDM Mask */
+
+/* ITM Integration Read Register Definitions */
+#define ITM_IRR_ATREADYM_Pos 0U /*!< ITM IRR: ATREADYM Position */
+#define ITM_IRR_ATREADYM_Msk (1UL /*<< ITM_IRR_ATREADYM_Pos*/) /*!< ITM IRR: ATREADYM Mask */
+
+/* ITM Integration Mode Control Register Definitions */
+#define ITM_IMCR_INTEGRATION_Pos 0U /*!< ITM IMCR: INTEGRATION Position */
+#define ITM_IMCR_INTEGRATION_Msk (1UL /*<< ITM_IMCR_INTEGRATION_Pos*/) /*!< ITM IMCR: INTEGRATION Mask */
+
+/* ITM Lock Status Register Definitions */
+#define ITM_LSR_ByteAcc_Pos 2U /*!< ITM LSR: ByteAcc Position */
+#define ITM_LSR_ByteAcc_Msk (1UL << ITM_LSR_ByteAcc_Pos) /*!< ITM LSR: ByteAcc Mask */
+
+#define ITM_LSR_Access_Pos 1U /*!< ITM LSR: Access Position */
+#define ITM_LSR_Access_Msk (1UL << ITM_LSR_Access_Pos) /*!< ITM LSR: Access Mask */
+
+#define ITM_LSR_Present_Pos 0U /*!< ITM LSR: Present Position */
+#define ITM_LSR_Present_Msk (1UL /*<< ITM_LSR_Present_Pos*/) /*!< ITM LSR: Present Mask */
+
+/*@}*/ /* end of group CMSIS_ITM */
+
+
+/**
+ \ingroup CMSIS_core_register
+ \defgroup CMSIS_DWT Data Watchpoint and Trace (DWT)
+ \brief Type definitions for the Data Watchpoint and Trace (DWT)
+ @{
+ */
+
+/**
+ \brief Structure type to access the Data Watchpoint and Trace Register (DWT).
+ */
+typedef struct
+{
+ __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) Control Register */
+ __IOM uint32_t CYCCNT; /*!< Offset: 0x004 (R/W) Cycle Count Register */
+ __IOM uint32_t CPICNT; /*!< Offset: 0x008 (R/W) CPI Count Register */
+ __IOM uint32_t EXCCNT; /*!< Offset: 0x00C (R/W) Exception Overhead Count Register */
+ __IOM uint32_t SLEEPCNT; /*!< Offset: 0x010 (R/W) Sleep Count Register */
+ __IOM uint32_t LSUCNT; /*!< Offset: 0x014 (R/W) LSU Count Register */
+ __IOM uint32_t FOLDCNT; /*!< Offset: 0x018 (R/W) Folded-instruction Count Register */
+ __IM uint32_t PCSR; /*!< Offset: 0x01C (R/ ) Program Counter Sample Register */
+ __IOM uint32_t COMP0; /*!< Offset: 0x020 (R/W) Comparator Register 0 */
+ __IOM uint32_t MASK0; /*!< Offset: 0x024 (R/W) Mask Register 0 */
+ __IOM uint32_t FUNCTION0; /*!< Offset: 0x028 (R/W) Function Register 0 */
+ uint32_t RESERVED0[1U];
+ __IOM uint32_t COMP1; /*!< Offset: 0x030 (R/W) Comparator Register 1 */
+ __IOM uint32_t MASK1; /*!< Offset: 0x034 (R/W) Mask Register 1 */
+ __IOM uint32_t FUNCTION1; /*!< Offset: 0x038 (R/W) Function Register 1 */
+ uint32_t RESERVED1[1U];
+ __IOM uint32_t COMP2; /*!< Offset: 0x040 (R/W) Comparator Register 2 */
+ __IOM uint32_t MASK2; /*!< Offset: 0x044 (R/W) Mask Register 2 */
+ __IOM uint32_t FUNCTION2; /*!< Offset: 0x048 (R/W) Function Register 2 */
+ uint32_t RESERVED2[1U];
+ __IOM uint32_t COMP3; /*!< Offset: 0x050 (R/W) Comparator Register 3 */
+ __IOM uint32_t MASK3; /*!< Offset: 0x054 (R/W) Mask Register 3 */
+ __IOM uint32_t FUNCTION3; /*!< Offset: 0x058 (R/W) Function Register 3 */
+} DWT_Type;
+
+/* DWT Control Register Definitions */
+#define DWT_CTRL_NUMCOMP_Pos 28U /*!< DWT CTRL: NUMCOMP Position */
+#define DWT_CTRL_NUMCOMP_Msk (0xFUL << DWT_CTRL_NUMCOMP_Pos) /*!< DWT CTRL: NUMCOMP Mask */
+
+#define DWT_CTRL_NOTRCPKT_Pos 27U /*!< DWT CTRL: NOTRCPKT Position */
+#define DWT_CTRL_NOTRCPKT_Msk (0x1UL << DWT_CTRL_NOTRCPKT_Pos) /*!< DWT CTRL: NOTRCPKT Mask */
+
+#define DWT_CTRL_NOEXTTRIG_Pos 26U /*!< DWT CTRL: NOEXTTRIG Position */
+#define DWT_CTRL_NOEXTTRIG_Msk (0x1UL << DWT_CTRL_NOEXTTRIG_Pos) /*!< DWT CTRL: NOEXTTRIG Mask */
+
+#define DWT_CTRL_NOCYCCNT_Pos 25U /*!< DWT CTRL: NOCYCCNT Position */
+#define DWT_CTRL_NOCYCCNT_Msk (0x1UL << DWT_CTRL_NOCYCCNT_Pos) /*!< DWT CTRL: NOCYCCNT Mask */
+
+#define DWT_CTRL_NOPRFCNT_Pos 24U /*!< DWT CTRL: NOPRFCNT Position */
+#define DWT_CTRL_NOPRFCNT_Msk (0x1UL << DWT_CTRL_NOPRFCNT_Pos) /*!< DWT CTRL: NOPRFCNT Mask */
+
+#define DWT_CTRL_CYCEVTENA_Pos 22U /*!< DWT CTRL: CYCEVTENA Position */
+#define DWT_CTRL_CYCEVTENA_Msk (0x1UL << DWT_CTRL_CYCEVTENA_Pos) /*!< DWT CTRL: CYCEVTENA Mask */
+
+#define DWT_CTRL_FOLDEVTENA_Pos 21U /*!< DWT CTRL: FOLDEVTENA Position */
+#define DWT_CTRL_FOLDEVTENA_Msk (0x1UL << DWT_CTRL_FOLDEVTENA_Pos) /*!< DWT CTRL: FOLDEVTENA Mask */
+
+#define DWT_CTRL_LSUEVTENA_Pos 20U /*!< DWT CTRL: LSUEVTENA Position */
+#define DWT_CTRL_LSUEVTENA_Msk (0x1UL << DWT_CTRL_LSUEVTENA_Pos) /*!< DWT CTRL: LSUEVTENA Mask */
+
+#define DWT_CTRL_SLEEPEVTENA_Pos 19U /*!< DWT CTRL: SLEEPEVTENA Position */
+#define DWT_CTRL_SLEEPEVTENA_Msk (0x1UL << DWT_CTRL_SLEEPEVTENA_Pos) /*!< DWT CTRL: SLEEPEVTENA Mask */
+
+#define DWT_CTRL_EXCEVTENA_Pos 18U /*!< DWT CTRL: EXCEVTENA Position */
+#define DWT_CTRL_EXCEVTENA_Msk (0x1UL << DWT_CTRL_EXCEVTENA_Pos) /*!< DWT CTRL: EXCEVTENA Mask */
+
+#define DWT_CTRL_CPIEVTENA_Pos 17U /*!< DWT CTRL: CPIEVTENA Position */
+#define DWT_CTRL_CPIEVTENA_Msk (0x1UL << DWT_CTRL_CPIEVTENA_Pos) /*!< DWT CTRL: CPIEVTENA Mask */
+
+#define DWT_CTRL_EXCTRCENA_Pos 16U /*!< DWT CTRL: EXCTRCENA Position */
+#define DWT_CTRL_EXCTRCENA_Msk (0x1UL << DWT_CTRL_EXCTRCENA_Pos) /*!< DWT CTRL: EXCTRCENA Mask */
+
+#define DWT_CTRL_PCSAMPLENA_Pos 12U /*!< DWT CTRL: PCSAMPLENA Position */
+#define DWT_CTRL_PCSAMPLENA_Msk (0x1UL << DWT_CTRL_PCSAMPLENA_Pos) /*!< DWT CTRL: PCSAMPLENA Mask */
+
+#define DWT_CTRL_SYNCTAP_Pos 10U /*!< DWT CTRL: SYNCTAP Position */
+#define DWT_CTRL_SYNCTAP_Msk (0x3UL << DWT_CTRL_SYNCTAP_Pos) /*!< DWT CTRL: SYNCTAP Mask */
+
+#define DWT_CTRL_CYCTAP_Pos 9U /*!< DWT CTRL: CYCTAP Position */
+#define DWT_CTRL_CYCTAP_Msk (0x1UL << DWT_CTRL_CYCTAP_Pos) /*!< DWT CTRL: CYCTAP Mask */
+
+#define DWT_CTRL_POSTINIT_Pos 5U /*!< DWT CTRL: POSTINIT Position */
+#define DWT_CTRL_POSTINIT_Msk (0xFUL << DWT_CTRL_POSTINIT_Pos) /*!< DWT CTRL: POSTINIT Mask */
+
+#define DWT_CTRL_POSTPRESET_Pos 1U /*!< DWT CTRL: POSTPRESET Position */
+#define DWT_CTRL_POSTPRESET_Msk (0xFUL << DWT_CTRL_POSTPRESET_Pos) /*!< DWT CTRL: POSTPRESET Mask */
+
+#define DWT_CTRL_CYCCNTENA_Pos 0U /*!< DWT CTRL: CYCCNTENA Position */
+#define DWT_CTRL_CYCCNTENA_Msk (0x1UL /*<< DWT_CTRL_CYCCNTENA_Pos*/) /*!< DWT CTRL: CYCCNTENA Mask */
+
+/* DWT CPI Count Register Definitions */
+#define DWT_CPICNT_CPICNT_Pos 0U /*!< DWT CPICNT: CPICNT Position */
+#define DWT_CPICNT_CPICNT_Msk (0xFFUL /*<< DWT_CPICNT_CPICNT_Pos*/) /*!< DWT CPICNT: CPICNT Mask */
+
+/* DWT Exception Overhead Count Register Definitions */
+#define DWT_EXCCNT_EXCCNT_Pos 0U /*!< DWT EXCCNT: EXCCNT Position */
+#define DWT_EXCCNT_EXCCNT_Msk (0xFFUL /*<< DWT_EXCCNT_EXCCNT_Pos*/) /*!< DWT EXCCNT: EXCCNT Mask */
+
+/* DWT Sleep Count Register Definitions */
+#define DWT_SLEEPCNT_SLEEPCNT_Pos 0U /*!< DWT SLEEPCNT: SLEEPCNT Position */
+#define DWT_SLEEPCNT_SLEEPCNT_Msk (0xFFUL /*<< DWT_SLEEPCNT_SLEEPCNT_Pos*/) /*!< DWT SLEEPCNT: SLEEPCNT Mask */
+
+/* DWT LSU Count Register Definitions */
+#define DWT_LSUCNT_LSUCNT_Pos 0U /*!< DWT LSUCNT: LSUCNT Position */
+#define DWT_LSUCNT_LSUCNT_Msk (0xFFUL /*<< DWT_LSUCNT_LSUCNT_Pos*/) /*!< DWT LSUCNT: LSUCNT Mask */
+
+/* DWT Folded-instruction Count Register Definitions */
+#define DWT_FOLDCNT_FOLDCNT_Pos 0U /*!< DWT FOLDCNT: FOLDCNT Position */
+#define DWT_FOLDCNT_FOLDCNT_Msk (0xFFUL /*<< DWT_FOLDCNT_FOLDCNT_Pos*/) /*!< DWT FOLDCNT: FOLDCNT Mask */
+
+/* DWT Comparator Mask Register Definitions */
+#define DWT_MASK_MASK_Pos 0U /*!< DWT MASK: MASK Position */
+#define DWT_MASK_MASK_Msk (0x1FUL /*<< DWT_MASK_MASK_Pos*/) /*!< DWT MASK: MASK Mask */
+
+/* DWT Comparator Function Register Definitions */
+#define DWT_FUNCTION_MATCHED_Pos 24U /*!< DWT FUNCTION: MATCHED Position */
+#define DWT_FUNCTION_MATCHED_Msk (0x1UL << DWT_FUNCTION_MATCHED_Pos) /*!< DWT FUNCTION: MATCHED Mask */
+
+#define DWT_FUNCTION_DATAVADDR1_Pos 16U /*!< DWT FUNCTION: DATAVADDR1 Position */
+#define DWT_FUNCTION_DATAVADDR1_Msk (0xFUL << DWT_FUNCTION_DATAVADDR1_Pos) /*!< DWT FUNCTION: DATAVADDR1 Mask */
+
+#define DWT_FUNCTION_DATAVADDR0_Pos 12U /*!< DWT FUNCTION: DATAVADDR0 Position */
+#define DWT_FUNCTION_DATAVADDR0_Msk (0xFUL << DWT_FUNCTION_DATAVADDR0_Pos) /*!< DWT FUNCTION: DATAVADDR0 Mask */
+
+#define DWT_FUNCTION_DATAVSIZE_Pos 10U /*!< DWT FUNCTION: DATAVSIZE Position */
+#define DWT_FUNCTION_DATAVSIZE_Msk (0x3UL << DWT_FUNCTION_DATAVSIZE_Pos) /*!< DWT FUNCTION: DATAVSIZE Mask */
+
+#define DWT_FUNCTION_LNK1ENA_Pos 9U /*!< DWT FUNCTION: LNK1ENA Position */
+#define DWT_FUNCTION_LNK1ENA_Msk (0x1UL << DWT_FUNCTION_LNK1ENA_Pos) /*!< DWT FUNCTION: LNK1ENA Mask */
+
+#define DWT_FUNCTION_DATAVMATCH_Pos 8U /*!< DWT FUNCTION: DATAVMATCH Position */
+#define DWT_FUNCTION_DATAVMATCH_Msk (0x1UL << DWT_FUNCTION_DATAVMATCH_Pos) /*!< DWT FUNCTION: DATAVMATCH Mask */
+
+#define DWT_FUNCTION_CYCMATCH_Pos 7U /*!< DWT FUNCTION: CYCMATCH Position */
+#define DWT_FUNCTION_CYCMATCH_Msk (0x1UL << DWT_FUNCTION_CYCMATCH_Pos) /*!< DWT FUNCTION: CYCMATCH Mask */
+
+#define DWT_FUNCTION_EMITRANGE_Pos 5U /*!< DWT FUNCTION: EMITRANGE Position */
+#define DWT_FUNCTION_EMITRANGE_Msk (0x1UL << DWT_FUNCTION_EMITRANGE_Pos) /*!< DWT FUNCTION: EMITRANGE Mask */
+
+#define DWT_FUNCTION_FUNCTION_Pos 0U /*!< DWT FUNCTION: FUNCTION Position */
+#define DWT_FUNCTION_FUNCTION_Msk (0xFUL /*<< DWT_FUNCTION_FUNCTION_Pos*/) /*!< DWT FUNCTION: FUNCTION Mask */
+
+/*@}*/ /* end of group CMSIS_DWT */
+
+
+/**
+ \ingroup CMSIS_core_register
+ \defgroup CMSIS_TPI Trace Port Interface (TPI)
+ \brief Type definitions for the Trace Port Interface (TPI)
+ @{
+ */
+
+/**
+ \brief Structure type to access the Trace Port Interface Register (TPI).
+ */
+typedef struct
+{
+ __IOM uint32_t SSPSR; /*!< Offset: 0x000 (R/ ) Supported Parallel Port Size Register */
+ __IOM uint32_t CSPSR; /*!< Offset: 0x004 (R/W) Current Parallel Port Size Register */
+ uint32_t RESERVED0[2U];
+ __IOM uint32_t ACPR; /*!< Offset: 0x010 (R/W) Asynchronous Clock Prescaler Register */
+ uint32_t RESERVED1[55U];
+ __IOM uint32_t SPPR; /*!< Offset: 0x0F0 (R/W) Selected Pin Protocol Register */
+ uint32_t RESERVED2[131U];
+ __IM uint32_t FFSR; /*!< Offset: 0x300 (R/ ) Formatter and Flush Status Register */
+ __IOM uint32_t FFCR; /*!< Offset: 0x304 (R/W) Formatter and Flush Control Register */
+ __IM uint32_t FSCR; /*!< Offset: 0x308 (R/ ) Formatter Synchronization Counter Register */
+ uint32_t RESERVED3[759U];
+ __IM uint32_t TRIGGER; /*!< Offset: 0xEE8 (R/ ) TRIGGER */
+ __IM uint32_t FIFO0; /*!< Offset: 0xEEC (R/ ) Integration ETM Data */
+ __IM uint32_t ITATBCTR2; /*!< Offset: 0xEF0 (R/ ) ITATBCTR2 */
+ uint32_t RESERVED4[1U];
+ __IM uint32_t ITATBCTR0; /*!< Offset: 0xEF8 (R/ ) ITATBCTR0 */
+ __IM uint32_t FIFO1; /*!< Offset: 0xEFC (R/ ) Integration ITM Data */
+ __IOM uint32_t ITCTRL; /*!< Offset: 0xF00 (R/W) Integration Mode Control */
+ uint32_t RESERVED5[39U];
+ __IOM uint32_t CLAIMSET; /*!< Offset: 0xFA0 (R/W) Claim tag set */
+ __IOM uint32_t CLAIMCLR; /*!< Offset: 0xFA4 (R/W) Claim tag clear */
+ uint32_t RESERVED7[8U];
+ __IM uint32_t DEVID; /*!< Offset: 0xFC8 (R/ ) TPIU_DEVID */
+ __IM uint32_t DEVTYPE; /*!< Offset: 0xFCC (R/ ) TPIU_DEVTYPE */
+} TPI_Type;
+
+/* TPI Asynchronous Clock Prescaler Register Definitions */
+#define TPI_ACPR_PRESCALER_Pos 0U /*!< @Deprecated TPI ACPR: PRESCALER Position */
+#define TPI_ACPR_PRESCALER_Msk (0x1FFFUL /*<< TPI_ACPR_PRESCALER_Pos*/) /*!< @Deprecated TPI ACPR: PRESCALER Mask */
+
+#define TPI_ACPR_SWOSCALER_Pos 0U /*!< TPI ACPR: SWOSCALER Position */
+#define TPI_ACPR_SWOSCALER_Msk (0xFFFFUL /*<< TPI_ACPR_SWOSCALER_Pos*/) /*!< TPI ACPR: SWOSCALER Mask */
+
+/* TPI Selected Pin Protocol Register Definitions */
+#define TPI_SPPR_TXMODE_Pos 0U /*!< TPI SPPR: TXMODE Position */
+#define TPI_SPPR_TXMODE_Msk (0x3UL /*<< TPI_SPPR_TXMODE_Pos*/) /*!< TPI SPPR: TXMODE Mask */
+
+/* TPI Formatter and Flush Status Register Definitions */
+#define TPI_FFSR_FtNonStop_Pos 3U /*!< TPI FFSR: FtNonStop Position */
+#define TPI_FFSR_FtNonStop_Msk (0x1UL << TPI_FFSR_FtNonStop_Pos) /*!< TPI FFSR: FtNonStop Mask */
+
+#define TPI_FFSR_TCPresent_Pos 2U /*!< TPI FFSR: TCPresent Position */
+#define TPI_FFSR_TCPresent_Msk (0x1UL << TPI_FFSR_TCPresent_Pos) /*!< TPI FFSR: TCPresent Mask */
+
+#define TPI_FFSR_FtStopped_Pos 1U /*!< TPI FFSR: FtStopped Position */
+#define TPI_FFSR_FtStopped_Msk (0x1UL << TPI_FFSR_FtStopped_Pos) /*!< TPI FFSR: FtStopped Mask */
+
+#define TPI_FFSR_FlInProg_Pos 0U /*!< TPI FFSR: FlInProg Position */
+#define TPI_FFSR_FlInProg_Msk (0x1UL /*<< TPI_FFSR_FlInProg_Pos*/) /*!< TPI FFSR: FlInProg Mask */
+
+/* TPI Formatter and Flush Control Register Definitions */
+#define TPI_FFCR_TrigIn_Pos 8U /*!< TPI FFCR: TrigIn Position */
+#define TPI_FFCR_TrigIn_Msk (0x1UL << TPI_FFCR_TrigIn_Pos) /*!< TPI FFCR: TrigIn Mask */
+
+#define TPI_FFCR_EnFCont_Pos 1U /*!< TPI FFCR: EnFCont Position */
+#define TPI_FFCR_EnFCont_Msk (0x1UL << TPI_FFCR_EnFCont_Pos) /*!< TPI FFCR: EnFCont Mask */
+
+/* TPI TRIGGER Register Definitions */
+#define TPI_TRIGGER_TRIGGER_Pos 0U /*!< TPI TRIGGER: TRIGGER Position */
+#define TPI_TRIGGER_TRIGGER_Msk (0x1UL /*<< TPI_TRIGGER_TRIGGER_Pos*/) /*!< TPI TRIGGER: TRIGGER Mask */
+
+/* TPI Integration ETM Data Register Definitions (FIFO0) */
+#define TPI_FIFO0_ITM_ATVALID_Pos 29U /*!< TPI FIFO0: ITM_ATVALID Position */
+#define TPI_FIFO0_ITM_ATVALID_Msk (0x3UL << TPI_FIFO0_ITM_ATVALID_Pos) /*!< TPI FIFO0: ITM_ATVALID Mask */
+
+#define TPI_FIFO0_ITM_bytecount_Pos 27U /*!< TPI FIFO0: ITM_bytecount Position */
+#define TPI_FIFO0_ITM_bytecount_Msk (0x3UL << TPI_FIFO0_ITM_bytecount_Pos) /*!< TPI FIFO0: ITM_bytecount Mask */
+
+#define TPI_FIFO0_ETM_ATVALID_Pos 26U /*!< TPI FIFO0: ETM_ATVALID Position */
+#define TPI_FIFO0_ETM_ATVALID_Msk (0x3UL << TPI_FIFO0_ETM_ATVALID_Pos) /*!< TPI FIFO0: ETM_ATVALID Mask */
+
+#define TPI_FIFO0_ETM_bytecount_Pos 24U /*!< TPI FIFO0: ETM_bytecount Position */
+#define TPI_FIFO0_ETM_bytecount_Msk (0x3UL << TPI_FIFO0_ETM_bytecount_Pos) /*!< TPI FIFO0: ETM_bytecount Mask */
+
+#define TPI_FIFO0_ETM2_Pos 16U /*!< TPI FIFO0: ETM2 Position */
+#define TPI_FIFO0_ETM2_Msk (0xFFUL << TPI_FIFO0_ETM2_Pos) /*!< TPI FIFO0: ETM2 Mask */
+
+#define TPI_FIFO0_ETM1_Pos 8U /*!< TPI FIFO0: ETM1 Position */
+#define TPI_FIFO0_ETM1_Msk (0xFFUL << TPI_FIFO0_ETM1_Pos) /*!< TPI FIFO0: ETM1 Mask */
+
+#define TPI_FIFO0_ETM0_Pos 0U /*!< TPI FIFO0: ETM0 Position */
+#define TPI_FIFO0_ETM0_Msk (0xFFUL /*<< TPI_FIFO0_ETM0_Pos*/) /*!< TPI FIFO0: ETM0 Mask */
+
+/* TPI ITATBCTR2 Register Definitions */
+#define TPI_ITATBCTR2_ATREADY_Pos 0U /*!< TPI ITATBCTR2: ATREADY Position */
+#define TPI_ITATBCTR2_ATREADY_Msk (0x1UL /*<< TPI_ITATBCTR2_ATREADY_Pos*/) /*!< TPI ITATBCTR2: ATREADY Mask */
+
+/* TPI Integration ITM Data Register Definitions (FIFO1) */
+#define TPI_FIFO1_ITM_ATVALID_Pos 29U /*!< TPI FIFO1: ITM_ATVALID Position */
+#define TPI_FIFO1_ITM_ATVALID_Msk (0x3UL << TPI_FIFO1_ITM_ATVALID_Pos) /*!< TPI FIFO1: ITM_ATVALID Mask */
+
+#define TPI_FIFO1_ITM_bytecount_Pos 27U /*!< TPI FIFO1: ITM_bytecount Position */
+#define TPI_FIFO1_ITM_bytecount_Msk (0x3UL << TPI_FIFO1_ITM_bytecount_Pos) /*!< TPI FIFO1: ITM_bytecount Mask */
+
+#define TPI_FIFO1_ETM_ATVALID_Pos 26U /*!< TPI FIFO1: ETM_ATVALID Position */
+#define TPI_FIFO1_ETM_ATVALID_Msk (0x3UL << TPI_FIFO1_ETM_ATVALID_Pos) /*!< TPI FIFO1: ETM_ATVALID Mask */
+
+#define TPI_FIFO1_ETM_bytecount_Pos 24U /*!< TPI FIFO1: ETM_bytecount Position */
+#define TPI_FIFO1_ETM_bytecount_Msk (0x3UL << TPI_FIFO1_ETM_bytecount_Pos) /*!< TPI FIFO1: ETM_bytecount Mask */
+
+#define TPI_FIFO1_ITM2_Pos 16U /*!< TPI FIFO1: ITM2 Position */
+#define TPI_FIFO1_ITM2_Msk (0xFFUL << TPI_FIFO1_ITM2_Pos) /*!< TPI FIFO1: ITM2 Mask */
+
+#define TPI_FIFO1_ITM1_Pos 8U /*!< TPI FIFO1: ITM1 Position */
+#define TPI_FIFO1_ITM1_Msk (0xFFUL << TPI_FIFO1_ITM1_Pos) /*!< TPI FIFO1: ITM1 Mask */
+
+#define TPI_FIFO1_ITM0_Pos 0U /*!< TPI FIFO1: ITM0 Position */
+#define TPI_FIFO1_ITM0_Msk (0xFFUL /*<< TPI_FIFO1_ITM0_Pos*/) /*!< TPI FIFO1: ITM0 Mask */
+
+/* TPI ITATBCTR0 Register Definitions */
+#define TPI_ITATBCTR0_ATREADY_Pos 0U /*!< TPI ITATBCTR0: ATREADY Position */
+#define TPI_ITATBCTR0_ATREADY_Msk (0x1UL /*<< TPI_ITATBCTR0_ATREADY_Pos*/) /*!< TPI ITATBCTR0: ATREADY Mask */
+
+/* TPI Integration Mode Control Register Definitions */
+#define TPI_ITCTRL_Mode_Pos 0U /*!< TPI ITCTRL: Mode Position */
+#define TPI_ITCTRL_Mode_Msk (0x1UL /*<< TPI_ITCTRL_Mode_Pos*/) /*!< TPI ITCTRL: Mode Mask */
+
+/* TPI DEVID Register Definitions */
+#define TPI_DEVID_NRZVALID_Pos 11U /*!< TPI DEVID: NRZVALID Position */
+#define TPI_DEVID_NRZVALID_Msk (0x1UL << TPI_DEVID_NRZVALID_Pos) /*!< TPI DEVID: NRZVALID Mask */
+
+#define TPI_DEVID_MANCVALID_Pos 10U /*!< TPI DEVID: MANCVALID Position */
+#define TPI_DEVID_MANCVALID_Msk (0x1UL << TPI_DEVID_MANCVALID_Pos) /*!< TPI DEVID: MANCVALID Mask */
+
+#define TPI_DEVID_PTINVALID_Pos 9U /*!< TPI DEVID: PTINVALID Position */
+#define TPI_DEVID_PTINVALID_Msk (0x1UL << TPI_DEVID_PTINVALID_Pos) /*!< TPI DEVID: PTINVALID Mask */
+
+#define TPI_DEVID_MinBufSz_Pos 6U /*!< TPI DEVID: MinBufSz Position */
+#define TPI_DEVID_MinBufSz_Msk (0x7UL << TPI_DEVID_MinBufSz_Pos) /*!< TPI DEVID: MinBufSz Mask */
+
+#define TPI_DEVID_AsynClkIn_Pos 5U /*!< TPI DEVID: AsynClkIn Position */
+#define TPI_DEVID_AsynClkIn_Msk (0x1UL << TPI_DEVID_AsynClkIn_Pos) /*!< TPI DEVID: AsynClkIn Mask */
+
+#define TPI_DEVID_NrTraceInput_Pos 0U /*!< TPI DEVID: NrTraceInput Position */
+#define TPI_DEVID_NrTraceInput_Msk (0x1FUL /*<< TPI_DEVID_NrTraceInput_Pos*/) /*!< TPI DEVID: NrTraceInput Mask */
+
+/* TPI DEVTYPE Register Definitions */
+#define TPI_DEVTYPE_MajorType_Pos 4U /*!< TPI DEVTYPE: MajorType Position */
+#define TPI_DEVTYPE_MajorType_Msk (0xFUL << TPI_DEVTYPE_MajorType_Pos) /*!< TPI DEVTYPE: MajorType Mask */
+
+#define TPI_DEVTYPE_SubType_Pos 0U /*!< TPI DEVTYPE: SubType Position */
+#define TPI_DEVTYPE_SubType_Msk (0xFUL /*<< TPI_DEVTYPE_SubType_Pos*/) /*!< TPI DEVTYPE: SubType Mask */
+
+/*@}*/ /* end of group CMSIS_TPI */
+
+
+#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U)
+/**
+ \ingroup CMSIS_core_register
+ \defgroup CMSIS_MPU Memory Protection Unit (MPU)
+ \brief Type definitions for the Memory Protection Unit (MPU)
+ @{
+ */
+
+/**
+ \brief Structure type to access the Memory Protection Unit (MPU).
+ */
+typedef struct
+{
+ __IM uint32_t TYPE; /*!< Offset: 0x000 (R/ ) MPU Type Register */
+ __IOM uint32_t CTRL; /*!< Offset: 0x004 (R/W) MPU Control Register */
+ __IOM uint32_t RNR; /*!< Offset: 0x008 (R/W) MPU Region RNRber Register */
+ __IOM uint32_t RBAR; /*!< Offset: 0x00C (R/W) MPU Region Base Address Register */
+ __IOM uint32_t RASR; /*!< Offset: 0x010 (R/W) MPU Region Attribute and Size Register */
+ __IOM uint32_t RBAR_A1; /*!< Offset: 0x014 (R/W) MPU Alias 1 Region Base Address Register */
+ __IOM uint32_t RASR_A1; /*!< Offset: 0x018 (R/W) MPU Alias 1 Region Attribute and Size Register */
+ __IOM uint32_t RBAR_A2; /*!< Offset: 0x01C (R/W) MPU Alias 2 Region Base Address Register */
+ __IOM uint32_t RASR_A2; /*!< Offset: 0x020 (R/W) MPU Alias 2 Region Attribute and Size Register */
+ __IOM uint32_t RBAR_A3; /*!< Offset: 0x024 (R/W) MPU Alias 3 Region Base Address Register */
+ __IOM uint32_t RASR_A3; /*!< Offset: 0x028 (R/W) MPU Alias 3 Region Attribute and Size Register */
+} MPU_Type;
+
+#define MPU_TYPE_RALIASES 4U
+
+/* MPU Type Register Definitions */
+#define MPU_TYPE_IREGION_Pos 16U /*!< MPU TYPE: IREGION Position */
+#define MPU_TYPE_IREGION_Msk (0xFFUL << MPU_TYPE_IREGION_Pos) /*!< MPU TYPE: IREGION Mask */
+
+#define MPU_TYPE_DREGION_Pos 8U /*!< MPU TYPE: DREGION Position */
+#define MPU_TYPE_DREGION_Msk (0xFFUL << MPU_TYPE_DREGION_Pos) /*!< MPU TYPE: DREGION Mask */
+
+#define MPU_TYPE_SEPARATE_Pos 0U /*!< MPU TYPE: SEPARATE Position */
+#define MPU_TYPE_SEPARATE_Msk (1UL /*<< MPU_TYPE_SEPARATE_Pos*/) /*!< MPU TYPE: SEPARATE Mask */
+
+/* MPU Control Register Definitions */
+#define MPU_CTRL_PRIVDEFENA_Pos 2U /*!< MPU CTRL: PRIVDEFENA Position */
+#define MPU_CTRL_PRIVDEFENA_Msk (1UL << MPU_CTRL_PRIVDEFENA_Pos) /*!< MPU CTRL: PRIVDEFENA Mask */
+
+#define MPU_CTRL_HFNMIENA_Pos 1U /*!< MPU CTRL: HFNMIENA Position */
+#define MPU_CTRL_HFNMIENA_Msk (1UL << MPU_CTRL_HFNMIENA_Pos) /*!< MPU CTRL: HFNMIENA Mask */
+
+#define MPU_CTRL_ENABLE_Pos 0U /*!< MPU CTRL: ENABLE Position */
+#define MPU_CTRL_ENABLE_Msk (1UL /*<< MPU_CTRL_ENABLE_Pos*/) /*!< MPU CTRL: ENABLE Mask */
+
+/* MPU Region Number Register Definitions */
+#define MPU_RNR_REGION_Pos 0U /*!< MPU RNR: REGION Position */
+#define MPU_RNR_REGION_Msk (0xFFUL /*<< MPU_RNR_REGION_Pos*/) /*!< MPU RNR: REGION Mask */
+
+/* MPU Region Base Address Register Definitions */
+#define MPU_RBAR_ADDR_Pos 5U /*!< MPU RBAR: ADDR Position */
+#define MPU_RBAR_ADDR_Msk (0x7FFFFFFUL << MPU_RBAR_ADDR_Pos) /*!< MPU RBAR: ADDR Mask */
+
+#define MPU_RBAR_VALID_Pos 4U /*!< MPU RBAR: VALID Position */
+#define MPU_RBAR_VALID_Msk (1UL << MPU_RBAR_VALID_Pos) /*!< MPU RBAR: VALID Mask */
+
+#define MPU_RBAR_REGION_Pos 0U /*!< MPU RBAR: REGION Position */
+#define MPU_RBAR_REGION_Msk (0xFUL /*<< MPU_RBAR_REGION_Pos*/) /*!< MPU RBAR: REGION Mask */
+
+/* MPU Region Attribute and Size Register Definitions */
+#define MPU_RASR_ATTRS_Pos 16U /*!< MPU RASR: MPU Region Attribute field Position */
+#define MPU_RASR_ATTRS_Msk (0xFFFFUL << MPU_RASR_ATTRS_Pos) /*!< MPU RASR: MPU Region Attribute field Mask */
+
+#define MPU_RASR_XN_Pos 28U /*!< MPU RASR: ATTRS.XN Position */
+#define MPU_RASR_XN_Msk (1UL << MPU_RASR_XN_Pos) /*!< MPU RASR: ATTRS.XN Mask */
+
+#define MPU_RASR_AP_Pos 24U /*!< MPU RASR: ATTRS.AP Position */
+#define MPU_RASR_AP_Msk (0x7UL << MPU_RASR_AP_Pos) /*!< MPU RASR: ATTRS.AP Mask */
+
+#define MPU_RASR_TEX_Pos 19U /*!< MPU RASR: ATTRS.TEX Position */
+#define MPU_RASR_TEX_Msk (0x7UL << MPU_RASR_TEX_Pos) /*!< MPU RASR: ATTRS.TEX Mask */
+
+#define MPU_RASR_S_Pos 18U /*!< MPU RASR: ATTRS.S Position */
+#define MPU_RASR_S_Msk (1UL << MPU_RASR_S_Pos) /*!< MPU RASR: ATTRS.S Mask */
+
+#define MPU_RASR_C_Pos 17U /*!< MPU RASR: ATTRS.C Position */
+#define MPU_RASR_C_Msk (1UL << MPU_RASR_C_Pos) /*!< MPU RASR: ATTRS.C Mask */
+
+#define MPU_RASR_B_Pos 16U /*!< MPU RASR: ATTRS.B Position */
+#define MPU_RASR_B_Msk (1UL << MPU_RASR_B_Pos) /*!< MPU RASR: ATTRS.B Mask */
+
+#define MPU_RASR_SRD_Pos 8U /*!< MPU RASR: Sub-Region Disable Position */
+#define MPU_RASR_SRD_Msk (0xFFUL << MPU_RASR_SRD_Pos) /*!< MPU RASR: Sub-Region Disable Mask */
+
+#define MPU_RASR_SIZE_Pos 1U /*!< MPU RASR: Region Size Field Position */
+#define MPU_RASR_SIZE_Msk (0x1FUL << MPU_RASR_SIZE_Pos) /*!< MPU RASR: Region Size Field Mask */
+
+#define MPU_RASR_ENABLE_Pos 0U /*!< MPU RASR: Region enable bit Position */
+#define MPU_RASR_ENABLE_Msk (1UL /*<< MPU_RASR_ENABLE_Pos*/) /*!< MPU RASR: Region enable bit Disable Mask */
+
+/*@} end of group CMSIS_MPU */
+#endif /* defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) */
+
+
+/**
+ \ingroup CMSIS_core_register
+ \defgroup CMSIS_FPU Floating Point Unit (FPU)
+ \brief Type definitions for the Floating Point Unit (FPU)
+ @{
+ */
+
+/**
+ \brief Structure type to access the Floating Point Unit (FPU).
+ */
+typedef struct
+{
+ uint32_t RESERVED0[1U];
+ __IOM uint32_t FPCCR; /*!< Offset: 0x004 (R/W) Floating-Point Context Control Register */
+ __IOM uint32_t FPCAR; /*!< Offset: 0x008 (R/W) Floating-Point Context Address Register */
+ __IOM uint32_t FPDSCR; /*!< Offset: 0x00C (R/W) Floating-Point Default Status Control Register */
+ __IM uint32_t MVFR0; /*!< Offset: 0x010 (R/ ) Media and FP Feature Register 0 */
+ __IM uint32_t MVFR1; /*!< Offset: 0x014 (R/ ) Media and FP Feature Register 1 */
+} FPU_Type;
+
+/* Floating-Point Context Control Register Definitions */
+#define FPU_FPCCR_ASPEN_Pos 31U /*!< FPCCR: ASPEN bit Position */
+#define FPU_FPCCR_ASPEN_Msk (1UL << FPU_FPCCR_ASPEN_Pos) /*!< FPCCR: ASPEN bit Mask */
+
+#define FPU_FPCCR_LSPEN_Pos 30U /*!< FPCCR: LSPEN Position */
+#define FPU_FPCCR_LSPEN_Msk (1UL << FPU_FPCCR_LSPEN_Pos) /*!< FPCCR: LSPEN bit Mask */
+
+#define FPU_FPCCR_MONRDY_Pos 8U /*!< FPCCR: MONRDY Position */
+#define FPU_FPCCR_MONRDY_Msk (1UL << FPU_FPCCR_MONRDY_Pos) /*!< FPCCR: MONRDY bit Mask */
+
+#define FPU_FPCCR_BFRDY_Pos 6U /*!< FPCCR: BFRDY Position */
+#define FPU_FPCCR_BFRDY_Msk (1UL << FPU_FPCCR_BFRDY_Pos) /*!< FPCCR: BFRDY bit Mask */
+
+#define FPU_FPCCR_MMRDY_Pos 5U /*!< FPCCR: MMRDY Position */
+#define FPU_FPCCR_MMRDY_Msk (1UL << FPU_FPCCR_MMRDY_Pos) /*!< FPCCR: MMRDY bit Mask */
+
+#define FPU_FPCCR_HFRDY_Pos 4U /*!< FPCCR: HFRDY Position */
+#define FPU_FPCCR_HFRDY_Msk (1UL << FPU_FPCCR_HFRDY_Pos) /*!< FPCCR: HFRDY bit Mask */
+
+#define FPU_FPCCR_THREAD_Pos 3U /*!< FPCCR: processor mode bit Position */
+#define FPU_FPCCR_THREAD_Msk (1UL << FPU_FPCCR_THREAD_Pos) /*!< FPCCR: processor mode active bit Mask */
+
+#define FPU_FPCCR_USER_Pos 1U /*!< FPCCR: privilege level bit Position */
+#define FPU_FPCCR_USER_Msk (1UL << FPU_FPCCR_USER_Pos) /*!< FPCCR: privilege level bit Mask */
+
+#define FPU_FPCCR_LSPACT_Pos 0U /*!< FPCCR: Lazy state preservation active bit Position */
+#define FPU_FPCCR_LSPACT_Msk (1UL /*<< FPU_FPCCR_LSPACT_Pos*/) /*!< FPCCR: Lazy state preservation active bit Mask */
+
+/* Floating-Point Context Address Register Definitions */
+#define FPU_FPCAR_ADDRESS_Pos 3U /*!< FPCAR: ADDRESS bit Position */
+#define FPU_FPCAR_ADDRESS_Msk (0x1FFFFFFFUL << FPU_FPCAR_ADDRESS_Pos) /*!< FPCAR: ADDRESS bit Mask */
+
+/* Floating-Point Default Status Control Register Definitions */
+#define FPU_FPDSCR_AHP_Pos 26U /*!< FPDSCR: AHP bit Position */
+#define FPU_FPDSCR_AHP_Msk (1UL << FPU_FPDSCR_AHP_Pos) /*!< FPDSCR: AHP bit Mask */
+
+#define FPU_FPDSCR_DN_Pos 25U /*!< FPDSCR: DN bit Position */
+#define FPU_FPDSCR_DN_Msk (1UL << FPU_FPDSCR_DN_Pos) /*!< FPDSCR: DN bit Mask */
+
+#define FPU_FPDSCR_FZ_Pos 24U /*!< FPDSCR: FZ bit Position */
+#define FPU_FPDSCR_FZ_Msk (1UL << FPU_FPDSCR_FZ_Pos) /*!< FPDSCR: FZ bit Mask */
+
+#define FPU_FPDSCR_RMode_Pos 22U /*!< FPDSCR: RMode bit Position */
+#define FPU_FPDSCR_RMode_Msk (3UL << FPU_FPDSCR_RMode_Pos) /*!< FPDSCR: RMode bit Mask */
+
+/* Media and FP Feature Register 0 Definitions */
+#define FPU_MVFR0_FP_rounding_modes_Pos 28U /*!< MVFR0: FP rounding modes bits Position */
+#define FPU_MVFR0_FP_rounding_modes_Msk (0xFUL << FPU_MVFR0_FP_rounding_modes_Pos) /*!< MVFR0: FP rounding modes bits Mask */
+
+#define FPU_MVFR0_Short_vectors_Pos 24U /*!< MVFR0: Short vectors bits Position */
+#define FPU_MVFR0_Short_vectors_Msk (0xFUL << FPU_MVFR0_Short_vectors_Pos) /*!< MVFR0: Short vectors bits Mask */
+
+#define FPU_MVFR0_Square_root_Pos 20U /*!< MVFR0: Square root bits Position */
+#define FPU_MVFR0_Square_root_Msk (0xFUL << FPU_MVFR0_Square_root_Pos) /*!< MVFR0: Square root bits Mask */
+
+#define FPU_MVFR0_Divide_Pos 16U /*!< MVFR0: Divide bits Position */
+#define FPU_MVFR0_Divide_Msk (0xFUL << FPU_MVFR0_Divide_Pos) /*!< MVFR0: Divide bits Mask */
+
+#define FPU_MVFR0_FP_excep_trapping_Pos 12U /*!< MVFR0: FP exception trapping bits Position */
+#define FPU_MVFR0_FP_excep_trapping_Msk (0xFUL << FPU_MVFR0_FP_excep_trapping_Pos) /*!< MVFR0: FP exception trapping bits Mask */
+
+#define FPU_MVFR0_Double_precision_Pos 8U /*!< MVFR0: Double-precision bits Position */
+#define FPU_MVFR0_Double_precision_Msk (0xFUL << FPU_MVFR0_Double_precision_Pos) /*!< MVFR0: Double-precision bits Mask */
+
+#define FPU_MVFR0_Single_precision_Pos 4U /*!< MVFR0: Single-precision bits Position */
+#define FPU_MVFR0_Single_precision_Msk (0xFUL << FPU_MVFR0_Single_precision_Pos) /*!< MVFR0: Single-precision bits Mask */
+
+#define FPU_MVFR0_A_SIMD_registers_Pos 0U /*!< MVFR0: A_SIMD registers bits Position */
+#define FPU_MVFR0_A_SIMD_registers_Msk (0xFUL /*<< FPU_MVFR0_A_SIMD_registers_Pos*/) /*!< MVFR0: A_SIMD registers bits Mask */
+
+/* Media and FP Feature Register 1 Definitions */
+#define FPU_MVFR1_FP_fused_MAC_Pos 28U /*!< MVFR1: FP fused MAC bits Position */
+#define FPU_MVFR1_FP_fused_MAC_Msk (0xFUL << FPU_MVFR1_FP_fused_MAC_Pos) /*!< MVFR1: FP fused MAC bits Mask */
+
+#define FPU_MVFR1_FP_HPFP_Pos 24U /*!< MVFR1: FP HPFP bits Position */
+#define FPU_MVFR1_FP_HPFP_Msk (0xFUL << FPU_MVFR1_FP_HPFP_Pos) /*!< MVFR1: FP HPFP bits Mask */
+
+#define FPU_MVFR1_D_NaN_mode_Pos 4U /*!< MVFR1: D_NaN mode bits Position */
+#define FPU_MVFR1_D_NaN_mode_Msk (0xFUL << FPU_MVFR1_D_NaN_mode_Pos) /*!< MVFR1: D_NaN mode bits Mask */
+
+#define FPU_MVFR1_FtZ_mode_Pos 0U /*!< MVFR1: FtZ mode bits Position */
+#define FPU_MVFR1_FtZ_mode_Msk (0xFUL /*<< FPU_MVFR1_FtZ_mode_Pos*/) /*!< MVFR1: FtZ mode bits Mask */
+
+/*@} end of group CMSIS_FPU */
+
+
+/**
+ \ingroup CMSIS_core_register
+ \defgroup CMSIS_CoreDebug Core Debug Registers (CoreDebug)
+ \brief Type definitions for the Core Debug Registers
+ @{
+ */
+
+/**
+ \brief Structure type to access the Core Debug Register (CoreDebug).
+ */
+typedef struct
+{
+ __IOM uint32_t DHCSR; /*!< Offset: 0x000 (R/W) Debug Halting Control and Status Register */
+ __OM uint32_t DCRSR; /*!< Offset: 0x004 ( /W) Debug Core Register Selector Register */
+ __IOM uint32_t DCRDR; /*!< Offset: 0x008 (R/W) Debug Core Register Data Register */
+ __IOM uint32_t DEMCR; /*!< Offset: 0x00C (R/W) Debug Exception and Monitor Control Register */
+} CoreDebug_Type;
+
+/* Debug Halting Control and Status Register Definitions */
+#define CoreDebug_DHCSR_DBGKEY_Pos 16U /*!< CoreDebug DHCSR: DBGKEY Position */
+#define CoreDebug_DHCSR_DBGKEY_Msk (0xFFFFUL << CoreDebug_DHCSR_DBGKEY_Pos) /*!< CoreDebug DHCSR: DBGKEY Mask */
+
+#define CoreDebug_DHCSR_S_RESET_ST_Pos 25U /*!< CoreDebug DHCSR: S_RESET_ST Position */
+#define CoreDebug_DHCSR_S_RESET_ST_Msk (1UL << CoreDebug_DHCSR_S_RESET_ST_Pos) /*!< CoreDebug DHCSR: S_RESET_ST Mask */
+
+#define CoreDebug_DHCSR_S_RETIRE_ST_Pos 24U /*!< CoreDebug DHCSR: S_RETIRE_ST Position */
+#define CoreDebug_DHCSR_S_RETIRE_ST_Msk (1UL << CoreDebug_DHCSR_S_RETIRE_ST_Pos) /*!< CoreDebug DHCSR: S_RETIRE_ST Mask */
+
+#define CoreDebug_DHCSR_S_LOCKUP_Pos 19U /*!< CoreDebug DHCSR: S_LOCKUP Position */
+#define CoreDebug_DHCSR_S_LOCKUP_Msk (1UL << CoreDebug_DHCSR_S_LOCKUP_Pos) /*!< CoreDebug DHCSR: S_LOCKUP Mask */
+
+#define CoreDebug_DHCSR_S_SLEEP_Pos 18U /*!< CoreDebug DHCSR: S_SLEEP Position */
+#define CoreDebug_DHCSR_S_SLEEP_Msk (1UL << CoreDebug_DHCSR_S_SLEEP_Pos) /*!< CoreDebug DHCSR: S_SLEEP Mask */
+
+#define CoreDebug_DHCSR_S_HALT_Pos 17U /*!< CoreDebug DHCSR: S_HALT Position */
+#define CoreDebug_DHCSR_S_HALT_Msk (1UL << CoreDebug_DHCSR_S_HALT_Pos) /*!< CoreDebug DHCSR: S_HALT Mask */
+
+#define CoreDebug_DHCSR_S_REGRDY_Pos 16U /*!< CoreDebug DHCSR: S_REGRDY Position */
+#define CoreDebug_DHCSR_S_REGRDY_Msk (1UL << CoreDebug_DHCSR_S_REGRDY_Pos) /*!< CoreDebug DHCSR: S_REGRDY Mask */
+
+#define CoreDebug_DHCSR_C_SNAPSTALL_Pos 5U /*!< CoreDebug DHCSR: C_SNAPSTALL Position */
+#define CoreDebug_DHCSR_C_SNAPSTALL_Msk (1UL << CoreDebug_DHCSR_C_SNAPSTALL_Pos) /*!< CoreDebug DHCSR: C_SNAPSTALL Mask */
+
+#define CoreDebug_DHCSR_C_MASKINTS_Pos 3U /*!< CoreDebug DHCSR: C_MASKINTS Position */
+#define CoreDebug_DHCSR_C_MASKINTS_Msk (1UL << CoreDebug_DHCSR_C_MASKINTS_Pos) /*!< CoreDebug DHCSR: C_MASKINTS Mask */
+
+#define CoreDebug_DHCSR_C_STEP_Pos 2U /*!< CoreDebug DHCSR: C_STEP Position */
+#define CoreDebug_DHCSR_C_STEP_Msk (1UL << CoreDebug_DHCSR_C_STEP_Pos) /*!< CoreDebug DHCSR: C_STEP Mask */
+
+#define CoreDebug_DHCSR_C_HALT_Pos 1U /*!< CoreDebug DHCSR: C_HALT Position */
+#define CoreDebug_DHCSR_C_HALT_Msk (1UL << CoreDebug_DHCSR_C_HALT_Pos) /*!< CoreDebug DHCSR: C_HALT Mask */
+
+#define CoreDebug_DHCSR_C_DEBUGEN_Pos 0U /*!< CoreDebug DHCSR: C_DEBUGEN Position */
+#define CoreDebug_DHCSR_C_DEBUGEN_Msk (1UL /*<< CoreDebug_DHCSR_C_DEBUGEN_Pos*/) /*!< CoreDebug DHCSR: C_DEBUGEN Mask */
+
+/* Debug Core Register Selector Register Definitions */
+#define CoreDebug_DCRSR_REGWnR_Pos 16U /*!< CoreDebug DCRSR: REGWnR Position */
+#define CoreDebug_DCRSR_REGWnR_Msk (1UL << CoreDebug_DCRSR_REGWnR_Pos) /*!< CoreDebug DCRSR: REGWnR Mask */
+
+#define CoreDebug_DCRSR_REGSEL_Pos 0U /*!< CoreDebug DCRSR: REGSEL Position */
+#define CoreDebug_DCRSR_REGSEL_Msk (0x1FUL /*<< CoreDebug_DCRSR_REGSEL_Pos*/) /*!< CoreDebug DCRSR: REGSEL Mask */
+
+/* Debug Exception and Monitor Control Register Definitions */
+#define CoreDebug_DEMCR_TRCENA_Pos 24U /*!< CoreDebug DEMCR: TRCENA Position */
+#define CoreDebug_DEMCR_TRCENA_Msk (1UL << CoreDebug_DEMCR_TRCENA_Pos) /*!< CoreDebug DEMCR: TRCENA Mask */
+
+#define CoreDebug_DEMCR_MON_REQ_Pos 19U /*!< CoreDebug DEMCR: MON_REQ Position */
+#define CoreDebug_DEMCR_MON_REQ_Msk (1UL << CoreDebug_DEMCR_MON_REQ_Pos) /*!< CoreDebug DEMCR: MON_REQ Mask */
+
+#define CoreDebug_DEMCR_MON_STEP_Pos 18U /*!< CoreDebug DEMCR: MON_STEP Position */
+#define CoreDebug_DEMCR_MON_STEP_Msk (1UL << CoreDebug_DEMCR_MON_STEP_Pos) /*!< CoreDebug DEMCR: MON_STEP Mask */
+
+#define CoreDebug_DEMCR_MON_PEND_Pos 17U /*!< CoreDebug DEMCR: MON_PEND Position */
+#define CoreDebug_DEMCR_MON_PEND_Msk (1UL << CoreDebug_DEMCR_MON_PEND_Pos) /*!< CoreDebug DEMCR: MON_PEND Mask */
+
+#define CoreDebug_DEMCR_MON_EN_Pos 16U /*!< CoreDebug DEMCR: MON_EN Position */
+#define CoreDebug_DEMCR_MON_EN_Msk (1UL << CoreDebug_DEMCR_MON_EN_Pos) /*!< CoreDebug DEMCR: MON_EN Mask */
+
+#define CoreDebug_DEMCR_VC_HARDERR_Pos 10U /*!< CoreDebug DEMCR: VC_HARDERR Position */
+#define CoreDebug_DEMCR_VC_HARDERR_Msk (1UL << CoreDebug_DEMCR_VC_HARDERR_Pos) /*!< CoreDebug DEMCR: VC_HARDERR Mask */
+
+#define CoreDebug_DEMCR_VC_INTERR_Pos 9U /*!< CoreDebug DEMCR: VC_INTERR Position */
+#define CoreDebug_DEMCR_VC_INTERR_Msk (1UL << CoreDebug_DEMCR_VC_INTERR_Pos) /*!< CoreDebug DEMCR: VC_INTERR Mask */
+
+#define CoreDebug_DEMCR_VC_BUSERR_Pos 8U /*!< CoreDebug DEMCR: VC_BUSERR Position */
+#define CoreDebug_DEMCR_VC_BUSERR_Msk (1UL << CoreDebug_DEMCR_VC_BUSERR_Pos) /*!< CoreDebug DEMCR: VC_BUSERR Mask */
+
+#define CoreDebug_DEMCR_VC_STATERR_Pos 7U /*!< CoreDebug DEMCR: VC_STATERR Position */
+#define CoreDebug_DEMCR_VC_STATERR_Msk (1UL << CoreDebug_DEMCR_VC_STATERR_Pos) /*!< CoreDebug DEMCR: VC_STATERR Mask */
+
+#define CoreDebug_DEMCR_VC_CHKERR_Pos 6U /*!< CoreDebug DEMCR: VC_CHKERR Position */
+#define CoreDebug_DEMCR_VC_CHKERR_Msk (1UL << CoreDebug_DEMCR_VC_CHKERR_Pos) /*!< CoreDebug DEMCR: VC_CHKERR Mask */
+
+#define CoreDebug_DEMCR_VC_NOCPERR_Pos 5U /*!< CoreDebug DEMCR: VC_NOCPERR Position */
+#define CoreDebug_DEMCR_VC_NOCPERR_Msk (1UL << CoreDebug_DEMCR_VC_NOCPERR_Pos) /*!< CoreDebug DEMCR: VC_NOCPERR Mask */
+
+#define CoreDebug_DEMCR_VC_MMERR_Pos 4U /*!< CoreDebug DEMCR: VC_MMERR Position */
+#define CoreDebug_DEMCR_VC_MMERR_Msk (1UL << CoreDebug_DEMCR_VC_MMERR_Pos) /*!< CoreDebug DEMCR: VC_MMERR Mask */
+
+#define CoreDebug_DEMCR_VC_CORERESET_Pos 0U /*!< CoreDebug DEMCR: VC_CORERESET Position */
+#define CoreDebug_DEMCR_VC_CORERESET_Msk (1UL /*<< CoreDebug_DEMCR_VC_CORERESET_Pos*/) /*!< CoreDebug DEMCR: VC_CORERESET Mask */
+
+/*@} 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 ITM_BASE (0xE0000000UL) /*!< ITM Base Address */
+#define DWT_BASE (0xE0001000UL) /*!< DWT Base Address */
+#define TPI_BASE (0xE0040000UL) /*!< TPI Base Address */
+#define CoreDebug_BASE (0xE000EDF0UL) /*!< Core Debug 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 SCnSCB ((SCnSCB_Type *) SCS_BASE ) /*!< System control Register not in SCB */
+#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 */
+#define ITM ((ITM_Type *) ITM_BASE ) /*!< ITM configuration struct */
+#define DWT ((DWT_Type *) DWT_BASE ) /*!< DWT configuration struct */
+#define TPI ((TPI_Type *) TPI_BASE ) /*!< TPI configuration struct */
+#define CoreDebug ((CoreDebug_Type *) CoreDebug_BASE) /*!< Core Debug configuration struct */
+
+#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U)
+ #define MPU_BASE (SCS_BASE + 0x0D90UL) /*!< Memory Protection Unit */
+ #define MPU ((MPU_Type *) MPU_BASE ) /*!< Memory Protection Unit */
+#endif
+
+#define FPU_BASE (SCS_BASE + 0x0F30UL) /*!< Floating Point Unit */
+#define FPU ((FPU_Type *) FPU_BASE ) /*!< Floating Point Unit */
+
+/*@} */
+
+
+
+/*******************************************************************************
+ * Hardware Abstraction Layer
+ Core Function Interface contains:
+ - Core NVIC Functions
+ - Core SysTick Functions
+ - Core Debug 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
+ #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
+
+
+
+/**
+ \brief Set Priority Grouping
+ \details Sets the priority grouping field using the required unlock sequence.
+ The parameter PriorityGroup is assigned to the field SCB->AIRCR [10:8] PRIGROUP field.
+ Only values from 0..7 are used.
+ 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 Priority grouping field.
+ */
+__STATIC_INLINE void __NVIC_SetPriorityGrouping(uint32_t PriorityGroup)
+{
+ uint32_t reg_value;
+ uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */
+
+ reg_value = SCB->AIRCR; /* read old register configuration */
+ reg_value &= ~((uint32_t)(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk)); /* clear bits to change */
+ reg_value = (reg_value |
+ ((uint32_t)0x5FAUL << SCB_AIRCR_VECTKEY_Pos) |
+ (PriorityGroupTmp << SCB_AIRCR_PRIGROUP_Pos) ); /* Insert write key and priority group */
+ SCB->AIRCR = reg_value;
+}
+
+
+/**
+ \brief Get Priority Grouping
+ \details Reads the priority grouping field from the NVIC Interrupt Controller.
+ \return Priority grouping field (SCB->AIRCR [10:8] PRIGROUP field).
+ */
+__STATIC_INLINE uint32_t __NVIC_GetPriorityGrouping(void)
+{
+ return ((uint32_t)((SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) >> SCB_AIRCR_PRIGROUP_Pos));
+}
+
+
+/**
+ \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[(((uint32_t)IRQn) >> 5UL)] = (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[(((uint32_t)IRQn) >> 5UL)] & (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[(((uint32_t)IRQn) >> 5UL)] = (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[(((uint32_t)IRQn) >> 5UL)] & (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[(((uint32_t)IRQn) >> 5UL)] = (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[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL));
+ }
+}
+
+
+/**
+ \brief Get Active Interrupt
+ \details Reads the active register in the NVIC and returns the active bit for the device specific interrupt.
+ \param [in] IRQn Device specific interrupt number.
+ \return 0 Interrupt status is not active.
+ \return 1 Interrupt status is active.
+ \note IRQn must not be negative.
+ */
+__STATIC_INLINE uint32_t __NVIC_GetActive(IRQn_Type IRQn)
+{
+ if ((int32_t)(IRQn) >= 0)
+ {
+ return((uint32_t)(((NVIC->IABR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL));
+ }
+ else
+ {
+ return(0U);
+ }
+}
+
+
+/**
+ \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[((uint32_t)IRQn)] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL);
+ }
+ else
+ {
+ SCB->SHP[(((uint32_t)IRQn) & 0xFUL)-4UL] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL);
+ }
+}
+
+
+/**
+ \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[((uint32_t)IRQn)] >> (8U - __NVIC_PRIO_BITS)));
+ }
+ else
+ {
+ return(((uint32_t)SCB->SHP[(((uint32_t)IRQn) & 0xFUL)-4UL] >> (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.
+ VTOR must been relocated to SRAM before.
+ \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 *)SCB->VTOR;
+ 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 *)SCB->VTOR;
+ return vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET];
+}
+
+
+/**
+ \brief System Reset
+ \details Initiates a system reset request to reset the MCU.
+ */
+__STATIC_INLINE void __NVIC_SystemReset(void)
+{
+ __DSB(); /* Ensure all outstanding memory accesses included
+ buffered write are completed before reset */
+ SCB->AIRCR = (uint32_t)((0x5FAUL << SCB_AIRCR_VECTKEY_Pos) |
+ (SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) |
+ SCB_AIRCR_SYSRESETREQ_Msk ); /* Keep priority group unchanged */
+ __DSB(); /* Ensure completion of memory access */
+
+ for(;;) /* wait until reset */
+ {
+ __NOP();
+ }
+}
+
+/*@} end of CMSIS_Core_NVICFunctions */
+
+/* ########################## MPU functions #################################### */
+
+#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U)
+
+#include "mpu_armv7.h"
+
+#endif
+
+
+/* ########################## 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)
+{
+ uint32_t mvfr0;
+
+ mvfr0 = FPU->MVFR0;
+ if ((mvfr0 & (FPU_MVFR0_Single_precision_Msk | FPU_MVFR0_Double_precision_Msk)) == 0x020U)
+ {
+ return 1U; /* Single precision FPU */
+ }
+ else
+ {
+ 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 <b>__Vendor_SysTickConfig</b> is set to 1, then the
+ function <b>SysTick_Config</b> is not included. In this case, the file <b><i>device</i>.h</b>
+ 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 */
+
+
+
+/* ##################################### Debug In/Output function ########################################### */
+/**
+ \ingroup CMSIS_Core_FunctionInterface
+ \defgroup CMSIS_core_DebugFunctions ITM Functions
+ \brief Functions that access the ITM debug interface.
+ @{
+ */
+
+extern volatile int32_t ITM_RxBuffer; /*!< External variable to receive characters. */
+#define ITM_RXBUFFER_EMPTY ((int32_t)0x5AA55AA5U) /*!< Value identifying \ref ITM_RxBuffer is ready for next character. */
+
+
+/**
+ \brief ITM Send Character
+ \details Transmits a character via the ITM channel 0, and
+ \li Just returns when no debugger is connected that has booked the output.
+ \li Is blocking when a debugger is connected, but the previous character sent has not been transmitted.
+ \param [in] ch Character to transmit.
+ \returns Character to transmit.
+ */
+__STATIC_INLINE uint32_t ITM_SendChar (uint32_t ch)
+{
+ if (((ITM->TCR & ITM_TCR_ITMENA_Msk) != 0UL) && /* ITM enabled */
+ ((ITM->TER & 1UL ) != 0UL) ) /* ITM Port #0 enabled */
+ {
+ while (ITM->PORT[0U].u32 == 0UL)
+ {
+ __NOP();
+ }
+ ITM->PORT[0U].u8 = (uint8_t)ch;
+ }
+ return (ch);
+}
+
+
+/**
+ \brief ITM Receive Character
+ \details Inputs a character via the external variable \ref ITM_RxBuffer.
+ \return Received character.
+ \return -1 No character pending.
+ */
+__STATIC_INLINE int32_t ITM_ReceiveChar (void)
+{
+ int32_t ch = -1; /* no character available */
+
+ if (ITM_RxBuffer != ITM_RXBUFFER_EMPTY)
+ {
+ ch = ITM_RxBuffer;
+ ITM_RxBuffer = ITM_RXBUFFER_EMPTY; /* ready for next character */
+ }
+
+ return (ch);
+}
+
+
+/**
+ \brief ITM Check Character
+ \details Checks whether a character is pending for reading in the variable \ref ITM_RxBuffer.
+ \return 0 No character available.
+ \return 1 Character available.
+ */
+__STATIC_INLINE int32_t ITM_CheckChar (void)
+{
+
+ if (ITM_RxBuffer == ITM_RXBUFFER_EMPTY)
+ {
+ return (0); /* no character available */
+ }
+ else
+ {
+ return (1); /* character available */
+ }
+}
+
+/*@} end of CMSIS_core_DebugFunctions */
+
+
+
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __CORE_CM4_H_DEPENDANT */
+
+#endif /* __CMSIS_GENERIC */
diff --git a/CMSIS/fsl_device_registers.h b/CMSIS/fsl_device_registers.h
new file mode 100644
index 0000000..2bfaa90
--- /dev/null
+++ b/CMSIS/fsl_device_registers.h
@@ -0,0 +1,64 @@
+/*
+ * The Clear BSD License
+ * Copyright 2014-2016 Freescale Semiconductor, Inc.
+ * Copyright 2016-2017 NXP
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted (subject to the limitations in the
+ * disclaimer below) provided that the following conditions are met:
+ *
+ * * Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ *
+ * * 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.
+ *
+ * * Neither the name of the copyright holder nor the names of its
+ * contributors may be used to endorse or promote products derived from
+ * this software without specific prior written permission.
+ *
+ * NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE
+ * GRANTED BY THIS LICENSE. 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.
+ *
+ */
+
+#ifndef __FSL_DEVICE_REGISTERS_H__
+#define __FSL_DEVICE_REGISTERS_H__
+
+/*
+ * Include the cpu specific register header files.
+ *
+ * The CPU macro should be declared in the project or makefile.
+ */
+#if (defined(CPU_MK02FN128VFM10) || defined(CPU_MK02FN128VLF10) || defined(CPU_MK02FN128VLH10) || \
+ defined(CPU_MK02FN64VFM10) || defined(CPU_MK02FN64VLF10) || defined(CPU_MK02FN64VLH10))
+
+#define K02F12810_SERIES
+
+/* CMSIS-style register definitions */
+#include "MK02F12810.h"
+/* CPU specific feature definitions */
+#include "MK02F12810_features.h"
+
+#else
+ #error "No valid CPU defined!"
+#endif
+
+#endif /* __FSL_DEVICE_REGISTERS_H__ */
+
+/*******************************************************************************
+ * EOF
+ ******************************************************************************/
diff --git a/CMSIS/mpu_armv7.h b/CMSIS/mpu_armv7.h
new file mode 100644
index 0000000..aa180c9
--- /dev/null
+++ b/CMSIS/mpu_armv7.h
@@ -0,0 +1,197 @@
+/******************************************************************************
+ * @file mpu_armv7.h
+ * @brief CMSIS MPU API for Armv7-M MPU
+ * @version V5.0.4
+ * @date 10. January 2018
+ ******************************************************************************/
+/*
+ * Copyright (c) 2017-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 ARM_MPU_ARMV7_H
+#define ARM_MPU_ARMV7_H
+
+#define ARM_MPU_REGION_SIZE_32B ((uint8_t)0x04U)
+#define ARM_MPU_REGION_SIZE_64B ((uint8_t)0x05U)
+#define ARM_MPU_REGION_SIZE_128B ((uint8_t)0x06U)
+#define ARM_MPU_REGION_SIZE_256B ((uint8_t)0x07U)
+#define ARM_MPU_REGION_SIZE_512B ((uint8_t)0x08U)
+#define ARM_MPU_REGION_SIZE_1KB ((uint8_t)0x09U)
+#define ARM_MPU_REGION_SIZE_2KB ((uint8_t)0x0AU)
+#define ARM_MPU_REGION_SIZE_4KB ((uint8_t)0x0BU)
+#define ARM_MPU_REGION_SIZE_8KB ((uint8_t)0x0CU)
+#define ARM_MPU_REGION_SIZE_16KB ((uint8_t)0x0DU)
+#define ARM_MPU_REGION_SIZE_32KB ((uint8_t)0x0EU)
+#define ARM_MPU_REGION_SIZE_64KB ((uint8_t)0x0FU)
+#define ARM_MPU_REGION_SIZE_128KB ((uint8_t)0x10U)
+#define ARM_MPU_REGION_SIZE_256KB ((uint8_t)0x11U)
+#define ARM_MPU_REGION_SIZE_512KB ((uint8_t)0x12U)
+#define ARM_MPU_REGION_SIZE_1MB ((uint8_t)0x13U)
+#define ARM_MPU_REGION_SIZE_2MB ((uint8_t)0x14U)
+#define ARM_MPU_REGION_SIZE_4MB ((uint8_t)0x15U)
+#define ARM_MPU_REGION_SIZE_8MB ((uint8_t)0x16U)
+#define ARM_MPU_REGION_SIZE_16MB ((uint8_t)0x17U)
+#define ARM_MPU_REGION_SIZE_32MB ((uint8_t)0x18U)
+#define ARM_MPU_REGION_SIZE_64MB ((uint8_t)0x19U)
+#define ARM_MPU_REGION_SIZE_128MB ((uint8_t)0x1AU)
+#define ARM_MPU_REGION_SIZE_256MB ((uint8_t)0x1BU)
+#define ARM_MPU_REGION_SIZE_512MB ((uint8_t)0x1CU)
+#define ARM_MPU_REGION_SIZE_1GB ((uint8_t)0x1DU)
+#define ARM_MPU_REGION_SIZE_2GB ((uint8_t)0x1EU)
+#define ARM_MPU_REGION_SIZE_4GB ((uint8_t)0x1FU)
+
+#define ARM_MPU_AP_NONE 0U
+#define ARM_MPU_AP_PRIV 1U
+#define ARM_MPU_AP_URO 2U
+#define ARM_MPU_AP_FULL 3U
+#define ARM_MPU_AP_PRO 5U
+#define ARM_MPU_AP_RO 6U
+
+/** MPU Region Base Address Register Value
+*
+* \param Region The region to be configured, number 0 to 15.
+* \param BaseAddress The base address for the region.
+*/
+#define ARM_MPU_RBAR(Region, BaseAddress) \
+ (((BaseAddress) & MPU_RBAR_ADDR_Msk) | \
+ ((Region) & MPU_RBAR_REGION_Msk) | \
+ (MPU_RBAR_VALID_Msk))
+
+/**
+* MPU Region Attribute and Size Register Value
+*
+* \param DisableExec Instruction access disable bit, 1= disable instruction fetches.
+* \param AccessPermission Data access permissions, allows you to configure read/write access for User and Privileged mode.
+* \param TypeExtField Type extension field, allows you to configure memory access type, for example strongly ordered, peripheral.
+* \param IsShareable Region is shareable between multiple bus masters.
+* \param IsCacheable Region is cacheable, i.e. its value may be kept in cache.
+* \param IsBufferable Region is bufferable, i.e. using write-back caching. Cacheable but non-bufferable regions use write-through policy.
+* \param SubRegionDisable Sub-region disable field.
+* \param Size Region size of the region to be configured, for example 4K, 8K.
+*/
+#define ARM_MPU_RASR(DisableExec, AccessPermission, TypeExtField, IsShareable, IsCacheable, IsBufferable, SubRegionDisable, Size) \
+ ((((DisableExec ) << MPU_RASR_XN_Pos) & MPU_RASR_XN_Msk) | \
+ (((AccessPermission) << MPU_RASR_AP_Pos) & MPU_RASR_AP_Msk) | \
+ (((TypeExtField ) << MPU_RASR_TEX_Pos) & MPU_RASR_TEX_Msk) | \
+ (((IsShareable ) << MPU_RASR_S_Pos) & MPU_RASR_S_Msk) | \
+ (((IsCacheable ) << MPU_RASR_C_Pos) & MPU_RASR_C_Msk) | \
+ (((IsBufferable ) << MPU_RASR_B_Pos) & MPU_RASR_B_Msk) | \
+ (((SubRegionDisable) << MPU_RASR_SRD_Pos) & MPU_RASR_SRD_Msk) | \
+ (((Size ) << MPU_RASR_SIZE_Pos) & MPU_RASR_SIZE_Msk) | \
+ (MPU_RASR_ENABLE_Msk))
+
+
+/**
+* Struct for a single MPU Region
+*/
+typedef struct {
+ uint32_t RBAR; //!< The region base address register value (RBAR)
+ uint32_t RASR; //!< The region attribute and size register value (RASR) \ref MPU_RASR
+} ARM_MPU_Region_t;
+
+/** Enable the MPU.
+* \param MPU_Control Default access permissions for unconfigured regions.
+*/
+__STATIC_INLINE void ARM_MPU_Enable(uint32_t MPU_Control)
+{
+ __DSB();
+ __ISB();
+ MPU->CTRL = MPU_Control | MPU_CTRL_ENABLE_Msk;
+#ifdef SCB_SHCSR_MEMFAULTENA_Msk
+ SCB->SHCSR |= SCB_SHCSR_MEMFAULTENA_Msk;
+#endif
+}
+
+/** Disable the MPU.
+*/
+__STATIC_INLINE void ARM_MPU_Disable(void)
+{
+ __DSB();
+ __ISB();
+#ifdef SCB_SHCSR_MEMFAULTENA_Msk
+ SCB->SHCSR &= ~SCB_SHCSR_MEMFAULTENA_Msk;
+#endif
+ MPU->CTRL &= ~MPU_CTRL_ENABLE_Msk;
+}
+
+/** Clear and disable the given MPU region.
+* \param rnr Region number to be cleared.
+*/
+__STATIC_INLINE void ARM_MPU_ClrRegion(uint32_t rnr)
+{
+ MPU->RNR = rnr;
+ MPU->RASR = 0U;
+}
+
+/** Configure an MPU region.
+* \param rbar Value for RBAR register.
+* \param rsar Value for RSAR register.
+*/
+__STATIC_INLINE void ARM_MPU_SetRegion(uint32_t rbar, uint32_t rasr)
+{
+ MPU->RBAR = rbar;
+ MPU->RASR = rasr;
+}
+
+/** Configure the given MPU region.
+* \param rnr Region number to be configured.
+* \param rbar Value for RBAR register.
+* \param rsar Value for RSAR register.
+*/
+__STATIC_INLINE void ARM_MPU_SetRegionEx(uint32_t rnr, uint32_t rbar, uint32_t rasr)
+{
+ MPU->RNR = rnr;
+ MPU->RBAR = rbar;
+ MPU->RASR = rasr;
+}
+
+/** Memcopy with strictly ordered memory access, e.g. for register targets.
+* \param dst Destination data is copied to.
+* \param src Source data is copied from.
+* \param len Amount of data words to be copied.
+*/
+__STATIC_INLINE void orderedCpy(volatile uint32_t* dst, const uint32_t* __RESTRICT src, uint32_t len)
+{
+ uint32_t i;
+ for (i = 0U; i < len; ++i)
+ {
+ dst[i] = src[i];
+ }
+}
+
+/** Load the given number of MPU regions from a table.
+* \param table Pointer to the MPU configuration table.
+* \param cnt Amount of regions to be configured.
+*/
+__STATIC_INLINE void ARM_MPU_Load(ARM_MPU_Region_t const* table, uint32_t cnt)
+{
+ const uint32_t rowWordSize = sizeof(ARM_MPU_Region_t)/4U;
+ while (cnt > MPU_TYPE_RALIASES) {
+ orderedCpy(&(MPU->RBAR), &(table->RBAR), MPU_TYPE_RALIASES*rowWordSize);
+ table += MPU_TYPE_RALIASES;
+ cnt -= MPU_TYPE_RALIASES;
+ }
+ orderedCpy(&(MPU->RBAR), &(table->RBAR), cnt*rowWordSize);
+}
+
+#endif
diff --git a/CMSIS/mpu_armv8.h b/CMSIS/mpu_armv8.h
new file mode 100644
index 0000000..0ccfc74
--- /dev/null
+++ b/CMSIS/mpu_armv8.h
@@ -0,0 +1,333 @@
+/******************************************************************************
+ * @file mpu_armv8.h
+ * @brief CMSIS MPU API for Armv8-M MPU
+ * @version V5.0.4
+ * @date 10. January 2018
+ ******************************************************************************/
+/*
+ * Copyright (c) 2017-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 ARM_MPU_ARMV8_H
+#define ARM_MPU_ARMV8_H
+
+/** \brief Attribute for device memory (outer only) */
+#define ARM_MPU_ATTR_DEVICE ( 0U )
+
+/** \brief Attribute for non-cacheable, normal memory */
+#define ARM_MPU_ATTR_NON_CACHEABLE ( 4U )
+
+/** \brief Attribute for normal memory (outer and inner)
+* \param NT Non-Transient: Set to 1 for non-transient data.
+* \param WB Write-Back: Set to 1 to use write-back update policy.
+* \param RA Read Allocation: Set to 1 to use cache allocation on read miss.
+* \param WA Write Allocation: Set to 1 to use cache allocation on write miss.
+*/
+#define ARM_MPU_ATTR_MEMORY_(NT, WB, RA, WA) \
+ (((NT & 1U) << 3U) | ((WB & 1U) << 2U) | ((RA & 1U) << 1U) | (WA & 1U))
+
+/** \brief Device memory type non Gathering, non Re-ordering, non Early Write Acknowledgement */
+#define ARM_MPU_ATTR_DEVICE_nGnRnE (0U)
+
+/** \brief Device memory type non Gathering, non Re-ordering, Early Write Acknowledgement */
+#define ARM_MPU_ATTR_DEVICE_nGnRE (1U)
+
+/** \brief Device memory type non Gathering, Re-ordering, Early Write Acknowledgement */
+#define ARM_MPU_ATTR_DEVICE_nGRE (2U)
+
+/** \brief Device memory type Gathering, Re-ordering, Early Write Acknowledgement */
+#define ARM_MPU_ATTR_DEVICE_GRE (3U)
+
+/** \brief Memory Attribute
+* \param O Outer memory attributes
+* \param I O == ARM_MPU_ATTR_DEVICE: Device memory attributes, else: Inner memory attributes
+*/
+#define ARM_MPU_ATTR(O, I) (((O & 0xFU) << 4U) | (((O & 0xFU) != 0U) ? (I & 0xFU) : ((I & 0x3U) << 2U)))
+
+/** \brief Normal memory non-shareable */
+#define ARM_MPU_SH_NON (0U)
+
+/** \brief Normal memory outer shareable */
+#define ARM_MPU_SH_OUTER (2U)
+
+/** \brief Normal memory inner shareable */
+#define ARM_MPU_SH_INNER (3U)
+
+/** \brief Memory access permissions
+* \param RO Read-Only: Set to 1 for read-only memory.
+* \param NP Non-Privileged: Set to 1 for non-privileged memory.
+*/
+#define ARM_MPU_AP_(RO, NP) (((RO & 1U) << 1U) | (NP & 1U))
+
+/** \brief Region Base Address Register value
+* \param BASE The base address bits [31:5] of a memory region. The value is zero extended. Effective address gets 32 byte aligned.
+* \param SH Defines the Shareability domain for this memory region.
+* \param RO Read-Only: Set to 1 for a read-only memory region.
+* \param NP Non-Privileged: Set to 1 for a non-privileged memory region.
+* \oaram XN eXecute Never: Set to 1 for a non-executable memory region.
+*/
+#define ARM_MPU_RBAR(BASE, SH, RO, NP, XN) \
+ ((BASE & MPU_RBAR_BASE_Pos) | \
+ ((SH << MPU_RBAR_SH_Pos) & MPU_RBAR_SH_Msk) | \
+ ((ARM_MPU_AP_(RO, NP) << MPU_RBAR_AP_Pos) & MPU_RBAR_AP_Msk) | \
+ ((XN << MPU_RBAR_XN_Pos) & MPU_RBAR_XN_Msk))
+
+/** \brief Region Limit Address Register value
+* \param LIMIT The limit address bits [31:5] for this memory region. The value is one extended.
+* \param IDX The attribute index to be associated with this memory region.
+*/
+#define ARM_MPU_RLAR(LIMIT, IDX) \
+ ((LIMIT & MPU_RLAR_LIMIT_Msk) | \
+ ((IDX << MPU_RLAR_AttrIndx_Pos) & MPU_RLAR_AttrIndx_Msk) | \
+ (MPU_RLAR_EN_Msk))
+
+/**
+* Struct for a single MPU Region
+*/
+typedef struct {
+ uint32_t RBAR; /*!< Region Base Address Register value */
+ uint32_t RLAR; /*!< Region Limit Address Register value */
+} ARM_MPU_Region_t;
+
+/** Enable the MPU.
+* \param MPU_Control Default access permissions for unconfigured regions.
+*/
+__STATIC_INLINE void ARM_MPU_Enable(uint32_t MPU_Control)
+{
+ __DSB();
+ __ISB();
+ MPU->CTRL = MPU_Control | MPU_CTRL_ENABLE_Msk;
+#ifdef SCB_SHCSR_MEMFAULTENA_Msk
+ SCB->SHCSR |= SCB_SHCSR_MEMFAULTENA_Msk;
+#endif
+}
+
+/** Disable the MPU.
+*/
+__STATIC_INLINE void ARM_MPU_Disable(void)
+{
+ __DSB();
+ __ISB();
+#ifdef SCB_SHCSR_MEMFAULTENA_Msk
+ SCB->SHCSR &= ~SCB_SHCSR_MEMFAULTENA_Msk;
+#endif
+ MPU->CTRL &= ~MPU_CTRL_ENABLE_Msk;
+}
+
+#ifdef MPU_NS
+/** Enable the Non-secure MPU.
+* \param MPU_Control Default access permissions for unconfigured regions.
+*/
+__STATIC_INLINE void ARM_MPU_Enable_NS(uint32_t MPU_Control)
+{
+ __DSB();
+ __ISB();
+ MPU_NS->CTRL = MPU_Control | MPU_CTRL_ENABLE_Msk;
+#ifdef SCB_SHCSR_MEMFAULTENA_Msk
+ SCB_NS->SHCSR |= SCB_SHCSR_MEMFAULTENA_Msk;
+#endif
+}
+
+/** Disable the Non-secure MPU.
+*/
+__STATIC_INLINE void ARM_MPU_Disable_NS(void)
+{
+ __DSB();
+ __ISB();
+#ifdef SCB_SHCSR_MEMFAULTENA_Msk
+ SCB_NS->SHCSR &= ~SCB_SHCSR_MEMFAULTENA_Msk;
+#endif
+ MPU_NS->CTRL &= ~MPU_CTRL_ENABLE_Msk;
+}
+#endif
+
+/** Set the memory attribute encoding to the given MPU.
+* \param mpu Pointer to the MPU to be configured.
+* \param idx The attribute index to be set [0-7]
+* \param attr The attribute value to be set.
+*/
+__STATIC_INLINE void ARM_MPU_SetMemAttrEx(MPU_Type* mpu, uint8_t idx, uint8_t attr)
+{
+ const uint8_t reg = idx / 4U;
+ const uint32_t pos = ((idx % 4U) * 8U);
+ const uint32_t mask = 0xFFU << pos;
+
+ if (reg >= (sizeof(mpu->MAIR) / sizeof(mpu->MAIR[0]))) {
+ return; // invalid index
+ }
+
+ mpu->MAIR[reg] = ((mpu->MAIR[reg] & ~mask) | ((attr << pos) & mask));
+}
+
+/** Set the memory attribute encoding.
+* \param idx The attribute index to be set [0-7]
+* \param attr The attribute value to be set.
+*/
+__STATIC_INLINE void ARM_MPU_SetMemAttr(uint8_t idx, uint8_t attr)
+{
+ ARM_MPU_SetMemAttrEx(MPU, idx, attr);
+}
+
+#ifdef MPU_NS
+/** Set the memory attribute encoding to the Non-secure MPU.
+* \param idx The attribute index to be set [0-7]
+* \param attr The attribute value to be set.
+*/
+__STATIC_INLINE void ARM_MPU_SetMemAttr_NS(uint8_t idx, uint8_t attr)
+{
+ ARM_MPU_SetMemAttrEx(MPU_NS, idx, attr);
+}
+#endif
+
+/** Clear and disable the given MPU region of the given MPU.
+* \param mpu Pointer to MPU to be used.
+* \param rnr Region number to be cleared.
+*/
+__STATIC_INLINE void ARM_MPU_ClrRegionEx(MPU_Type* mpu, uint32_t rnr)
+{
+ mpu->RNR = rnr;
+ mpu->RLAR = 0U;
+}
+
+/** Clear and disable the given MPU region.
+* \param rnr Region number to be cleared.
+*/
+__STATIC_INLINE void ARM_MPU_ClrRegion(uint32_t rnr)
+{
+ ARM_MPU_ClrRegionEx(MPU, rnr);
+}
+
+#ifdef MPU_NS
+/** Clear and disable the given Non-secure MPU region.
+* \param rnr Region number to be cleared.
+*/
+__STATIC_INLINE void ARM_MPU_ClrRegion_NS(uint32_t rnr)
+{
+ ARM_MPU_ClrRegionEx(MPU_NS, rnr);
+}
+#endif
+
+/** Configure the given MPU region of the given MPU.
+* \param mpu Pointer to MPU to be used.
+* \param rnr Region number to be configured.
+* \param rbar Value for RBAR register.
+* \param rlar Value for RLAR register.
+*/
+__STATIC_INLINE void ARM_MPU_SetRegionEx(MPU_Type* mpu, uint32_t rnr, uint32_t rbar, uint32_t rlar)
+{
+ mpu->RNR = rnr;
+ mpu->RBAR = rbar;
+ mpu->RLAR = rlar;
+}
+
+/** Configure the given MPU region.
+* \param rnr Region number to be configured.
+* \param rbar Value for RBAR register.
+* \param rlar Value for RLAR register.
+*/
+__STATIC_INLINE void ARM_MPU_SetRegion(uint32_t rnr, uint32_t rbar, uint32_t rlar)
+{
+ ARM_MPU_SetRegionEx(MPU, rnr, rbar, rlar);
+}
+
+#ifdef MPU_NS
+/** Configure the given Non-secure MPU region.
+* \param rnr Region number to be configured.
+* \param rbar Value for RBAR register.
+* \param rlar Value for RLAR register.
+*/
+__STATIC_INLINE void ARM_MPU_SetRegion_NS(uint32_t rnr, uint32_t rbar, uint32_t rlar)
+{
+ ARM_MPU_SetRegionEx(MPU_NS, rnr, rbar, rlar);
+}
+#endif
+
+/** Memcopy with strictly ordered memory access, e.g. for register targets.
+* \param dst Destination data is copied to.
+* \param src Source data is copied from.
+* \param len Amount of data words to be copied.
+*/
+__STATIC_INLINE void orderedCpy(volatile uint32_t* dst, const uint32_t* __RESTRICT src, uint32_t len)
+{
+ uint32_t i;
+ for (i = 0U; i < len; ++i)
+ {
+ dst[i] = src[i];
+ }
+}
+
+/** Load the given number of MPU regions from a table to the given MPU.
+* \param mpu Pointer to the MPU registers to be used.
+* \param rnr First region number to be configured.
+* \param table Pointer to the MPU configuration table.
+* \param cnt Amount of regions to be configured.
+*/
+__STATIC_INLINE void ARM_MPU_LoadEx(MPU_Type* mpu, uint32_t rnr, ARM_MPU_Region_t const* table, uint32_t cnt)
+{
+ const uint32_t rowWordSize = sizeof(ARM_MPU_Region_t)/4U;
+ if (cnt == 1U) {
+ mpu->RNR = rnr;
+ orderedCpy(&(mpu->RBAR), &(table->RBAR), rowWordSize);
+ } else {
+ uint32_t rnrBase = rnr & ~(MPU_TYPE_RALIASES-1U);
+ uint32_t rnrOffset = rnr % MPU_TYPE_RALIASES;
+
+ mpu->RNR = rnrBase;
+ while ((rnrOffset + cnt) > MPU_TYPE_RALIASES) {
+ uint32_t c = MPU_TYPE_RALIASES - rnrOffset;
+ orderedCpy(&(mpu->RBAR)+(rnrOffset*2U), &(table->RBAR), c*rowWordSize);
+ table += c;
+ cnt -= c;
+ rnrOffset = 0U;
+ rnrBase += MPU_TYPE_RALIASES;
+ mpu->RNR = rnrBase;
+ }
+
+ orderedCpy(&(mpu->RBAR)+(rnrOffset*2U), &(table->RBAR), cnt*rowWordSize);
+ }
+}
+
+/** Load the given number of MPU regions from a table.
+* \param rnr First region number to be configured.
+* \param table Pointer to the MPU configuration table.
+* \param cnt Amount of regions to be configured.
+*/
+__STATIC_INLINE void ARM_MPU_Load(uint32_t rnr, ARM_MPU_Region_t const* table, uint32_t cnt)
+{
+ ARM_MPU_LoadEx(MPU, rnr, table, cnt);
+}
+
+#ifdef MPU_NS
+/** Load the given number of MPU regions from a table to the Non-secure MPU.
+* \param rnr First region number to be configured.
+* \param table Pointer to the MPU configuration table.
+* \param cnt Amount of regions to be configured.
+*/
+__STATIC_INLINE void ARM_MPU_Load_NS(uint32_t rnr, ARM_MPU_Region_t const* table, uint32_t cnt)
+{
+ ARM_MPU_LoadEx(MPU_NS, rnr, table, cnt);
+}
+#endif
+
+#endif
+
diff --git a/CMSIS/system_MK02F12810.c b/CMSIS/system_MK02F12810.c
new file mode 100644
index 0000000..9caf3f4
--- /dev/null
+++ b/CMSIS/system_MK02F12810.c
@@ -0,0 +1,229 @@
+/*
+** ###################################################################
+** Processors: MK02FN128VFM10
+** MK02FN128VLF10
+** MK02FN128VLH10
+** MK02FN64VFM10
+** MK02FN64VLF10
+** MK02FN64VLH10
+**
+** Compilers: Keil ARM C/C++ Compiler
+** Freescale C/C++ for Embedded ARM
+** GNU C Compiler
+** IAR ANSI C/C++ Compiler for ARM
+** MCUXpresso Compiler
+**
+** Reference manual: K02P64M100SFARM, Rev. 0, February 14, 2014
+** Version: rev. 0.5, 2015-02-19
+** Build: b171226
+**
+** Abstract:
+** Provides a system configuration function and a global variable that
+** contains the system frequency. It configures the device and initializes
+** the oscillator (PLL) that is part of the microcontroller device.
+**
+** The Clear BSD License
+** Copyright 2016 Freescale Semiconductor, Inc.
+** Copyright 2016-2017 NXP
+** All rights reserved.
+**
+** Redistribution and use in source and binary forms, with or without
+** modification, are permitted (subject to the limitations in the
+** disclaimer below) provided that the following conditions are met:
+**
+** * Redistributions of source code must retain the above copyright
+** notice, this list of conditions and the following disclaimer.
+**
+** * 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.
+**
+** * Neither the name of the copyright holder nor the names of its
+** contributors may be used to endorse or promote products derived from
+** this software without specific prior written permission.
+**
+** NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE
+** GRANTED BY THIS LICENSE. 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.
+**
+** http: www.nxp.com
+** mail: support@nxp.com
+**
+** Revisions:
+** - rev. 0.1 (2014-02-24)
+** Initial version
+** - rev. 0.2 (2014-07-15)
+** Module access macro module_BASES replaced by module_BASE_PTRS.
+** Update of system and startup files.
+** - rev. 0.3 (2014-08-28)
+** Update of system files - default clock configuration changed.
+** Update of startup files - possibility to override DefaultISR added.
+** - rev. 0.4 (2014-10-14)
+** Interrupt INT_LPTimer renamed to INT_LPTMR0, interrupt INT_Watchdog renamed to INT_WDOG_EWM.
+** - rev. 0.5 (2015-02-19)
+** Renamed interrupt vector LLW to LLWU.
+**
+** ###################################################################
+*/
+
+/*!
+ * @file MK02F12810
+ * @version 0.5
+ * @date 2015-02-19
+ * @brief Device specific configuration file for MK02F12810 (implementation file)
+ *
+ * Provides a system configuration function and a global variable that contains
+ * the system frequency. It configures the device and initializes the oscillator
+ * (PLL) that is part of the microcontroller device.
+ */
+
+#include <stdint.h>
+#include "fsl_device_registers.h"
+
+
+
+/* ----------------------------------------------------------------------------
+ -- Core clock
+ ---------------------------------------------------------------------------- */
+
+uint32_t SystemCoreClock = DEFAULT_SYSTEM_CLOCK;
+
+/* ----------------------------------------------------------------------------
+ -- SystemInit()
+ ---------------------------------------------------------------------------- */
+
+void SystemInit (void) {
+#if ((__FPU_PRESENT == 1) && (__FPU_USED == 1))
+ SCB->CPACR |= ((3UL << 10*2) | (3UL << 11*2)); /* set CP10, CP11 Full Access */
+#endif /* ((__FPU_PRESENT == 1) && (__FPU_USED == 1)) */
+
+#if (DISABLE_WDOG)
+ /* WDOG->UNLOCK: WDOGUNLOCK=0xC520 */
+ WDOG->UNLOCK = WDOG_UNLOCK_WDOGUNLOCK(0xC520); /* Key 1 */
+ /* WDOG->UNLOCK: WDOGUNLOCK=0xD928 */
+ WDOG->UNLOCK = WDOG_UNLOCK_WDOGUNLOCK(0xD928); /* Key 2 */
+ /* WDOG->STCTRLH: ?=0,DISTESTWDOG=0,BYTESEL=0,TESTSEL=0,TESTWDOG=0,?=0,?=1,WAITEN=1,STOPEN=1,DBGEN=0,ALLOWUPDATE=1,WINEN=0,IRQRSTEN=0,CLKSRC=1,WDOGEN=0 */
+ WDOG->STCTRLH = WDOG_STCTRLH_BYTESEL(0x00) |
+ WDOG_STCTRLH_WAITEN_MASK |
+ WDOG_STCTRLH_STOPEN_MASK |
+ WDOG_STCTRLH_ALLOWUPDATE_MASK |
+ WDOG_STCTRLH_CLKSRC_MASK |
+ 0x0100U;
+#endif /* (DISABLE_WDOG) */
+
+ SystemInitHook();
+}
+
+/* ----------------------------------------------------------------------------
+ -- SystemCoreClockUpdate()
+ ---------------------------------------------------------------------------- */
+
+void SystemCoreClockUpdate (void) {
+
+ uint32_t MCGOUTClock; /* Variable to store output clock frequency of the MCG module */
+ uint16_t Divider;
+
+ if ((MCG->C1 & MCG_C1_CLKS_MASK) == 0x00U) {
+ /* FLL is selected */
+ if ((MCG->C1 & MCG_C1_IREFS_MASK) == 0x00U) {
+ /* External reference clock is selected */
+ switch (MCG->C7 & MCG_C7_OSCSEL_MASK) {
+ case 0x00U:
+ MCGOUTClock = CPU_XTAL_CLK_HZ; /* System oscillator drives MCG clock */
+ break;
+ case 0x02U:
+ default:
+ MCGOUTClock = CPU_INT_IRC_CLK_HZ; /* IRC 48MHz oscillator drives MCG clock */
+ break;
+ }
+ if (((MCG->C2 & MCG_C2_RANGE_MASK) != 0x00U) && ((MCG->C7 & MCG_C7_OSCSEL_MASK) != 0x01U)) {
+ switch (MCG->C1 & MCG_C1_FRDIV_MASK) {
+ case 0x38U:
+ Divider = 1536U;
+ break;
+ case 0x30U:
+ Divider = 1280U;
+ break;
+ default:
+ Divider = (uint16_t)(32LU << ((MCG->C1 & MCG_C1_FRDIV_MASK) >> MCG_C1_FRDIV_SHIFT));
+ break;
+ }
+ } else {/* ((MCG->C2 & MCG_C2_RANGE_MASK) != 0x00U) */
+ Divider = (uint16_t)(1LU << ((MCG->C1 & MCG_C1_FRDIV_MASK) >> MCG_C1_FRDIV_SHIFT));
+ }
+ MCGOUTClock = (MCGOUTClock / Divider); /* Calculate the divided FLL reference clock */
+ } else { /* (!((MCG->C1 & MCG_C1_IREFS_MASK) == 0x00U)) */
+ MCGOUTClock = CPU_INT_SLOW_CLK_HZ; /* The slow internal reference clock is selected */
+ } /* (!((MCG->C1 & MCG_C1_IREFS_MASK) == 0x00U)) */
+ /* Select correct multiplier to calculate the MCG output clock */
+ switch (MCG->C4 & (MCG_C4_DMX32_MASK | MCG_C4_DRST_DRS_MASK)) {
+ case 0x00U:
+ MCGOUTClock *= 640U;
+ break;
+ case 0x20U:
+ MCGOUTClock *= 1280U;
+ break;
+ case 0x40U:
+ MCGOUTClock *= 1920U;
+ break;
+ case 0x60U:
+ MCGOUTClock *= 2560U;
+ break;
+ case 0x80U:
+ MCGOUTClock *= 732U;
+ break;
+ case 0xA0U:
+ MCGOUTClock *= 1464U;
+ break;
+ case 0xC0U:
+ MCGOUTClock *= 2197U;
+ break;
+ case 0xE0U:
+ MCGOUTClock *= 2929U;
+ break;
+ default:
+ break;
+ }
+ } else if ((MCG->C1 & MCG_C1_CLKS_MASK) == 0x40U) {
+ /* Internal reference clock is selected */
+ if ((MCG->C2 & MCG_C2_IRCS_MASK) == 0x00U) {
+ MCGOUTClock = CPU_INT_SLOW_CLK_HZ; /* Slow internal reference clock selected */
+ } else { /* (!((MCG->C2 & MCG_C2_IRCS_MASK) == 0x00U)) */
+ Divider = (uint16_t)(0x01LU << ((MCG->SC & MCG_SC_FCRDIV_MASK) >> MCG_SC_FCRDIV_SHIFT));
+ MCGOUTClock = (uint32_t) (CPU_INT_FAST_CLK_HZ / Divider); /* Fast internal reference clock selected */
+ } /* (!((MCG->C2 & MCG_C2_IRCS_MASK) == 0x00U)) */
+ } else if ((MCG->C1 & MCG_C1_CLKS_MASK) == 0x80U) {
+ /* External reference clock is selected */
+ switch (MCG->C7 & MCG_C7_OSCSEL_MASK) {
+ case 0x00U:
+ MCGOUTClock = CPU_XTAL_CLK_HZ; /* System oscillator drives MCG clock */
+ break;
+ case 0x02U:
+ default:
+ MCGOUTClock = CPU_INT_IRC_CLK_HZ; /* IRC 48MHz oscillator drives MCG clock */
+ break;
+ }
+ } else { /* (!((MCG->C1 & MCG_C1_CLKS_MASK) == 0x80U)) */
+ /* Reserved value */
+ return;
+ } /* (!((MCG->C1 & MCG_C1_CLKS_MASK) == 0x80U)) */
+ SystemCoreClock = (MCGOUTClock / (0x01U + ((SIM->CLKDIV1 & SIM_CLKDIV1_OUTDIV1_MASK) >> SIM_CLKDIV1_OUTDIV1_SHIFT)));
+}
+
+/* ----------------------------------------------------------------------------
+ -- SystemInitHook()
+ ---------------------------------------------------------------------------- */
+
+__attribute__ ((weak)) void SystemInitHook (void) {
+ /* Void implementation of the weak function. */
+}
diff --git a/CMSIS/system_MK02F12810.h b/CMSIS/system_MK02F12810.h
new file mode 100644
index 0000000..dfcf658
--- /dev/null
+++ b/CMSIS/system_MK02F12810.h
@@ -0,0 +1,166 @@
+/*
+** ###################################################################
+** Processors: MK02FN128VFM10
+** MK02FN128VLF10
+** MK02FN128VLH10
+** MK02FN64VFM10
+** MK02FN64VLF10
+** MK02FN64VLH10
+**
+** Compilers: Keil ARM C/C++ Compiler
+** Freescale C/C++ for Embedded ARM
+** GNU C Compiler
+** IAR ANSI C/C++ Compiler for ARM
+** MCUXpresso Compiler
+**
+** Reference manual: K02P64M100SFARM, Rev. 0, February 14, 2014
+** Version: rev. 0.5, 2015-02-19
+** Build: b171226
+**
+** Abstract:
+** Provides a system configuration function and a global variable that
+** contains the system frequency. It configures the device and initializes
+** the oscillator (PLL) that is part of the microcontroller device.
+**
+** The Clear BSD License
+** Copyright 2016 Freescale Semiconductor, Inc.
+** Copyright 2016-2017 NXP
+** All rights reserved.
+**
+** Redistribution and use in source and binary forms, with or without
+** modification, are permitted (subject to the limitations in the
+** disclaimer below) provided that the following conditions are met:
+**
+** * Redistributions of source code must retain the above copyright
+** notice, this list of conditions and the following disclaimer.
+**
+** * 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.
+**
+** * Neither the name of the copyright holder nor the names of its
+** contributors may be used to endorse or promote products derived from
+** this software without specific prior written permission.
+**
+** NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE
+** GRANTED BY THIS LICENSE. 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.
+**
+** http: www.nxp.com
+** mail: support@nxp.com
+**
+** Revisions:
+** - rev. 0.1 (2014-02-24)
+** Initial version
+** - rev. 0.2 (2014-07-15)
+** Module access macro module_BASES replaced by module_BASE_PTRS.
+** Update of system and startup files.
+** - rev. 0.3 (2014-08-28)
+** Update of system files - default clock configuration changed.
+** Update of startup files - possibility to override DefaultISR added.
+** - rev. 0.4 (2014-10-14)
+** Interrupt INT_LPTimer renamed to INT_LPTMR0, interrupt INT_Watchdog renamed to INT_WDOG_EWM.
+** - rev. 0.5 (2015-02-19)
+** Renamed interrupt vector LLW to LLWU.
+**
+** ###################################################################
+*/
+
+/*!
+ * @file MK02F12810
+ * @version 0.5
+ * @date 2015-02-19
+ * @brief Device specific configuration file for MK02F12810 (header file)
+ *
+ * Provides a system configuration function and a global variable that contains
+ * the system frequency. It configures the device and initializes the oscillator
+ * (PLL) that is part of the microcontroller device.
+ */
+
+#ifndef _SYSTEM_MK02F12810_H_
+#define _SYSTEM_MK02F12810_H_ /**< Symbol preventing repeated inclusion */
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+#include <stdint.h>
+
+
+#ifndef DISABLE_WDOG
+ #define DISABLE_WDOG 1
+#endif
+
+/* Define clock source values */
+
+#define CPU_XTAL_CLK_HZ 8000000u /* Value of the external crystal or oscillator clock frequency in Hz */
+#define CPU_XTAL32k_CLK_HZ 0u /* No RTC clock available */
+#define CPU_INT_SLOW_CLK_HZ 32768u /* Value of the slow internal oscillator clock frequency in Hz */
+#define CPU_INT_FAST_CLK_HZ 4000000u /* Value of the fast internal oscillator clock frequency in Hz */
+#define CPU_INT_IRC_CLK_HZ 48000000u /* Value of the 48M internal oscillator clock frequency in Hz */
+
+/* RTC oscillator setting */
+
+/* Low power mode enable */
+/* SMC_PMPROT: AHSRUN=1,AVLP=1,ALLS=1,AVLLS=1 */
+#define SYSTEM_SMC_PMPROT_VALUE 0xAAU /* SMC_PMPROT */
+
+#define DEFAULT_SYSTEM_CLOCK 20971520u /* Default System clock value */
+
+
+/**
+ * @brief System clock frequency (core clock)
+ *
+ * The system clock frequency supplied to the SysTick timer and the processor
+ * core clock. This variable can be used by the user application to setup the
+ * SysTick timer or configure other parameters. It may also be used by debugger to
+ * query the frequency of the debug timer or configure the trace clock speed
+ * SystemCoreClock is initialized with a correct predefined value.
+ */
+extern uint32_t SystemCoreClock;
+
+/**
+ * @brief Setup the microcontroller system.
+ *
+ * Typically this function configures the oscillator (PLL) that is part of the
+ * microcontroller device. For systems with variable clock speed it also updates
+ * the variable SystemCoreClock. SystemInit is called from startup_device file.
+ */
+void SystemInit (void);
+
+/**
+ * @brief Updates the SystemCoreClock variable.
+ *
+ * It must be called whenever the core clock is changed during program
+ * execution. SystemCoreClockUpdate() evaluates the clock register settings and calculates
+ * the current core clock.
+ */
+void SystemCoreClockUpdate (void);
+
+/**
+ * @brief SystemInit function hook.
+ *
+ * This weak function allows to call specific initialization code during the
+ * SystemInit() execution.This can be used when an application specific code needs
+ * to be called as close to the reset entry as possible (for example the Multicore
+ * Manager MCMGR_EarlyInit() function call).
+ * NOTE: No global r/w variables can be used in this hook function because the
+ * initialization of these variables happens after this function.
+ */
+void SystemInitHook (void);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* _SYSTEM_MK02F12810_H_ */