From ed46e1a38ae2de97b55c1843bad8b813bd4936e3 Mon Sep 17 00:00:00 2001 From: mindchasers Date: Sun, 7 Jul 2019 17:58:07 -0400 Subject: initial commit of private island ARM test suite --- .cproject | 605 +++ .gitattributes | 1 + .gitignore | 2 + .project | 27 + .settings/language.settings.xml | 17 + CMSIS/MK02F12810.h | 6290 +++++++++++++++++++++++++++++++ CMSIS/MK02F12810_features.h | 2013 ++++++++++ CMSIS/arm_common_tables.h | 121 + CMSIS/arm_const_structs.h | 66 + CMSIS/arm_math.h | 7157 ++++++++++++++++++++++++++++++++++++ CMSIS/cmsis_armcc.h | 870 +++++ CMSIS/cmsis_armclang.h | 1877 ++++++++++ CMSIS/cmsis_compiler.h | 266 ++ CMSIS/cmsis_gcc.h | 2088 +++++++++++ CMSIS/cmsis_iccarm.h | 913 +++++ CMSIS/cmsis_version.h | 39 + CMSIS/core_armv8mbl.h | 1896 ++++++++++ CMSIS/core_armv8mml.h | 2960 +++++++++++++++ CMSIS/core_cm4.h | 2118 +++++++++++ CMSIS/fsl_device_registers.h | 64 + CMSIS/mpu_armv7.h | 197 + CMSIS/mpu_armv8.h | 333 ++ CMSIS/system_MK02F12810.c | 229 ++ CMSIS/system_MK02F12810.h | 166 + LICENSE | 201 + MK02_DARSENA_V02.mex | 223 ++ README | 30 + board/board.c | 49 + board/board.h | 76 + board/clock_config.c | 165 + board/clock_config.h | 69 + board/peripherals.c | 50 + board/peripherals.h | 56 + board/pin_mux.c | 235 ++ board/pin_mux.h | 162 + drivers/fsl_adc16.c | 380 ++ drivers/fsl_adc16.h | 529 +++ drivers/fsl_clock.c | 1397 +++++++ drivers/fsl_clock.h | 1286 +++++++ drivers/fsl_cmp.c | 295 ++ drivers/fsl_cmp.h | 347 ++ drivers/fsl_common.c | 192 + drivers/fsl_common.h | 576 +++ drivers/fsl_crc.c | 292 ++ drivers/fsl_crc.h | 197 + drivers/fsl_dac.c | 230 ++ drivers/fsl_dac.h | 382 ++ drivers/fsl_dmamux.c | 103 + drivers/fsl_dmamux.h | 204 + drivers/fsl_dspi.c | 1807 +++++++++ drivers/fsl_dspi.h | 1248 +++++++ drivers/fsl_dspi_edma.c | 1446 ++++++++ drivers/fsl_dspi_edma.h | 306 ++ drivers/fsl_edma.c | 2299 ++++++++++++ drivers/fsl_edma.h | 957 +++++ drivers/fsl_gpio.c | 235 ++ drivers/fsl_gpio.h | 594 +++ drivers/fsl_i2c.c | 2005 ++++++++++ drivers/fsl_i2c.h | 821 +++++ drivers/fsl_i2c_edma.c | 570 +++ drivers/fsl_i2c_edma.h | 141 + drivers/fsl_pit.c | 138 + drivers/fsl_pit.h | 358 ++ drivers/fsl_port.h | 497 +++ drivers/fsl_uart.c | 1356 +++++++ drivers/fsl_uart.h | 808 ++++ source/cmds.c | 48 + source/cmds.h | 100 + source/ecp5_driver.c | 123 + source/ecp5_driver.h | 34 + source/flexbus.h | 48 + source/main.c | 272 ++ source/main.h | 42 + source/phy_driver.c | 234 ++ source/phy_driver.h | 33 + source/pmic.h | 49 + source/pwr_driver.c | 113 + source/pwr_driver.h | 26 + source/semihost_hardfault.c | 109 + source/spi.c | 159 + source/spi.h | 71 + source/utils.c | 156 + source/utils.h | 27 + startup/startup_mk02f12810.c | 823 +++++ utilities/fsl_debug_console.c | 366 ++ utilities/fsl_debug_console.h | 207 ++ utilities/fsl_debug_console_conf.h | 160 + utilities/fsl_io.c | 815 ++++ utilities/fsl_io.h | 140 + utilities/fsl_log.c | 587 +++ utilities/fsl_log.h | 146 + utilities/fsl_str.c | 1327 +++++++ utilities/fsl_str.h | 92 + 93 files changed, 59934 insertions(+) create mode 100644 .cproject create mode 100644 .gitattributes create mode 100644 .gitignore create mode 100644 .project create mode 100644 .settings/language.settings.xml create mode 100644 CMSIS/MK02F12810.h create mode 100644 CMSIS/MK02F12810_features.h create mode 100644 CMSIS/arm_common_tables.h create mode 100644 CMSIS/arm_const_structs.h create mode 100644 CMSIS/arm_math.h create mode 100644 CMSIS/cmsis_armcc.h create mode 100644 CMSIS/cmsis_armclang.h create mode 100644 CMSIS/cmsis_compiler.h create mode 100644 CMSIS/cmsis_gcc.h create mode 100644 CMSIS/cmsis_iccarm.h create mode 100644 CMSIS/cmsis_version.h create mode 100644 CMSIS/core_armv8mbl.h create mode 100644 CMSIS/core_armv8mml.h create mode 100644 CMSIS/core_cm4.h create mode 100644 CMSIS/fsl_device_registers.h create mode 100644 CMSIS/mpu_armv7.h create mode 100644 CMSIS/mpu_armv8.h create mode 100644 CMSIS/system_MK02F12810.c create mode 100644 CMSIS/system_MK02F12810.h create mode 100644 LICENSE create mode 100755 MK02_DARSENA_V02.mex create mode 100644 README create mode 100644 board/board.c create mode 100644 board/board.h create mode 100644 board/clock_config.c create mode 100644 board/clock_config.h create mode 100644 board/peripherals.c create mode 100644 board/peripherals.h create mode 100755 board/pin_mux.c create mode 100755 board/pin_mux.h create mode 100644 drivers/fsl_adc16.c create mode 100644 drivers/fsl_adc16.h create mode 100644 drivers/fsl_clock.c create mode 100644 drivers/fsl_clock.h create mode 100644 drivers/fsl_cmp.c create mode 100644 drivers/fsl_cmp.h create mode 100644 drivers/fsl_common.c create mode 100644 drivers/fsl_common.h create mode 100644 drivers/fsl_crc.c create mode 100644 drivers/fsl_crc.h create mode 100644 drivers/fsl_dac.c create mode 100644 drivers/fsl_dac.h create mode 100644 drivers/fsl_dmamux.c create mode 100644 drivers/fsl_dmamux.h create mode 100644 drivers/fsl_dspi.c create mode 100644 drivers/fsl_dspi.h create mode 100644 drivers/fsl_dspi_edma.c create mode 100644 drivers/fsl_dspi_edma.h create mode 100644 drivers/fsl_edma.c create mode 100644 drivers/fsl_edma.h create mode 100644 drivers/fsl_gpio.c create mode 100644 drivers/fsl_gpio.h create mode 100644 drivers/fsl_i2c.c create mode 100644 drivers/fsl_i2c.h create mode 100644 drivers/fsl_i2c_edma.c create mode 100644 drivers/fsl_i2c_edma.h create mode 100644 drivers/fsl_pit.c create mode 100644 drivers/fsl_pit.h create mode 100644 drivers/fsl_port.h create mode 100644 drivers/fsl_uart.c create mode 100644 drivers/fsl_uart.h create mode 100644 source/cmds.c create mode 100644 source/cmds.h create mode 100644 source/ecp5_driver.c create mode 100644 source/ecp5_driver.h create mode 100644 source/flexbus.h create mode 100644 source/main.c create mode 100644 source/main.h create mode 100644 source/phy_driver.c create mode 100644 source/phy_driver.h create mode 100644 source/pmic.h create mode 100644 source/pwr_driver.c create mode 100644 source/pwr_driver.h create mode 100644 source/semihost_hardfault.c create mode 100644 source/spi.c create mode 100644 source/spi.h create mode 100644 source/utils.c create mode 100644 source/utils.h create mode 100644 startup/startup_mk02f12810.c create mode 100644 utilities/fsl_debug_console.c create mode 100644 utilities/fsl_debug_console.h create mode 100644 utilities/fsl_debug_console_conf.h create mode 100644 utilities/fsl_io.c create mode 100644 utilities/fsl_io.h create mode 100644 utilities/fsl_log.c create mode 100644 utilities/fsl_log.h create mode 100644 utilities/fsl_str.c create mode 100644 utilities/fsl_str.h diff --git a/.cproject b/.cproject new file mode 100644 index 0000000..ae5c37b --- /dev/null +++ b/.cproject @@ -0,0 +1,605 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + <?xml version="1.0" encoding="UTF-8"?> +<TargetConfig> +<Properties property_3="NXP" property_4="MK02FN128xxx10" property_count="5" version="100200"/> +<infoList vendor="NXP"><info chip="MK02FN128xxx10" name="MK02FN128xxx10"><chip><name>MK02FN128xxx10</name> +<family>K0x</family> +<vendor>NXP</vendor> +<memory can_program="true" id="Flash" is_ro="true" size="128" type="Flash"/> +<memory id="RAM" size="16" type="RAM"/> +<memoryInstance derived_from="Flash" driver="FTFA_2K.cfx" id="PROGRAM_FLASH" location="0x00000000" size="0x00020000"/> +<memoryInstance derived_from="RAM" id="SRAM_UPPER" location="0x20000000" size="0x00002000"/> +<memoryInstance derived_from="RAM" id="SRAM_LOWER" location="0x1fffe000" size="0x00002000"/> +<peripheralInstance derived_from="FTFA-FlashConfig" determined="infoFile" id="FTFA-FlashConfig" location="0x400"/> +<peripheralInstance derived_from="DMA" determined="infoFile" id="DMA" location="0x40008000"/> +<peripheralInstance derived_from="FMC" determined="infoFile" id="FMC" location="0x4001F000"/> +<peripheralInstance derived_from="FTFA" determined="infoFile" id="FTFA" location="0x40020000"/> +<peripheralInstance derived_from="DMAMUX" determined="infoFile" id="DMAMUX" location="0x40021000"/> +<peripheralInstance derived_from="SPI0" determined="infoFile" id="SPI0" location="0x4002C000"/> +<peripheralInstance derived_from="CRC" determined="infoFile" id="CRC" location="0x40032000"/> +<peripheralInstance derived_from="PDB0" determined="infoFile" id="PDB0" location="0x40036000"/> +<peripheralInstance derived_from="PIT" determined="infoFile" id="PIT" location="0x40037000"/> +<peripheralInstance derived_from="FTM0" determined="infoFile" id="FTM0" location="0x40038000"/> +<peripheralInstance derived_from="FTM1" determined="infoFile" id="FTM1" location="0x40039000"/> +<peripheralInstance derived_from="FTM2" determined="infoFile" id="FTM2" location="0x4003A000"/> +<peripheralInstance derived_from="ADC0" determined="infoFile" id="ADC0" location="0x4003B000"/> +<peripheralInstance derived_from="DAC0" determined="infoFile" id="DAC0" location="0x4003F000"/> +<peripheralInstance derived_from="LPTMR0" determined="infoFile" id="LPTMR0" location="0x40040000"/> +<peripheralInstance derived_from="SIM" determined="infoFile" id="SIM" location="0x40047000"/> +<peripheralInstance derived_from="PORTA" determined="infoFile" id="PORTA" location="0x40049000"/> +<peripheralInstance derived_from="PORTB" determined="infoFile" id="PORTB" location="0x4004A000"/> +<peripheralInstance derived_from="PORTC" determined="infoFile" id="PORTC" location="0x4004B000"/> +<peripheralInstance derived_from="PORTD" determined="infoFile" id="PORTD" location="0x4004C000"/> +<peripheralInstance derived_from="PORTE" determined="infoFile" id="PORTE" location="0x4004D000"/> +<peripheralInstance derived_from="WDOG" determined="infoFile" id="WDOG" location="0x40052000"/> +<peripheralInstance derived_from="EWM" determined="infoFile" id="EWM" location="0x40061000"/> +<peripheralInstance derived_from="MCG" determined="infoFile" id="MCG" location="0x40064000"/> +<peripheralInstance derived_from="OSC" determined="infoFile" id="OSC" location="0x40065000"/> +<peripheralInstance derived_from="I2C0" determined="infoFile" id="I2C0" location="0x40066000"/> +<peripheralInstance derived_from="UART0" determined="infoFile" id="UART0" location="0x4006A000"/> +<peripheralInstance derived_from="UART1" determined="infoFile" id="UART1" location="0x4006B000"/> +<peripheralInstance derived_from="CMP0" determined="infoFile" id="CMP0" location="0x40073000"/> +<peripheralInstance derived_from="CMP1" determined="infoFile" id="CMP1" location="0x40073008"/> +<peripheralInstance derived_from="VREF" determined="infoFile" id="VREF" location="0x40074000"/> +<peripheralInstance derived_from="LLWU" determined="infoFile" id="LLWU" location="0x4007C000"/> +<peripheralInstance derived_from="PMC" determined="infoFile" id="PMC" location="0x4007D000"/> +<peripheralInstance derived_from="SMC" determined="infoFile" id="SMC" location="0x4007E000"/> +<peripheralInstance derived_from="RCM" determined="infoFile" id="RCM" location="0x4007F000"/> +<peripheralInstance derived_from="GPIOA" determined="infoFile" id="GPIOA" location="0x400FF000"/> +<peripheralInstance derived_from="GPIOB" determined="infoFile" id="GPIOB" location="0x400FF040"/> +<peripheralInstance derived_from="GPIOC" determined="infoFile" id="GPIOC" location="0x400FF080"/> +<peripheralInstance derived_from="GPIOD" determined="infoFile" id="GPIOD" location="0x400FF0C0"/> +<peripheralInstance derived_from="GPIOE" determined="infoFile" id="GPIOE" location="0x400FF100"/> +<peripheralInstance derived_from="SystemControl" determined="infoFile" id="SystemControl" location="0xE000E000"/> +<peripheralInstance derived_from="SysTick" determined="infoFile" id="SysTick" location="0xE000E010"/> +<peripheralInstance derived_from="NVIC" determined="infoFile" id="NVIC" location="0xE000E100"/> +<peripheralInstance derived_from="MCM" determined="infoFile" id="MCM" location="0xE0080000"/> +</chip> +<processor><name gcc_name="cortex-m4">Cortex-M4</name> +<family>Cortex-M</family> +</processor> +<link href="MK02F12810_internal_peripheral.xml" show="embed" type="simple"/> +</info> +</infoList> +</TargetConfig> + + + SDK_2.x_MK02FN128xxx10 + 2.4.1 + middleware.baremetal.MK02F12810;platform.drivers.clock.MK02F12810;platform.Include_common.MK02F12810;platform.Include_core_cm4.MK02F12810;platform.devices.MK02F12810_CMSIS.MK02F12810;platform.drivers.common.MK02F12810;platform.drivers.edma.MK02F12810;platform.drivers.uart.MK02F12810;platform.drivers.adc16.MK02F12810;platform.drivers.cmp.MK02F12810;platform.drivers.crc.MK02F12810;platform.drivers.dac.MK02F12810;platform.drivers.dmamux.MK02F12810;platform.drivers.dspi.MK02F12810;platform.drivers.dspi_edma.MK02F12810;platform.drivers.i2c.MK02F12810;platform.drivers.i2c_edma.MK02F12810;platform.drivers.gpio.MK02F12810;platform.utilities.debug_console.MK02F12810;platform.devices.MK02F12810_startup.MK02F12810; + MK02FN128VFM10 + cm4 + + + + diff --git a/.gitattributes b/.gitattributes new file mode 100644 index 0000000..176a458 --- /dev/null +++ b/.gitattributes @@ -0,0 +1 @@ +* text=auto diff --git a/.gitignore b/.gitignore new file mode 100644 index 0000000..4982869 --- /dev/null +++ b/.gitignore @@ -0,0 +1,2 @@ +Debug +*.bak diff --git a/.project b/.project new file mode 100644 index 0000000..aba4126 --- /dev/null +++ b/.project @@ -0,0 +1,27 @@ + + + k02_cb_redlib + + + + + + org.eclipse.cdt.managedbuilder.core.genmakebuilder + clean,full,incremental, + + + + + org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder + full,incremental, + + + + + + org.eclipse.cdt.core.cnature + com.nxp.mcuxpresso.core.datamodels.sdkNature + org.eclipse.cdt.managedbuilder.core.managedBuildNature + org.eclipse.cdt.managedbuilder.core.ScannerConfigNature + + diff --git a/.settings/language.settings.xml b/.settings/language.settings.xml new file mode 100644 index 0000000..b156ab1 --- /dev/null +++ b/.settings/language.settings.xml @@ -0,0 +1,17 @@ + + + + + + + + + + + + + + + + + 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 Lib 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 arm_math.h which is placed in the Include 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 arm_math.h 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 CMSIS\\DSP_Lib\\Source\\ARM 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. + * + *
+ * CMSIS-DSP in ARM::CMSIS Pack + * ----------------------------- + * + * The following files relevant to CMSIS-DSP are present in the ARM::CMSIS 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 | + * + *
+ * 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: + *
+ *     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;
+ * 
+ * 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 numRows X numCols + * and the values are arranged in row order. That is, the + * matrix element (i, j) is stored at: + *
+ *     pData[i*numCols + j]
+ * 
+ * + * \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 arm_mat_init_f32(), arm_mat_init_q31() + * and arm_mat_init_q15() 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: + *
+ * arm_matrix_instance_f32 S = {nRows, nColumns, pData};
+ * arm_matrix_instance_q31 S = {nRows, nColumns, pData};
+ * arm_matrix_instance_q15 S = {nRows, nColumns, pData};
+ * 
+ * where nRows specifies the number of rows, nColumns + * specifies the number of columns, and pData 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: + *
+ *     ARM_MATH_SIZE_MISMATCH
+ * 
+ * Otherwise the functions return + *
+ *     ARM_MATH_SUCCESS
+ * 
+ * There is some overhead associated with this matrix size checking. + * The matrix size checking is enabled via the \#define + *
+ *     ARM_MATH_MATRIX_CHECK
+ * 
+ * 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 ARM_MATH_SUCCESS. + */ + +/** + * @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 + * numTaps 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 + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS 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 + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS 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 + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS 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 + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS 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 + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS 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 + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS 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 ARM_MATH_SIZE_MISMATCH + * or ARM_MATH_SUCCESS 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 ARM_MATH_SIZE_MISMATCH + * or ARM_MATH_SUCCESS 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 ARM_MATH_SIZE_MISMATCH + * or ARM_MATH_SUCCESS 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 + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS 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 + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS 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 + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS 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 + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS 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 + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS 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 + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS 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 + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS 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 + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS 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 + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS 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 + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS 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 + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS 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 fftLenReal 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 N 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 N 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 + * blockSize is not a multiple of M. + */ + 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 + * blockSize is not a multiple of M. + */ + 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 + * blockSize is not a multiple of M. + */ + 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 numTaps is not a multiple of the interpolation factor L. + */ + 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 numTaps is not a multiple of the interpolation factor L. + */ + 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 numTaps is not a multiple of the interpolation factor L. + */ + 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. + * S points to an instance of the PID control data structure. in + * is the input sample value. The functions return the output value. + * + * \par Algorithm: + *
+   *    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  
+ * + * \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. + * + * Scaling and Overflow Behavior: + * \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. + * + * Scaling and Overflow Behavior: + * \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 Ia, Ib and Ic to calculate currents + * in the two-phase orthogonal stator axis Ialpha and Ibeta. + * When Ialpha is superposed with Ia as shown in the figure below + * \image html clarke.gif Stator current space vector and its components in (a,b). + * and Ia + Ib + Ic = 0, in this condition Ialpha and Ibeta + * can be calculated using only Ia and Ib. + * + * 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 Ia and Ib are the instantaneous stator phases and + * pIalpha and pIbeta 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 a + * @param[in] Ib input three-phase coordinate b + * @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 a + * @param[in] Ib input three-phase coordinate b + * @param[out] pIalpha points to output two-phase orthogonal vector axis alpha + * @param[out] pIbeta points to output two-phase orthogonal vector axis beta + * + * Scaling and Overflow Behavior: + * \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 pIa and pIb are the instantaneous stator phases and + * Ialpha and Ibeta 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 a + * @param[out] pIb points to output three-phase coordinate b + */ + 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 a + * @param[out] pIb points to output three-phase coordinate b + * + * Scaling and Overflow Behavior: + * \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 Ialpha and the Ibeta 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 Ialpha and Ibeta are the stator vector components, + * pId and pIq are rotor vector components and cosVal and sinVal 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 + * + * Scaling and Overflow Behavior: + * \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 pIalpha and pIbeta are the stator vector components, + * Id and Iq are rotor vector components and cosVal and sinVal 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 + * + * Scaling and Overflow Behavior: + * \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: + *
+   *       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
+   * 
+ * + * \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. + * S points to an instance of the Linear Interpolate function data structure. + * x 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 x 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 x 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 x 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: + *
+   *      x1 = x0 - f(x0)/f'(x0)
+   * 
+ * where x1 is the current estimate, + * x0 is the previous estimate, and + * f'(x0) is the derivative of f() evaluated at x0. + * For the square root function, the algorithm reduces to: + *
+   *     x0 = in/2                         [initial guess]
+   *     x1 = 1/2 * ( x0 + in / x0)        [each iteration]
+   * 
+ */ + + + /** + * @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 + * in 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 + * in 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 + * in 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 f(x, y) 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. + * + * Algorithm + * \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: + *
+   *   typedef struct
+   *   {
+   *     uint16_t numRows;
+   *     uint16_t numCols;
+   *     float32_t *pData;
+   * } arm_bilinear_interp_instance_f32;
+   * 
+ * + * \par + * where numRows specifies the number of rows in the table; + * numCols specifies the number of columns in the table; + * and pData points to an array of size numRows*numCols values. + * The data table pTable is organized in row order and the supplied data values fall on integer indexes. + * That is, table element (x,y) is located at pTable[x + y*numCols] where x and y are integers. + * + * \par + * Let (x, y) specify the desired interpolation point. Then define: + *
+   *     XF = floor(x)
+   *     YF = floor(y)
+   * 
+ * \par + * The interpolated output point is computed as: + *
+   *  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)
+   * 
+ * 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 /* 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 + +/* + * Arm Compiler 4/5 + */ +#if defined ( __CC_ARM ) + #include "cmsis_armcc.h" + + +/* + * Arm Compiler 6 (armclang) + */ +#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) + #include "cmsis_armclang.h" + + +/* + * GNU Compiler + */ +#elif defined ( __GNUC__ ) + #include "cmsis_gcc.h" + + +/* + * IAR Compiler + */ +#elif defined ( __ICCARM__ ) + #include + + +/* + * TI Arm Compiler + */ +#elif defined ( __TI_ARM__ ) + #include + + #ifndef __ASM + #define __ASM __asm + #endif + #ifndef __INLINE + #define __INLINE inline + #endif + #ifndef __STATIC_INLINE + #define __STATIC_INLINE static inline + #endif + #ifndef __STATIC_FORCEINLINE + #define __STATIC_FORCEINLINE __STATIC_INLINE + #endif + #ifndef __NO_RETURN + #define __NO_RETURN __attribute__((noreturn)) + #endif + #ifndef __USED + #define __USED __attribute__((used)) + #endif + #ifndef __WEAK + #define __WEAK __attribute__((weak)) + #endif + #ifndef __PACKED + #define __PACKED __attribute__((packed)) + #endif + #ifndef __PACKED_STRUCT + #define __PACKED_STRUCT struct __attribute__((packed)) + #endif + #ifndef __PACKED_UNION + #define __PACKED_UNION union __attribute__((packed)) + #endif + #ifndef __UNALIGNED_UINT32 /* deprecated */ + struct __attribute__((packed)) T_UINT32 { uint32_t v; }; + #define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v) + #endif + #ifndef __UNALIGNED_UINT16_WRITE + __PACKED_STRUCT T_UINT16_WRITE { uint16_t v; }; + #define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void*)(addr))->v) = (val)) + #endif + #ifndef __UNALIGNED_UINT16_READ + __PACKED_STRUCT T_UINT16_READ { uint16_t v; }; + #define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v) + #endif + #ifndef __UNALIGNED_UINT32_WRITE + __PACKED_STRUCT T_UINT32_WRITE { uint32_t v; }; + #define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val)) + #endif + #ifndef __UNALIGNED_UINT32_READ + __PACKED_STRUCT T_UINT32_READ { uint32_t v; }; + #define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v) + #endif + #ifndef __ALIGNED + #define __ALIGNED(x) __attribute__((aligned(x))) + #endif + #ifndef __RESTRICT + #warning No compiler specific solution for __RESTRICT. __RESTRICT is ignored. + #define __RESTRICT + #endif + + +/* + * TASKING Compiler + */ +#elif defined ( __TASKING__ ) + /* + * The CMSIS functions have been implemented as intrinsics in the compiler. + * Please use "carm -?i" to get an up to date list of all intrinsics, + * Including the CMSIS ones. + */ + + #ifndef __ASM + #define __ASM __asm + #endif + #ifndef __INLINE + #define __INLINE inline + #endif + #ifndef __STATIC_INLINE + #define __STATIC_INLINE static inline + #endif + #ifndef __STATIC_FORCEINLINE + #define __STATIC_FORCEINLINE __STATIC_INLINE + #endif + #ifndef __NO_RETURN + #define __NO_RETURN __attribute__((noreturn)) + #endif + #ifndef __USED + #define __USED __attribute__((used)) + #endif + #ifndef __WEAK + #define __WEAK __attribute__((weak)) + #endif + #ifndef __PACKED + #define __PACKED __packed__ + #endif + #ifndef __PACKED_STRUCT + #define __PACKED_STRUCT struct __packed__ + #endif + #ifndef __PACKED_UNION + #define __PACKED_UNION union __packed__ + #endif + #ifndef __UNALIGNED_UINT32 /* deprecated */ + struct __packed__ T_UINT32 { uint32_t v; }; + #define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v) + #endif + #ifndef __UNALIGNED_UINT16_WRITE + __PACKED_STRUCT T_UINT16_WRITE { uint16_t v; }; + #define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void *)(addr))->v) = (val)) + #endif + #ifndef __UNALIGNED_UINT16_READ + __PACKED_STRUCT T_UINT16_READ { uint16_t v; }; + #define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v) + #endif + #ifndef __UNALIGNED_UINT32_WRITE + __PACKED_STRUCT T_UINT32_WRITE { uint32_t v; }; + #define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val)) + #endif + #ifndef __UNALIGNED_UINT32_READ + __PACKED_STRUCT T_UINT32_READ { uint32_t v; }; + #define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v) + #endif + #ifndef __ALIGNED + #define __ALIGNED(x) __align(x) + #endif + #ifndef __RESTRICT + #warning No compiler specific solution for __RESTRICT. __RESTRICT is ignored. + #define __RESTRICT + #endif + + +/* + * COSMIC Compiler + */ +#elif defined ( __CSMC__ ) + #include + + #ifndef __ASM + #define __ASM _asm + #endif + #ifndef __INLINE + #define __INLINE inline + #endif + #ifndef __STATIC_INLINE + #define __STATIC_INLINE static inline + #endif + #ifndef __STATIC_FORCEINLINE + #define __STATIC_FORCEINLINE __STATIC_INLINE + #endif + #ifndef __NO_RETURN + // NO RETURN is automatically detected hence no warning here + #define __NO_RETURN + #endif + #ifndef __USED + #warning No compiler specific solution for __USED. __USED is ignored. + #define __USED + #endif + #ifndef __WEAK + #define __WEAK __weak + #endif + #ifndef __PACKED + #define __PACKED @packed + #endif + #ifndef __PACKED_STRUCT + #define __PACKED_STRUCT @packed struct + #endif + #ifndef __PACKED_UNION + #define __PACKED_UNION @packed union + #endif + #ifndef __UNALIGNED_UINT32 /* deprecated */ + @packed struct T_UINT32 { uint32_t v; }; + #define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v) + #endif + #ifndef __UNALIGNED_UINT16_WRITE + __PACKED_STRUCT T_UINT16_WRITE { uint16_t v; }; + #define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void *)(addr))->v) = (val)) + #endif + #ifndef __UNALIGNED_UINT16_READ + __PACKED_STRUCT T_UINT16_READ { uint16_t v; }; + #define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v) + #endif + #ifndef __UNALIGNED_UINT32_WRITE + __PACKED_STRUCT T_UINT32_WRITE { uint32_t v; }; + #define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val)) + #endif + #ifndef __UNALIGNED_UINT32_READ + __PACKED_STRUCT T_UINT32_READ { uint32_t v; }; + #define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v) + #endif + #ifndef __ALIGNED + #warning No compiler specific solution for __ALIGNED. __ALIGNED is ignored. + #define __ALIGNED(x) + #endif + #ifndef __RESTRICT + #warning No compiler specific solution for __RESTRICT. __RESTRICT is ignored. + #define __RESTRICT + #endif + + +#else + #error Unknown compiler. +#endif + + +#endif /* __CMSIS_COMPILER_H */ + diff --git a/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 + + #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 + +#ifdef __cplusplus + extern "C" { +#endif + +/** + \page CMSIS_MISRA_Exceptions MISRA-C:2004 Compliance Exceptions + CMSIS violates the following MISRA-C:2004 rules: + + \li Required Rule 8.5, object/function definition in header file.
+ Function definitions in header files are used to allow 'inlining'. + + \li Required Rule 18.4, declaration of union type or object of union type: '{...}'.
+ Unions are used for effective representation of core registers. + + \li Advisory Rule 19.7, Function-like macro defined.
+ Function-like macros are used to allow more efficient code. + */ + + +/******************************************************************************* + * CMSIS definitions + ******************************************************************************/ +/** + \ingroup Cortex_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 + + IO Type Qualifiers are used + \li to specify the access to peripheral variables. + \li for automatic generation of peripheral register debug information. +*/ +#ifdef __cplusplus + #define __I volatile /*!< Defines 'read only' permissions */ +#else + #define __I volatile const /*!< Defines 'read only' permissions */ +#endif +#define __O volatile /*!< Defines 'write only' permissions */ +#define __IO volatile /*!< Defines 'read / write' permissions */ + +/* following defines should be used for structure members */ +#define __IM volatile const /*! Defines 'read only' structure member permissions */ +#define __OM volatile /*! Defines 'write only' structure member permissions */ +#define __IOM volatile /*! Defines 'read / write' structure member permissions */ + +/*@} end of group 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 __Vendor_SysTickConfig is set to 1, then the + function SysTick_Config is not included. In this case, the file device.h + must contain a vendor-specific implementation of this function. + */ +__STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks) +{ + if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) + { + return (1UL); /* Reload value impossible */ + } + + SysTick->LOAD = (uint32_t)(ticks - 1UL); /* set reload register */ + NVIC_SetPriority (SysTick_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL); /* set Priority for Systick Interrupt */ + SysTick->VAL = 0UL; /* Load the SysTick Counter Value */ + SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | + SysTick_CTRL_TICKINT_Msk | + SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ + return (0UL); /* Function successful */ +} + +#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 __Vendor_SysTickConfig is set to 1, then the + function TZ_SysTick_Config_NS is not included. In this case, the file device.h + 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 + +#ifdef __cplusplus + extern "C" { +#endif + +/** + \page CMSIS_MISRA_Exceptions MISRA-C:2004 Compliance Exceptions + CMSIS violates the following MISRA-C:2004 rules: + + \li Required Rule 8.5, object/function definition in header file.
+ Function definitions in header files are used to allow 'inlining'. + + \li Required Rule 18.4, declaration of union type or object of union type: '{...}'.
+ Unions are used for effective representation of core registers. + + \li Advisory Rule 19.7, Function-like macro defined.
+ Function-like macros are used to allow more efficient code. + */ + + +/******************************************************************************* + * CMSIS definitions + ******************************************************************************/ +/** + \ingroup Cortex_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 + + IO Type Qualifiers are used + \li to specify the access to peripheral variables. + \li for automatic generation of peripheral register debug information. +*/ +#ifdef __cplusplus + #define __I volatile /*!< Defines 'read only' permissions */ +#else + #define __I volatile const /*!< Defines 'read only' permissions */ +#endif +#define __O volatile /*!< Defines 'write only' permissions */ +#define __IO volatile /*!< Defines 'read / write' permissions */ + +/* following defines should be used for structure members */ +#define __IM volatile const /*! Defines 'read only' structure member permissions */ +#define __OM volatile /*! Defines 'write only' structure member permissions */ +#define __IOM volatile /*! Defines 'read / write' structure member permissions */ + +/*@} end of group 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 __Vendor_SysTickConfig is set to 1, then the + function SysTick_Config is not included. In this case, the file device.h + must contain a vendor-specific implementation of this function. + */ +__STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks) +{ + if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) + { + return (1UL); /* Reload value impossible */ + } + + SysTick->LOAD = (uint32_t)(ticks - 1UL); /* set reload register */ + NVIC_SetPriority (SysTick_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL); /* set Priority for Systick Interrupt */ + SysTick->VAL = 0UL; /* Load the SysTick Counter Value */ + SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | + SysTick_CTRL_TICKINT_Msk | + SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ + return (0UL); /* Function successful */ +} + +#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 __Vendor_SysTickConfig is set to 1, then the + function TZ_SysTick_Config_NS is not included. In this case, the file device.h + 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 + +#ifdef __cplusplus + extern "C" { +#endif + +/** + \page CMSIS_MISRA_Exceptions MISRA-C:2004 Compliance Exceptions + CMSIS violates the following MISRA-C:2004 rules: + + \li Required Rule 8.5, object/function definition in header file.
+ Function definitions in header files are used to allow 'inlining'. + + \li Required Rule 18.4, declaration of union type or object of union type: '{...}'.
+ Unions are used for effective representation of core registers. + + \li Advisory Rule 19.7, Function-like macro defined.
+ Function-like macros are used to allow more efficient code. + */ + + +/******************************************************************************* + * CMSIS definitions + ******************************************************************************/ +/** + \ingroup Cortex_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 + + IO Type Qualifiers are used + \li to specify the access to peripheral variables. + \li for automatic generation of peripheral register debug information. +*/ +#ifdef __cplusplus + #define __I volatile /*!< Defines 'read only' permissions */ +#else + #define __I volatile const /*!< Defines 'read only' permissions */ +#endif +#define __O volatile /*!< Defines 'write only' permissions */ +#define __IO volatile /*!< Defines 'read / write' permissions */ + +/* following defines should be used for structure members */ +#define __IM volatile const /*! Defines 'read only' structure member permissions */ +#define __OM volatile /*! Defines 'write only' structure member permissions */ +#define __IOM volatile /*! Defines 'read / write' structure member permissions */ + +/*@} end of group Cortex_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 __Vendor_SysTickConfig is set to 1, then the + function SysTick_Config is not included. In this case, the file device.h + must contain a vendor-specific implementation of this function. + */ +__STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks) +{ + if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) + { + return (1UL); /* Reload value impossible */ + } + + SysTick->LOAD = (uint32_t)(ticks - 1UL); /* set reload register */ + NVIC_SetPriority (SysTick_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL); /* set Priority for Systick Interrupt */ + SysTick->VAL = 0UL; /* Load the SysTick Counter Value */ + SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | + SysTick_CTRL_TICKINT_Msk | + SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ + return (0UL); /* Function successful */ +} + +#endif + +/*@} end of CMSIS_Core_SysTickFunctions */ + + + +/* ##################################### 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 +#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 + + +#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_ */ diff --git a/LICENSE b/LICENSE new file mode 100644 index 0000000..261eeb9 --- /dev/null +++ b/LICENSE @@ -0,0 +1,201 @@ + Apache License + Version 2.0, January 2004 + http://www.apache.org/licenses/ + + TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION + + 1. Definitions. + + "License" shall mean the terms and conditions for use, reproduction, + and distribution as defined by Sections 1 through 9 of this document. + + "Licensor" shall mean the copyright owner or entity authorized by + the copyright owner that is granting the License. + + "Legal Entity" shall mean the union of the acting entity and all + other entities that control, are controlled by, or are under common + control with that entity. For the purposes of this definition, + "control" means (i) the power, direct or indirect, to cause the + direction or management of such entity, whether by contract or + otherwise, or (ii) ownership of fifty percent (50%) or more of the + outstanding shares, or (iii) beneficial ownership of such entity. + + "You" (or "Your") shall mean an individual or Legal Entity + exercising permissions granted by this License. + + "Source" form shall mean the preferred form for making modifications, + including but not limited to software source code, documentation + source, and configuration files. + + "Object" form shall mean any form resulting from mechanical + transformation or translation of a Source form, including but + not limited to compiled object code, generated documentation, + and conversions to other media types. + + "Work" shall mean the work of authorship, whether in Source or + Object form, made available under the License, as indicated by a + copyright notice that is included in or attached to the work + (an example is provided in the Appendix below). + + "Derivative Works" shall mean any work, whether in Source or Object + form, that is based on (or derived from) the Work and for which the + editorial revisions, annotations, elaborations, or other modifications + represent, as a whole, an original work of authorship. For the purposes + of this License, Derivative Works shall not include works that remain + separable from, or merely link (or bind by name) to the interfaces of, + the Work and Derivative Works thereof. + + "Contribution" shall mean any work of authorship, including + the original version of the Work and any modifications or additions + to that Work or Derivative Works thereof, that is intentionally + submitted to Licensor for inclusion in the Work by the copyright owner + or by an individual or Legal Entity authorized to submit on behalf of + the copyright owner. For the purposes of this definition, "submitted" + means any form of electronic, verbal, or written communication sent + to the Licensor or its representatives, including but not limited to + communication on electronic mailing lists, source code control systems, + and issue tracking systems that are managed by, or on behalf of, the + Licensor for the purpose of discussing and improving the Work, but + excluding communication that is conspicuously marked or otherwise + designated in writing by the copyright owner as "Not a Contribution." + + "Contributor" shall mean Licensor and any individual or Legal Entity + on behalf of whom a Contribution has been received by Licensor and + subsequently incorporated within the Work. + + 2. Grant of Copyright License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + copyright license to reproduce, prepare Derivative Works of, + publicly display, publicly perform, sublicense, and distribute the + Work and such Derivative Works in Source or Object form. + + 3. Grant of Patent License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + (except as stated in this section) patent license to make, have made, + use, offer to sell, sell, import, and otherwise transfer the Work, + where such license applies only to those patent claims licensable + by such Contributor that are necessarily infringed by their + Contribution(s) alone or by combination of their Contribution(s) + with the Work to which such Contribution(s) was submitted. If You + institute patent litigation against any entity (including a + cross-claim or counterclaim in a lawsuit) alleging that the Work + or a Contribution incorporated within the Work constitutes direct + or contributory patent infringement, then any patent licenses + granted to You under this License for that Work shall terminate + as of the date such litigation is filed. + + 4. Redistribution. You may reproduce and distribute copies of the + Work or Derivative Works thereof in any medium, with or without + modifications, and in Source or Object form, provided that You + meet the following conditions: + + (a) You must give any other recipients of the Work or + Derivative Works a copy of this License; and + + (b) You must cause any modified files to carry prominent notices + stating that You changed the files; and + + (c) You must retain, in the Source form of any Derivative Works + that You distribute, all copyright, patent, trademark, and + attribution notices from the Source form of the Work, + excluding those notices that do not pertain to any part of + the Derivative Works; and + + (d) If the Work includes a "NOTICE" text file as part of its + distribution, then any Derivative Works that You distribute must + include a readable copy of the attribution notices contained + within such NOTICE file, excluding those notices that do not + pertain to any part of the Derivative Works, in at least one + of the following places: within a NOTICE text file distributed + as part of the Derivative Works; within the Source form or + documentation, if provided along with the Derivative Works; or, + within a display generated by the Derivative Works, if and + wherever such third-party notices normally appear. The contents + of the NOTICE file are for informational purposes only and + do not modify the License. You may add Your own attribution + notices within Derivative Works that You distribute, alongside + or as an addendum to the NOTICE text from the Work, provided + that such additional attribution notices cannot be construed + as modifying the License. + + You may add Your own copyright statement to Your modifications and + may provide additional or different license terms and conditions + for use, reproduction, or distribution of Your modifications, or + for any such Derivative Works as a whole, provided Your use, + reproduction, and distribution of the Work otherwise complies with + the conditions stated in this License. + + 5. Submission of Contributions. Unless You explicitly state otherwise, + any Contribution intentionally submitted for inclusion in the Work + by You to the Licensor shall be under the terms and conditions of + this License, without any additional terms or conditions. + Notwithstanding the above, nothing herein shall supersede or modify + the terms of any separate license agreement you may have executed + with Licensor regarding such Contributions. + + 6. Trademarks. This License does not grant permission to use the trade + names, trademarks, service marks, or product names of the Licensor, + except as required for reasonable and customary use in describing the + origin of the Work and reproducing the content of the NOTICE file. + + 7. Disclaimer of Warranty. Unless required by applicable law or + agreed to in writing, Licensor provides the Work (and each + Contributor provides its Contributions) on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or + implied, including, without limitation, any warranties or conditions + of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A + PARTICULAR PURPOSE. You are solely responsible for determining the + appropriateness of using or redistributing the Work and assume any + risks associated with Your exercise of permissions under this License. + + 8. Limitation of Liability. In no event and under no legal theory, + whether in tort (including negligence), contract, or otherwise, + unless required by applicable law (such as deliberate and grossly + negligent acts) or agreed to in writing, shall any Contributor be + liable to You for damages, including any direct, indirect, special, + incidental, or consequential damages of any character arising as a + result of this License or out of the use or inability to use the + Work (including but not limited to damages for loss of goodwill, + work stoppage, computer failure or malfunction, or any and all + other commercial damages or losses), even if such Contributor + has been advised of the possibility of such damages. + + 9. Accepting Warranty or Additional Liability. While redistributing + the Work or Derivative Works thereof, You may choose to offer, + and charge a fee for, acceptance of support, warranty, indemnity, + or other liability obligations and/or rights consistent with this + License. However, in accepting such obligations, You may act only + on Your own behalf and on Your sole responsibility, not on behalf + of any other Contributor, and only if You agree to indemnify, + defend, and hold each Contributor harmless for any liability + incurred by, or claims asserted against, such Contributor by reason + of your accepting any such warranty or additional liability. + + END OF TERMS AND CONDITIONS + + APPENDIX: How to apply the Apache License to your work. + + To apply the Apache License to your work, attach the following + boilerplate notice, with the fields enclosed by brackets "[]" + replaced with your own identifying information. (Don't include + the brackets!) The text should be enclosed in the appropriate + comment syntax for the file format. We also recommend that a + file or class name and description of purpose be included on the + same "printed page" as the copyright notice for easier + identification within third-party archives. + + Copyright [yyyy] [name of copyright owner] + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. diff --git a/MK02_DARSENA_V02.mex b/MK02_DARSENA_V02.mex new file mode 100755 index 0000000..65cf5bf --- /dev/null +++ b/MK02_DARSENA_V02.mex @@ -0,0 +1,223 @@ + + + + MK02FN128xxx10 + MK02FN128VFM10 + + ksdk2_0 + + + + + + + true + false + + + + + 4.0.0 + + + + + + + + + + + + + + + + + + + + + + + + + Configures pin routing and optionally pin electrical features.&lt;br/&gt; + + true + core0 + true + + + + + true + + + + + true + + + + + true + + + + + true + + + + + true + + + + + true + + + + + true + + + + + true + + + + + true + + + + + true + + + + + true + + + + + true + + + + + true + + + + + true + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 4.0.0 + + + + + + + + + true + + + + + + + + + + + + + + + + + true + + + + + + N/A + + + + + + \ No newline at end of file diff --git a/README b/README new file mode 100644 index 0000000..38becc7 --- /dev/null +++ b/README @@ -0,0 +1,30 @@ +# privateisland ARM test suite + +ARM Test Code for Open Source FPGA Network Processor for Security, IoT, and Control. + +See LICENSE in this folder and reference to LICENSE in header of each source code file + +Contributors must agree to Contributor License Agreement (to be added). + +Project depends on NXP SDK for Kinetis. + +Either create an SDK for the MK02FN128xxx10 at https://mcuxpresso.nxp.com/en/dashboard or contact support@mindchaseres.com + +See included MEX file for generation of pin and clock definition + +It is assumed that the developer is using NXP's MCUXpresso IDE. This IDE includes the GNU Arm Embedded Toolchain + +Importing the project: + +File -> Import -> General -> Existing Projects into Workspace + +Project assumes developer is using OpenOCD to debug. See the following links depending on debug environment: + +https://mindchasers.com/dev/openocd-darsena + +https://mindchasers.com/dev/openocd-darsena-windows + +It is also possible to use the mainline Eclipse with a self managed GNU Arm Embedded Toolchain + + + diff --git a/board/board.c b/board/board.c new file mode 100644 index 0000000..2689053 --- /dev/null +++ b/board/board.c @@ -0,0 +1,49 @@ +/* + * Copyright 2016-2018 NXP + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without modification, + * are permitted provided that the following conditions are met: + * + * o Redistributions of source code must retain the above copyright notice, this list + * of conditions and the following disclaimer. + * + * o 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. + * + * o Neither the name of NXP Semiconductor, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from this + * software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED + * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR + * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES + * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON + * ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT + * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS + * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ + +/** + * @file board.c + * @brief Board initialization file. + */ + +/* This is a template for board specific configuration created by MCUXpresso IDE Project Wizard.*/ + +#include +#include "board.h" +#include "fsl_debug_console.h" + +/** + * @brief Set up and initialize all required blocks and functions related to the board hardware. + */ +void BOARD_InitDebugConsole(void) { + uint32_t uartClkSrcFreq = BOARD_DEBUG_UART_CLK_FREQ; + + DbgConsole_Init(BOARD_DEBUG_UART_BASEADDR, BOARD_DEBUG_UART_BAUDRATE, BOARD_DEBUG_UART_TYPE, uartClkSrcFreq); +} diff --git a/board/board.h b/board/board.h new file mode 100644 index 0000000..4d4811b --- /dev/null +++ b/board/board.h @@ -0,0 +1,76 @@ +/* + * Copyright 2016-2018 NXP Semiconductor, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without modification, + * are permitted provided that the following conditions are met: + * + * o Redistributions of source code must retain the above copyright notice, this list + * of conditions and the following disclaimer. + * + * o 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. + * + * o Neither the name of NXP Semiconductor, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from this + * software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED + * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR + * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES + * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON + * ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT + * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS + * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ + +/** + * @file board.h + * @brief Board initialization header file. + */ + +/* This is a template for board specific configuration created by MCUXpresso IDE Project Wizard.*/ + +#ifndef _BOARD_H_ +#define _BOARD_H_ + +#include "fsl_common.h" + +/** + * @brief The board name + */ +#define BOARD_NAME "darsena" + +/*! @brief The UART to use for debug messages. */ +#define BOARD_USE_UART +#define BOARD_DEBUG_UART_TYPE DEBUG_CONSOLE_DEVICE_TYPE_UART +#define BOARD_DEBUG_UART_BASEADDR (uint32_t) UART0 +#define BOARD_DEBUG_UART_CLKSRC SYS_CLK +#define BOARD_DEBUG_UART_CLK_FREQ CLOCK_GetCoreSysClkFreq() +#define BOARD_UART_IRQ UART0_RX_TX_IRQn +#define BOARD_UART_IRQ_HANDLER UART0_RX_TX_IRQHandler + +#ifndef BOARD_DEBUG_UART_BAUDRATE +#define BOARD_DEBUG_UART_BAUDRATE 115200 +#endif /* BOARD_DEBUG_UART_BAUDRATE */ + +#if defined(__cplusplus) +extern "C" { +#endif /* __cplusplus */ + +/** + * @brief Initialize board specific settings. + */ +void BOARD_InitDebugConsole(void); + +#if defined(__cplusplus) +} +#endif /* __cplusplus */ + +#endif /* _BOARD_H_ */ + + diff --git a/board/clock_config.c b/board/clock_config.c new file mode 100644 index 0000000..0f332c4 --- /dev/null +++ b/board/clock_config.c @@ -0,0 +1,165 @@ +/*********************************************************************************************************************** + * This file was generated by the MCUXpresso Config Tools. Any manual edits made to this file + * will be overwritten if the respective MCUXpresso Config Tools is used to update this file. + **********************************************************************************************************************/ +/* + * How to setup clock using clock driver functions: + * + * 1. CLOCK_SetSimSafeDivs, to make sure core clock, bus clock, flexbus clock + * and flash clock are in allowed range during clock mode switch. + * + * 2. Call CLOCK_Osc0Init to setup OSC clock, if it is used in target mode. + * + * 3. Set MCG configuration, MCG includes three parts: FLL clock, PLL clock and + * internal reference clock(MCGIRCLK). Follow the steps to setup: + * + * 1). Call CLOCK_BootToXxxMode to set MCG to target mode. + * + * 2). If target mode is FBI/BLPI/PBI mode, the MCGIRCLK has been configured + * correctly. For other modes, need to call CLOCK_SetInternalRefClkConfig + * explicitly to setup MCGIRCLK. + * + * 3). Don't need to configure FLL explicitly, because if target mode is FLL + * mode, then FLL has been configured by the function CLOCK_BootToXxxMode, + * if the target mode is not FLL mode, the FLL is disabled. + * + * 4). If target mode is PEE/PBE/PEI/PBI mode, then the related PLL has been + * setup by CLOCK_BootToXxxMode. In FBE/FBI/FEE/FBE mode, the PLL could + * be enabled independently, call CLOCK_EnablePll0 explicitly in this case. + * + * 4. Call CLOCK_SetSimConfig to set the clock configuration in SIM. + */ + +/* clang-format off */ +/* TEXT BELOW IS USED AS SETTING FOR TOOLS ************************************* +!!GlobalInfo +product: Clocks v4.1 +processor: MK02FN128xxx10 +package_id: MK02FN128VFM10 +mcu_data: ksdk2_0 +processor_version: 4.0.0 + * BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR TOOLS **********/ +/* clang-format on */ + +#include "clock_config.h" + +/******************************************************************************* + * Definitions + ******************************************************************************/ +#define MCG_IRCLK_DISABLE 0U /*!< MCGIRCLK disabled */ +#define OSC_CAP0P 0U /*!< Oscillator 0pF capacitor load */ +#define OSC_ER_CLK_DISABLE 0U /*!< Disable external reference clock */ +#define SIM_OSC32KSEL_OSC32KCLK_CLK 0U /*!< OSC32KSEL select: OSC32KCLK clock */ +#define SIM_PLLFLLSEL_MCGFLLCLK_CLK 0U /*!< PLLFLL select: MCGFLLCLK clock */ + +/******************************************************************************* + * Variables + ******************************************************************************/ +/* System clock frequency. */ +extern uint32_t SystemCoreClock; + +/******************************************************************************* + * Code + ******************************************************************************/ +/*FUNCTION********************************************************************** + * + * Function Name : CLOCK_CONFIG_FllStableDelay + * Description : This function is used to delay for FLL stable. + * + *END**************************************************************************/ +static void CLOCK_CONFIG_FllStableDelay(void) +{ + uint32_t i = 30000U; + while (i--) + { + __NOP(); + } +} + +/******************************************************************************* + ************************ BOARD_InitBootClocks function ************************ + ******************************************************************************/ +void BOARD_InitBootClocks(void) +{ + BOARD_BootClockRUN(); +} + +/******************************************************************************* + ********************** Configuration BOARD_BootClockRUN *********************** + ******************************************************************************/ +/* clang-format off */ +/* TEXT BELOW IS USED AS SETTING FOR TOOLS ************************************* +!!Configuration +name: BOARD_BootClockRUN +called_from_default_init: true +outputs: +- {id: Bus_clock.outFreq, value: 41.94304 MHz} +- {id: Core_clock.outFreq, value: 41.94304 MHz} +- {id: Flash_clock.outFreq, value: 20.97152 MHz} +- {id: LPO_clock.outFreq, value: 1 kHz} +- {id: MCGFFCLK.outFreq, value: 32.768 kHz} +- {id: PLLFLLCLK.outFreq, value: 41.94304 MHz} +- {id: System_clock.outFreq, value: 41.94304 MHz} +settings: +- {id: MCG.FLL_mul.scale, value: '1280', locked: true} + * BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR TOOLS **********/ +/* clang-format on */ + +/******************************************************************************* + * Variables for BOARD_BootClockRUN configuration + ******************************************************************************/ +const mcg_config_t mcgConfig_BOARD_BootClockRUN = + { + .mcgMode = kMCG_ModeFEI, /* FEI - FLL Engaged Internal */ + .irclkEnableMode = MCG_IRCLK_DISABLE, /* MCGIRCLK disabled */ + .ircs = kMCG_IrcSlow, /* Slow internal reference clock selected */ + .fcrdiv = 0x1U, /* Fast IRC divider: divided by 2 */ + .frdiv = 0x0U, /* FLL reference clock divider: divided by 1 */ + .drs = kMCG_DrsMid, /* Mid frequency range */ + .dmx32 = kMCG_Dmx32Default, /* DCO has a default range of 25% */ + .oscsel = kMCG_OscselOsc, /* Selects System Oscillator (OSCCLK) */ + }; +const sim_clock_config_t simConfig_BOARD_BootClockRUN = + { + .pllFllSel = SIM_PLLFLLSEL_MCGFLLCLK_CLK, /* PLLFLL select: MCGFLLCLK clock */ + .er32kSrc = SIM_OSC32KSEL_OSC32KCLK_CLK, /* OSC32KSEL select: OSC32KCLK clock */ + .clkdiv1 = 0x10000U, /* SIM_CLKDIV1 - OUTDIV1: /1, OUTDIV2: /1, OUTDIV4: /2 */ + }; +const osc_config_t oscConfig_BOARD_BootClockRUN = + { + .freq = 0U, /* Oscillator frequency: 0Hz */ + .capLoad = (OSC_CAP0P), /* Oscillator capacity load: 0pF */ + .workMode = kOSC_ModeExt, /* Use external clock */ + .oscerConfig = + { + .enableMode = OSC_ER_CLK_DISABLE, /* Disable external reference clock */ + .erclkDiv = 0, /* Divider for OSCERCLK: divided by 1 */ + } + }; + +/******************************************************************************* + * Code for BOARD_BootClockRUN configuration + ******************************************************************************/ +void BOARD_BootClockRUN(void) +{ + /* Set the system clock dividers in SIM to safe value. */ + CLOCK_SetSimSafeDivs(); + /* Set MCG to FEI mode. */ +#if FSL_CLOCK_DRIVER_VERSION >= MAKE_VERSION(2, 2, 0) + CLOCK_BootToFeiMode(mcgConfig_BOARD_BootClockRUN.dmx32, + mcgConfig_BOARD_BootClockRUN.drs, + CLOCK_CONFIG_FllStableDelay); +#else + CLOCK_BootToFeiMode(mcgConfig_BOARD_BootClockRUN.drs, + CLOCK_CONFIG_FllStableDelay); +#endif + /* Configure the Internal Reference clock (MCGIRCLK). */ + CLOCK_SetInternalRefClkConfig(mcgConfig_BOARD_BootClockRUN.irclkEnableMode, + mcgConfig_BOARD_BootClockRUN.ircs, + mcgConfig_BOARD_BootClockRUN.fcrdiv); + /* Set the clock configuration in SIM module. */ + CLOCK_SetSimConfig(&simConfig_BOARD_BootClockRUN); + /* Set SystemCoreClock variable. */ + SystemCoreClock = BOARD_BOOTCLOCKRUN_CORE_CLOCK; +} + diff --git a/board/clock_config.h b/board/clock_config.h new file mode 100644 index 0000000..eb0f8be --- /dev/null +++ b/board/clock_config.h @@ -0,0 +1,69 @@ +/*********************************************************************************************************************** + * This file was generated by the MCUXpresso Config Tools. Any manual edits made to this file + * will be overwritten if the respective MCUXpresso Config Tools is used to update this file. + **********************************************************************************************************************/ + +#ifndef _CLOCK_CONFIG_H_ +#define _CLOCK_CONFIG_H_ + +#include "fsl_common.h" + +/******************************************************************************* + * Definitions + ******************************************************************************/ + +/******************************************************************************* + ************************ BOARD_InitBootClocks function ************************ + ******************************************************************************/ + +#if defined(__cplusplus) +extern "C" { +#endif /* __cplusplus*/ + +/*! + * @brief This function executes default configuration of clocks. + * + */ +void BOARD_InitBootClocks(void); + +#if defined(__cplusplus) +} +#endif /* __cplusplus*/ + +/******************************************************************************* + ********************** Configuration BOARD_BootClockRUN *********************** + ******************************************************************************/ +/******************************************************************************* + * Definitions for BOARD_BootClockRUN configuration + ******************************************************************************/ +#define BOARD_BOOTCLOCKRUN_CORE_CLOCK 41943040U /*!< Core clock frequency: 41943040Hz */ + +/*! @brief MCG set for BOARD_BootClockRUN configuration. + */ +extern const mcg_config_t mcgConfig_BOARD_BootClockRUN; +/*! @brief SIM module set for BOARD_BootClockRUN configuration. + */ +extern const sim_clock_config_t simConfig_BOARD_BootClockRUN; +/*! @brief OSC set for BOARD_BootClockRUN configuration. + */ +extern const osc_config_t oscConfig_BOARD_BootClockRUN; + +/******************************************************************************* + * API for BOARD_BootClockRUN configuration + ******************************************************************************/ +#if defined(__cplusplus) +extern "C" { +#endif /* __cplusplus*/ + +/*! + * @brief This function executes configuration of clocks. + * + */ +void BOARD_BootClockRUN(void); + +#if defined(__cplusplus) +} +#endif /* __cplusplus*/ + +#endif /* _CLOCK_CONFIG_H_ */ + diff --git a/board/peripherals.c b/board/peripherals.c new file mode 100644 index 0000000..c3d271d --- /dev/null +++ b/board/peripherals.c @@ -0,0 +1,50 @@ +/* + * Copyright 2017-2018 NXP + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without modification, + * are permitted provided that the following conditions are met: + * + * o Redistributions of source code must retain the above copyright notice, this list + * of conditions and the following disclaimer. + * + * o 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. + * + * o Neither the name of NXP Semiconductor, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from this + * software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED + * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR + * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES + * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON + * ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT + * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS + * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ + +/* TEXT BELOW IS USED AS SETTING FOR TOOLS ************************************* +!!GlobalInfo +product: Peripherals v1.0 +* BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR TOOLS **********/ + +/** + * @file peripherals.c + * @brief Peripherals initialization file. + */ + +/* This is a template for board specific configuration created by MCUXpresso IDE Project Wizard.*/ + +#include "peripherals.h" + +/** + * @brief Set up and initialize all required blocks and functions related to the peripherals hardware. + */ +void BOARD_InitBootPeripherals(void) { + /* The user initialization should be placed here */ +} diff --git a/board/peripherals.h b/board/peripherals.h new file mode 100644 index 0000000..cfc3b4f --- /dev/null +++ b/board/peripherals.h @@ -0,0 +1,56 @@ +/* + * Copyright 2017-2018 NXP + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without modification, + * are permitted provided that the following conditions are met: + * + * o Redistributions of source code must retain the above copyright notice, this list + * of conditions and the following disclaimer. + * + * o 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. + * + * o Neither the name of NXP Semiconductor, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from this + * software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED + * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR + * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES + * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON + * ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT + * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS + * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ + +/** + * @file peripherals.h + * @brief Peripherals initialization header file. + */ + +/* This is a template for board specific configuration created by MCUXpresso IDE Project Wizard.*/ + +#ifndef _PERIPHERALS_H_ +#define _PERIPHERALS_H_ + +#if defined(__cplusplus) +extern "C" { +#endif /* __cplusplus */ + +/** + * @brief Initialize peripherals specific settings. + */ +void BOARD_InitBootPeripherals(void); + +#if defined(__cplusplus) +} +#endif /* __cplusplus */ + +#endif /* _PERIPHERALS_H_ */ + + diff --git a/board/pin_mux.c b/board/pin_mux.c new file mode 100755 index 0000000..b3862ea --- /dev/null +++ b/board/pin_mux.c @@ -0,0 +1,235 @@ +/*********************************************************************************************************************** + * This file was generated by the MCUXpresso Config Tools. Any manual edits made to this file + * will be overwritten if the respective MCUXpresso Config Tools is used to update this file. + **********************************************************************************************************************/ + +/* clang-format off */ +/* + * TEXT BELOW IS USED AS SETTING FOR TOOLS ************************************* +!!GlobalInfo +product: Pins v4.1 +processor: MK02FN128xxx10 +package_id: MK02FN128VFM10 +mcu_data: ksdk2_0 +processor_version: 4.0.0 +pin_labels: +- {pin_num: '6', pin_signal: ADC0_SE7a/ADC0_DM2/PTE19/SPI0_SIN/UART1_RTS_b/I2C0_SCL, label: I2C_SCL, identifier: I2C_SCL} +- {pin_num: '16', pin_signal: PTA4/LLWU_P3/FTM0_CH1/NMI_b, label: PMIC_INTN, identifier: PMIC_INTN} +- {pin_num: '11', pin_signal: ADC0_SE18/PTE25/I2C0_SDA/EWM_IN, label: PB6, identifier: PB6} +- {pin_num: '29', pin_signal: PTD4/LLWU_P14/SPI0_PCS1/UART0_RTS_b/FTM0_CH4/EWM_IN, label: FPGA_RESETN, identifier: FPGA_RESETN} +- {pin_num: '17', pin_signal: EXTAL0/PTA18/FTM0_FLT2/FTM_CLKIN0, label: PMIC_DCDC_E, identifier: PMIC_DCDC_E} +- {pin_num: '22', pin_signal: ADC0_SE15/PTC1/LLWU_P6/SPI0_PCS3/UART1_RTS_b/FTM0_CH0, label: FPGA_GPIO, identifier: FPGA_GPIO} +- {pin_num: '19', pin_signal: RESET_b, label: UC_RESETN, identifier: UC_RESETN} +- {pin_num: '20', pin_signal: ADC0_SE8/PTB0/LLWU_P5/I2C0_SCL/FTM1_CH0/FTM1_QD_PHA, label: FCFG_PGMN, identifier: FCFG_PGMN} +- {pin_num: '21', pin_signal: ADC0_SE9/PTB1/I2C0_SDA/FTM1_CH1/FTM1_QD_PHB, label: FCFG_DONE, identifier: FCFG_DONE} +- {pin_num: '25', pin_signal: PTC4/LLWU_P8/SPI0_PCS0/UART1_TX/FTM0_CH3/CMP1_OUT, label: SPI0_PCS, identifier: SPI_PCS} +- {pin_num: '26', pin_signal: PTC5/LLWU_P9/SPI0_SCK/LPTMR0_ALT2/CMP0_OUT/FTM0_CH2, label: SPI_SCLK, identifier: SPI_SCLK} +- {pin_num: '27', pin_signal: CMP0_IN0/PTC6/LLWU_P10/SPI0_SOUT/PDB0_EXTRG, label: SPI_MOSI, identifier: SPI_MOSI} +- {pin_num: '28', pin_signal: CMP0_IN1/PTC7/SPI0_SIN, label: SPI_MISO, identifier: SPI_MISO} +- {pin_num: '30', pin_signal: ADC0_SE6b/PTD5/SPI0_PCS2/UART0_CTS_b/FTM0_CH5/EWM_OUT_b, label: FPGA_INT, identifier: FPGA_INT} +- {pin_num: '31', pin_signal: ADC0_SE7b/PTD6/LLWU_P15/SPI0_PCS3/UART0_RX/FTM0_CH0/FTM0_FLT0, label: UART_RX, identifier: UART_RX} +- {pin_num: '32', pin_signal: PTD7/UART0_TX/FTM0_CH1/FTM0_FLT1, label: UART_TX, identifier: UART_TX} +- {pin_num: '5', pin_signal: ADC0_SE6a/ADC0_DP2/PTE18/SPI0_SOUT/UART1_CTS_b/I2C0_SDA, label: I2C_SDA, identifier: I2C_SDA} +- {pin_num: '10', pin_signal: ADC0_SE17/PTE24/I2C0_SCL/EWM_OUT_b, label: PB7, identifier: PB7} +- {pin_num: '18', pin_signal: XTAL0/PTA19/FTM1_FLT0/FTM_CLKIN1/LPTMR0_ALT1, label: PMIC_LDO_E, identifier: PMIC_LDO_E} + * BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR TOOLS *********** + */ +/* clang-format on */ + +#include "fsl_common.h" +#include "fsl_port.h" +#include "fsl_gpio.h" +#include "pin_mux.h" + +/* FUNCTION ************************************************************************************************************ + * + * Function Name : BOARD_InitBootPins + * Description : Calls initialization functions. + * + * END ****************************************************************************************************************/ +void BOARD_InitBootPins(void) +{ + BOARD_InitPins(); +} + +/* clang-format off */ +/* + * TEXT BELOW IS USED AS SETTING FOR TOOLS ************************************* +BOARD_InitPins: +- options: {callFromInitBoot: 'true', coreID: core0, enableClock: 'true'} +- pin_list: + - {pin_num: '15', peripheral: JTAG, signal: JTAG_TMS_SWD_DIO, pin_signal: PTA3/UART0_RTS_b/FTM0_CH0/JTAG_TMS/SWD_DIO} + - {pin_num: '12', peripheral: JTAG, signal: JTAG_TCLK_SWD_CLK, pin_signal: PTA0/UART0_CTS_b/FTM0_CH5/JTAG_TCLK/SWD_CLK} + - {pin_num: '14', peripheral: JTAG, signal: TDO, pin_signal: PTA2/UART0_TX/JTAG_TDO/TRACE_SWO} + - {pin_num: '13', peripheral: JTAG, signal: TDI, pin_signal: PTA1/UART0_RX/JTAG_TDI} + - {pin_num: '11', peripheral: GPIOE, signal: 'GPIO, 25', pin_signal: ADC0_SE18/PTE25/I2C0_SDA/EWM_IN, direction: OUTPUT, gpio_init_state: 'false'} + - {pin_num: '32', peripheral: UART0, signal: TX, pin_signal: PTD7/UART0_TX/FTM0_CH1/FTM0_FLT1} + - {pin_num: '31', peripheral: UART0, signal: RX, pin_signal: ADC0_SE7b/PTD6/LLWU_P15/SPI0_PCS3/UART0_RX/FTM0_CH0/FTM0_FLT0} + - {pin_num: '1', peripheral: SUPPLY, signal: 'VDD, 0', pin_signal: VDD1} + - {pin_num: '2', peripheral: SUPPLY, signal: 'VSS, 0', pin_signal: VSS2} + - {pin_num: '3', peripheral: ADC0, signal: 'DP, 1', pin_signal: ADC0_SE4a/ADC0_DP1/PTE16/SPI0_PCS0/UART1_TX/FTM_CLKIN0/FTM0_FLT3} + - {pin_num: '4', peripheral: ADC0, signal: 'DM, 1', pin_signal: ADC0_SE5a/ADC0_DM1/PTE17/SPI0_SCK/UART1_RX/FTM_CLKIN1/LPTMR0_ALT3} + - {pin_num: '7', peripheral: SUPPLY, signal: 'VDDA, 1', pin_signal: VDDA/VREFH} + - {pin_num: '8', peripheral: SUPPLY, signal: 'pwr_vssa, 1', pin_signal: VSSA/VREFL} + - {pin_num: '9', peripheral: DAC0, signal: OUT, pin_signal: DAC0_OUT/CMP1_IN3/ADC0_SE23} + - {pin_num: '16', peripheral: SystemControl, signal: NMI, pin_signal: PTA4/LLWU_P3/FTM0_CH1/NMI_b} + - {pin_num: '17', peripheral: GPIOA, signal: 'GPIO, 18', pin_signal: EXTAL0/PTA18/FTM0_FLT2/FTM_CLKIN0} + - {pin_num: '19', peripheral: RCM, signal: RESET, pin_signal: RESET_b} + - {pin_num: '20', peripheral: GPIOB, signal: 'GPIO, 0', pin_signal: ADC0_SE8/PTB0/LLWU_P5/I2C0_SCL/FTM1_CH0/FTM1_QD_PHA} + - {pin_num: '21', peripheral: GPIOB, signal: 'GPIO, 1', pin_signal: ADC0_SE9/PTB1/I2C0_SDA/FTM1_CH1/FTM1_QD_PHB} + - {pin_num: '25', peripheral: SPI0, signal: PCS0_SS, pin_signal: PTC4/LLWU_P8/SPI0_PCS0/UART1_TX/FTM0_CH3/CMP1_OUT, direction: OUTPUT} + - {pin_num: '29', peripheral: GPIOD, signal: 'GPIO, 4', pin_signal: PTD4/LLWU_P14/SPI0_PCS1/UART0_RTS_b/FTM0_CH4/EWM_IN, direction: OUTPUT} + - {pin_num: '30', peripheral: GPIOD, signal: 'GPIO, 5', pin_signal: ADC0_SE6b/PTD5/SPI0_PCS2/UART0_CTS_b/FTM0_CH5/EWM_OUT_b, direction: INPUT, gpio_interrupt: kPORT_InterruptLogicOne} + - {pin_num: '26', peripheral: SPI0, signal: SCK, pin_signal: PTC5/LLWU_P9/SPI0_SCK/LPTMR0_ALT2/CMP0_OUT/FTM0_CH2} + - {pin_num: '27', peripheral: SPI0, signal: SOUT, pin_signal: CMP0_IN0/PTC6/LLWU_P10/SPI0_SOUT/PDB0_EXTRG} + - {pin_num: '28', peripheral: SPI0, signal: SIN, pin_signal: CMP0_IN1/PTC7/SPI0_SIN} + - {pin_num: '6', peripheral: I2C0, signal: SCL, pin_signal: ADC0_SE7a/ADC0_DM2/PTE19/SPI0_SIN/UART1_RTS_b/I2C0_SCL} + - {pin_num: '5', peripheral: I2C0, signal: SDA, pin_signal: ADC0_SE6a/ADC0_DP2/PTE18/SPI0_SOUT/UART1_CTS_b/I2C0_SDA, identifier: '', open_drain: enable} + - {pin_num: '10', peripheral: GPIOE, signal: 'GPIO, 24', pin_signal: ADC0_SE17/PTE24/I2C0_SCL/EWM_OUT_b} + - {pin_num: '23', peripheral: CMP1, signal: 'IN, 0', pin_signal: ADC0_SE4b/CMP1_IN0/PTC2/SPI0_PCS2/UART1_CTS_b/FTM0_CH1} + - {pin_num: '24', peripheral: CMP1, signal: 'IN, 1', pin_signal: CMP1_IN1/PTC3/LLWU_P7/SPI0_PCS1/UART1_RX/FTM0_CH2/CLKOUT} + - {pin_num: '18', peripheral: GPIOA, signal: 'GPIO, 19', pin_signal: XTAL0/PTA19/FTM1_FLT0/FTM_CLKIN1/LPTMR0_ALT1} + - {pin_num: '22', peripheral: GPIOC, signal: 'GPIO, 1', pin_signal: ADC0_SE15/PTC1/LLWU_P6/SPI0_PCS3/UART1_RTS_b/FTM0_CH0} + * BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR TOOLS *********** + */ +/* clang-format on */ + +/* FUNCTION ************************************************************************************************************ + * + * Function Name : BOARD_InitPins + * Description : Configures pin routing and optionally pin electrical features. + * + * END ****************************************************************************************************************/ +void BOARD_InitPins(void) +{ + /* Port A Clock Gate Control: Clock enabled */ + CLOCK_EnableClock(kCLOCK_PortA); + /* Port B Clock Gate Control: Clock enabled */ + CLOCK_EnableClock(kCLOCK_PortB); + /* Port C Clock Gate Control: Clock enabled */ + CLOCK_EnableClock(kCLOCK_PortC); + /* Port D Clock Gate Control: Clock enabled */ + CLOCK_EnableClock(kCLOCK_PortD); + /* Port E Clock Gate Control: Clock enabled */ + CLOCK_EnableClock(kCLOCK_PortE); + + gpio_pin_config_t FPGA_RESETN_config = { + .pinDirection = kGPIO_DigitalOutput, + .outputLogic = 0U + }; + /* Initialize GPIO functionality on pin PTD4 (pin 29) */ + GPIO_PinInit(BOARD_INITPINS_FPGA_RESETN_GPIO, BOARD_INITPINS_FPGA_RESETN_PIN, &FPGA_RESETN_config); + + gpio_pin_config_t FPGA_INT_config = { + .pinDirection = kGPIO_DigitalInput, + .outputLogic = 0U + }; + /* Initialize GPIO functionality on pin PTD5 (pin 30) */ + GPIO_PinInit(BOARD_INITPINS_FPGA_INT_GPIO, BOARD_INITPINS_FPGA_INT_PIN, &FPGA_INT_config); + + gpio_pin_config_t PB6_config = { + .pinDirection = kGPIO_DigitalOutput, + .outputLogic = 0U + }; + /* Initialize GPIO functionality on pin PTE25 (pin 11) */ + GPIO_PinInit(BOARD_INITPINS_PB6_GPIO, BOARD_INITPINS_PB6_PIN, &PB6_config); + + /* PORTA0 (pin 12) is configured as JTAG_TCLK */ + PORT_SetPinMux(PORTA, 0U, kPORT_MuxAlt7); + + /* PORTA1 (pin 13) is configured as JTAG_TDI */ + PORT_SetPinMux(PORTA, 1U, kPORT_MuxAlt7); + + /* PORTA18 (pin 17) is configured as PTA18 */ + PORT_SetPinMux(BOARD_INITPINS_PMIC_DCDC_E_PORT, BOARD_INITPINS_PMIC_DCDC_E_PIN, kPORT_MuxAsGpio); + + /* PORTA19 (pin 18) is configured as PTA19 */ + PORT_SetPinMux(BOARD_INITPINS_PMIC_LDO_E_PORT, BOARD_INITPINS_PMIC_LDO_E_PIN, kPORT_MuxAsGpio); + + /* PORTA2 (pin 14) is configured as JTAG_TDO */ + PORT_SetPinMux(PORTA, 2U, kPORT_MuxAlt7); + + /* PORTA3 (pin 15) is configured as JTAG_TMS */ + PORT_SetPinMux(PORTA, 3U, kPORT_MuxAlt7); + + /* PORTA4 (pin 16) is configured as NMI_b */ + PORT_SetPinMux(BOARD_INITPINS_PMIC_INTN_PORT, BOARD_INITPINS_PMIC_INTN_PIN, kPORT_MuxAlt7); + + /* PORTB0 (pin 20) is configured as PTB0 */ + PORT_SetPinMux(BOARD_INITPINS_FCFG_PGMN_PORT, BOARD_INITPINS_FCFG_PGMN_PIN, kPORT_MuxAsGpio); + + /* PORTB1 (pin 21) is configured as PTB1 */ + PORT_SetPinMux(BOARD_INITPINS_FCFG_DONE_PORT, BOARD_INITPINS_FCFG_DONE_PIN, kPORT_MuxAsGpio); + + /* PORTC1 (pin 22) is configured as PTC1 */ + PORT_SetPinMux(BOARD_INITPINS_FPGA_GPIO_PORT, BOARD_INITPINS_FPGA_GPIO_PIN, kPORT_MuxAsGpio); + + /* PORTC2 (pin 23) is configured as CMP1_IN0 */ + PORT_SetPinMux(PORTC, 2U, kPORT_PinDisabledOrAnalog); + + /* PORTC3 (pin 24) is configured as CMP1_IN1 */ + PORT_SetPinMux(PORTC, 3U, kPORT_PinDisabledOrAnalog); + + /* PORTC4 (pin 25) is configured as SPI0_PCS0 */ + PORT_SetPinMux(BOARD_INITPINS_SPI_PCS_PORT, BOARD_INITPINS_SPI_PCS_PIN, kPORT_MuxAlt2); + + /* PORTC5 (pin 26) is configured as SPI0_SCK */ + PORT_SetPinMux(BOARD_INITPINS_SPI_SCLK_PORT, BOARD_INITPINS_SPI_SCLK_PIN, kPORT_MuxAlt2); + + /* PORTC6 (pin 27) is configured as SPI0_SOUT */ + PORT_SetPinMux(BOARD_INITPINS_SPI_MOSI_PORT, BOARD_INITPINS_SPI_MOSI_PIN, kPORT_MuxAlt2); + + /* PORTC7 (pin 28) is configured as SPI0_SIN */ + PORT_SetPinMux(BOARD_INITPINS_SPI_MISO_PORT, BOARD_INITPINS_SPI_MISO_PIN, kPORT_MuxAlt2); + + /* PORTD4 (pin 29) is configured as PTD4 */ + PORT_SetPinMux(BOARD_INITPINS_FPGA_RESETN_PORT, BOARD_INITPINS_FPGA_RESETN_PIN, kPORT_MuxAsGpio); + + /* PORTD5 (pin 30) is configured as PTD5 */ + PORT_SetPinMux(BOARD_INITPINS_FPGA_INT_PORT, BOARD_INITPINS_FPGA_INT_PIN, kPORT_MuxAsGpio); + + /* Interrupt configuration on PORTD5 (pin 30): Interrupt when logic one */ + PORT_SetPinInterruptConfig(BOARD_INITPINS_FPGA_INT_PORT, BOARD_INITPINS_FPGA_INT_PIN, kPORT_InterruptLogicOne); + + /* PORTD6 (pin 31) is configured as UART0_RX */ + PORT_SetPinMux(BOARD_INITPINS_UART_RX_PORT, BOARD_INITPINS_UART_RX_PIN, kPORT_MuxAlt3); + + /* PORTD7 (pin 32) is configured as UART0_TX */ + PORT_SetPinMux(BOARD_INITPINS_UART_TX_PORT, BOARD_INITPINS_UART_TX_PIN, kPORT_MuxAlt3); + + /* PORTE16 (pin 3) is configured as ADC0_DP1 */ + PORT_SetPinMux(PORTE, 16U, kPORT_PinDisabledOrAnalog); + + /* PORTE17 (pin 4) is configured as ADC0_DM1 */ + PORT_SetPinMux(PORTE, 17U, kPORT_PinDisabledOrAnalog); + + /* PORTE18 (pin 5) is configured as I2C0_SDA */ + PORT_SetPinMux(PORTE, 18U, kPORT_MuxAlt4); + + PORTE->PCR[18] = ((PORTE->PCR[18] & + /* Mask bits to zero which are setting */ + (~(PORT_PCR_ODE_MASK | PORT_PCR_ISF_MASK))) + + /* Open Drain Enable: Open drain output is enabled on the corresponding pin, if the pin is + * configured as a digital output. */ + | PORT_PCR_ODE(kPORT_OpenDrainEnable)); + + /* PORTE19 (pin 6) is configured as I2C0_SCL */ + PORT_SetPinMux(BOARD_INITPINS_I2C_SCL_PORT, BOARD_INITPINS_I2C_SCL_PIN, kPORT_MuxAlt4); + + /* PORTE24 (pin 10) is configured as PTE24 */ + PORT_SetPinMux(BOARD_INITPINS_PB7_PORT, BOARD_INITPINS_PB7_PIN, kPORT_MuxAsGpio); + + /* PORTE25 (pin 11) is configured as PTE25 */ + PORT_SetPinMux(BOARD_INITPINS_PB6_PORT, BOARD_INITPINS_PB6_PIN, kPORT_MuxAsGpio); + + SIM->SOPT5 = ((SIM->SOPT5 & + /* Mask bits to zero which are setting */ + (~(SIM_SOPT5_UART0TXSRC_MASK))) + + /* UART 0 transmit data source select: UART0_TX pin. */ + | SIM_SOPT5_UART0TXSRC(SOPT5_UART0TXSRC_UART_TX)); +} +/*********************************************************************************************************************** + * EOF + **********************************************************************************************************************/ diff --git a/board/pin_mux.h b/board/pin_mux.h new file mode 100755 index 0000000..9a4cf79 --- /dev/null +++ b/board/pin_mux.h @@ -0,0 +1,162 @@ +/*********************************************************************************************************************** + * This file was generated by the MCUXpresso Config Tools. Any manual edits made to this file + * will be overwritten if the respective MCUXpresso Config Tools is used to update this file. + **********************************************************************************************************************/ + +#ifndef _PIN_MUX_H_ +#define _PIN_MUX_H_ + +/*! + * @addtogroup pin_mux + * @{ + */ + +/*********************************************************************************************************************** + * API + **********************************************************************************************************************/ + +#if defined(__cplusplus) +extern "C" { +#endif + +/*! + * @brief Calls initialization functions. + * + */ +void BOARD_InitBootPins(void); + +#define SOPT5_UART0TXSRC_UART_TX 0x00u /*!<@brief UART 0 transmit data source select: UART0_TX pin */ + +/*! @name PORTE25 (number 11), PB6 + @{ */ +#define BOARD_INITPINS_PB6_GPIO GPIOE /*!<@brief GPIO device name: GPIOE */ +#define BOARD_INITPINS_PB6_PORT PORTE /*!<@brief PORT device name: PORTE */ +#define BOARD_INITPINS_PB6_PIN 25U /*!<@brief PORTE pin index: 25 */ + /* @} */ + +/*! @name PORTD7 (number 32), UART_TX + @{ */ +#define BOARD_INITPINS_UART_TX_PORT PORTD /*!<@brief PORT device name: PORTD */ +#define BOARD_INITPINS_UART_TX_PIN 7U /*!<@brief PORTD pin index: 7 */ + /* @} */ + +/*! @name PORTD6 (number 31), UART_RX + @{ */ +#define BOARD_INITPINS_UART_RX_PORT PORTD /*!<@brief PORT device name: PORTD */ +#define BOARD_INITPINS_UART_RX_PIN 6U /*!<@brief PORTD pin index: 6 */ + /* @} */ + +/*! @name PORTA4 (number 16), PMIC_INTN + @{ */ +#define BOARD_INITPINS_PMIC_INTN_PORT PORTA /*!<@brief PORT device name: PORTA */ +#define BOARD_INITPINS_PMIC_INTN_PIN 4U /*!<@brief PORTA pin index: 4 */ + /* @} */ + +/*! @name PORTA18 (number 17), PMIC_DCDC_E + @{ */ +#define BOARD_INITPINS_PMIC_DCDC_E_GPIO GPIOA /*!<@brief GPIO device name: GPIOA */ +#define BOARD_INITPINS_PMIC_DCDC_E_PORT PORTA /*!<@brief PORT device name: PORTA */ +#define BOARD_INITPINS_PMIC_DCDC_E_PIN 18U /*!<@brief PORTA pin index: 18 */ + /* @} */ + +/*! @name RESET_b (number 19), UC_RESETN + @{ */ +/* @} */ + +/*! @name PORTB0 (number 20), FCFG_PGMN + @{ */ +#define BOARD_INITPINS_FCFG_PGMN_GPIO GPIOB /*!<@brief GPIO device name: GPIOB */ +#define BOARD_INITPINS_FCFG_PGMN_PORT PORTB /*!<@brief PORT device name: PORTB */ +#define BOARD_INITPINS_FCFG_PGMN_PIN 0U /*!<@brief PORTB pin index: 0 */ + /* @} */ + +/*! @name PORTB1 (number 21), FCFG_DONE + @{ */ +#define BOARD_INITPINS_FCFG_DONE_GPIO GPIOB /*!<@brief GPIO device name: GPIOB */ +#define BOARD_INITPINS_FCFG_DONE_PORT PORTB /*!<@brief PORT device name: PORTB */ +#define BOARD_INITPINS_FCFG_DONE_PIN 1U /*!<@brief PORTB pin index: 1 */ + /* @} */ + +/*! @name PORTC4 (number 25), SPI0_PCS + @{ */ +#define BOARD_INITPINS_SPI_PCS_PORT PORTC /*!<@brief PORT device name: PORTC */ +#define BOARD_INITPINS_SPI_PCS_PIN 4U /*!<@brief PORTC pin index: 4 */ + /* @} */ + +/*! @name PORTD4 (number 29), FPGA_RESETN + @{ */ +#define BOARD_INITPINS_FPGA_RESETN_GPIO GPIOD /*!<@brief GPIO device name: GPIOD */ +#define BOARD_INITPINS_FPGA_RESETN_PORT PORTD /*!<@brief PORT device name: PORTD */ +#define BOARD_INITPINS_FPGA_RESETN_PIN 4U /*!<@brief PORTD pin index: 4 */ + /* @} */ + +/*! @name PORTD5 (number 30), FPGA_INT + @{ */ +#define BOARD_INITPINS_FPGA_INT_GPIO GPIOD /*!<@brief GPIO device name: GPIOD */ +#define BOARD_INITPINS_FPGA_INT_PORT PORTD /*!<@brief PORT device name: PORTD */ +#define BOARD_INITPINS_FPGA_INT_PIN 5U /*!<@brief PORTD pin index: 5 */ + /* @} */ + +/*! @name PORTC5 (number 26), SPI_SCLK + @{ */ +#define BOARD_INITPINS_SPI_SCLK_PORT PORTC /*!<@brief PORT device name: PORTC */ +#define BOARD_INITPINS_SPI_SCLK_PIN 5U /*!<@brief PORTC pin index: 5 */ + /* @} */ + +/*! @name PORTC6 (number 27), SPI_MOSI + @{ */ +#define BOARD_INITPINS_SPI_MOSI_PORT PORTC /*!<@brief PORT device name: PORTC */ +#define BOARD_INITPINS_SPI_MOSI_PIN 6U /*!<@brief PORTC pin index: 6 */ + /* @} */ + +/*! @name PORTC7 (number 28), SPI_MISO + @{ */ +#define BOARD_INITPINS_SPI_MISO_PORT PORTC /*!<@brief PORT device name: PORTC */ +#define BOARD_INITPINS_SPI_MISO_PIN 7U /*!<@brief PORTC pin index: 7 */ + /* @} */ + +/*! @name PORTE19 (number 6), I2C_SCL + @{ */ +#define BOARD_INITPINS_I2C_SCL_PORT PORTE /*!<@brief PORT device name: PORTE */ +#define BOARD_INITPINS_I2C_SCL_PIN 19U /*!<@brief PORTE pin index: 19 */ + /* @} */ + +/*! @name PORTE24 (number 10), PB7 + @{ */ +#define BOARD_INITPINS_PB7_GPIO GPIOE /*!<@brief GPIO device name: GPIOE */ +#define BOARD_INITPINS_PB7_PORT PORTE /*!<@brief PORT device name: PORTE */ +#define BOARD_INITPINS_PB7_PIN 24U /*!<@brief PORTE pin index: 24 */ + /* @} */ + +/*! @name PORTA19 (number 18), PMIC_LDO_E + @{ */ +#define BOARD_INITPINS_PMIC_LDO_E_GPIO GPIOA /*!<@brief GPIO device name: GPIOA */ +#define BOARD_INITPINS_PMIC_LDO_E_PORT PORTA /*!<@brief PORT device name: PORTA */ +#define BOARD_INITPINS_PMIC_LDO_E_PIN 19U /*!<@brief PORTA pin index: 19 */ + /* @} */ + +/*! @name PORTC1 (number 22), FPGA_GPIO + @{ */ +#define BOARD_INITPINS_FPGA_GPIO_GPIO GPIOC /*!<@brief GPIO device name: GPIOC */ +#define BOARD_INITPINS_FPGA_GPIO_PORT PORTC /*!<@brief PORT device name: PORTC */ +#define BOARD_INITPINS_FPGA_GPIO_PIN 1U /*!<@brief PORTC pin index: 1 */ + /* @} */ + +/*! + * @brief Configures pin routing and optionally pin electrical features. + * + */ +void BOARD_InitPins(void); + +#if defined(__cplusplus) +} +#endif + +/*! + * @} + */ +#endif /* _PIN_MUX_H_ */ + +/*********************************************************************************************************************** + * EOF + **********************************************************************************************************************/ diff --git a/drivers/fsl_adc16.c b/drivers/fsl_adc16.c new file mode 100644 index 0000000..dcafbf8 --- /dev/null +++ b/drivers/fsl_adc16.c @@ -0,0 +1,380 @@ +/* + * The Clear BSD License + * Copyright (c) 2015, 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: + * + * o Redistributions of source code must retain the above copyright notice, this list + * of conditions and the following disclaimer. + * + * o 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. + * + * o 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. + */ + +#include "fsl_adc16.h" + +/* Component ID definition, used by tools. */ +#ifndef FSL_COMPONENT_ID +#define FSL_COMPONENT_ID "platform.drivers.adc16" +#endif + + +/******************************************************************************* + * Prototypes + ******************************************************************************/ +/*! + * @brief Get instance number for ADC16 module. + * + * @param base ADC16 peripheral base address + */ +static uint32_t ADC16_GetInstance(ADC_Type *base); + +/******************************************************************************* + * Variables + ******************************************************************************/ +/*! @brief Pointers to ADC16 bases for each instance. */ +static ADC_Type *const s_adc16Bases[] = ADC_BASE_PTRS; + +#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) +/*! @brief Pointers to ADC16 clocks for each instance. */ +static const clock_ip_name_t s_adc16Clocks[] = ADC16_CLOCKS; +#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */ + +/******************************************************************************* + * Code + ******************************************************************************/ +static uint32_t ADC16_GetInstance(ADC_Type *base) +{ + uint32_t instance; + + /* Find the instance index from base address mappings. */ + for (instance = 0; instance < ARRAY_SIZE(s_adc16Bases); instance++) + { + if (s_adc16Bases[instance] == base) + { + break; + } + } + + assert(instance < ARRAY_SIZE(s_adc16Bases)); + + return instance; +} + +void ADC16_Init(ADC_Type *base, const adc16_config_t *config) +{ + assert(NULL != config); + + uint32_t tmp32; + +#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) + /* Enable the clock. */ + CLOCK_EnableClock(s_adc16Clocks[ADC16_GetInstance(base)]); +#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */ + + /* ADCx_CFG1. */ + tmp32 = ADC_CFG1_ADICLK(config->clockSource) | ADC_CFG1_MODE(config->resolution); + if (kADC16_LongSampleDisabled != config->longSampleMode) + { + tmp32 |= ADC_CFG1_ADLSMP_MASK; + } + tmp32 |= ADC_CFG1_ADIV(config->clockDivider); + if (config->enableLowPower) + { + tmp32 |= ADC_CFG1_ADLPC_MASK; + } + base->CFG1 = tmp32; + + /* ADCx_CFG2. */ + tmp32 = base->CFG2 & ~(ADC_CFG2_ADACKEN_MASK | ADC_CFG2_ADHSC_MASK | ADC_CFG2_ADLSTS_MASK); + if (kADC16_LongSampleDisabled != config->longSampleMode) + { + tmp32 |= ADC_CFG2_ADLSTS(config->longSampleMode); + } + if (config->enableHighSpeed) + { + tmp32 |= ADC_CFG2_ADHSC_MASK; + } + if (config->enableAsynchronousClock) + { + tmp32 |= ADC_CFG2_ADACKEN_MASK; + } + base->CFG2 = tmp32; + + /* ADCx_SC2. */ + tmp32 = base->SC2 & ~(ADC_SC2_REFSEL_MASK); + tmp32 |= ADC_SC2_REFSEL(config->referenceVoltageSource); + base->SC2 = tmp32; + + /* ADCx_SC3. */ + if (config->enableContinuousConversion) + { + base->SC3 |= ADC_SC3_ADCO_MASK; + } + else + { + base->SC3 &= ~ADC_SC3_ADCO_MASK; + } +} + +void ADC16_Deinit(ADC_Type *base) +{ +#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) + /* Disable the clock. */ + CLOCK_DisableClock(s_adc16Clocks[ADC16_GetInstance(base)]); +#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */ +} + +void ADC16_GetDefaultConfig(adc16_config_t *config) +{ + assert(NULL != config); + + config->referenceVoltageSource = kADC16_ReferenceVoltageSourceVref; + config->clockSource = kADC16_ClockSourceAsynchronousClock; + config->enableAsynchronousClock = true; + config->clockDivider = kADC16_ClockDivider8; + config->resolution = kADC16_ResolutionSE12Bit; + config->longSampleMode = kADC16_LongSampleDisabled; + config->enableHighSpeed = false; + config->enableLowPower = false; + config->enableContinuousConversion = false; +} + +#if defined(FSL_FEATURE_ADC16_HAS_CALIBRATION) && FSL_FEATURE_ADC16_HAS_CALIBRATION +status_t ADC16_DoAutoCalibration(ADC_Type *base) +{ + bool bHWTrigger = false; + volatile uint32_t tmp32; /* 'volatile' here is for the dummy read of ADCx_R[0] register. */ + status_t status = kStatus_Success; + + /* The calibration would be failed when in hardwar mode. + * Remember the hardware trigger state here and restore it later if the hardware trigger is enabled.*/ + if (0U != (ADC_SC2_ADTRG_MASK & base->SC2)) + { + bHWTrigger = true; + base->SC2 &= ~ADC_SC2_ADTRG_MASK; + } + + /* Clear the CALF and launch the calibration. */ + base->SC3 |= ADC_SC3_CAL_MASK | ADC_SC3_CALF_MASK; + while (0U == (kADC16_ChannelConversionDoneFlag & ADC16_GetChannelStatusFlags(base, 0U))) + { + /* Check the CALF when the calibration is active. */ + if (0U != (kADC16_CalibrationFailedFlag & ADC16_GetStatusFlags(base))) + { + status = kStatus_Fail; + break; + } + } + tmp32 = base->R[0]; /* Dummy read to clear COCO caused by calibration. */ + + /* Restore the hardware trigger setting if it was enabled before. */ + if (bHWTrigger) + { + base->SC2 |= ADC_SC2_ADTRG_MASK; + } + /* Check the CALF at the end of calibration. */ + if (0U != (kADC16_CalibrationFailedFlag & ADC16_GetStatusFlags(base))) + { + status = kStatus_Fail; + } + if (kStatus_Success != status) /* Check if the calibration process is succeed. */ + { + return status; + } + + /* Calculate the calibration values. */ + tmp32 = base->CLP0 + base->CLP1 + base->CLP2 + base->CLP3 + base->CLP4 + base->CLPS; + tmp32 = 0x8000U | (tmp32 >> 1U); + base->PG = tmp32; + +#if defined(FSL_FEATURE_ADC16_HAS_DIFF_MODE) && FSL_FEATURE_ADC16_HAS_DIFF_MODE + tmp32 = base->CLM0 + base->CLM1 + base->CLM2 + base->CLM3 + base->CLM4 + base->CLMS; + tmp32 = 0x8000U | (tmp32 >> 1U); + base->MG = tmp32; +#endif /* FSL_FEATURE_ADC16_HAS_DIFF_MODE */ + + return kStatus_Success; +} +#endif /* FSL_FEATURE_ADC16_HAS_CALIBRATION */ + +#if defined(FSL_FEATURE_ADC16_HAS_MUX_SELECT) && FSL_FEATURE_ADC16_HAS_MUX_SELECT +void ADC16_SetChannelMuxMode(ADC_Type *base, adc16_channel_mux_mode_t mode) +{ + if (kADC16_ChannelMuxA == mode) + { + base->CFG2 &= ~ADC_CFG2_MUXSEL_MASK; + } + else /* kADC16_ChannelMuxB. */ + { + base->CFG2 |= ADC_CFG2_MUXSEL_MASK; + } +} +#endif /* FSL_FEATURE_ADC16_HAS_MUX_SELECT */ + +void ADC16_SetHardwareCompareConfig(ADC_Type *base, const adc16_hardware_compare_config_t *config) +{ + uint32_t tmp32 = base->SC2 & ~(ADC_SC2_ACFE_MASK | ADC_SC2_ACFGT_MASK | ADC_SC2_ACREN_MASK); + + if (!config) /* Pass "NULL" to disable the feature. */ + { + base->SC2 = tmp32; + return; + } + /* Enable the feature. */ + tmp32 |= ADC_SC2_ACFE_MASK; + + /* Select the hardware compare working mode. */ + switch (config->hardwareCompareMode) + { + case kADC16_HardwareCompareMode0: + break; + case kADC16_HardwareCompareMode1: + tmp32 |= ADC_SC2_ACFGT_MASK; + break; + case kADC16_HardwareCompareMode2: + tmp32 |= ADC_SC2_ACREN_MASK; + break; + case kADC16_HardwareCompareMode3: + tmp32 |= ADC_SC2_ACFGT_MASK | ADC_SC2_ACREN_MASK; + break; + default: + break; + } + base->SC2 = tmp32; + + /* Load the compare values. */ + base->CV1 = ADC_CV1_CV(config->value1); + base->CV2 = ADC_CV2_CV(config->value2); +} + +#if defined(FSL_FEATURE_ADC16_HAS_HW_AVERAGE) && FSL_FEATURE_ADC16_HAS_HW_AVERAGE +void ADC16_SetHardwareAverage(ADC_Type *base, adc16_hardware_average_mode_t mode) +{ + uint32_t tmp32 = base->SC3 & ~(ADC_SC3_AVGE_MASK | ADC_SC3_AVGS_MASK); + + if (kADC16_HardwareAverageDisabled != mode) + { + tmp32 |= ADC_SC3_AVGE_MASK | ADC_SC3_AVGS(mode); + } + base->SC3 = tmp32; +} +#endif /* FSL_FEATURE_ADC16_HAS_HW_AVERAGE */ + +#if defined(FSL_FEATURE_ADC16_HAS_PGA) && FSL_FEATURE_ADC16_HAS_PGA +void ADC16_SetPGAConfig(ADC_Type *base, const adc16_pga_config_t *config) +{ + uint32_t tmp32; + + if (!config) /* Passing "NULL" is to disable the feature. */ + { + base->PGA = 0U; + return; + } + + /* Enable the PGA and set the gain value. */ + tmp32 = ADC_PGA_PGAEN_MASK | ADC_PGA_PGAG(config->pgaGain); + + /* Configure the misc features for PGA. */ + if (config->enableRunInNormalMode) + { + tmp32 |= ADC_PGA_PGALPb_MASK; + } +#if defined(FSL_FEATURE_ADC16_HAS_PGA_CHOPPING) && FSL_FEATURE_ADC16_HAS_PGA_CHOPPING + if (config->disablePgaChopping) + { + tmp32 |= ADC_PGA_PGACHPb_MASK; + } +#endif /* FSL_FEATURE_ADC16_HAS_PGA_CHOPPING */ +#if defined(FSL_FEATURE_ADC16_HAS_PGA_OFFSET_MEASUREMENT) && FSL_FEATURE_ADC16_HAS_PGA_OFFSET_MEASUREMENT + if (config->enableRunInOffsetMeasurement) + { + tmp32 |= ADC_PGA_PGAOFSM_MASK; + } +#endif /* FSL_FEATURE_ADC16_HAS_PGA_OFFSET_MEASUREMENT */ + base->PGA = tmp32; +} +#endif /* FSL_FEATURE_ADC16_HAS_PGA */ + +uint32_t ADC16_GetStatusFlags(ADC_Type *base) +{ + uint32_t ret = 0; + + if (0U != (base->SC2 & ADC_SC2_ADACT_MASK)) + { + ret |= kADC16_ActiveFlag; + } +#if defined(FSL_FEATURE_ADC16_HAS_CALIBRATION) && FSL_FEATURE_ADC16_HAS_CALIBRATION + if (0U != (base->SC3 & ADC_SC3_CALF_MASK)) + { + ret |= kADC16_CalibrationFailedFlag; + } +#endif /* FSL_FEATURE_ADC16_HAS_CALIBRATION */ + return ret; +} + +void ADC16_ClearStatusFlags(ADC_Type *base, uint32_t mask) +{ +#if defined(FSL_FEATURE_ADC16_HAS_CALIBRATION) && FSL_FEATURE_ADC16_HAS_CALIBRATION + if (0U != (mask & kADC16_CalibrationFailedFlag)) + { + base->SC3 |= ADC_SC3_CALF_MASK; + } +#endif /* FSL_FEATURE_ADC16_HAS_CALIBRATION */ +} + +void ADC16_SetChannelConfig(ADC_Type *base, uint32_t channelGroup, const adc16_channel_config_t *config) +{ + assert(channelGroup < ADC_SC1_COUNT); + assert(NULL != config); + + uint32_t sc1 = ADC_SC1_ADCH(config->channelNumber); /* Set the channel number. */ + +#if defined(FSL_FEATURE_ADC16_HAS_DIFF_MODE) && FSL_FEATURE_ADC16_HAS_DIFF_MODE + /* Enable the differential conversion. */ + if (config->enableDifferentialConversion) + { + sc1 |= ADC_SC1_DIFF_MASK; + } +#endif /* FSL_FEATURE_ADC16_HAS_DIFF_MODE */ + /* Enable the interrupt when the conversion is done. */ + if (config->enableInterruptOnConversionCompleted) + { + sc1 |= ADC_SC1_AIEN_MASK; + } + base->SC1[channelGroup] = sc1; +} + +uint32_t ADC16_GetChannelStatusFlags(ADC_Type *base, uint32_t channelGroup) +{ + assert(channelGroup < ADC_SC1_COUNT); + + uint32_t ret = 0U; + + if (0U != (base->SC1[channelGroup] & ADC_SC1_COCO_MASK)) + { + ret |= kADC16_ChannelConversionDoneFlag; + } + return ret; +} diff --git a/drivers/fsl_adc16.h b/drivers/fsl_adc16.h new file mode 100644 index 0000000..da0604f --- /dev/null +++ b/drivers/fsl_adc16.h @@ -0,0 +1,529 @@ +/* + * The Clear BSD License + * Copyright (c) 2015, 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: + * + * o Redistributions of source code must retain the above copyright notice, this list + * of conditions and the following disclaimer. + * + * o 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. + * + * o 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_ADC16_H_ +#define _FSL_ADC16_H_ + +#include "fsl_common.h" + +/*! + * @addtogroup adc16 + * @{ + */ + + +/******************************************************************************* + * Definitions + ******************************************************************************/ + +/*! @name Driver version */ +/*@{*/ +/*! @brief ADC16 driver version 2.0.0. */ +#define FSL_ADC16_DRIVER_VERSION (MAKE_VERSION(2, 0, 0)) +/*@}*/ + +/*! + * @brief Channel status flags. + */ +enum _adc16_channel_status_flags +{ + kADC16_ChannelConversionDoneFlag = ADC_SC1_COCO_MASK, /*!< Conversion done. */ +}; + +/*! + * @brief Converter status flags. + */ +enum _adc16_status_flags +{ + kADC16_ActiveFlag = ADC_SC2_ADACT_MASK, /*!< Converter is active. */ +#if defined(FSL_FEATURE_ADC16_HAS_CALIBRATION) && FSL_FEATURE_ADC16_HAS_CALIBRATION + kADC16_CalibrationFailedFlag = ADC_SC3_CALF_MASK, /*!< Calibration is failed. */ +#endif /* FSL_FEATURE_ADC16_HAS_CALIBRATION */ +}; + +#if defined(FSL_FEATURE_ADC16_HAS_MUX_SELECT) && FSL_FEATURE_ADC16_HAS_MUX_SELECT +/*! + * @brief Channel multiplexer mode for each channel. + * + * For some ADC16 channels, there are two pin selections in channel multiplexer. For example, ADC0_SE4a and ADC0_SE4b + * are the different channels that share the same channel number. + */ +typedef enum _adc_channel_mux_mode +{ + kADC16_ChannelMuxA = 0U, /*!< For channel with channel mux a. */ + kADC16_ChannelMuxB = 1U, /*!< For channel with channel mux b. */ +} adc16_channel_mux_mode_t; +#endif /* FSL_FEATURE_ADC16_HAS_MUX_SELECT */ + +/*! + * @brief Clock divider for the converter. + */ +typedef enum _adc16_clock_divider +{ + kADC16_ClockDivider1 = 0U, /*!< For divider 1 from the input clock to the module. */ + kADC16_ClockDivider2 = 1U, /*!< For divider 2 from the input clock to the module. */ + kADC16_ClockDivider4 = 2U, /*!< For divider 4 from the input clock to the module. */ + kADC16_ClockDivider8 = 3U, /*!< For divider 8 from the input clock to the module. */ +} adc16_clock_divider_t; + +/*! + *@brief Converter's resolution. + */ +typedef enum _adc16_resolution +{ + /* This group of enumeration is for internal use which is related to register setting. */ + kADC16_Resolution8or9Bit = 0U, /*!< Single End 8-bit or Differential Sample 9-bit. */ + kADC16_Resolution12or13Bit = 1U, /*!< Single End 12-bit or Differential Sample 13-bit. */ + kADC16_Resolution10or11Bit = 2U, /*!< Single End 10-bit or Differential Sample 11-bit. */ + + /* This group of enumeration is for a public user. */ + kADC16_ResolutionSE8Bit = kADC16_Resolution8or9Bit, /*!< Single End 8-bit. */ + kADC16_ResolutionSE12Bit = kADC16_Resolution12or13Bit, /*!< Single End 12-bit. */ + kADC16_ResolutionSE10Bit = kADC16_Resolution10or11Bit, /*!< Single End 10-bit. */ +#if defined(FSL_FEATURE_ADC16_HAS_DIFF_MODE) && FSL_FEATURE_ADC16_HAS_DIFF_MODE + kADC16_ResolutionDF9Bit = kADC16_Resolution8or9Bit, /*!< Differential Sample 9-bit. */ + kADC16_ResolutionDF13Bit = kADC16_Resolution12or13Bit, /*!< Differential Sample 13-bit. */ + kADC16_ResolutionDF11Bit = kADC16_Resolution10or11Bit, /*!< Differential Sample 11-bit. */ +#endif /* FSL_FEATURE_ADC16_HAS_DIFF_MODE */ + +#if defined(FSL_FEATURE_ADC16_MAX_RESOLUTION) && (FSL_FEATURE_ADC16_MAX_RESOLUTION >= 16U) + /* 16-bit is supported by default. */ + kADC16_Resolution16Bit = 3U, /*!< Single End 16-bit or Differential Sample 16-bit. */ + kADC16_ResolutionSE16Bit = kADC16_Resolution16Bit, /*!< Single End 16-bit. */ +#if defined(FSL_FEATURE_ADC16_HAS_DIFF_MODE) && FSL_FEATURE_ADC16_HAS_DIFF_MODE + kADC16_ResolutionDF16Bit = kADC16_Resolution16Bit, /*!< Differential Sample 16-bit. */ +#endif /* FSL_FEATURE_ADC16_HAS_DIFF_MODE */ +#endif /* FSL_FEATURE_ADC16_MAX_RESOLUTION >= 16U */ +} adc16_resolution_t; + +/*! + * @brief Clock source. + */ +typedef enum _adc16_clock_source +{ + kADC16_ClockSourceAlt0 = 0U, /*!< Selection 0 of the clock source. */ + kADC16_ClockSourceAlt1 = 1U, /*!< Selection 1 of the clock source. */ + kADC16_ClockSourceAlt2 = 2U, /*!< Selection 2 of the clock source. */ + kADC16_ClockSourceAlt3 = 3U, /*!< Selection 3 of the clock source. */ + + /* Chip defined clock source */ + kADC16_ClockSourceAsynchronousClock = kADC16_ClockSourceAlt3, /*!< Using internal asynchronous clock. */ +} adc16_clock_source_t; + +/*! + * @brief Long sample mode. + */ +typedef enum _adc16_long_sample_mode +{ + kADC16_LongSampleCycle24 = 0U, /*!< 20 extra ADCK cycles, 24 ADCK cycles total. */ + kADC16_LongSampleCycle16 = 1U, /*!< 12 extra ADCK cycles, 16 ADCK cycles total. */ + kADC16_LongSampleCycle10 = 2U, /*!< 6 extra ADCK cycles, 10 ADCK cycles total. */ + kADC16_LongSampleCycle6 = 3U, /*!< 2 extra ADCK cycles, 6 ADCK cycles total. */ + kADC16_LongSampleDisabled = 4U, /*!< Disable the long sample feature. */ +} adc16_long_sample_mode_t; + +/*! + * @brief Reference voltage source. + */ +typedef enum _adc16_reference_voltage_source +{ + kADC16_ReferenceVoltageSourceVref = 0U, /*!< For external pins pair of VrefH and VrefL. */ + kADC16_ReferenceVoltageSourceValt = 1U, /*!< For alternate reference pair of ValtH and ValtL. */ +} adc16_reference_voltage_source_t; + +#if defined(FSL_FEATURE_ADC16_HAS_HW_AVERAGE) && FSL_FEATURE_ADC16_HAS_HW_AVERAGE +/*! + * @brief Hardware average mode. + */ +typedef enum _adc16_hardware_average_mode +{ + kADC16_HardwareAverageCount4 = 0U, /*!< For hardware average with 4 samples. */ + kADC16_HardwareAverageCount8 = 1U, /*!< For hardware average with 8 samples. */ + kADC16_HardwareAverageCount16 = 2U, /*!< For hardware average with 16 samples. */ + kADC16_HardwareAverageCount32 = 3U, /*!< For hardware average with 32 samples. */ + kADC16_HardwareAverageDisabled = 4U, /*!< Disable the hardware average feature.*/ +} adc16_hardware_average_mode_t; +#endif /* FSL_FEATURE_ADC16_HAS_HW_AVERAGE */ + +/*! + * @brief Hardware compare mode. + */ +typedef enum _adc16_hardware_compare_mode +{ + kADC16_HardwareCompareMode0 = 0U, /*!< x < value1. */ + kADC16_HardwareCompareMode1 = 1U, /*!< x > value1. */ + kADC16_HardwareCompareMode2 = 2U, /*!< if value1 <= value2, then x < value1 || x > value2; + else, value1 > x > value2. */ + kADC16_HardwareCompareMode3 = 3U, /*!< if value1 <= value2, then value1 <= x <= value2; + else x >= value1 || x <= value2. */ +} adc16_hardware_compare_mode_t; + +#if defined(FSL_FEATURE_ADC16_HAS_PGA) && FSL_FEATURE_ADC16_HAS_PGA +/*! + * @brief PGA's Gain mode. + */ +typedef enum _adc16_pga_gain +{ + kADC16_PGAGainValueOf1 = 0U, /*!< For amplifier gain of 1. */ + kADC16_PGAGainValueOf2 = 1U, /*!< For amplifier gain of 2. */ + kADC16_PGAGainValueOf4 = 2U, /*!< For amplifier gain of 4. */ + kADC16_PGAGainValueOf8 = 3U, /*!< For amplifier gain of 8. */ + kADC16_PGAGainValueOf16 = 4U, /*!< For amplifier gain of 16. */ + kADC16_PGAGainValueOf32 = 5U, /*!< For amplifier gain of 32. */ + kADC16_PGAGainValueOf64 = 6U, /*!< For amplifier gain of 64. */ +} adc16_pga_gain_t; +#endif /* FSL_FEATURE_ADC16_HAS_PGA */ + +/*! + * @brief ADC16 converter configuration. + */ +typedef struct _adc16_config +{ + adc16_reference_voltage_source_t referenceVoltageSource; /*!< Select the reference voltage source. */ + adc16_clock_source_t clockSource; /*!< Select the input clock source to converter. */ + bool enableAsynchronousClock; /*!< Enable the asynchronous clock output. */ + adc16_clock_divider_t clockDivider; /*!< Select the divider of input clock source. */ + adc16_resolution_t resolution; /*!< Select the sample resolution mode. */ + adc16_long_sample_mode_t longSampleMode; /*!< Select the long sample mode. */ + bool enableHighSpeed; /*!< Enable the high-speed mode. */ + bool enableLowPower; /*!< Enable low power. */ + bool enableContinuousConversion; /*!< Enable continuous conversion mode. */ +} adc16_config_t; + +/*! + * @brief ADC16 Hardware comparison configuration. + */ +typedef struct _adc16_hardware_compare_config +{ + adc16_hardware_compare_mode_t hardwareCompareMode; /*!< Select the hardware compare mode. + See "adc16_hardware_compare_mode_t". */ + int16_t value1; /*!< Setting value1 for hardware compare mode. */ + int16_t value2; /*!< Setting value2 for hardware compare mode. */ +} adc16_hardware_compare_config_t; + +/*! + * @brief ADC16 channel conversion configuration. + */ +typedef struct _adc16_channel_config +{ + uint32_t channelNumber; /*!< Setting the conversion channel number. The available range is 0-31. + See channel connection information for each chip in Reference + Manual document. */ + bool enableInterruptOnConversionCompleted; /*!< Generate an interrupt request once the conversion is completed. */ +#if defined(FSL_FEATURE_ADC16_HAS_DIFF_MODE) && FSL_FEATURE_ADC16_HAS_DIFF_MODE + bool enableDifferentialConversion; /*!< Using Differential sample mode. */ +#endif /* FSL_FEATURE_ADC16_HAS_DIFF_MODE */ +} adc16_channel_config_t; + +#if defined(FSL_FEATURE_ADC16_HAS_PGA) && FSL_FEATURE_ADC16_HAS_PGA +/*! + * @brief ADC16 programmable gain amplifier configuration. + */ +typedef struct _adc16_pga_config +{ + adc16_pga_gain_t pgaGain; /*!< Setting PGA gain. */ + bool enableRunInNormalMode; /*!< Enable PGA working in normal mode, or low power mode by default. */ +#if defined(FSL_FEATURE_ADC16_HAS_PGA_CHOPPING) && FSL_FEATURE_ADC16_HAS_PGA_CHOPPING + bool disablePgaChopping; /*!< Disable the PGA chopping function. + The PGA employs chopping to remove/reduce offset and 1/f noise and offers + an offset measurement configuration that aids the offset calibration. */ +#endif /* FSL_FEATURE_ADC16_HAS_PGA_CHOPPING */ +#if defined(FSL_FEATURE_ADC16_HAS_PGA_OFFSET_MEASUREMENT) && FSL_FEATURE_ADC16_HAS_PGA_OFFSET_MEASUREMENT + bool enableRunInOffsetMeasurement; /*!< Enable the PGA working in offset measurement mode. + When this feature is enabled, the PGA disconnects itself from the external + inputs and auto-configures into offset measurement mode. With this field + set, run the ADC in the recommended settings and enable the maximum hardware + averaging to get the PGA offset number. The output is the + (PGA offset * (64+1)) for the given PGA setting. */ +#endif /* FSL_FEATURE_ADC16_HAS_PGA_OFFSET_MEASUREMENT */ +} adc16_pga_config_t; +#endif /* FSL_FEATURE_ADC16_HAS_PGA */ + +#if defined(__cplusplus) +extern "C" { +#endif + +/******************************************************************************* + * API + ******************************************************************************/ + +/*! + * @name Initialization + * @{ + */ + +/*! + * @brief Initializes the ADC16 module. + * + * @param base ADC16 peripheral base address. + * @param config Pointer to configuration structure. See "adc16_config_t". + */ +void ADC16_Init(ADC_Type *base, const adc16_config_t *config); + +/*! + * @brief De-initializes the ADC16 module. + * + * @param base ADC16 peripheral base address. + */ +void ADC16_Deinit(ADC_Type *base); + +/*! + * @brief Gets an available pre-defined settings for the converter's configuration. + * + * This function initializes the converter configuration structure with available settings. The default values are as follows. + * @code + * config->referenceVoltageSource = kADC16_ReferenceVoltageSourceVref; + * config->clockSource = kADC16_ClockSourceAsynchronousClock; + * config->enableAsynchronousClock = true; + * config->clockDivider = kADC16_ClockDivider8; + * config->resolution = kADC16_ResolutionSE12Bit; + * config->longSampleMode = kADC16_LongSampleDisabled; + * config->enableHighSpeed = false; + * config->enableLowPower = false; + * config->enableContinuousConversion = false; + * @endcode + * @param config Pointer to the configuration structure. + */ +void ADC16_GetDefaultConfig(adc16_config_t *config); + +#if defined(FSL_FEATURE_ADC16_HAS_CALIBRATION) && FSL_FEATURE_ADC16_HAS_CALIBRATION +/*! + * @brief Automates the hardware calibration. + * + * This auto calibration helps to adjust the plus/minus side gain automatically. + * Execute the calibration before using the converter. Note that the hardware trigger should be used + * during the calibration. + * + * @param base ADC16 peripheral base address. + * + * @return Execution status. + * @retval kStatus_Success Calibration is done successfully. + * @retval kStatus_Fail Calibration has failed. + */ +status_t ADC16_DoAutoCalibration(ADC_Type *base); +#endif /* FSL_FEATURE_ADC16_HAS_CALIBRATION */ + +#if defined(FSL_FEATURE_ADC16_HAS_OFFSET_CORRECTION) && FSL_FEATURE_ADC16_HAS_OFFSET_CORRECTION +/*! + * @brief Sets the offset value for the conversion result. + * + * This offset value takes effect on the conversion result. If the offset value is not zero, the reading result + * is subtracted by it. Note, the hardware calibration fills the offset value automatically. + * + * @param base ADC16 peripheral base address. + * @param value Setting offset value. + */ +static inline void ADC16_SetOffsetValue(ADC_Type *base, int16_t value) +{ + base->OFS = (uint32_t)(value); +} +#endif /* FSL_FEATURE_ADC16_HAS_OFFSET_CORRECTION */ + +/* @} */ + +/*! + * @name Advanced Features + * @{ + */ + +#if defined(FSL_FEATURE_ADC16_HAS_DMA) && FSL_FEATURE_ADC16_HAS_DMA +/*! + * @brief Enables generating the DMA trigger when the conversion is complete. + * + * @param base ADC16 peripheral base address. + * @param enable Switcher of the DMA feature. "true" means enabled, "false" means not enabled. + */ +static inline void ADC16_EnableDMA(ADC_Type *base, bool enable) +{ + if (enable) + { + base->SC2 |= ADC_SC2_DMAEN_MASK; + } + else + { + base->SC2 &= ~ADC_SC2_DMAEN_MASK; + } +} +#endif /* FSL_FEATURE_ADC16_HAS_DMA */ + +/*! + * @brief Enables the hardware trigger mode. + * + * @param base ADC16 peripheral base address. + * @param enable Switcher of the hardware trigger feature. "true" means enabled, "false" means not enabled. + */ +static inline void ADC16_EnableHardwareTrigger(ADC_Type *base, bool enable) +{ + if (enable) + { + base->SC2 |= ADC_SC2_ADTRG_MASK; + } + else + { + base->SC2 &= ~ADC_SC2_ADTRG_MASK; + } +} + +#if defined(FSL_FEATURE_ADC16_HAS_MUX_SELECT) && FSL_FEATURE_ADC16_HAS_MUX_SELECT +/*! + * @brief Sets the channel mux mode. + * + * Some sample pins share the same channel index. The channel mux mode decides which pin is used for an + * indicated channel. + * + * @param base ADC16 peripheral base address. + * @param mode Setting channel mux mode. See "adc16_channel_mux_mode_t". + */ +void ADC16_SetChannelMuxMode(ADC_Type *base, adc16_channel_mux_mode_t mode); +#endif /* FSL_FEATURE_ADC16_HAS_MUX_SELECT */ + +/*! + * @brief Configures the hardware compare mode. + * + * The hardware compare mode provides a way to process the conversion result automatically by using hardware. Only the result + * in the compare range is available. To compare the range, see "adc16_hardware_compare_mode_t" or the appopriate reference + * manual for more information. + * + * @param base ADC16 peripheral base address. + * @param config Pointer to the "adc16_hardware_compare_config_t" structure. Passing "NULL" disables the feature. + */ +void ADC16_SetHardwareCompareConfig(ADC_Type *base, const adc16_hardware_compare_config_t *config); + +#if defined(FSL_FEATURE_ADC16_HAS_HW_AVERAGE) && FSL_FEATURE_ADC16_HAS_HW_AVERAGE +/*! + * @brief Sets the hardware average mode. + * + * The hardware average mode provides a way to process the conversion result automatically by using hardware. The multiple + * conversion results are accumulated and averaged internally making them easier to read. + * + * @param base ADC16 peripheral base address. + * @param mode Setting the hardware average mode. See "adc16_hardware_average_mode_t". + */ +void ADC16_SetHardwareAverage(ADC_Type *base, adc16_hardware_average_mode_t mode); +#endif /* FSL_FEATURE_ADC16_HAS_HW_AVERAGE */ + +#if defined(FSL_FEATURE_ADC16_HAS_PGA) && FSL_FEATURE_ADC16_HAS_PGA +/*! + * @brief Configures the PGA for the converter's front end. + * + * @param base ADC16 peripheral base address. + * @param config Pointer to the "adc16_pga_config_t" structure. Passing "NULL" disables the feature. + */ +void ADC16_SetPGAConfig(ADC_Type *base, const adc16_pga_config_t *config); +#endif /* FSL_FEATURE_ADC16_HAS_PGA */ + +/*! + * @brief Gets the status flags of the converter. + * + * @param base ADC16 peripheral base address. + * + * @return Flags' mask if indicated flags are asserted. See "_adc16_status_flags". + */ +uint32_t ADC16_GetStatusFlags(ADC_Type *base); + +/*! + * @brief Clears the status flags of the converter. + * + * @param base ADC16 peripheral base address. + * @param mask Mask value for the cleared flags. See "_adc16_status_flags". + */ +void ADC16_ClearStatusFlags(ADC_Type *base, uint32_t mask); + +/* @} */ + +/*! + * @name Conversion Channel + * @{ + */ + +/*! + * @brief Configures the conversion channel. + * + * This operation triggers the conversion when in software trigger mode. When in hardware trigger mode, this API + * configures the channel while the external trigger source helps to trigger the conversion. + * + * Note that the "Channel Group" has a detailed description. + * To allow sequential conversions of the ADC to be triggered by internal peripherals, the ADC has more than one + * group of status and control registers, one for each conversion. The channel group parameter indicates which group of + * registers are used, for example, channel group 0 is for Group A registers and channel group 1 is for Group B registers. The + * channel groups are used in a "ping-pong" approach to control the ADC operation. At any point, only one of + * the channel groups is actively controlling ADC conversions. The channel group 0 is used for both software and hardware + * trigger modes. Channel group 1 and greater indicates multiple channel group registers for + * use only in hardware trigger mode. See the chip configuration information in the appropriate MCU reference manual for the + * number of SC1n registers (channel groups) specific to this device. Channel group 1 or greater are not used + * for software trigger operation. Therefore, writing to these channel groups does not initiate a new conversion. + * Updating the channel group 0 while a different channel group is actively controlling a conversion is allowed and + * vice versa. Writing any of the channel group registers while that specific channel group is actively controlling a + * conversion aborts the current conversion. + * + * @param base ADC16 peripheral base address. + * @param channelGroup Channel group index. + * @param config Pointer to the "adc16_channel_config_t" structure for the conversion channel. + */ +void ADC16_SetChannelConfig(ADC_Type *base, uint32_t channelGroup, const adc16_channel_config_t *config); + +/*! + * @brief Gets the conversion value. + * + * @param base ADC16 peripheral base address. + * @param channelGroup Channel group index. + * + * @return Conversion value. + */ +static inline uint32_t ADC16_GetChannelConversionValue(ADC_Type *base, uint32_t channelGroup) +{ + assert(channelGroup < ADC_R_COUNT); + + return base->R[channelGroup]; +} + +/*! + * @brief Gets the status flags of channel. + * + * @param base ADC16 peripheral base address. + * @param channelGroup Channel group index. + * + * @return Flags' mask if indicated flags are asserted. See "_adc16_channel_status_flags". + */ +uint32_t ADC16_GetChannelStatusFlags(ADC_Type *base, uint32_t channelGroup); + +/* @} */ + +#if defined(__cplusplus) +} +#endif +/*! + * @} + */ +#endif /* _FSL_ADC16_H_ */ diff --git a/drivers/fsl_clock.c b/drivers/fsl_clock.c new file mode 100644 index 0000000..c00f8dd --- /dev/null +++ b/drivers/fsl_clock.c @@ -0,0 +1,1397 @@ +/* + * The Clear BSD License + * Copyright (c) 2015, Freescale Semiconductor, Inc. + * Copyright (c) 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: + * + * o Redistributions of source code must retain the above copyright notice, this list + * of conditions and the following disclaimer. + * + * o 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. + * + * o Neither the name of 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. + */ + +#include "fsl_clock.h" + +/******************************************************************************* + * Definitions + ******************************************************************************/ +/* Component ID definition, used by tools. */ +#ifndef FSL_COMPONENT_ID +#define FSL_COMPONENT_ID "platform.drivers.clock" +#endif + +/* Macro definition remap workaround. */ +#if (defined(MCG_C2_EREFS_MASK) && !(defined(MCG_C2_EREFS0_MASK))) +#define MCG_C2_EREFS0_MASK MCG_C2_EREFS_MASK +#endif +#if (defined(MCG_C2_HGO_MASK) && !(defined(MCG_C2_HGO0_MASK))) +#define MCG_C2_HGO0_MASK MCG_C2_HGO_MASK +#endif +#if (defined(MCG_C2_RANGE_MASK) && !(defined(MCG_C2_RANGE0_MASK))) +#define MCG_C2_RANGE0_MASK MCG_C2_RANGE_MASK +#endif +#if (defined(MCG_C6_CME_MASK) && !(defined(MCG_C6_CME0_MASK))) +#define MCG_C6_CME0_MASK MCG_C6_CME_MASK +#endif + +/* PLL fixed multiplier when there is not PRDIV and VDIV. */ +#define PLL_FIXED_MULT (375U) +/* Max frequency of the reference clock used for internal clock trim. */ +#define TRIM_REF_CLK_MIN (8000000U) +/* Min frequency of the reference clock used for internal clock trim. */ +#define TRIM_REF_CLK_MAX (16000000U) +/* Max trim value of fast internal reference clock. */ +#define TRIM_FIRC_MAX (5000000U) +/* Min trim value of fast internal reference clock. */ +#define TRIM_FIRC_MIN (3000000U) +/* Max trim value of fast internal reference clock. */ +#define TRIM_SIRC_MAX (39063U) +/* Min trim value of fast internal reference clock. */ +#define TRIM_SIRC_MIN (31250U) + +#define MCG_S_IRCST_VAL ((MCG->S & MCG_S_IRCST_MASK) >> MCG_S_IRCST_SHIFT) +#define MCG_S_CLKST_VAL ((MCG->S & MCG_S_CLKST_MASK) >> MCG_S_CLKST_SHIFT) +#define MCG_S_IREFST_VAL ((MCG->S & MCG_S_IREFST_MASK) >> MCG_S_IREFST_SHIFT) +#define MCG_S_PLLST_VAL ((MCG->S & MCG_S_PLLST_MASK) >> MCG_S_PLLST_SHIFT) +#define MCG_C1_FRDIV_VAL ((MCG->C1 & MCG_C1_FRDIV_MASK) >> MCG_C1_FRDIV_SHIFT) +#define MCG_C2_LP_VAL ((MCG->C2 & MCG_C2_LP_MASK) >> MCG_C2_LP_SHIFT) +#define MCG_C2_RANGE_VAL ((MCG->C2 & MCG_C2_RANGE_MASK) >> MCG_C2_RANGE_SHIFT) +#define MCG_SC_FCRDIV_VAL ((MCG->SC & MCG_SC_FCRDIV_MASK) >> MCG_SC_FCRDIV_SHIFT) +#define MCG_S2_PLLCST_VAL ((MCG->S2 & MCG_S2_PLLCST_MASK) >> MCG_S2_PLLCST_SHIFT) +#define MCG_C7_OSCSEL_VAL ((MCG->C7 & MCG_C7_OSCSEL_MASK) >> MCG_C7_OSCSEL_SHIFT) +#define MCG_C4_DMX32_VAL ((MCG->C4 & MCG_C4_DMX32_MASK) >> MCG_C4_DMX32_SHIFT) +#define MCG_C4_DRST_DRS_VAL ((MCG->C4 & MCG_C4_DRST_DRS_MASK) >> MCG_C4_DRST_DRS_SHIFT) +#define MCG_C7_PLL32KREFSEL_VAL ((MCG->C7 & MCG_C7_PLL32KREFSEL_MASK) >> MCG_C7_PLL32KREFSEL_SHIFT) +#define MCG_C5_PLLREFSEL0_VAL ((MCG->C5 & MCG_C5_PLLREFSEL0_MASK) >> MCG_C5_PLLREFSEL0_SHIFT) +#define MCG_C11_PLLREFSEL1_VAL ((MCG->C11 & MCG_C11_PLLREFSEL1_MASK) >> MCG_C11_PLLREFSEL1_SHIFT) +#define MCG_C11_PRDIV1_VAL ((MCG->C11 & MCG_C11_PRDIV1_MASK) >> MCG_C11_PRDIV1_SHIFT) +#define MCG_C12_VDIV1_VAL ((MCG->C12 & MCG_C12_VDIV1_MASK) >> MCG_C12_VDIV1_SHIFT) +#define MCG_C5_PRDIV0_VAL ((MCG->C5 & MCG_C5_PRDIV0_MASK) >> MCG_C5_PRDIV0_SHIFT) +#define MCG_C6_VDIV0_VAL ((MCG->C6 & MCG_C6_VDIV0_MASK) >> MCG_C6_VDIV0_SHIFT) + +#define OSC_MODE_MASK (MCG_C2_EREFS0_MASK | MCG_C2_HGO0_MASK | MCG_C2_RANGE0_MASK) + +#define SIM_CLKDIV1_OUTDIV1_VAL ((SIM->CLKDIV1 & SIM_CLKDIV1_OUTDIV1_MASK) >> SIM_CLKDIV1_OUTDIV1_SHIFT) +#define SIM_CLKDIV1_OUTDIV2_VAL ((SIM->CLKDIV1 & SIM_CLKDIV1_OUTDIV2_MASK) >> SIM_CLKDIV1_OUTDIV2_SHIFT) +#define SIM_CLKDIV1_OUTDIV4_VAL ((SIM->CLKDIV1 & SIM_CLKDIV1_OUTDIV4_MASK) >> SIM_CLKDIV1_OUTDIV4_SHIFT) +#define SIM_SOPT1_OSC32KSEL_VAL ((SIM->SOPT1 & SIM_SOPT1_OSC32KSEL_MASK) >> SIM_SOPT1_OSC32KSEL_SHIFT) +#define SIM_SOPT2_PLLFLLSEL_VAL ((SIM->SOPT2 & SIM_SOPT2_PLLFLLSEL_MASK) >> SIM_SOPT2_PLLFLLSEL_SHIFT) + +/* MCG_S_CLKST definition. */ +enum _mcg_clkout_stat +{ + kMCG_ClkOutStatFll, /* FLL. */ + kMCG_ClkOutStatInt, /* Internal clock. */ + kMCG_ClkOutStatExt, /* External clock. */ + kMCG_ClkOutStatPll /* PLL. */ +}; + +/* MCG_S_PLLST definition. */ +enum _mcg_pllst +{ + kMCG_PllstFll, /* FLL is used. */ + kMCG_PllstPll /* PLL is used. */ +}; + +/******************************************************************************* + * Variables + ******************************************************************************/ + +/* Slow internal reference clock frequency. */ +static uint32_t s_slowIrcFreq = 32768U; +/* Fast internal reference clock frequency. */ +static uint32_t s_fastIrcFreq = 4000000U; + +/* External XTAL0 (OSC0) clock frequency. */ +uint32_t g_xtal0Freq; +/* External XTAL32K clock frequency. */ +uint32_t g_xtal32Freq; + +/******************************************************************************* + * Prototypes + ******************************************************************************/ + +/*! + * @brief Get the MCG external reference clock frequency. + * + * Get the current MCG external reference clock frequency in Hz. It is + * the frequency select by MCG_C7[OSCSEL]. This is an internal function. + * + * @return MCG external reference clock frequency in Hz. + */ +static uint32_t CLOCK_GetMcgExtClkFreq(void); + +/*! + * @brief Get the MCG FLL external reference clock frequency. + * + * Get the current MCG FLL external reference clock frequency in Hz. It is + * the frequency after by MCG_C1[FRDIV]. This is an internal function. + * + * @return MCG FLL external reference clock frequency in Hz. + */ +static uint32_t CLOCK_GetFllExtRefClkFreq(void); + +/*! + * @brief Get the MCG FLL reference clock frequency. + * + * Get the current MCG FLL reference clock frequency in Hz. It is + * the frequency select by MCG_C1[IREFS]. This is an internal function. + * + * @return MCG FLL reference clock frequency in Hz. + */ +static uint32_t CLOCK_GetFllRefClkFreq(void); + +/*! + * @brief Get the frequency of clock selected by MCG_C2[IRCS]. + * + * This clock's two output: + * 1. MCGOUTCLK when MCG_S[CLKST]=0. + * 2. MCGIRCLK when MCG_C1[IRCLKEN]=1. + * + * @return The frequency in Hz. + */ +static uint32_t CLOCK_GetInternalRefClkSelectFreq(void); + +/*! + * @brief Calculate the RANGE value base on crystal frequency. + * + * To setup external crystal oscillator, must set the register bits RANGE + * base on the crystal frequency. This function returns the RANGE base on the + * input frequency. This is an internal function. + * + * @param freq Crystal frequency in Hz. + * @return The RANGE value. + */ +static uint8_t CLOCK_GetOscRangeFromFreq(uint32_t freq); + +#ifndef MCG_USER_CONFIG_FLL_STABLE_DELAY_EN +/*! + * @brief Delay function to wait FLL stable. + * + * Delay function to wait FLL stable in FEI mode or FEE mode, should wait at least + * 1ms. Every time changes FLL setting, should wait this time for FLL stable. + */ +static void CLOCK_FllStableDelay(void); +#endif + +/******************************************************************************* + * Code + ******************************************************************************/ + +#ifndef MCG_USER_CONFIG_FLL_STABLE_DELAY_EN +static void CLOCK_FllStableDelay(void) +{ + /* + Should wait at least 1ms. Because in these modes, the core clock is 100MHz + at most, so this function could obtain the 1ms delay. + */ + volatile uint32_t i = 30000U; + while (i--) + { + __NOP(); + } +} +#else /* With MCG_USER_CONFIG_FLL_STABLE_DELAY_EN defined. */ +/* Once user defines the MCG_USER_CONFIG_FLL_STABLE_DELAY_EN to use their own delay function, he has to + * create his own CLOCK_FllStableDelay() function in application code. Since the clock functions in this + * file would call the CLOCK_FllStableDelay() regardness how it is defined. + */ +extern void CLOCK_FllStableDelay(void); +#endif /* MCG_USER_CONFIG_FLL_STABLE_DELAY_EN */ + +static uint32_t CLOCK_GetMcgExtClkFreq(void) +{ + uint32_t freq; + + switch (MCG_C7_OSCSEL_VAL) + { + case 0U: + /* Please call CLOCK_SetXtal0Freq base on board setting before using OSC0 clock. */ + assert(g_xtal0Freq); + freq = g_xtal0Freq; + break; + case 1U: + /* Please call CLOCK_SetXtal32Freq base on board setting before using XTAL32K/RTC_CLKIN clock. */ + assert(g_xtal32Freq); + freq = g_xtal32Freq; + break; + case 2U: + freq = MCG_INTERNAL_IRC_48M; + break; + default: + freq = 0U; + break; + } + + return freq; +} + +static uint32_t CLOCK_GetFllExtRefClkFreq(void) +{ + /* FllExtRef = McgExtRef / FllExtRefDiv */ + uint8_t frdiv; + uint8_t range; + uint8_t oscsel; + + uint32_t freq = CLOCK_GetMcgExtClkFreq(); + + if (!freq) + { + return freq; + } + + frdiv = MCG_C1_FRDIV_VAL; + freq >>= frdiv; + + range = MCG_C2_RANGE_VAL; + oscsel = MCG_C7_OSCSEL_VAL; + + /* + When should use divider 32, 64, 128, 256, 512, 1024, 1280, 1536. + 1. MCG_C7[OSCSEL] selects IRC48M. + 2. MCG_C7[OSCSEL] selects OSC0 and MCG_C2[RANGE] is not 0. + */ + if (((0U != range) && (kMCG_OscselOsc == oscsel)) || (kMCG_OscselIrc == oscsel)) + { + switch (frdiv) + { + case 0: + case 1: + case 2: + case 3: + case 4: + case 5: + freq >>= 5u; + break; + case 6: + /* 64*20=1280 */ + freq /= 20u; + break; + case 7: + /* 128*12=1536 */ + freq /= 12u; + break; + default: + freq = 0u; + break; + } + } + + return freq; +} + +static uint32_t CLOCK_GetInternalRefClkSelectFreq(void) +{ + if (kMCG_IrcSlow == MCG_S_IRCST_VAL) + { + /* Slow internal reference clock selected*/ + return s_slowIrcFreq; + } + else + { + /* Fast internal reference clock selected*/ + return s_fastIrcFreq >> MCG_SC_FCRDIV_VAL; + } +} + +static uint32_t CLOCK_GetFllRefClkFreq(void) +{ + /* If use external reference clock. */ + if (kMCG_FllSrcExternal == MCG_S_IREFST_VAL) + { + return CLOCK_GetFllExtRefClkFreq(); + } + /* If use internal reference clock. */ + else + { + return s_slowIrcFreq; + } +} + +static uint8_t CLOCK_GetOscRangeFromFreq(uint32_t freq) +{ + uint8_t range; + + if (freq <= 39063U) + { + range = 0U; + } + else if (freq <= 8000000U) + { + range = 1U; + } + else + { + range = 2U; + } + + return range; +} + +uint32_t CLOCK_GetOsc0ErClkUndivFreq(void) +{ + if (OSC0->CR & OSC_CR_ERCLKEN_MASK) + { + /* Please call CLOCK_SetXtal0Freq base on board setting before using OSC0 clock. */ + assert(g_xtal0Freq); + return g_xtal0Freq; + } + else + { + return 0U; + } +} + +uint32_t CLOCK_GetOsc0ErClkDivFreq(void) +{ + if (OSC0->CR & OSC_CR_ERCLKEN_MASK) + { + /* Please call CLOCK_SetXtal0Freq base on board setting before using OSC0 clock. */ + assert(g_xtal0Freq); + return g_xtal0Freq >> ((OSC0->DIV & OSC_DIV_ERPS_MASK) >> OSC_DIV_ERPS_SHIFT); + } + else + { + return 0U; + } +} + +uint32_t CLOCK_GetEr32kClkFreq(void) +{ + uint32_t freq; + + switch (SIM_SOPT1_OSC32KSEL_VAL) + { + case 0U: /* OSC 32k clock */ + freq = (CLOCK_GetOsc0ErClkUndivFreq() == 32768U) ? 32768U : 0U; + break; + case 3U: /* LPO clock */ + freq = LPO_CLK_FREQ; + break; + default: + freq = 0U; + break; + } + return freq; +} + +uint32_t CLOCK_GetPllFllSelClkFreq(void) +{ + uint32_t freq; + + switch (SIM_SOPT2_PLLFLLSEL_VAL) + { + case 0U: /* FLL. */ + freq = CLOCK_GetFllFreq(); + break; + case 3U: /* MCG IRC48M. */ + freq = MCG_INTERNAL_IRC_48M; + break; + default: + freq = 0U; + break; + } + + return freq; +} + +uint32_t CLOCK_GetOsc0ErClkFreq(void) +{ + return CLOCK_GetOsc0ErClkDivFreq(); +} + +uint32_t CLOCK_GetPlatClkFreq(void) +{ + return CLOCK_GetOutClkFreq() / (SIM_CLKDIV1_OUTDIV1_VAL + 1); +} + +uint32_t CLOCK_GetFlashClkFreq(void) +{ + return CLOCK_GetOutClkFreq() / (SIM_CLKDIV1_OUTDIV4_VAL + 1); +} + +uint32_t CLOCK_GetBusClkFreq(void) +{ + return CLOCK_GetOutClkFreq() / (SIM_CLKDIV1_OUTDIV2_VAL + 1); +} + +uint32_t CLOCK_GetCoreSysClkFreq(void) +{ + return CLOCK_GetOutClkFreq() / (SIM_CLKDIV1_OUTDIV1_VAL + 1); +} + +uint32_t CLOCK_GetFreq(clock_name_t clockName) +{ + uint32_t freq; + + switch (clockName) + { + case kCLOCK_CoreSysClk: + case kCLOCK_PlatClk: + freq = CLOCK_GetOutClkFreq() / (SIM_CLKDIV1_OUTDIV1_VAL + 1); + break; + case kCLOCK_BusClk: + freq = CLOCK_GetOutClkFreq() / (SIM_CLKDIV1_OUTDIV2_VAL + 1); + break; + case kCLOCK_FlashClk: + freq = CLOCK_GetOutClkFreq() / (SIM_CLKDIV1_OUTDIV4_VAL + 1); + break; + case kCLOCK_PllFllSelClk: + freq = CLOCK_GetPllFllSelClkFreq(); + break; + case kCLOCK_Er32kClk: + freq = CLOCK_GetEr32kClkFreq(); + break; + case kCLOCK_McgFixedFreqClk: + freq = CLOCK_GetFixedFreqClkFreq(); + break; + case kCLOCK_McgInternalRefClk: + freq = CLOCK_GetInternalRefClkFreq(); + break; + case kCLOCK_McgFllClk: + freq = CLOCK_GetFllFreq(); + break; + case kCLOCK_McgIrc48MClk: + freq = MCG_INTERNAL_IRC_48M; + break; + case kCLOCK_LpoClk: + freq = LPO_CLK_FREQ; + break; + case kCLOCK_Osc0ErClkUndiv: + freq = CLOCK_GetOsc0ErClkUndivFreq(); + break; + case kCLOCK_Osc0ErClk: + freq = CLOCK_GetOsc0ErClkDivFreq(); + break; + default: + freq = 0U; + break; + } + + return freq; +} + +void CLOCK_SetSimConfig(sim_clock_config_t const *config) +{ + SIM->CLKDIV1 = config->clkdiv1; + CLOCK_SetPllFllSelClock(config->pllFllSel); + CLOCK_SetEr32kClock(config->er32kSrc); +} + +uint32_t CLOCK_GetOutClkFreq(void) +{ + uint32_t mcgoutclk; + uint32_t clkst = MCG_S_CLKST_VAL; + + switch (clkst) + { + case kMCG_ClkOutStatFll: + mcgoutclk = CLOCK_GetFllFreq(); + break; + case kMCG_ClkOutStatInt: + mcgoutclk = CLOCK_GetInternalRefClkSelectFreq(); + break; + case kMCG_ClkOutStatExt: + mcgoutclk = CLOCK_GetMcgExtClkFreq(); + break; + default: + mcgoutclk = 0U; + break; + } + return mcgoutclk; +} + +uint32_t CLOCK_GetFllFreq(void) +{ + static const uint16_t fllFactorTable[4][2] = {{640, 732}, {1280, 1464}, {1920, 2197}, {2560, 2929}}; + + uint8_t drs, dmx32; + uint32_t freq; + + /* If FLL is not enabled currently, then return 0U. */ + if ((MCG->C2 & MCG_C2_LP_MASK)) + { + return 0U; + } + + /* Get FLL reference clock frequency. */ + freq = CLOCK_GetFllRefClkFreq(); + if (!freq) + { + return freq; + } + + drs = MCG_C4_DRST_DRS_VAL; + dmx32 = MCG_C4_DMX32_VAL; + + return freq * fllFactorTable[drs][dmx32]; +} + +uint32_t CLOCK_GetInternalRefClkFreq(void) +{ + /* If MCGIRCLK is gated. */ + if (!(MCG->C1 & MCG_C1_IRCLKEN_MASK)) + { + return 0U; + } + + return CLOCK_GetInternalRefClkSelectFreq(); +} + +uint32_t CLOCK_GetFixedFreqClkFreq(void) +{ + uint32_t freq = CLOCK_GetFllRefClkFreq(); + + /* MCGFFCLK must be no more than MCGOUTCLK/8. */ + if ((freq) && (freq <= (CLOCK_GetOutClkFreq() / 8U))) + { + return freq; + } + else + { + return 0U; + } +} + +status_t CLOCK_SetExternalRefClkConfig(mcg_oscsel_t oscsel) +{ + bool needDelay; + uint32_t i; + +#if (defined(MCG_CONFIG_CHECK_PARAM) && MCG_CONFIG_CHECK_PARAM) + /* If change MCG_C7[OSCSEL] and external reference clock is system clock source, return error. */ + if ((MCG_C7_OSCSEL_VAL != oscsel) && (!(MCG->S & MCG_S_IREFST_MASK))) + { + return kStatus_MCG_SourceUsed; + } +#endif /* MCG_CONFIG_CHECK_PARAM */ + + if (MCG_C7_OSCSEL_VAL != oscsel) + { + /* If change OSCSEL, need to delay, ERR009878. */ + needDelay = true; + } + else + { + needDelay = false; + } + + MCG->C7 = (MCG->C7 & ~MCG_C7_OSCSEL_MASK) | MCG_C7_OSCSEL(oscsel); + if (needDelay) + { + /* ERR009878 Delay at least 50 micro-seconds for external clock change valid. */ + i = 1500U; + while (i--) + { + __NOP(); + } + } + + return kStatus_Success; +} + +status_t CLOCK_SetInternalRefClkConfig(uint8_t enableMode, mcg_irc_mode_t ircs, uint8_t fcrdiv) +{ + uint32_t mcgOutClkState = MCG_S_CLKST_VAL; + mcg_irc_mode_t curIrcs = (mcg_irc_mode_t)MCG_S_IRCST_VAL; + uint8_t curFcrdiv = MCG_SC_FCRDIV_VAL; + +#if (defined(MCG_CONFIG_CHECK_PARAM) && MCG_CONFIG_CHECK_PARAM) + /* If MCGIRCLK is used as system clock source. */ + if (kMCG_ClkOutStatInt == mcgOutClkState) + { + /* If need to change MCGIRCLK source or driver, return error. */ + if (((kMCG_IrcFast == curIrcs) && (fcrdiv != curFcrdiv)) || (ircs != curIrcs)) + { + return kStatus_MCG_SourceUsed; + } + } +#endif + + /* If need to update the FCRDIV. */ + if (fcrdiv != curFcrdiv) + { + /* If fast IRC is in use currently, change to slow IRC. */ + if ((kMCG_IrcFast == curIrcs) && ((mcgOutClkState == kMCG_ClkOutStatInt) || (MCG->C1 & MCG_C1_IRCLKEN_MASK))) + { + MCG->C2 = ((MCG->C2 & ~MCG_C2_IRCS_MASK) | (MCG_C2_IRCS(kMCG_IrcSlow))); + while (MCG_S_IRCST_VAL != kMCG_IrcSlow) + { + } + } + /* Update FCRDIV. */ + MCG->SC = (MCG->SC & ~(MCG_SC_FCRDIV_MASK | MCG_SC_ATMF_MASK | MCG_SC_LOCS0_MASK)) | MCG_SC_FCRDIV(fcrdiv); + } + + /* Set internal reference clock selection. */ + MCG->C2 = (MCG->C2 & ~MCG_C2_IRCS_MASK) | (MCG_C2_IRCS(ircs)); + MCG->C1 = (MCG->C1 & ~(MCG_C1_IRCLKEN_MASK | MCG_C1_IREFSTEN_MASK)) | (uint8_t)enableMode; + + /* If MCGIRCLK is used, need to wait for MCG_S_IRCST. */ + if ((mcgOutClkState == kMCG_ClkOutStatInt) || (enableMode & kMCG_IrclkEnable)) + { + while (MCG_S_IRCST_VAL != ircs) + { + } + } + + return kStatus_Success; +} + +void CLOCK_SetOsc0MonitorMode(mcg_monitor_mode_t mode) +{ + /* Clear the previous flag, MCG_SC[LOCS0]. */ + MCG->SC &= ~MCG_SC_ATMF_MASK; + + if (kMCG_MonitorNone == mode) + { + MCG->C6 &= ~MCG_C6_CME0_MASK; + } + else + { + if (kMCG_MonitorInt == mode) + { + MCG->C2 &= ~MCG_C2_LOCRE0_MASK; + } + else + { + MCG->C2 |= MCG_C2_LOCRE0_MASK; + } + MCG->C6 |= MCG_C6_CME0_MASK; + } +} + +uint32_t CLOCK_GetStatusFlags(void) +{ + uint32_t ret = 0U; + uint8_t mcg_s = MCG->S; + + if (MCG->SC & MCG_SC_LOCS0_MASK) + { + ret |= kMCG_Osc0LostFlag; + } + if (mcg_s & MCG_S_OSCINIT0_MASK) + { + ret |= kMCG_Osc0InitFlag; + } + return ret; +} + +void CLOCK_ClearStatusFlags(uint32_t mask) +{ + if (mask & kMCG_Osc0LostFlag) + { + MCG->SC &= ~MCG_SC_ATMF_MASK; + } +} + +void CLOCK_InitOsc0(osc_config_t const *config) +{ + uint8_t range = CLOCK_GetOscRangeFromFreq(config->freq); + + OSC_SetCapLoad(OSC0, config->capLoad); + OSC_SetExtRefClkConfig(OSC0, &config->oscerConfig); + + MCG->C2 = ((MCG->C2 & ~OSC_MODE_MASK) | MCG_C2_RANGE(range) | (uint8_t)config->workMode); + + if ((kOSC_ModeExt != config->workMode) && (OSC0->CR & OSC_CR_ERCLKEN_MASK)) + { + /* Wait for stable. */ + while (!(MCG->S & MCG_S_OSCINIT0_MASK)) + { + } + } +} + +void CLOCK_DeinitOsc0(void) +{ + OSC0->CR = 0U; + MCG->C2 &= ~OSC_MODE_MASK; +} + +status_t CLOCK_TrimInternalRefClk(uint32_t extFreq, uint32_t desireFreq, uint32_t *actualFreq, mcg_atm_select_t atms) +{ + uint32_t multi; /* extFreq / desireFreq */ + uint32_t actv; /* Auto trim value. */ + uint8_t mcg_sc; + + static const uint32_t trimRange[2][2] = { + /* Min Max */ + {TRIM_SIRC_MIN, TRIM_SIRC_MAX}, /* Slow IRC. */ + {TRIM_FIRC_MIN, TRIM_FIRC_MAX} /* Fast IRC. */ + }; + + if ((extFreq > TRIM_REF_CLK_MAX) || (extFreq < TRIM_REF_CLK_MIN)) + { + return kStatus_MCG_AtmBusClockInvalid; + } + + /* Check desired frequency range. */ + if ((desireFreq < trimRange[atms][0]) || (desireFreq > trimRange[atms][1])) + { + return kStatus_MCG_AtmDesiredFreqInvalid; + } + + /* + Make sure internal reference clock is not used to generate bus clock. + Here only need to check (MCG_S_IREFST == 1). + */ + if (MCG_S_IREFST(kMCG_FllSrcInternal) == (MCG->S & MCG_S_IREFST_MASK)) + { + return kStatus_MCG_AtmIrcUsed; + } + + multi = extFreq / desireFreq; + actv = multi * 21U; + + if (kMCG_AtmSel4m == atms) + { + actv *= 128U; + } + + /* Now begin to start trim. */ + MCG->ATCVL = (uint8_t)actv; + MCG->ATCVH = (uint8_t)(actv >> 8U); + + mcg_sc = MCG->SC; + mcg_sc &= ~(MCG_SC_ATMS_MASK | MCG_SC_LOCS0_MASK); + mcg_sc |= (MCG_SC_ATMF_MASK | MCG_SC_ATMS(atms)); + MCG->SC = (mcg_sc | MCG_SC_ATME_MASK); + + /* Wait for finished. */ + while (MCG->SC & MCG_SC_ATME_MASK) + { + } + + /* Error occurs? */ + if (MCG->SC & MCG_SC_ATMF_MASK) + { + /* Clear the failed flag. */ + MCG->SC = mcg_sc; + return kStatus_MCG_AtmHardwareFail; + } + + *actualFreq = extFreq / multi; + + if (kMCG_AtmSel4m == atms) + { + s_fastIrcFreq = *actualFreq; + } + else + { + s_slowIrcFreq = *actualFreq; + } + + return kStatus_Success; +} + +mcg_mode_t CLOCK_GetMode(void) +{ + mcg_mode_t mode = kMCG_ModeError; + uint32_t clkst = MCG_S_CLKST_VAL; + uint32_t irefst = MCG_S_IREFST_VAL; + uint32_t lp = MCG_C2_LP_VAL; + + /*------------------------------------------------------------------ + Mode and Registers + ____________________________________________________________________ + + Mode | CLKST | IREFST | PLLST | LP + ____________________________________________________________________ + + FEI | 00(FLL) | 1(INT) | 0(FLL) | X + ____________________________________________________________________ + + FEE | 00(FLL) | 0(EXT) | 0(FLL) | X + ____________________________________________________________________ + + FBE | 10(EXT) | 0(EXT) | 0(FLL) | 0(NORMAL) + ____________________________________________________________________ + + FBI | 01(INT) | 1(INT) | 0(FLL) | 0(NORMAL) + ____________________________________________________________________ + + BLPI | 01(INT) | 1(INT) | 0(FLL) | 1(LOW POWER) + ____________________________________________________________________ + + BLPE | 10(EXT) | 0(EXT) | X | 1(LOW POWER) + ____________________________________________________________________ + + PEE | 11(PLL) | 0(EXT) | 1(PLL) | X + ____________________________________________________________________ + + PBE | 10(EXT) | 0(EXT) | 1(PLL) | O(NORMAL) + ____________________________________________________________________ + + PBI | 01(INT) | 1(INT) | 1(PLL) | 0(NORMAL) + ____________________________________________________________________ + + PEI | 11(PLL) | 1(INT) | 1(PLL) | X + ____________________________________________________________________ + + ----------------------------------------------------------------------*/ + + switch (clkst) + { + case kMCG_ClkOutStatFll: + if (kMCG_FllSrcExternal == irefst) + { + mode = kMCG_ModeFEE; + } + else + { + mode = kMCG_ModeFEI; + } + break; + case kMCG_ClkOutStatInt: + if (lp) + { + mode = kMCG_ModeBLPI; + } + else + { + { + mode = kMCG_ModeFBI; + } + } + break; + case kMCG_ClkOutStatExt: + if (lp) + { + mode = kMCG_ModeBLPE; + } + else + { + { + mode = kMCG_ModeFBE; + } + } + break; + default: + break; + } + + return mode; +} + +status_t CLOCK_SetFeiMode(mcg_dmx32_t dmx32, mcg_drs_t drs, void (*fllStableDelay)(void)) +{ + uint8_t mcg_c4; + bool change_drs = false; + +#if (defined(MCG_CONFIG_CHECK_PARAM) && MCG_CONFIG_CHECK_PARAM) + mcg_mode_t mode = CLOCK_GetMode(); + if (!((kMCG_ModeFEI == mode) || (kMCG_ModeFBI == mode) || (kMCG_ModeFBE == mode) || (kMCG_ModeFEE == mode))) + { + return kStatus_MCG_ModeUnreachable; + } +#endif + mcg_c4 = MCG->C4; + + /* + Errata: ERR007993 + Workaround: Invert MCG_C4[DMX32] or change MCG_C4[DRST_DRS] before + reference clock source changes, then reset to previous value after + reference clock changes. + */ + if (kMCG_FllSrcExternal == MCG_S_IREFST_VAL) + { + change_drs = true; + /* Change the LSB of DRST_DRS. */ + MCG->C4 ^= (1U << MCG_C4_DRST_DRS_SHIFT); + } + + /* Set CLKS and IREFS. */ + MCG->C1 = + ((MCG->C1 & ~(MCG_C1_CLKS_MASK | MCG_C1_IREFS_MASK))) | (MCG_C1_CLKS(kMCG_ClkOutSrcOut) /* CLKS = 0 */ + | MCG_C1_IREFS(kMCG_FllSrcInternal)); /* IREFS = 1 */ + + /* Wait and check status. */ + while (kMCG_FllSrcInternal != MCG_S_IREFST_VAL) + { + } + + /* Errata: ERR007993 */ + if (change_drs) + { + MCG->C4 = mcg_c4; + } + + /* In FEI mode, the MCG_C4[DMX32] is set to 0U. */ + MCG->C4 = (mcg_c4 & ~(MCG_C4_DMX32_MASK | MCG_C4_DRST_DRS_MASK)) | (MCG_C4_DMX32(dmx32) | MCG_C4_DRST_DRS(drs)); + + /* Check MCG_S[CLKST] */ + while (kMCG_ClkOutStatFll != MCG_S_CLKST_VAL) + { + } + + /* Wait for FLL stable time. */ + if (fllStableDelay) + { + fllStableDelay(); + } + + return kStatus_Success; +} + +status_t CLOCK_SetFeeMode(uint8_t frdiv, mcg_dmx32_t dmx32, mcg_drs_t drs, void (*fllStableDelay)(void)) +{ + uint8_t mcg_c4; + bool change_drs = false; + +#if (defined(MCG_CONFIG_CHECK_PARAM) && MCG_CONFIG_CHECK_PARAM) + mcg_mode_t mode = CLOCK_GetMode(); + if (!((kMCG_ModeFEE == mode) || (kMCG_ModeFBI == mode) || (kMCG_ModeFBE == mode) || (kMCG_ModeFEI == mode))) + { + return kStatus_MCG_ModeUnreachable; + } +#endif + mcg_c4 = MCG->C4; + + /* + Errata: ERR007993 + Workaround: Invert MCG_C4[DMX32] or change MCG_C4[DRST_DRS] before + reference clock source changes, then reset to previous value after + reference clock changes. + */ + if (kMCG_FllSrcInternal == MCG_S_IREFST_VAL) + { + change_drs = true; + /* Change the LSB of DRST_DRS. */ + MCG->C4 ^= (1U << MCG_C4_DRST_DRS_SHIFT); + } + + /* Set CLKS and IREFS. */ + MCG->C1 = ((MCG->C1 & ~(MCG_C1_CLKS_MASK | MCG_C1_FRDIV_MASK | MCG_C1_IREFS_MASK)) | + (MCG_C1_CLKS(kMCG_ClkOutSrcOut) /* CLKS = 0 */ + | MCG_C1_FRDIV(frdiv) /* FRDIV */ + | MCG_C1_IREFS(kMCG_FllSrcExternal))); /* IREFS = 0 */ + + /* If use external crystal as clock source, wait for it stable. */ + if (MCG_C7_OSCSEL(kMCG_OscselOsc) == (MCG->C7 & MCG_C7_OSCSEL_MASK)) + { + if (MCG->C2 & MCG_C2_EREFS_MASK) + { + while (!(MCG->S & MCG_S_OSCINIT0_MASK)) + { + } + } + } + + /* Wait and check status. */ + while (kMCG_FllSrcExternal != MCG_S_IREFST_VAL) + { + } + + /* Errata: ERR007993 */ + if (change_drs) + { + MCG->C4 = mcg_c4; + } + + /* Set DRS and DMX32. */ + mcg_c4 = ((mcg_c4 & ~(MCG_C4_DMX32_MASK | MCG_C4_DRST_DRS_MASK)) | (MCG_C4_DMX32(dmx32) | MCG_C4_DRST_DRS(drs))); + MCG->C4 = mcg_c4; + + /* Wait for DRST_DRS update. */ + while (MCG->C4 != mcg_c4) + { + } + + /* Check MCG_S[CLKST] */ + while (kMCG_ClkOutStatFll != MCG_S_CLKST_VAL) + { + } + + /* Wait for FLL stable time. */ + if (fllStableDelay) + { + fllStableDelay(); + } + + return kStatus_Success; +} + +status_t CLOCK_SetFbiMode(mcg_dmx32_t dmx32, mcg_drs_t drs, void (*fllStableDelay)(void)) +{ + uint8_t mcg_c4; + bool change_drs = false; + +#if (defined(MCG_CONFIG_CHECK_PARAM) && MCG_CONFIG_CHECK_PARAM) + mcg_mode_t mode = CLOCK_GetMode(); + + if (!((kMCG_ModeFEE == mode) || (kMCG_ModeFBI == mode) || (kMCG_ModeFBE == mode) || (kMCG_ModeFEI == mode) || + (kMCG_ModeBLPI == mode))) + + { + return kStatus_MCG_ModeUnreachable; + } +#endif + + mcg_c4 = MCG->C4; + + MCG->C2 &= ~MCG_C2_LP_MASK; /* Disable lowpower. */ + + /* + Errata: ERR007993 + Workaround: Invert MCG_C4[DMX32] or change MCG_C4[DRST_DRS] before + reference clock source changes, then reset to previous value after + reference clock changes. + */ + if (kMCG_FllSrcExternal == MCG_S_IREFST_VAL) + { + change_drs = true; + /* Change the LSB of DRST_DRS. */ + MCG->C4 ^= (1U << MCG_C4_DRST_DRS_SHIFT); + } + + /* Set CLKS and IREFS. */ + MCG->C1 = + ((MCG->C1 & ~(MCG_C1_CLKS_MASK | MCG_C1_IREFS_MASK)) | (MCG_C1_CLKS(kMCG_ClkOutSrcInternal) /* CLKS = 1 */ + | MCG_C1_IREFS(kMCG_FllSrcInternal))); /* IREFS = 1 */ + + /* Wait and check status. */ + while (kMCG_FllSrcInternal != MCG_S_IREFST_VAL) + { + } + + /* Errata: ERR007993 */ + if (change_drs) + { + MCG->C4 = mcg_c4; + } + + while (kMCG_ClkOutStatInt != MCG_S_CLKST_VAL) + { + } + + MCG->C4 = (mcg_c4 & ~(MCG_C4_DMX32_MASK | MCG_C4_DRST_DRS_MASK)) | (MCG_C4_DMX32(dmx32) | MCG_C4_DRST_DRS(drs)); + + /* Wait for FLL stable time. */ + if (fllStableDelay) + { + fllStableDelay(); + } + + return kStatus_Success; +} + +status_t CLOCK_SetFbeMode(uint8_t frdiv, mcg_dmx32_t dmx32, mcg_drs_t drs, void (*fllStableDelay)(void)) +{ + uint8_t mcg_c4; + bool change_drs = false; + +#if (defined(MCG_CONFIG_CHECK_PARAM) && MCG_CONFIG_CHECK_PARAM) + mcg_mode_t mode = CLOCK_GetMode(); + if (!((kMCG_ModeFEE == mode) || (kMCG_ModeFBI == mode) || (kMCG_ModeFBE == mode) || (kMCG_ModeFEI == mode) || + (kMCG_ModeBLPE == mode))) + { + return kStatus_MCG_ModeUnreachable; + } +#endif + + /* Set LP bit to enable the FLL */ + MCG->C2 &= ~MCG_C2_LP_MASK; + + mcg_c4 = MCG->C4; + + /* + Errata: ERR007993 + Workaround: Invert MCG_C4[DMX32] or change MCG_C4[DRST_DRS] before + reference clock source changes, then reset to previous value after + reference clock changes. + */ + if (kMCG_FllSrcInternal == MCG_S_IREFST_VAL) + { + change_drs = true; + /* Change the LSB of DRST_DRS. */ + MCG->C4 ^= (1U << MCG_C4_DRST_DRS_SHIFT); + } + + /* Set CLKS and IREFS. */ + MCG->C1 = ((MCG->C1 & ~(MCG_C1_CLKS_MASK | MCG_C1_FRDIV_MASK | MCG_C1_IREFS_MASK)) | + (MCG_C1_CLKS(kMCG_ClkOutSrcExternal) /* CLKS = 2 */ + | MCG_C1_FRDIV(frdiv) /* FRDIV = frdiv */ + | MCG_C1_IREFS(kMCG_FllSrcExternal))); /* IREFS = 0 */ + + /* If use external crystal as clock source, wait for it stable. */ + if (MCG_C7_OSCSEL(kMCG_OscselOsc) == (MCG->C7 & MCG_C7_OSCSEL_MASK)) + { + if (MCG->C2 & MCG_C2_EREFS_MASK) + { + while (!(MCG->S & MCG_S_OSCINIT0_MASK)) + { + } + } + } + + /* Wait for Reference clock Status bit to clear */ + while (kMCG_FllSrcExternal != MCG_S_IREFST_VAL) + { + } + + /* Errata: ERR007993 */ + if (change_drs) + { + MCG->C4 = mcg_c4; + } + + /* Set DRST_DRS and DMX32. */ + mcg_c4 = ((mcg_c4 & ~(MCG_C4_DMX32_MASK | MCG_C4_DRST_DRS_MASK)) | (MCG_C4_DMX32(dmx32) | MCG_C4_DRST_DRS(drs))); + + /* Wait for clock status bits to show clock source is ext ref clk */ + while (kMCG_ClkOutStatExt != MCG_S_CLKST_VAL) + { + } + + /* Wait for fll stable time. */ + if (fllStableDelay) + { + fllStableDelay(); + } + + return kStatus_Success; +} + +status_t CLOCK_SetBlpiMode(void) +{ +#if (defined(MCG_CONFIG_CHECK_PARAM) && MCG_CONFIG_CHECK_PARAM) + if (MCG_S_CLKST_VAL != kMCG_ClkOutStatInt) + { + return kStatus_MCG_ModeUnreachable; + } +#endif /* MCG_CONFIG_CHECK_PARAM */ + + /* Set LP. */ + MCG->C2 |= MCG_C2_LP_MASK; + + return kStatus_Success; +} + +status_t CLOCK_SetBlpeMode(void) +{ +#if (defined(MCG_CONFIG_CHECK_PARAM) && MCG_CONFIG_CHECK_PARAM) + if (MCG_S_CLKST_VAL != kMCG_ClkOutStatExt) + { + return kStatus_MCG_ModeUnreachable; + } +#endif + + /* Set LP bit to enter BLPE mode. */ + MCG->C2 |= MCG_C2_LP_MASK; + + return kStatus_Success; +} + +status_t CLOCK_ExternalModeToFbeModeQuick(void) +{ +#if (defined(MCG_CONFIG_CHECK_PARAM) && MCG_CONFIG_CHECK_PARAM) + if (MCG->S & MCG_S_IREFST_MASK) + { + return kStatus_MCG_ModeInvalid; + } +#endif /* MCG_CONFIG_CHECK_PARAM */ + + /* Disable low power */ + MCG->C2 &= ~MCG_C2_LP_MASK; + + MCG->C1 = ((MCG->C1 & ~MCG_C1_CLKS_MASK) | MCG_C1_CLKS(kMCG_ClkOutSrcExternal)); + while (MCG_S_CLKST_VAL != kMCG_ClkOutStatExt) + { + } + + return kStatus_Success; +} + +status_t CLOCK_InternalModeToFbiModeQuick(void) +{ +#if (defined(MCG_CONFIG_CHECK_PARAM) && MCG_CONFIG_CHECK_PARAM) + if (!(MCG->S & MCG_S_IREFST_MASK)) + { + return kStatus_MCG_ModeInvalid; + } +#endif + + /* Disable low power */ + MCG->C2 &= ~MCG_C2_LP_MASK; + + MCG->C1 = ((MCG->C1 & ~MCG_C1_CLKS_MASK) | MCG_C1_CLKS(kMCG_ClkOutSrcInternal)); + while (MCG_S_CLKST_VAL != kMCG_ClkOutStatInt) + { + } + + return kStatus_Success; +} + +status_t CLOCK_BootToFeiMode(mcg_dmx32_t dmx32, mcg_drs_t drs, void (*fllStableDelay)(void)) +{ + return CLOCK_SetFeiMode(dmx32, drs, fllStableDelay); +} + +status_t CLOCK_BootToFeeMode( + mcg_oscsel_t oscsel, uint8_t frdiv, mcg_dmx32_t dmx32, mcg_drs_t drs, void (*fllStableDelay)(void)) +{ + CLOCK_SetExternalRefClkConfig(oscsel); + + return CLOCK_SetFeeMode(frdiv, dmx32, drs, fllStableDelay); +} + +status_t CLOCK_BootToBlpiMode(uint8_t fcrdiv, mcg_irc_mode_t ircs, uint8_t ircEnableMode) +{ + /* If reset mode is FEI mode, set MCGIRCLK and always success. */ + CLOCK_SetInternalRefClkConfig(ircEnableMode, ircs, fcrdiv); + + /* If reset mode is not BLPI, first enter FBI mode. */ + MCG->C1 = (MCG->C1 & ~MCG_C1_CLKS_MASK) | MCG_C1_CLKS(kMCG_ClkOutSrcInternal); + while (MCG_S_CLKST_VAL != kMCG_ClkOutStatInt) + { + } + + /* Enter BLPI mode. */ + MCG->C2 |= MCG_C2_LP_MASK; + + return kStatus_Success; +} + +status_t CLOCK_BootToBlpeMode(mcg_oscsel_t oscsel) +{ + CLOCK_SetExternalRefClkConfig(oscsel); + + /* Set to FBE mode. */ + MCG->C1 = + ((MCG->C1 & ~(MCG_C1_CLKS_MASK | MCG_C1_IREFS_MASK)) | (MCG_C1_CLKS(kMCG_ClkOutSrcExternal) /* CLKS = 2 */ + | MCG_C1_IREFS(kMCG_FllSrcExternal))); /* IREFS = 0 */ + + /* If use external crystal as clock source, wait for it stable. */ + if (MCG_C7_OSCSEL(kMCG_OscselOsc) == (MCG->C7 & MCG_C7_OSCSEL_MASK)) + { + if (MCG->C2 & MCG_C2_EREFS_MASK) + { + while (!(MCG->S & MCG_S_OSCINIT0_MASK)) + { + } + } + } + + /* Wait for MCG_S[CLKST] and MCG_S[IREFST]. */ + while ((MCG->S & (MCG_S_IREFST_MASK | MCG_S_CLKST_MASK)) != + (MCG_S_IREFST(kMCG_FllSrcExternal) | MCG_S_CLKST(kMCG_ClkOutStatExt))) + { + } + + /* In FBE now, start to enter BLPE. */ + MCG->C2 |= MCG_C2_LP_MASK; + + return kStatus_Success; +} + +/* + The transaction matrix. It defines the path for mode switch, the row is for + current mode and the column is target mode. + For example, switch from FEI to PEE: + 1. Current mode FEI, next mode is mcgModeMatrix[FEI][PEE] = FBE, so swith to FBE. + 2. Current mode FBE, next mode is mcgModeMatrix[FBE][PEE] = PBE, so swith to PBE. + 3. Current mode PBE, next mode is mcgModeMatrix[PBE][PEE] = PEE, so swith to PEE. + Thus the MCG mode has changed from FEI to PEE. + */ +static const mcg_mode_t mcgModeMatrix[6][6] = { + {kMCG_ModeFEI, kMCG_ModeFBI, kMCG_ModeFBI, kMCG_ModeFEE, kMCG_ModeFBE, kMCG_ModeFBE}, /* FEI */ + {kMCG_ModeFEI, kMCG_ModeFBI, kMCG_ModeBLPI, kMCG_ModeFEE, kMCG_ModeFBE, kMCG_ModeFBE}, /* FBI */ + {kMCG_ModeFBI, kMCG_ModeFBI, kMCG_ModeBLPI, kMCG_ModeFBI, kMCG_ModeFBI, kMCG_ModeFBI}, /* BLPI */ + {kMCG_ModeFEI, kMCG_ModeFBI, kMCG_ModeFBI, kMCG_ModeFEE, kMCG_ModeFBE, kMCG_ModeFBE}, /* FEE */ + {kMCG_ModeFEI, kMCG_ModeFBI, kMCG_ModeFBI, kMCG_ModeFEE, kMCG_ModeFBE, kMCG_ModeBLPE}, /* FBE */ + {kMCG_ModeFBE, kMCG_ModeFBE, kMCG_ModeFBE, kMCG_ModeFBE, kMCG_ModeFBE, kMCG_ModeBLPE}, /* BLPE */ + /* FEI FBI BLPI FEE FBE BLPE */ +}; + +status_t CLOCK_SetMcgConfig(const mcg_config_t *config) +{ + mcg_mode_t next_mode; + status_t status = kStatus_Success; + + /* If need to change external clock, MCG_C7[OSCSEL]. */ + if (MCG_C7_OSCSEL_VAL != config->oscsel) + { + /* If external clock is in use, change to FEI first. */ + if (kMCG_FllSrcExternal == MCG_S_IREFST_VAL) + { + CLOCK_ExternalModeToFbeModeQuick(); + CLOCK_SetFeiMode(config->dmx32, config->drs, NULL); + } + + CLOCK_SetExternalRefClkConfig(config->oscsel); + } + + /* Re-configure MCGIRCLK, if MCGIRCLK is used as system clock source, then change to FEI/PEI first. */ + if (MCG_S_CLKST_VAL == kMCG_ClkOutStatInt) + { + MCG->C2 &= ~MCG_C2_LP_MASK; /* Disable lowpower. */ + + { + CLOCK_SetFeiMode(config->dmx32, config->drs, CLOCK_FllStableDelay); + } + } + + /* Configure MCGIRCLK. */ + CLOCK_SetInternalRefClkConfig(config->irclkEnableMode, config->ircs, config->fcrdiv); + + next_mode = CLOCK_GetMode(); + + do + { + next_mode = mcgModeMatrix[next_mode][config->mcgMode]; + + switch (next_mode) + { + case kMCG_ModeFEI: + status = CLOCK_SetFeiMode(config->dmx32, config->drs, CLOCK_FllStableDelay); + break; + case kMCG_ModeFEE: + status = CLOCK_SetFeeMode(config->frdiv, config->dmx32, config->drs, CLOCK_FllStableDelay); + break; + case kMCG_ModeFBI: + status = CLOCK_SetFbiMode(config->dmx32, config->drs, NULL); + break; + case kMCG_ModeFBE: + status = CLOCK_SetFbeMode(config->frdiv, config->dmx32, config->drs, NULL); + break; + case kMCG_ModeBLPI: + status = CLOCK_SetBlpiMode(); + break; + case kMCG_ModeBLPE: + status = CLOCK_SetBlpeMode(); + break; + default: + break; + } + if (kStatus_Success != status) + { + return status; + } + } while (next_mode != config->mcgMode); + + return kStatus_Success; +} diff --git a/drivers/fsl_clock.h b/drivers/fsl_clock.h new file mode 100644 index 0000000..3e0f384 --- /dev/null +++ b/drivers/fsl_clock.h @@ -0,0 +1,1286 @@ +/* + * The Clear BSD License + * Copyright (c) 2015, Freescale Semiconductor, Inc. + * Copyright (c) 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: + * + * o Redistributions of source code must retain the above copyright notice, this list + * of conditions and the following disclaimer. + * + * o 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. + * + * o Neither the name of 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_CLOCK_H_ +#define _FSL_CLOCK_H_ + +#include "fsl_common.h" + +/*! @addtogroup clock */ +/*! @{ */ + +/*! @file */ + +/******************************************************************************* + * Configurations + ******************************************************************************/ + +/*! @brief Configures whether to check a parameter in a function. + * + * Some MCG settings must be changed with conditions, for example: + * 1. MCGIRCLK settings, such as the source, divider, and the trim value should not change when + * MCGIRCLK is used as a system clock source. + * 2. MCG_C7[OSCSEL] should not be changed when the external reference clock is used + * as a system clock source. For example, in FBE/BLPE/PBE modes. + * 3. The users should only switch between the supported clock modes. + * + * MCG functions check the parameter and MCG status before setting, if not allowed + * to change, the functions return error. The parameter checking increases code size, + * if code size is a critical requirement, change #MCG_CONFIG_CHECK_PARAM to 0 to + * disable parameter checking. + */ +#ifndef MCG_CONFIG_CHECK_PARAM +#define MCG_CONFIG_CHECK_PARAM 0U +#endif + +/*! @brief Configure whether driver controls clock + * + * When set to 0, peripheral drivers will enable clock in initialize function + * and disable clock in de-initialize function. When set to 1, peripheral + * driver will not control the clock, application could contol the clock out of + * the driver. + * + * @note All drivers share this feature switcher. If it is set to 1, application + * should handle clock enable and disable for all drivers. + */ +#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)) +#define FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL 0 +#endif + +/******************************************************************************* + * Definitions + ******************************************************************************/ + +/*! @name Driver version */ +/*@{*/ +/*! @brief CLOCK driver version 2.2.1. */ +#define FSL_CLOCK_DRIVER_VERSION (MAKE_VERSION(2, 2, 1)) +/*@}*/ + +/*! @brief External XTAL0 (OSC0) clock frequency. + * + * The XTAL0/EXTAL0 (OSC0) clock frequency in Hz. When the clock is set up, use the + * function CLOCK_SetXtal0Freq to set the value in the clock driver. For example, + * if XTAL0 is 8 MHz: + * @code + * CLOCK_InitOsc0(...); // Set up the OSC0 + * CLOCK_SetXtal0Freq(80000000); // Set the XTAL0 value to the clock driver. + * @endcode + * + * This is important for the multicore platforms where only one core needs to set up the + * OSC0 using the CLOCK_InitOsc0. All other cores need to call the CLOCK_SetXtal0Freq + * to get a valid clock frequency. + */ +extern uint32_t g_xtal0Freq; + +/*! @brief External XTAL32/EXTAL32/RTC_CLKIN clock frequency. + * + * The XTAL32/EXTAL32/RTC_CLKIN clock frequency in Hz. When the clock is set up, use the + * function CLOCK_SetXtal32Freq to set the value in the clock driver. + * + * This is important for the multicore platforms where only one core needs to set up + * the clock. All other cores need to call the CLOCK_SetXtal32Freq + * to get a valid clock frequency. + */ +extern uint32_t g_xtal32Freq; + +/*! @brief IRC48M clock frequency in Hz. */ +#define MCG_INTERNAL_IRC_48M 48000000U + +#if (defined(OSC) && !(defined(OSC0))) +#define OSC0 OSC +#endif + +/*! @brief Clock ip name array for DMAMUX. */ +#define DMAMUX_CLOCKS \ + { \ + kCLOCK_Dmamux0 \ + } + +/*! @brief Clock ip name array for PORT. */ +#define PORT_CLOCKS \ + { \ + kCLOCK_PortA, kCLOCK_PortB, kCLOCK_PortC, kCLOCK_PortD, kCLOCK_PortE \ + } + +/*! @brief Clock ip name array for EWM. */ +#define EWM_CLOCKS \ + { \ + kCLOCK_Ewm0 \ + } + +/*! @brief Clock ip name array for PIT. */ +#define PIT_CLOCKS \ + { \ + kCLOCK_Pit0 \ + } + +/*! @brief Clock ip name array for DSPI. */ +#define DSPI_CLOCKS \ + { \ + kCLOCK_Spi0 \ + } + +/*! @brief Clock ip name array for LPTMR. */ +#define LPTMR_CLOCKS \ + { \ + kCLOCK_Lptmr0 \ + } + +/*! @brief Clock ip name array for FTM. */ +#define FTM_CLOCKS \ + { \ + kCLOCK_Ftm0, kCLOCK_Ftm1, kCLOCK_Ftm2 \ + } + +/*! @brief Clock ip name array for EDMA. */ +#define EDMA_CLOCKS \ + { \ + kCLOCK_Dma0 \ + } + +/*! @brief Clock ip name array for DAC. */ +#define DAC_CLOCKS \ + { \ + kCLOCK_Dac0 \ + } + +/*! @brief Clock ip name array for ADC16. */ +#define ADC16_CLOCKS \ + { \ + kCLOCK_Adc0 \ + } + +/*! @brief Clock ip name array for VREF. */ +#define VREF_CLOCKS \ + { \ + kCLOCK_Vref0 \ + } + +/*! @brief Clock ip name array for UART. */ +#define UART_CLOCKS \ + { \ + kCLOCK_Uart0, kCLOCK_Uart1 \ + } + +/*! @brief Clock ip name array for CRC. */ +#define CRC_CLOCKS \ + { \ + kCLOCK_Crc0 \ + } + +/*! @brief Clock ip name array for I2C. */ +#define I2C_CLOCKS \ + { \ + kCLOCK_I2c0 \ + } + +/*! @brief Clock ip name array for FTF. */ +#define FTF_CLOCKS \ + { \ + kCLOCK_Ftf0 \ + } + +/*! @brief Clock ip name array for PDB. */ +#define PDB_CLOCKS \ + { \ + kCLOCK_Pdb0 \ + } + +/*! @brief Clock ip name array for CMP. */ +#define CMP_CLOCKS \ + { \ + kCLOCK_Cmp0, kCLOCK_Cmp1 \ + } + +/*! + * @brief LPO clock frequency. + */ +#define LPO_CLK_FREQ 1000U + +/*! @brief Peripherals clock source definition. */ +#define SYS_CLK kCLOCK_CoreSysClk +#define BUS_CLK kCLOCK_BusClk +#define FAST_CLK kCLOCK_FastPeriphClk + +#define I2C0_CLK_SRC BUS_CLK +#define I2C1_CLK_SRC BUS_CLK +#define DSPI0_CLK_SRC BUS_CLK +#define DSPI1_CLK_SRC BUS_CLK +#define UART0_CLK_SRC SYS_CLK +#define UART1_CLK_SRC SYS_CLK +#define UART2_CLK_SRC BUS_CLK + +/*! @brief Clock name used to get clock frequency. */ +typedef enum _clock_name +{ + + /* ----------------------------- System layer clock -------------------------------*/ + kCLOCK_CoreSysClk, /*!< Core/system clock */ + kCLOCK_PlatClk, /*!< Platform clock */ + kCLOCK_BusClk, /*!< Bus clock */ + kCLOCK_FlexBusClk, /*!< FlexBus clock */ + kCLOCK_FlashClk, /*!< Flash clock */ + kCLOCK_FastPeriphClk, /*!< Fast peripheral clock */ + kCLOCK_PllFllSelClk, /*!< The clock after SIM[PLLFLLSEL]. */ + + /* ---------------------------------- OSC clock -----------------------------------*/ + kCLOCK_Er32kClk, /*!< External reference 32K clock (ERCLK32K) */ + kCLOCK_Osc0ErClk, /*!< OSC0 external reference clock (OSC0ERCLK) */ + kCLOCK_Osc1ErClk, /*!< OSC1 external reference clock (OSC1ERCLK) */ + kCLOCK_Osc0ErClkUndiv, /*!< OSC0 external reference undivided clock(OSC0ERCLK_UNDIV). */ + + /* ----------------------------- MCG and MCG-Lite clock ---------------------------*/ + kCLOCK_McgFixedFreqClk, /*!< MCG fixed frequency clock (MCGFFCLK) */ + kCLOCK_McgInternalRefClk, /*!< MCG internal reference clock (MCGIRCLK) */ + kCLOCK_McgFllClk, /*!< MCGFLLCLK */ + kCLOCK_McgPll0Clk, /*!< MCGPLL0CLK */ + kCLOCK_McgPll1Clk, /*!< MCGPLL1CLK */ + kCLOCK_McgExtPllClk, /*!< EXT_PLLCLK */ + kCLOCK_McgPeriphClk, /*!< MCG peripheral clock (MCGPCLK) */ + kCLOCK_McgIrc48MClk, /*!< MCG IRC48M clock */ + + /* --------------------------------- Other clock ----------------------------------*/ + kCLOCK_LpoClk, /*!< LPO clock */ + +} clock_name_t; + +/*------------------------------------------------------------------------------ + + clock_gate_t definition: + + 31 16 0 + ----------------------------------------------------------------- + | SIM_SCGC register offset | control bit offset in SCGC | + ----------------------------------------------------------------- + + For example, the SDHC clock gate is controlled by SIM_SCGC3[17], the + SIM_SCGC3 offset in SIM is 0x1030, then kCLOCK_GateSdhc0 is defined as + + kCLOCK_GateSdhc0 = (0x1030 << 16) | 17; + +------------------------------------------------------------------------------*/ + +#define CLK_GATE_REG_OFFSET_SHIFT 16U +#define CLK_GATE_REG_OFFSET_MASK 0xFFFF0000U +#define CLK_GATE_BIT_SHIFT_SHIFT 0U +#define CLK_GATE_BIT_SHIFT_MASK 0x0000FFFFU + +#define CLK_GATE_DEFINE(reg_offset, bit_shift) \ + ((((reg_offset) << CLK_GATE_REG_OFFSET_SHIFT) & CLK_GATE_REG_OFFSET_MASK) | \ + (((bit_shift) << CLK_GATE_BIT_SHIFT_SHIFT) & CLK_GATE_BIT_SHIFT_MASK)) + +#define CLK_GATE_ABSTRACT_REG_OFFSET(x) (((x)&CLK_GATE_REG_OFFSET_MASK) >> CLK_GATE_REG_OFFSET_SHIFT) +#define CLK_GATE_ABSTRACT_BITS_SHIFT(x) (((x)&CLK_GATE_BIT_SHIFT_MASK) >> CLK_GATE_BIT_SHIFT_SHIFT) + +/*! @brief Clock gate name used for CLOCK_EnableClock/CLOCK_DisableClock. */ +typedef enum _clock_ip_name +{ + kCLOCK_IpInvalid = 0U, + + kCLOCK_Ewm0 = CLK_GATE_DEFINE(0x1034U, 1U), + kCLOCK_I2c0 = CLK_GATE_DEFINE(0x1034U, 6U), + kCLOCK_Uart0 = CLK_GATE_DEFINE(0x1034U, 10U), + kCLOCK_Uart1 = CLK_GATE_DEFINE(0x1034U, 11U), + kCLOCK_Cmp0 = CLK_GATE_DEFINE(0x1034U, 19U), + kCLOCK_Cmp1 = CLK_GATE_DEFINE(0x1034U, 19U), + kCLOCK_Vref0 = CLK_GATE_DEFINE(0x1034U, 20U), + + kCLOCK_Lptmr0 = CLK_GATE_DEFINE(0x1038U, 0U), + kCLOCK_PortA = CLK_GATE_DEFINE(0x1038U, 9U), + kCLOCK_PortB = CLK_GATE_DEFINE(0x1038U, 10U), + kCLOCK_PortC = CLK_GATE_DEFINE(0x1038U, 11U), + kCLOCK_PortD = CLK_GATE_DEFINE(0x1038U, 12U), + kCLOCK_PortE = CLK_GATE_DEFINE(0x1038U, 13U), + + kCLOCK_Ftf0 = CLK_GATE_DEFINE(0x103CU, 0U), + kCLOCK_Dmamux0 = CLK_GATE_DEFINE(0x103CU, 1U), + kCLOCK_Spi0 = CLK_GATE_DEFINE(0x103CU, 12U), + kCLOCK_Crc0 = CLK_GATE_DEFINE(0x103CU, 18U), + kCLOCK_Pdb0 = CLK_GATE_DEFINE(0x103CU, 22U), + kCLOCK_Pit0 = CLK_GATE_DEFINE(0x103CU, 23U), + kCLOCK_Ftm0 = CLK_GATE_DEFINE(0x103CU, 24U), + kCLOCK_Ftm1 = CLK_GATE_DEFINE(0x103CU, 25U), + kCLOCK_Ftm2 = CLK_GATE_DEFINE(0x103CU, 26U), + kCLOCK_Adc0 = CLK_GATE_DEFINE(0x103CU, 27U), + kCLOCK_Dac0 = CLK_GATE_DEFINE(0x103CU, 31U), + + kCLOCK_Dma0 = CLK_GATE_DEFINE(0x1040U, 1U), +} clock_ip_name_t; + +/*!@brief SIM configuration structure for clock setting. */ +typedef struct _sim_clock_config +{ + uint8_t pllFllSel; /*!< PLL/FLL/IRC48M selection. */ + uint8_t er32kSrc; /*!< ERCLK32K source selection. */ + uint32_t clkdiv1; /*!< SIM_CLKDIV1. */ +} sim_clock_config_t; + +/*! @brief OSC work mode. */ +typedef enum _osc_mode +{ + kOSC_ModeExt = 0U, /*!< Use an external clock. */ +#if (defined(MCG_C2_EREFS_MASK) && !(defined(MCG_C2_EREFS0_MASK))) + kOSC_ModeOscLowPower = MCG_C2_EREFS_MASK, /*!< Oscillator low power. */ +#else + kOSC_ModeOscLowPower = MCG_C2_EREFS0_MASK, /*!< Oscillator low power. */ +#endif + kOSC_ModeOscHighGain = 0U +#if (defined(MCG_C2_EREFS_MASK) && !(defined(MCG_C2_EREFS0_MASK))) + | + MCG_C2_EREFS_MASK +#else + | + MCG_C2_EREFS0_MASK +#endif +#if (defined(MCG_C2_HGO_MASK) && !(defined(MCG_C2_HGO0_MASK))) + | + MCG_C2_HGO_MASK, /*!< Oscillator high gain. */ +#else + | + MCG_C2_HGO0_MASK, /*!< Oscillator high gain. */ +#endif +} osc_mode_t; + +/*! @brief Oscillator capacitor load setting.*/ +enum _osc_cap_load +{ + kOSC_Cap2P = OSC_CR_SC2P_MASK, /*!< 2 pF capacitor load */ + kOSC_Cap4P = OSC_CR_SC4P_MASK, /*!< 4 pF capacitor load */ + kOSC_Cap8P = OSC_CR_SC8P_MASK, /*!< 8 pF capacitor load */ + kOSC_Cap16P = OSC_CR_SC16P_MASK /*!< 16 pF capacitor load */ +}; + +/*! @brief OSCERCLK enable mode. */ +enum _oscer_enable_mode +{ + kOSC_ErClkEnable = OSC_CR_ERCLKEN_MASK, /*!< Enable. */ + kOSC_ErClkEnableInStop = OSC_CR_EREFSTEN_MASK /*!< Enable in stop mode. */ +}; + +/*! @brief OSC configuration for OSCERCLK. */ +typedef struct _oscer_config +{ + uint8_t enableMode; /*!< OSCERCLK enable mode. OR'ed value of @ref _oscer_enable_mode. */ + + uint8_t erclkDiv; /*!< Divider for OSCERCLK.*/ +} oscer_config_t; + +/*! + * @brief OSC Initialization Configuration Structure + * + * Defines the configuration data structure to initialize the OSC. + * When porting to a new board, set the following members + * according to the board setting: + * 1. freq: The external frequency. + * 2. workMode: The OSC module mode. + */ +typedef struct _osc_config +{ + uint32_t freq; /*!< External clock frequency. */ + uint8_t capLoad; /*!< Capacitor load setting. */ + osc_mode_t workMode; /*!< OSC work mode setting. */ + oscer_config_t oscerConfig; /*!< Configuration for OSCERCLK. */ +} osc_config_t; + +/*! @brief MCG FLL reference clock source select. */ +typedef enum _mcg_fll_src +{ + kMCG_FllSrcExternal, /*!< External reference clock is selected */ + kMCG_FllSrcInternal /*!< The slow internal reference clock is selected */ +} mcg_fll_src_t; + +/*! @brief MCG internal reference clock select */ +typedef enum _mcg_irc_mode +{ + kMCG_IrcSlow, /*!< Slow internal reference clock selected */ + kMCG_IrcFast /*!< Fast internal reference clock selected */ +} mcg_irc_mode_t; + +/*! @brief MCG DCO Maximum Frequency with 32.768 kHz Reference */ +typedef enum _mcg_dmx32 +{ + kMCG_Dmx32Default, /*!< DCO has a default range of 25% */ + kMCG_Dmx32Fine /*!< DCO is fine-tuned for maximum frequency with 32.768 kHz reference */ +} mcg_dmx32_t; + +/*! @brief MCG DCO range select */ +typedef enum _mcg_drs +{ + kMCG_DrsLow, /*!< Low frequency range */ + kMCG_DrsMid, /*!< Mid frequency range */ + kMCG_DrsMidHigh, /*!< Mid-High frequency range */ + kMCG_DrsHigh /*!< High frequency range */ +} mcg_drs_t; + +/*! @brief MCG PLL reference clock select */ +typedef enum _mcg_pll_ref_src +{ + kMCG_PllRefOsc0, /*!< Selects OSC0 as PLL reference clock */ + kMCG_PllRefOsc1 /*!< Selects OSC1 as PLL reference clock */ +} mcg_pll_ref_src_t; + +/*! @brief MCGOUT clock source. */ +typedef enum _mcg_clkout_src +{ + kMCG_ClkOutSrcOut, /*!< Output of the FLL is selected (reset default) */ + kMCG_ClkOutSrcInternal, /*!< Internal reference clock is selected */ + kMCG_ClkOutSrcExternal, /*!< External reference clock is selected */ +} mcg_clkout_src_t; + +/*! @brief MCG Automatic Trim Machine Select */ +typedef enum _mcg_atm_select +{ + kMCG_AtmSel32k, /*!< 32 kHz Internal Reference Clock selected */ + kMCG_AtmSel4m /*!< 4 MHz Internal Reference Clock selected */ +} mcg_atm_select_t; + +/*! @brief MCG OSC Clock Select */ +typedef enum _mcg_oscsel +{ + kMCG_OscselOsc, /*!< Selects System Oscillator (OSCCLK) */ + kMCG_OscselRtc, /*!< Selects 32 kHz RTC Oscillator */ + kMCG_OscselIrc /*!< Selects 48 MHz IRC Oscillator */ +} mcg_oscsel_t; + +/*! @brief MCG PLLCS select */ +typedef enum _mcg_pll_clk_select +{ + kMCG_PllClkSelPll0, /*!< PLL0 output clock is selected */ + kMCG_PllClkSelPll1 /* PLL1 output clock is selected */ +} mcg_pll_clk_select_t; + +/*! @brief MCG clock monitor mode. */ +typedef enum _mcg_monitor_mode +{ + kMCG_MonitorNone, /*!< Clock monitor is disabled. */ + kMCG_MonitorInt, /*!< Trigger interrupt when clock lost. */ + kMCG_MonitorReset /*!< System reset when clock lost. */ +} mcg_monitor_mode_t; + +/*! @brief MCG status. */ +enum _mcg_status +{ + kStatus_MCG_ModeUnreachable = MAKE_STATUS(kStatusGroup_MCG, 0), /*!< Can't switch to target mode. */ + kStatus_MCG_ModeInvalid = MAKE_STATUS(kStatusGroup_MCG, 1), /*!< Current mode invalid for the specific + function. */ + kStatus_MCG_AtmBusClockInvalid = MAKE_STATUS(kStatusGroup_MCG, 2), /*!< Invalid bus clock for ATM. */ + kStatus_MCG_AtmDesiredFreqInvalid = MAKE_STATUS(kStatusGroup_MCG, 3), /*!< Invalid desired frequency for ATM. */ + kStatus_MCG_AtmIrcUsed = MAKE_STATUS(kStatusGroup_MCG, 4), /*!< IRC is used when using ATM. */ + kStatus_MCG_AtmHardwareFail = MAKE_STATUS(kStatusGroup_MCG, 5), /*!< Hardware fail occurs during ATM. */ + kStatus_MCG_SourceUsed = MAKE_STATUS(kStatusGroup_MCG, 6) /*!< Can't change the clock source because + it is in use. */ +}; + +/*! @brief MCG status flags. */ +enum _mcg_status_flags_t +{ + kMCG_Osc0LostFlag = (1U << 0U), /*!< OSC0 lost. */ + kMCG_Osc0InitFlag = (1U << 1U), /*!< OSC0 crystal initialized. */ +}; + +/*! @brief MCG internal reference clock (MCGIRCLK) enable mode definition. */ +enum _mcg_irclk_enable_mode +{ + kMCG_IrclkEnable = MCG_C1_IRCLKEN_MASK, /*!< MCGIRCLK enable. */ + kMCG_IrclkEnableInStop = MCG_C1_IREFSTEN_MASK /*!< MCGIRCLK enable in stop mode. */ +}; + +/*! @brief MCG mode definitions */ +typedef enum _mcg_mode +{ + kMCG_ModeFEI = 0U, /*!< FEI - FLL Engaged Internal */ + kMCG_ModeFBI, /*!< FBI - FLL Bypassed Internal */ + kMCG_ModeBLPI, /*!< BLPI - Bypassed Low Power Internal */ + kMCG_ModeFEE, /*!< FEE - FLL Engaged External */ + kMCG_ModeFBE, /*!< FBE - FLL Bypassed External */ + kMCG_ModeBLPE, /*!< BLPE - Bypassed Low Power External */ + kMCG_ModeError /*!< Unknown mode */ +} mcg_mode_t; + +/*! @brief MCG mode change configuration structure + * + * When porting to a new board, set the following members + * according to the board setting: + * 1. frdiv: If the FLL uses the external reference clock, set this + * value to ensure that the external reference clock divided by frdiv is + * in the 31.25 kHz to 39.0625 kHz range. + * 2. The PLL reference clock divider PRDIV: PLL reference clock frequency after + * PRDIV should be in the FSL_FEATURE_MCG_PLL_REF_MIN to + * FSL_FEATURE_MCG_PLL_REF_MAX range. + */ +typedef struct _mcg_config +{ + mcg_mode_t mcgMode; /*!< MCG mode. */ + + /* ----------------------- MCGIRCCLK settings ------------------------ */ + uint8_t irclkEnableMode; /*!< MCGIRCLK enable mode. */ + mcg_irc_mode_t ircs; /*!< Source, MCG_C2[IRCS]. */ + uint8_t fcrdiv; /*!< Divider, MCG_SC[FCRDIV]. */ + + /* ------------------------ MCG FLL settings ------------------------- */ + uint8_t frdiv; /*!< Divider MCG_C1[FRDIV]. */ + mcg_drs_t drs; /*!< DCO range MCG_C4[DRST_DRS]. */ + mcg_dmx32_t dmx32; /*!< MCG_C4[DMX32]. */ + mcg_oscsel_t oscsel; /*!< OSC select MCG_C7[OSCSEL]. */ + + /* ------------------------ MCG PLL settings ------------------------- */ +} mcg_config_t; + +/******************************************************************************* + * API + ******************************************************************************/ + +#if defined(__cplusplus) +extern "C" { +#endif /* __cplusplus */ + +/*! + * @brief Enable the clock for specific IP. + * + * @param name Which clock to enable, see \ref clock_ip_name_t. + */ +static inline void CLOCK_EnableClock(clock_ip_name_t name) +{ + uint32_t regAddr = SIM_BASE + CLK_GATE_ABSTRACT_REG_OFFSET((uint32_t)name); + (*(volatile uint32_t *)regAddr) |= (1U << CLK_GATE_ABSTRACT_BITS_SHIFT((uint32_t)name)); +} + +/*! + * @brief Disable the clock for specific IP. + * + * @param name Which clock to disable, see \ref clock_ip_name_t. + */ +static inline void CLOCK_DisableClock(clock_ip_name_t name) +{ + uint32_t regAddr = SIM_BASE + CLK_GATE_ABSTRACT_REG_OFFSET((uint32_t)name); + (*(volatile uint32_t *)regAddr) &= ~(1U << CLK_GATE_ABSTRACT_BITS_SHIFT((uint32_t)name)); +} + +/*! + * @brief Set ERCLK32K source. + * + * @param src The value to set ERCLK32K clock source. + */ +static inline void CLOCK_SetEr32kClock(uint32_t src) +{ + SIM->SOPT1 = ((SIM->SOPT1 & ~SIM_SOPT1_OSC32KSEL_MASK) | SIM_SOPT1_OSC32KSEL(src)); +} + +/*! + * @brief Set debug trace clock source. + * + * @param src The value to set debug trace clock source. + */ +static inline void CLOCK_SetTraceClock(uint32_t src) +{ + SIM->SOPT2 = ((SIM->SOPT2 & ~SIM_SOPT2_TRACECLKSEL_MASK) | SIM_SOPT2_TRACECLKSEL(src)); +} + +/*! + * @brief Set PLLFLLSEL clock source. + * + * @param src The value to set PLLFLLSEL clock source. + */ +static inline void CLOCK_SetPllFllSelClock(uint32_t src) +{ + SIM->SOPT2 = ((SIM->SOPT2 & ~SIM_SOPT2_PLLFLLSEL_MASK) | SIM_SOPT2_PLLFLLSEL(src)); +} + +/*! + * @brief Set CLKOUT source. + * + * @param src The value to set CLKOUT source. + */ +static inline void CLOCK_SetClkOutClock(uint32_t src) +{ + SIM->SOPT2 = ((SIM->SOPT2 & ~SIM_SOPT2_CLKOUTSEL_MASK) | SIM_SOPT2_CLKOUTSEL(src)); +} + +/*! + * @brief System clock divider + * + * Set the SIM_CLKDIV1[OUTDIV1], SIM_CLKDIV1[OUTDIV2], SIM_CLKDIV1[OUTDIV4]. + * + * @param outdiv1 Clock 1 output divider value. + * + * @param outdiv2 Clock 2 output divider value. + * + * @param outdiv4 Clock 4 output divider value. + */ +static inline void CLOCK_SetOutDiv(uint32_t outdiv1, uint32_t outdiv2, uint32_t outdiv4) +{ + SIM->CLKDIV1 = SIM_CLKDIV1_OUTDIV1(outdiv1) | SIM_CLKDIV1_OUTDIV2(outdiv2) | SIM_CLKDIV1_OUTDIV4(outdiv4); +} + +/*! + * @brief Gets the clock frequency for a specific clock name. + * + * This function checks the current clock configurations and then calculates + * the clock frequency for a specific clock name defined in clock_name_t. + * The MCG must be properly configured before using this function. + * + * @param clockName Clock names defined in clock_name_t + * @return Clock frequency value in Hertz + */ +uint32_t CLOCK_GetFreq(clock_name_t clockName); + +/*! + * @brief Get the core clock or system clock frequency. + * + * @return Clock frequency in Hz. + */ +uint32_t CLOCK_GetCoreSysClkFreq(void); + +/*! + * @brief Get the platform clock frequency. + * + * @return Clock frequency in Hz. + */ +uint32_t CLOCK_GetPlatClkFreq(void); + +/*! + * @brief Get the bus clock frequency. + * + * @return Clock frequency in Hz. + */ +uint32_t CLOCK_GetBusClkFreq(void); + +/*! + * @brief Get the flash clock frequency. + * + * @return Clock frequency in Hz. + */ +uint32_t CLOCK_GetFlashClkFreq(void); + +/*! + * @brief Get the output clock frequency selected by SIM[PLLFLLSEL]. + * + * @return Clock frequency in Hz. + */ +uint32_t CLOCK_GetPllFllSelClkFreq(void); + +/*! + * @brief Get the external reference 32K clock frequency (ERCLK32K). + * + * @return Clock frequency in Hz. + */ +uint32_t CLOCK_GetEr32kClkFreq(void); + +/*! + * @brief Get the OSC0 external reference undivided clock frequency (OSC0ERCLK_UNDIV). + * + * @return Clock frequency in Hz. + */ +uint32_t CLOCK_GetOsc0ErClkUndivFreq(void); + +/*! + * @brief Get the OSC0 external reference clock frequency (OSC0ERCLK). + * + * @return Clock frequency in Hz. + */ + +uint32_t CLOCK_GetOsc0ErClkFreq(void); + +/*! + * @brief Get the OSC0 external reference divided clock frequency. + * + * @return Clock frequency in Hz. + */ +uint32_t CLOCK_GetOsc0ErClkDivFreq(void); + + +/*! + * @brief Set the clock configure in SIM module. + * + * This function sets system layer clock settings in SIM module. + * + * @param config Pointer to the configure structure. + */ +void CLOCK_SetSimConfig(sim_clock_config_t const *config); + +/*! + * @brief Set the system clock dividers in SIM to safe value. + * + * The system level clocks (core clock, bus clock, flexbus clock and flash clock) + * must be in allowed ranges. During MCG clock mode switch, the MCG output clock + * changes then the system level clocks may be out of range. This function could + * be used before MCG mode change, to make sure system level clocks are in allowed + * range. + * + * @param config Pointer to the configure structure. + */ +static inline void CLOCK_SetSimSafeDivs(void) +{ + SIM->CLKDIV1 = 0x11070000U; +} + +/*! @name MCG frequency functions. */ +/*@{*/ + +/*! + * @brief Gets the MCG output clock (MCGOUTCLK) frequency. + * + * This function gets the MCG output clock frequency in Hz based on the current MCG + * register value. + * + * @return The frequency of MCGOUTCLK. + */ +uint32_t CLOCK_GetOutClkFreq(void); + +/*! + * @brief Gets the MCG FLL clock (MCGFLLCLK) frequency. + * + * This function gets the MCG FLL clock frequency in Hz based on the current MCG + * register value. The FLL is enabled in FEI/FBI/FEE/FBE mode and + * disabled in low power state in other modes. + * + * @return The frequency of MCGFLLCLK. + */ +uint32_t CLOCK_GetFllFreq(void); + +/*! + * @brief Gets the MCG internal reference clock (MCGIRCLK) frequency. + * + * This function gets the MCG internal reference clock frequency in Hz based + * on the current MCG register value. + * + * @return The frequency of MCGIRCLK. + */ +uint32_t CLOCK_GetInternalRefClkFreq(void); + +/*! + * @brief Gets the MCG fixed frequency clock (MCGFFCLK) frequency. + * + * This function gets the MCG fixed frequency clock frequency in Hz based + * on the current MCG register value. + * + * @return The frequency of MCGFFCLK. + */ +uint32_t CLOCK_GetFixedFreqClkFreq(void); + +/*@}*/ + +/*! @name MCG clock configuration. */ +/*@{*/ + +/*! + * @brief Enables or disables the MCG low power. + * + * Enabling the MCG low power disables the PLL and FLL in bypass modes. In other words, + * in FBE and PBE modes, enabling low power sets the MCG to BLPE mode. In FBI and + * PBI modes, enabling low power sets the MCG to BLPI mode. + * When disabling the MCG low power, the PLL or FLL are enabled based on MCG settings. + * + * @param enable True to enable MCG low power, false to disable MCG low power. + */ +static inline void CLOCK_SetLowPowerEnable(bool enable) +{ + if (enable) + { + MCG->C2 |= MCG_C2_LP_MASK; + } + else + { + MCG->C2 &= ~MCG_C2_LP_MASK; + } +} + +/*! + * @brief Configures the Internal Reference clock (MCGIRCLK). + * + * This function sets the \c MCGIRCLK base on parameters. It also selects the IRC + * source. If the fast IRC is used, this function sets the fast IRC divider. + * This function also sets whether the \c MCGIRCLK is enabled in stop mode. + * Calling this function in FBI/PBI/BLPI modes may change the system clock. As a result, + * using the function in these modes it is not allowed. + * + * @param enableMode MCGIRCLK enable mode, OR'ed value of @ref _mcg_irclk_enable_mode. + * @param ircs MCGIRCLK clock source, choose fast or slow. + * @param fcrdiv Fast IRC divider setting (\c FCRDIV). + * @retval kStatus_MCG_SourceUsed Because the internall reference clock is used as a clock source, + * the confuration should not be changed. Otherwise, a glitch occurs. + * @retval kStatus_Success MCGIRCLK configuration finished successfully. + */ +status_t CLOCK_SetInternalRefClkConfig(uint8_t enableMode, mcg_irc_mode_t ircs, uint8_t fcrdiv); + +/*! + * @brief Selects the MCG external reference clock. + * + * Selects the MCG external reference clock source, changes the MCG_C7[OSCSEL], + * and waits for the clock source to be stable. Because the external reference + * clock should not be changed in FEE/FBE/BLPE/PBE/PEE modes, do not call this function in these modes. + * + * @param oscsel MCG external reference clock source, MCG_C7[OSCSEL]. + * @retval kStatus_MCG_SourceUsed Because the external reference clock is used as a clock source, + * the confuration should not be changed. Otherwise, a glitch occurs. + * @retval kStatus_Success External reference clock set successfully. + */ +status_t CLOCK_SetExternalRefClkConfig(mcg_oscsel_t oscsel); + +/*! + * @brief Set the FLL external reference clock divider value. + * + * Sets the FLL external reference clock divider value, the register MCG_C1[FRDIV]. + * + * @param frdiv The FLL external reference clock divider value, MCG_C1[FRDIV]. + */ +static inline void CLOCK_SetFllExtRefDiv(uint8_t frdiv) +{ + MCG->C1 = (MCG->C1 & ~MCG_C1_FRDIV_MASK) | MCG_C1_FRDIV(frdiv); +} + +/*@}*/ + +/*! @name MCG clock lock monitor functions. */ +/*@{*/ + +/*! + * @brief Sets the OSC0 clock monitor mode. + * + * This function sets the OSC0 clock monitor mode. See @ref mcg_monitor_mode_t for details. + * + * @param mode Monitor mode to set. + */ +void CLOCK_SetOsc0MonitorMode(mcg_monitor_mode_t mode); + +/*! + * @brief Gets the MCG status flags. + * + * This function gets the MCG clock status flags. All status flags are + * returned as a logical OR of the enumeration @ref _mcg_status_flags_t. To + * check a specific flag, compare the return value with the flag. + * + * Example: + * @code + // To check the clock lost lock status of OSC0 and PLL0. + uint32_t mcgFlags; + + mcgFlags = CLOCK_GetStatusFlags(); + + if (mcgFlags & kMCG_Osc0LostFlag) + { + // OSC0 clock lock lost. Do something. + } + if (mcgFlags & kMCG_Pll0LostFlag) + { + // PLL0 clock lock lost. Do something. + } + @endcode + * + * @return Logical OR value of the @ref _mcg_status_flags_t. + */ +uint32_t CLOCK_GetStatusFlags(void); + +/*! + * @brief Clears the MCG status flags. + * + * This function clears the MCG clock lock lost status. The parameter is a logical + * OR value of the flags to clear. See @ref _mcg_status_flags_t. + * + * Example: + * @code + // To clear the clock lost lock status flags of OSC0 and PLL0. + + CLOCK_ClearStatusFlags(kMCG_Osc0LostFlag | kMCG_Pll0LostFlag); + @endcode + * + * @param mask The status flags to clear. This is a logical OR of members of the + * enumeration @ref _mcg_status_flags_t. + */ +void CLOCK_ClearStatusFlags(uint32_t mask); + +/*@}*/ + +/*! + * @name OSC configuration + * @{ + */ + +/*! + * @brief Configures the OSC external reference clock (OSCERCLK). + * + * This function configures the OSC external reference clock (OSCERCLK). + * This is an example to enable the OSCERCLK in normal and stop modes and also set + * the output divider to 1: + * + @code + oscer_config_t config = + { + .enableMode = kOSC_ErClkEnable | kOSC_ErClkEnableInStop, + .erclkDiv = 1U, + }; + + OSC_SetExtRefClkConfig(OSC, &config); + @endcode + * + * @param base OSC peripheral address. + * @param config Pointer to the configuration structure. + */ +static inline void OSC_SetExtRefClkConfig(OSC_Type *base, oscer_config_t const *config) +{ + uint8_t reg = base->CR; + + reg &= ~(OSC_CR_ERCLKEN_MASK | OSC_CR_EREFSTEN_MASK); + reg |= config->enableMode; + + base->CR = reg; + + base->DIV = OSC_DIV_ERPS(config->erclkDiv); +} + +/*! + * @brief Sets the capacitor load configuration for the oscillator. + * + * This function sets the specified capacitors configuration for the oscillator. + * This should be done in the early system level initialization function call + * based on the system configuration. + * + * @param base OSC peripheral address. + * @param capLoad OR'ed value for the capacitor load option, see \ref _osc_cap_load. + * + * Example: + @code + // To enable only 2 pF and 8 pF capacitor load, please use like this. + OSC_SetCapLoad(OSC, kOSC_Cap2P | kOSC_Cap8P); + @endcode + */ +static inline void OSC_SetCapLoad(OSC_Type *base, uint8_t capLoad) +{ + uint8_t reg = base->CR; + + reg &= ~(OSC_CR_SC2P_MASK | OSC_CR_SC4P_MASK | OSC_CR_SC8P_MASK | OSC_CR_SC16P_MASK); + reg |= capLoad; + + base->CR = reg; +} + +/*! + * @brief Initializes the OSC0. + * + * This function initializes the OSC0 according to the board configuration. + * + * @param config Pointer to the OSC0 configuration structure. + */ +void CLOCK_InitOsc0(osc_config_t const *config); + +/*! + * @brief Deinitializes the OSC0. + * + * This function deinitializes the OSC0. + */ +void CLOCK_DeinitOsc0(void); + +/* @} */ + +/*! + * @name External clock frequency + * @{ + */ + +/*! + * @brief Sets the XTAL0 frequency based on board settings. + * + * @param freq The XTAL0/EXTAL0 input clock frequency in Hz. + */ +static inline void CLOCK_SetXtal0Freq(uint32_t freq) +{ + g_xtal0Freq = freq; +} + +/*! + * @brief Sets the XTAL32/RTC_CLKIN frequency based on board settings. + * + * @param freq The XTAL32/EXTAL32/RTC_CLKIN input clock frequency in Hz. + */ +static inline void CLOCK_SetXtal32Freq(uint32_t freq) +{ + g_xtal32Freq = freq; +} +/* @} */ + +/*! + * @name MCG auto-trim machine. + * @{ + */ + +/*! + * @brief Auto trims the internal reference clock. + * + * This function trims the internal reference clock by using the external clock. If + * successful, it returns the kStatus_Success and the frequency after + * trimming is received in the parameter @p actualFreq. If an error occurs, + * the error code is returned. + * + * @param extFreq External clock frequency, which should be a bus clock. + * @param desireFreq Frequency to trim to. + * @param actualFreq Actual frequency after trimming. + * @param atms Trim fast or slow internal reference clock. + * @retval kStatus_Success ATM success. + * @retval kStatus_MCG_AtmBusClockInvalid The bus clock is not in allowed range for the ATM. + * @retval kStatus_MCG_AtmDesiredFreqInvalid MCGIRCLK could not be trimmed to the desired frequency. + * @retval kStatus_MCG_AtmIrcUsed Could not trim because MCGIRCLK is used as a bus clock source. + * @retval kStatus_MCG_AtmHardwareFail Hardware fails while trimming. + */ +status_t CLOCK_TrimInternalRefClk(uint32_t extFreq, uint32_t desireFreq, uint32_t *actualFreq, mcg_atm_select_t atms); +/* @} */ + +/*! @name MCG mode functions. */ +/*@{*/ + +/*! + * @brief Gets the current MCG mode. + * + * This function checks the MCG registers and determines the current MCG mode. + * + * @return Current MCG mode or error code; See @ref mcg_mode_t. + */ +mcg_mode_t CLOCK_GetMode(void); + +/*! + * @brief Sets the MCG to FEI mode. + * + * This function sets the MCG to FEI mode. If setting to FEI mode fails + * from the current mode, this function returns an error. + * + * @param dmx32 DMX32 in FEI mode. + * @param drs The DCO range selection. + * @param fllStableDelay Delay function to ensure that the FLL is stable. Passing + * NULL does not cause a delay. + * @retval kStatus_MCG_ModeUnreachable Could not switch to the target mode. + * @retval kStatus_Success Switched to the target mode successfully. + * @note If @p dmx32 is set to kMCG_Dmx32Fine, the slow IRC must not be trimmed + * to a frequency above 32768 Hz. + */ +status_t CLOCK_SetFeiMode(mcg_dmx32_t dmx32, mcg_drs_t drs, void (*fllStableDelay)(void)); + +/*! + * @brief Sets the MCG to FEE mode. + * + * This function sets the MCG to FEE mode. If setting to FEE mode fails + * from the current mode, this function returns an error. + * + * @param frdiv FLL reference clock divider setting, FRDIV. + * @param dmx32 DMX32 in FEE mode. + * @param drs The DCO range selection. + * @param fllStableDelay Delay function to make sure FLL is stable. Passing + * NULL does not cause a delay. + * + * @retval kStatus_MCG_ModeUnreachable Could not switch to the target mode. + * @retval kStatus_Success Switched to the target mode successfully. + */ +status_t CLOCK_SetFeeMode(uint8_t frdiv, mcg_dmx32_t dmx32, mcg_drs_t drs, void (*fllStableDelay)(void)); + +/*! + * @brief Sets the MCG to FBI mode. + * + * This function sets the MCG to FBI mode. If setting to FBI mode fails + * from the current mode, this function returns an error. + * + * @param dmx32 DMX32 in FBI mode. + * @param drs The DCO range selection. + * @param fllStableDelay Delay function to make sure FLL is stable. If the FLL + * is not used in FBI mode, this parameter can be NULL. Passing + * NULL does not cause a delay. + * @retval kStatus_MCG_ModeUnreachable Could not switch to the target mode. + * @retval kStatus_Success Switched to the target mode successfully. + * @note If @p dmx32 is set to kMCG_Dmx32Fine, the slow IRC must not be trimmed + * to frequency above 32768 Hz. + */ +status_t CLOCK_SetFbiMode(mcg_dmx32_t dmx32, mcg_drs_t drs, void (*fllStableDelay)(void)); + +/*! + * @brief Sets the MCG to FBE mode. + * + * This function sets the MCG to FBE mode. If setting to FBE mode fails + * from the current mode, this function returns an error. + * + * @param frdiv FLL reference clock divider setting, FRDIV. + * @param dmx32 DMX32 in FBE mode. + * @param drs The DCO range selection. + * @param fllStableDelay Delay function to make sure FLL is stable. If the FLL + * is not used in FBE mode, this parameter can be NULL. Passing NULL + * does not cause a delay. + * @retval kStatus_MCG_ModeUnreachable Could not switch to the target mode. + * @retval kStatus_Success Switched to the target mode successfully. + */ +status_t CLOCK_SetFbeMode(uint8_t frdiv, mcg_dmx32_t dmx32, mcg_drs_t drs, void (*fllStableDelay)(void)); + +/*! + * @brief Sets the MCG to BLPI mode. + * + * This function sets the MCG to BLPI mode. If setting to BLPI mode fails + * from the current mode, this function returns an error. + * + * @retval kStatus_MCG_ModeUnreachable Could not switch to the target mode. + * @retval kStatus_Success Switched to the target mode successfully. + */ +status_t CLOCK_SetBlpiMode(void); + +/*! + * @brief Sets the MCG to BLPE mode. + * + * This function sets the MCG to BLPE mode. If setting to BLPE mode fails + * from the current mode, this function returns an error. + * + * @retval kStatus_MCG_ModeUnreachable Could not switch to the target mode. + * @retval kStatus_Success Switched to the target mode successfully. + */ +status_t CLOCK_SetBlpeMode(void); + +/*! + * @brief Switches the MCG to FBE mode from the external mode. + * + * This function switches the MCG from external modes (PEE/PBE/BLPE/FEE) to the FBE mode quickly. + * The external clock is used as the system clock souce and PLL is disabled. However, + * the FLL settings are not configured. This is a lite function with a small code size, which is useful + * during the mode switch. For example, to switch from PEE mode to FEI mode: + * + * @code + * CLOCK_ExternalModeToFbeModeQuick(); + * CLOCK_SetFeiMode(...); + * @endcode + * + * @retval kStatus_Success Switched successfully. + * @retval kStatus_MCG_ModeInvalid If the current mode is not an external mode, do not call this function. + */ +status_t CLOCK_ExternalModeToFbeModeQuick(void); + +/*! + * @brief Switches the MCG to FBI mode from internal modes. + * + * This function switches the MCG from internal modes (PEI/PBI/BLPI/FEI) to the FBI mode quickly. + * The MCGIRCLK is used as the system clock souce and PLL is disabled. However, + * FLL settings are not configured. This is a lite function with a small code size, which is useful + * during the mode switch. For example, to switch from PEI mode to FEE mode: + * + * @code + * CLOCK_InternalModeToFbiModeQuick(); + * CLOCK_SetFeeMode(...); + * @endcode + * + * @retval kStatus_Success Switched successfully. + * @retval kStatus_MCG_ModeInvalid If the current mode is not an internal mode, do not call this function. + */ +status_t CLOCK_InternalModeToFbiModeQuick(void); + +/*! + * @brief Sets the MCG to FEI mode during system boot up. + * + * This function sets the MCG to FEI mode from the reset mode. It can also be used to + * set up MCG during system boot up. + * + * @param dmx32 DMX32 in FEI mode. + * @param drs The DCO range selection. + * @param fllStableDelay Delay function to ensure that the FLL is stable. + * + * @retval kStatus_MCG_ModeUnreachable Could not switch to the target mode. + * @retval kStatus_Success Switched to the target mode successfully. + * @note If @p dmx32 is set to kMCG_Dmx32Fine, the slow IRC must not be trimmed + * to frequency above 32768 Hz. + */ +status_t CLOCK_BootToFeiMode(mcg_dmx32_t dmx32, mcg_drs_t drs, void (*fllStableDelay)(void)); + +/*! + * @brief Sets the MCG to FEE mode during system bootup. + * + * This function sets MCG to FEE mode from the reset mode. It can also be used to + * set up the MCG during system boot up. + * + * @param oscsel OSC clock select, OSCSEL. + * @param frdiv FLL reference clock divider setting, FRDIV. + * @param dmx32 DMX32 in FEE mode. + * @param drs The DCO range selection. + * @param fllStableDelay Delay function to ensure that the FLL is stable. + * + * @retval kStatus_MCG_ModeUnreachable Could not switch to the target mode. + * @retval kStatus_Success Switched to the target mode successfully. + */ +status_t CLOCK_BootToFeeMode( + mcg_oscsel_t oscsel, uint8_t frdiv, mcg_dmx32_t dmx32, mcg_drs_t drs, void (*fllStableDelay)(void)); + +/*! + * @brief Sets the MCG to BLPI mode during system boot up. + * + * This function sets the MCG to BLPI mode from the reset mode. It can also be used to + * set up the MCG during sytem boot up. + * + * @param fcrdiv Fast IRC divider, FCRDIV. + * @param ircs The internal reference clock to select, IRCS. + * @param ircEnableMode The MCGIRCLK enable mode, OR'ed value of @ref _mcg_irclk_enable_mode. + * + * @retval kStatus_MCG_SourceUsed Could not change MCGIRCLK setting. + * @retval kStatus_Success Switched to the target mode successfully. + */ +status_t CLOCK_BootToBlpiMode(uint8_t fcrdiv, mcg_irc_mode_t ircs, uint8_t ircEnableMode); + +/*! + * @brief Sets the MCG to BLPE mode during sytem boot up. + * + * This function sets the MCG to BLPE mode from the reset mode. It can also be used to + * set up the MCG during sytem boot up. + * + * @param oscsel OSC clock select, MCG_C7[OSCSEL]. + * + * @retval kStatus_MCG_ModeUnreachable Could not switch to the target mode. + * @retval kStatus_Success Switched to the target mode successfully. + */ +status_t CLOCK_BootToBlpeMode(mcg_oscsel_t oscsel); + +/*! + * @brief Sets the MCG to a target mode. + * + * This function sets MCG to a target mode defined by the configuration + * structure. If switching to the target mode fails, this function + * chooses the correct path. + * + * @param config Pointer to the target MCG mode configuration structure. + * @return Return kStatus_Success if switched successfully; Otherwise, it returns an error code #_mcg_status. + * + * @note If the external clock is used in the target mode, ensure that it is + * enabled. For example, if the OSC0 is used, set up OSC0 correctly before calling this + * function. + */ +status_t CLOCK_SetMcgConfig(mcg_config_t const *config); + +/*@}*/ + +#if defined(__cplusplus) +} +#endif /* __cplusplus */ + +/*! @} */ + +#endif /* _FSL_CLOCK_H_ */ diff --git a/drivers/fsl_cmp.c b/drivers/fsl_cmp.c new file mode 100644 index 0000000..98039cd --- /dev/null +++ b/drivers/fsl_cmp.c @@ -0,0 +1,295 @@ +/* + * The Clear BSD License + * Copyright (c) 2015, 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: + * + * o Redistributions of source code must retain the above copyright notice, this list + * of conditions and the following disclaimer. + * + * o 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. + * + * o 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. + */ + +#include "fsl_cmp.h" + +/* Component ID definition, used by tools. */ +#ifndef FSL_COMPONENT_ID +#define FSL_COMPONENT_ID "platform.drivers.cmp" +#endif + + +/******************************************************************************* + * Prototypes + ******************************************************************************/ +/*! + * @brief Get instance number for CMP module. + * + * @param base CMP peripheral base address + */ +static uint32_t CMP_GetInstance(CMP_Type *base); + +/******************************************************************************* + * Variables + ******************************************************************************/ +/*! @brief Pointers to CMP bases for each instance. */ +static CMP_Type *const s_cmpBases[] = CMP_BASE_PTRS; +#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) +/*! @brief Pointers to CMP clocks for each instance. */ +static const clock_ip_name_t s_cmpClocks[] = CMP_CLOCKS; +#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */ + +/******************************************************************************* + * Codes + ******************************************************************************/ +static uint32_t CMP_GetInstance(CMP_Type *base) +{ + uint32_t instance; + + /* Find the instance index from base address mappings. */ + for (instance = 0; instance < ARRAY_SIZE(s_cmpBases); instance++) + { + if (s_cmpBases[instance] == base) + { + break; + } + } + + assert(instance < ARRAY_SIZE(s_cmpBases)); + + return instance; +} + +void CMP_Init(CMP_Type *base, const cmp_config_t *config) +{ + assert(NULL != config); + + uint8_t tmp8; + +#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) + /* Enable the clock. */ + CLOCK_EnableClock(s_cmpClocks[CMP_GetInstance(base)]); +#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */ + + /* Configure. */ + CMP_Enable(base, false); /* Disable the CMP module during configuring. */ + /* CMPx_CR1. */ + tmp8 = base->CR1 & ~(CMP_CR1_PMODE_MASK | CMP_CR1_INV_MASK | CMP_CR1_COS_MASK | CMP_CR1_OPE_MASK); + if (config->enableHighSpeed) + { + tmp8 |= CMP_CR1_PMODE_MASK; + } + if (config->enableInvertOutput) + { + tmp8 |= CMP_CR1_INV_MASK; + } + if (config->useUnfilteredOutput) + { + tmp8 |= CMP_CR1_COS_MASK; + } + if (config->enablePinOut) + { + tmp8 |= CMP_CR1_OPE_MASK; + } +#if defined(FSL_FEATURE_CMP_HAS_TRIGGER_MODE) && FSL_FEATURE_CMP_HAS_TRIGGER_MODE + if (config->enableTriggerMode) + { + tmp8 |= CMP_CR1_TRIGM_MASK; + } + else + { + tmp8 &= ~CMP_CR1_TRIGM_MASK; + } +#endif /* FSL_FEATURE_CMP_HAS_TRIGGER_MODE */ + base->CR1 = tmp8; + + /* CMPx_CR0. */ + tmp8 = base->CR0 & ~CMP_CR0_HYSTCTR_MASK; + tmp8 |= CMP_CR0_HYSTCTR(config->hysteresisMode); + base->CR0 = tmp8; + + CMP_Enable(base, config->enableCmp); /* Enable the CMP module after configured or not. */ +} + +void CMP_Deinit(CMP_Type *base) +{ + /* Disable the CMP module. */ + CMP_Enable(base, false); + +#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) + /* Disable the clock. */ + CLOCK_DisableClock(s_cmpClocks[CMP_GetInstance(base)]); +#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */ +} + +void CMP_GetDefaultConfig(cmp_config_t *config) +{ + assert(NULL != config); + + config->enableCmp = true; /* Enable the CMP module after initialization. */ + config->hysteresisMode = kCMP_HysteresisLevel0; + config->enableHighSpeed = false; + config->enableInvertOutput = false; + config->useUnfilteredOutput = false; + config->enablePinOut = false; +#if defined(FSL_FEATURE_CMP_HAS_TRIGGER_MODE) && FSL_FEATURE_CMP_HAS_TRIGGER_MODE + config->enableTriggerMode = false; +#endif /* FSL_FEATURE_CMP_HAS_TRIGGER_MODE */ +} + +void CMP_SetInputChannels(CMP_Type *base, uint8_t positiveChannel, uint8_t negativeChannel) +{ + uint8_t tmp8 = base->MUXCR; + + tmp8 &= ~(CMP_MUXCR_PSEL_MASK | CMP_MUXCR_MSEL_MASK); + tmp8 |= CMP_MUXCR_PSEL(positiveChannel) | CMP_MUXCR_MSEL(negativeChannel); + base->MUXCR = tmp8; +} + +#if defined(FSL_FEATURE_CMP_HAS_DMA) && FSL_FEATURE_CMP_HAS_DMA +void CMP_EnableDMA(CMP_Type *base, bool enable) +{ + uint8_t tmp8 = base->SCR & ~(CMP_SCR_CFR_MASK | CMP_SCR_CFF_MASK); /* To avoid change the w1c bits. */ + + if (enable) + { + tmp8 |= CMP_SCR_DMAEN_MASK; + } + else + { + tmp8 &= ~CMP_SCR_DMAEN_MASK; + } + base->SCR = tmp8; +} +#endif /* FSL_FEATURE_CMP_HAS_DMA */ + +void CMP_SetFilterConfig(CMP_Type *base, const cmp_filter_config_t *config) +{ + assert(NULL != config); + + uint8_t tmp8; + +#if defined(FSL_FEATURE_CMP_HAS_EXTERNAL_SAMPLE_SUPPORT) && FSL_FEATURE_CMP_HAS_EXTERNAL_SAMPLE_SUPPORT + /* Choose the clock source for sampling. */ + if (config->enableSample) + { + base->CR1 |= CMP_CR1_SE_MASK; /* Choose the external SAMPLE clock. */ + } + else + { + base->CR1 &= ~CMP_CR1_SE_MASK; /* Choose the internal divided bus clock. */ + } +#endif /* FSL_FEATURE_CMP_HAS_EXTERNAL_SAMPLE_SUPPORT */ + /* Set the filter count. */ + tmp8 = base->CR0 & ~CMP_CR0_FILTER_CNT_MASK; + tmp8 |= CMP_CR0_FILTER_CNT(config->filterCount); + base->CR0 = tmp8; + /* Set the filter period. It is used as the divider to bus clock. */ + base->FPR = CMP_FPR_FILT_PER(config->filterPeriod); +} + +void CMP_SetDACConfig(CMP_Type *base, const cmp_dac_config_t *config) +{ + uint8_t tmp8 = 0U; + + if (NULL == config) + { + /* Passing "NULL" as input parameter means no available configuration. So the DAC feature is disabled.*/ + base->DACCR = 0U; + return; + } + /* CMPx_DACCR. */ + tmp8 |= CMP_DACCR_DACEN_MASK; /* Enable the internal DAC. */ + if (kCMP_VrefSourceVin2 == config->referenceVoltageSource) + { + tmp8 |= CMP_DACCR_VRSEL_MASK; + } + tmp8 |= CMP_DACCR_VOSEL(config->DACValue); + + base->DACCR = tmp8; +} + +void CMP_EnableInterrupts(CMP_Type *base, uint32_t mask) +{ + uint8_t tmp8 = base->SCR & ~(CMP_SCR_CFR_MASK | CMP_SCR_CFF_MASK); /* To avoid change the w1c bits. */ + + if (0U != (kCMP_OutputRisingInterruptEnable & mask)) + { + tmp8 |= CMP_SCR_IER_MASK; + } + if (0U != (kCMP_OutputFallingInterruptEnable & mask)) + { + tmp8 |= CMP_SCR_IEF_MASK; + } + base->SCR = tmp8; +} + +void CMP_DisableInterrupts(CMP_Type *base, uint32_t mask) +{ + uint8_t tmp8 = base->SCR & ~(CMP_SCR_CFR_MASK | CMP_SCR_CFF_MASK); /* To avoid change the w1c bits. */ + + if (0U != (kCMP_OutputRisingInterruptEnable & mask)) + { + tmp8 &= ~CMP_SCR_IER_MASK; + } + if (0U != (kCMP_OutputFallingInterruptEnable & mask)) + { + tmp8 &= ~CMP_SCR_IEF_MASK; + } + base->SCR = tmp8; +} + +uint32_t CMP_GetStatusFlags(CMP_Type *base) +{ + uint32_t ret32 = 0U; + + if (0U != (CMP_SCR_CFR_MASK & base->SCR)) + { + ret32 |= kCMP_OutputRisingEventFlag; + } + if (0U != (CMP_SCR_CFF_MASK & base->SCR)) + { + ret32 |= kCMP_OutputFallingEventFlag; + } + if (0U != (CMP_SCR_COUT_MASK & base->SCR)) + { + ret32 |= kCMP_OutputAssertEventFlag; + } + return ret32; +} + +void CMP_ClearStatusFlags(CMP_Type *base, uint32_t mask) +{ + uint8_t tmp8 = base->SCR & ~(CMP_SCR_CFR_MASK | CMP_SCR_CFF_MASK); /* To avoid change the w1c bits. */ + + if (0U != (kCMP_OutputRisingEventFlag & mask)) + { + tmp8 |= CMP_SCR_CFR_MASK; + } + if (0U != (kCMP_OutputFallingEventFlag & mask)) + { + tmp8 |= CMP_SCR_CFF_MASK; + } + base->SCR = tmp8; +} diff --git a/drivers/fsl_cmp.h b/drivers/fsl_cmp.h new file mode 100644 index 0000000..e228413 --- /dev/null +++ b/drivers/fsl_cmp.h @@ -0,0 +1,347 @@ +/* + * The Clear BSD License + * Copyright (c) 2015, 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: + * + * o Redistributions of source code must retain the above copyright notice, this list + * of conditions and the following disclaimer. + * + * o 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. + * + * o 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_CMP_H_ +#define _FSL_CMP_H_ + +#include "fsl_common.h" + +/*! + * @addtogroup cmp + * @{ + */ + + +/******************************************************************************* + * Definitions + ******************************************************************************/ + +/*! @name Driver version */ +/*@{*/ +/*! @brief CMP driver version 2.0.0. */ +#define FSL_CMP_DRIVER_VERSION (MAKE_VERSION(2, 0, 0)) +/*@}*/ + +/*! +* @brief Interrupt enable/disable mask. +*/ +enum _cmp_interrupt_enable +{ + kCMP_OutputRisingInterruptEnable = CMP_SCR_IER_MASK, /*!< Comparator interrupt enable rising. */ + kCMP_OutputFallingInterruptEnable = CMP_SCR_IEF_MASK, /*!< Comparator interrupt enable falling. */ +}; + +/*! + * @brief Status flags' mask. + */ +enum _cmp_status_flags +{ + kCMP_OutputRisingEventFlag = CMP_SCR_CFR_MASK, /*!< Rising-edge on the comparison output has occurred. */ + kCMP_OutputFallingEventFlag = CMP_SCR_CFF_MASK, /*!< Falling-edge on the comparison output has occurred. */ + kCMP_OutputAssertEventFlag = CMP_SCR_COUT_MASK, /*!< Return the current value of the analog comparator output. */ +}; + +/*! + * @brief CMP Hysteresis mode. + */ +typedef enum _cmp_hysteresis_mode +{ + kCMP_HysteresisLevel0 = 0U, /*!< Hysteresis level 0. */ + kCMP_HysteresisLevel1 = 1U, /*!< Hysteresis level 1. */ + kCMP_HysteresisLevel2 = 2U, /*!< Hysteresis level 2. */ + kCMP_HysteresisLevel3 = 3U, /*!< Hysteresis level 3. */ +} cmp_hysteresis_mode_t; + +/*! + * @brief CMP Voltage Reference source. + */ +typedef enum _cmp_reference_voltage_source +{ + kCMP_VrefSourceVin1 = 0U, /*!< Vin1 is selected as a resistor ladder network supply reference Vin. */ + kCMP_VrefSourceVin2 = 1U, /*!< Vin2 is selected as a resistor ladder network supply reference Vin. */ +} cmp_reference_voltage_source_t; + +/*! + * @brief Configures the comparator. + */ +typedef struct _cmp_config +{ + bool enableCmp; /*!< Enable the CMP module. */ + cmp_hysteresis_mode_t hysteresisMode; /*!< CMP Hysteresis mode. */ + bool enableHighSpeed; /*!< Enable High-speed (HS) comparison mode. */ + bool enableInvertOutput; /*!< Enable the inverted comparator output. */ + bool useUnfilteredOutput; /*!< Set the compare output(COUT) to equal COUTA(true) or COUT(false). */ + bool enablePinOut; /*!< The comparator output is available on the associated pin. */ +#if defined(FSL_FEATURE_CMP_HAS_TRIGGER_MODE) && FSL_FEATURE_CMP_HAS_TRIGGER_MODE + bool enableTriggerMode; /*!< Enable the trigger mode. */ +#endif /* FSL_FEATURE_CMP_HAS_TRIGGER_MODE */ +} cmp_config_t; + +/*! + * @brief Configures the filter. + */ +typedef struct _cmp_filter_config +{ +#if defined(FSL_FEATURE_CMP_HAS_EXTERNAL_SAMPLE_SUPPORT) && FSL_FEATURE_CMP_HAS_EXTERNAL_SAMPLE_SUPPORT + bool enableSample; /*!< Using the external SAMPLE as a sampling clock input or using a divided bus clock. */ +#endif /* FSL_FEATURE_CMP_HAS_EXTERNAL_SAMPLE_SUPPORT */ + uint8_t filterCount; /*!< Filter Sample Count. Available range is 1-7; 0 disables the filter.*/ + uint8_t filterPeriod; /*!< Filter Sample Period. The divider to the bus clock. Available range is 0-255. */ +} cmp_filter_config_t; + +/*! + * @brief Configures the internal DAC. + */ +typedef struct _cmp_dac_config +{ + cmp_reference_voltage_source_t referenceVoltageSource; /*!< Supply voltage reference source. */ + uint8_t DACValue; /*!< Value for the DAC Output Voltage. Available range is 0-63.*/ +} cmp_dac_config_t; + +#if defined(__cplusplus) +extern "C" { +#endif + +/******************************************************************************* + * API + ******************************************************************************/ + +/*! + * @name Initialization + * @{ + */ + +/*! + * @brief Initializes the CMP. + * + * This function initializes the CMP module. The operations included are as follows. + * - Enabling the clock for CMP module. + * - Configuring the comparator. + * - Enabling the CMP module. + * Note that for some devices, multiple CMP instances share the same clock gate. In this case, to enable the clock for + * any instance enables all CMPs. See the appropriate MCU reference manual for the clock assignment of the CMP. + * + * @param base CMP peripheral base address. + * @param config Pointer to the configuration structure. + */ +void CMP_Init(CMP_Type *base, const cmp_config_t *config); + +/*! + * @brief De-initializes the CMP module. + * + * This function de-initializes the CMP module. The operations included are as follows. + * - Disabling the CMP module. + * - Disabling the clock for CMP module. + * + * This function disables the clock for the CMP. + * Note that for some devices, multiple CMP instances share the same clock gate. In this case, before disabling the + * clock for the CMP, ensure that all the CMP instances are not used. + * + * @param base CMP peripheral base address. + */ +void CMP_Deinit(CMP_Type *base); + +/*! + * @brief Enables/disables the CMP module. + * + * @param base CMP peripheral base address. + * @param enable Enables or disables the module. + */ +static inline void CMP_Enable(CMP_Type *base, bool enable) +{ + if (enable) + { + base->CR1 |= CMP_CR1_EN_MASK; + } + else + { + base->CR1 &= ~CMP_CR1_EN_MASK; + } +} + +/*! +* @brief Initializes the CMP user configuration structure. +* +* This function initializes the user configuration structure to these default values. +* @code +* config->enableCmp = true; +* config->hysteresisMode = kCMP_HysteresisLevel0; +* config->enableHighSpeed = false; +* config->enableInvertOutput = false; +* config->useUnfilteredOutput = false; +* config->enablePinOut = false; +* config->enableTriggerMode = false; +* @endcode +* @param config Pointer to the configuration structure. +*/ +void CMP_GetDefaultConfig(cmp_config_t *config); + +/*! + * @brief Sets the input channels for the comparator. + * + * This function sets the input channels for the comparator. + * Note that two input channels cannot be set the same way in the application. When the user selects the same input + * from the analog mux to the positive and negative port, the comparator is disabled automatically. + * + * @param base CMP peripheral base address. + * @param positiveChannel Positive side input channel number. Available range is 0-7. + * @param negativeChannel Negative side input channel number. Available range is 0-7. + */ +void CMP_SetInputChannels(CMP_Type *base, uint8_t positiveChannel, uint8_t negativeChannel); + +/* @} */ + +/*! + * @name Advanced Features + * @{ + */ + +#if defined(FSL_FEATURE_CMP_HAS_DMA) && FSL_FEATURE_CMP_HAS_DMA +/*! + * @brief Enables/disables the DMA request for rising/falling events. + * + * This function enables/disables the DMA request for rising/falling events. Either event triggers the generation of + * the DMA request from CMP if the DMA feature is enabled. Both events are ignored for generating the DMA request from the CMP + * if the DMA is disabled. + * + * @param base CMP peripheral base address. + * @param enable Enables or disables the feature. + */ +void CMP_EnableDMA(CMP_Type *base, bool enable); +#endif /* FSL_FEATURE_CMP_HAS_DMA */ + +#if defined(FSL_FEATURE_CMP_HAS_WINDOW_MODE) && FSL_FEATURE_CMP_HAS_WINDOW_MODE +/*! + * @brief Enables/disables the window mode. + * + * @param base CMP peripheral base address. + * @param enable Enables or disables the feature. + */ +static inline void CMP_EnableWindowMode(CMP_Type *base, bool enable) +{ + if (enable) + { + base->CR1 |= CMP_CR1_WE_MASK; + } + else + { + base->CR1 &= ~CMP_CR1_WE_MASK; + } +} +#endif /* FSL_FEATURE_CMP_HAS_WINDOW_MODE */ + +#if defined(FSL_FEATURE_CMP_HAS_PASS_THROUGH_MODE) && FSL_FEATURE_CMP_HAS_PASS_THROUGH_MODE +/*! + * @brief Enables/disables the pass through mode. + * + * @param base CMP peripheral base address. + * @param enable Enables or disables the feature. + */ +static inline void CMP_EnablePassThroughMode(CMP_Type *base, bool enable) +{ + if (enable) + { + base->MUXCR |= CMP_MUXCR_PSTM_MASK; + } + else + { + base->MUXCR &= ~CMP_MUXCR_PSTM_MASK; + } +} +#endif /* FSL_FEATURE_CMP_HAS_PASS_THROUGH_MODE */ + +/*! + * @brief Configures the filter. + * + * @param base CMP peripheral base address. + * @param config Pointer to the configuration structure. + */ +void CMP_SetFilterConfig(CMP_Type *base, const cmp_filter_config_t *config); + +/*! + * @brief Configures the internal DAC. + * + * @param base CMP peripheral base address. + * @param config Pointer to the configuration structure. "NULL" disables the feature. + */ +void CMP_SetDACConfig(CMP_Type *base, const cmp_dac_config_t *config); + +/*! + * @brief Enables the interrupts. + * + * @param base CMP peripheral base address. + * @param mask Mask value for interrupts. See "_cmp_interrupt_enable". + */ +void CMP_EnableInterrupts(CMP_Type *base, uint32_t mask); + +/*! + * @brief Disables the interrupts. + * + * @param base CMP peripheral base address. + * @param mask Mask value for interrupts. See "_cmp_interrupt_enable". + */ +void CMP_DisableInterrupts(CMP_Type *base, uint32_t mask); + +/* @} */ + +/*! + * @name Results + * @{ + */ + +/*! + * @brief Gets the status flags. + * + * @param base CMP peripheral base address. + * + * @return Mask value for the asserted flags. See "_cmp_status_flags". + */ +uint32_t CMP_GetStatusFlags(CMP_Type *base); + +/*! + * @brief Clears the status flags. + * + * @param base CMP peripheral base address. + * @param mask Mask value for the flags. See "_cmp_status_flags". + */ +void CMP_ClearStatusFlags(CMP_Type *base, uint32_t mask); + +/* @} */ +#if defined(__cplusplus) +} +#endif +/*! + * @} + */ +#endif /* _FSL_CMP_H_ */ diff --git a/drivers/fsl_common.c b/drivers/fsl_common.c new file mode 100644 index 0000000..903faf5 --- /dev/null +++ b/drivers/fsl_common.c @@ -0,0 +1,192 @@ +/* +* The Clear BSD License +* Copyright (c) 2015-2016, Freescale Semiconductor, Inc. + * Copyright 2016 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: +* +* o Redistributions of source code must retain the above copyright notice, this list +* of conditions and the following disclaimer. +* +* o 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. +* +* o 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. +*/ + +#include "fsl_common.h" +#define SDK_MEM_MAGIC_NUMBER 12345U + +typedef struct _mem_align_control_block +{ + uint16_t identifier; /*!< Identifier for the memory control block. */ + uint16_t offset; /*!< offset from aligned adress to real address */ +} mem_align_cb_t; + +/* Component ID definition, used by tools. */ +#ifndef FSL_COMPONENT_ID +#define FSL_COMPONENT_ID "platform.drivers.common" +#endif + + +#ifndef __GIC_PRIO_BITS +#if defined(ENABLE_RAM_VECTOR_TABLE) +uint32_t InstallIRQHandler(IRQn_Type irq, uint32_t irqHandler) +{ +/* Addresses for VECTOR_TABLE and VECTOR_RAM come from the linker file */ +#if defined(__CC_ARM) + extern uint32_t Image$$VECTOR_ROM$$Base[]; + extern uint32_t Image$$VECTOR_RAM$$Base[]; + extern uint32_t Image$$RW_m_data$$Base[]; + +#define __VECTOR_TABLE Image$$VECTOR_ROM$$Base +#define __VECTOR_RAM Image$$VECTOR_RAM$$Base +#define __RAM_VECTOR_TABLE_SIZE (((uint32_t)Image$$RW_m_data$$Base - (uint32_t)Image$$VECTOR_RAM$$Base)) +#elif defined(__ICCARM__) + extern uint32_t __RAM_VECTOR_TABLE_SIZE[]; + extern uint32_t __VECTOR_TABLE[]; + extern uint32_t __VECTOR_RAM[]; +#elif defined(__GNUC__) + extern uint32_t __VECTOR_TABLE[]; + extern uint32_t __VECTOR_RAM[]; + extern uint32_t __RAM_VECTOR_TABLE_SIZE_BYTES[]; + uint32_t __RAM_VECTOR_TABLE_SIZE = (uint32_t)(__RAM_VECTOR_TABLE_SIZE_BYTES); +#endif /* defined(__CC_ARM) */ + uint32_t n; + uint32_t ret; + uint32_t irqMaskValue; + + irqMaskValue = DisableGlobalIRQ(); + if (SCB->VTOR != (uint32_t)__VECTOR_RAM) + { + /* Copy the vector table from ROM to RAM */ + for (n = 0; n < ((uint32_t)__RAM_VECTOR_TABLE_SIZE) / sizeof(uint32_t); n++) + { + __VECTOR_RAM[n] = __VECTOR_TABLE[n]; + } + /* Point the VTOR to the position of vector table */ + SCB->VTOR = (uint32_t)__VECTOR_RAM; + } + + ret = __VECTOR_RAM[irq + 16]; + /* make sure the __VECTOR_RAM is noncachable */ + __VECTOR_RAM[irq + 16] = irqHandler; + + EnableGlobalIRQ(irqMaskValue); + +/* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif + + return ret; +} +#endif /* ENABLE_RAM_VECTOR_TABLE. */ +#endif /* __GIC_PRIO_BITS. */ + +#ifndef QN908XC_SERIES +#if (defined(FSL_FEATURE_SOC_SYSCON_COUNT) && (FSL_FEATURE_SOC_SYSCON_COUNT > 0)) + +void EnableDeepSleepIRQ(IRQn_Type interrupt) +{ + uint32_t intNumber = (uint32_t)interrupt; + +#if (defined(FSL_FEATURE_SYSCON_STARTER_DISCONTINUOUS) && (FSL_FEATURE_SYSCON_STARTER_DISCONTINUOUS == 1)) + { + SYSCON->STARTERP1 = 1u << intNumber; + } +#else + { + uint32_t index = 0; + + while (intNumber >= 32u) + { + index++; + intNumber -= 32u; + } + + SYSCON->STARTERSET[index] = 1u << intNumber; + } +#endif /* FSL_FEATURE_STARTER_DISCONTINUOUS */ + EnableIRQ(interrupt); /* also enable interrupt at NVIC */ +} + +void DisableDeepSleepIRQ(IRQn_Type interrupt) +{ + uint32_t intNumber = (uint32_t)interrupt; + + DisableIRQ(interrupt); /* also disable interrupt at NVIC */ +#if (defined(FSL_FEATURE_SYSCON_STARTER_DISCONTINUOUS) && (FSL_FEATURE_SYSCON_STARTER_DISCONTINUOUS == 1)) + { + SYSCON->STARTERP1 &= ~(1u << intNumber); + } +#else + { + uint32_t index = 0; + + while (intNumber >= 32u) + { + index++; + intNumber -= 32u; + } + + SYSCON->STARTERCLR[index] = 1u << intNumber; + } +#endif /* FSL_FEATURE_STARTER_DISCONTINUOUS */ +} +#endif /* FSL_FEATURE_SOC_SYSCON_COUNT */ + +#endif /* QN908XC_SERIES */ + +void *SDK_Malloc(size_t size, size_t alignbytes) +{ + mem_align_cb_t *p_cb = NULL; + uint32_t alignedsize = SDK_SIZEALIGN(size, alignbytes) + alignbytes + sizeof(mem_align_cb_t); + void *p_align_addr, *p_addr = malloc(alignedsize); + + if (!p_addr) + { + return NULL; + } + + p_align_addr = (void *)SDK_SIZEALIGN((uint32_t)p_addr + sizeof(mem_align_cb_t), alignbytes); + + p_cb = (mem_align_cb_t *)((uint32_t)p_align_addr - 4); + p_cb->identifier = SDK_MEM_MAGIC_NUMBER; + p_cb->offset = (uint32_t)p_align_addr - (uint32_t)p_addr; + + return (void *)p_align_addr; +} + +void SDK_Free(void *ptr) +{ + mem_align_cb_t *p_cb = (mem_align_cb_t *)((uint32_t)ptr - 4); + + if (p_cb->identifier != SDK_MEM_MAGIC_NUMBER) + { + return; + } + + free((void *)((uint32_t)ptr - p_cb->offset)); +} + diff --git a/drivers/fsl_common.h b/drivers/fsl_common.h new file mode 100644 index 0000000..a53dbc2 --- /dev/null +++ b/drivers/fsl_common.h @@ -0,0 +1,576 @@ +/* + * The Clear BSD License + * Copyright (c) 2015-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: + * + * o Redistributions of source code must retain the above copyright notice, this list + * of conditions and the following disclaimer. + * + * o 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. + * + * o 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_COMMON_H_ +#define _FSL_COMMON_H_ + +#include +#include +#include +#include +#include + +#if defined(__ICCARM__) +#include +#endif + +#include "fsl_device_registers.h" + +/*! + * @addtogroup ksdk_common + * @{ + */ + +/******************************************************************************* + * Definitions + ******************************************************************************/ + +/*! @brief Construct a status code value from a group and code number. */ +#define MAKE_STATUS(group, code) ((((group)*100) + (code))) + +/*! @brief Construct the version number for drivers. */ +#define MAKE_VERSION(major, minor, bugfix) (((major) << 16) | ((minor) << 8) | (bugfix)) + +/*! @name Driver version */ +/*@{*/ +/*! @brief common driver version 2.0.0. */ +#define FSL_COMMON_DRIVER_VERSION (MAKE_VERSION(2, 0, 0)) +/*@}*/ + +/* Debug console type definition. */ +#define DEBUG_CONSOLE_DEVICE_TYPE_NONE 0U /*!< No debug console. */ +#define DEBUG_CONSOLE_DEVICE_TYPE_UART 1U /*!< Debug console base on UART. */ +#define DEBUG_CONSOLE_DEVICE_TYPE_LPUART 2U /*!< Debug console base on LPUART. */ +#define DEBUG_CONSOLE_DEVICE_TYPE_LPSCI 3U /*!< Debug console base on LPSCI. */ +#define DEBUG_CONSOLE_DEVICE_TYPE_USBCDC 4U /*!< Debug console base on USBCDC. */ +#define DEBUG_CONSOLE_DEVICE_TYPE_FLEXCOMM 5U /*!< Debug console base on USBCDC. */ +#define DEBUG_CONSOLE_DEVICE_TYPE_IUART 6U /*!< Debug console base on i.MX UART. */ +#define DEBUG_CONSOLE_DEVICE_TYPE_VUSART 7U /*!< Debug console base on LPC_USART. */ +#define DEBUG_CONSOLE_DEVICE_TYPE_MINI_USART 8U /*!< Debug console base on LPC_USART. */ +#define DEBUG_CONSOLE_DEVICE_TYPE_SWO 9U /*!< Debug console base on SWO. */ + +/*! @brief Status group numbers. */ +enum _status_groups +{ + kStatusGroup_Generic = 0, /*!< Group number for generic status codes. */ + kStatusGroup_FLASH = 1, /*!< Group number for FLASH status codes. */ + kStatusGroup_LPSPI = 4, /*!< Group number for LPSPI status codes. */ + kStatusGroup_FLEXIO_SPI = 5, /*!< Group number for FLEXIO SPI status codes. */ + kStatusGroup_DSPI = 6, /*!< Group number for DSPI status codes. */ + kStatusGroup_FLEXIO_UART = 7, /*!< Group number for FLEXIO UART status codes. */ + kStatusGroup_FLEXIO_I2C = 8, /*!< Group number for FLEXIO I2C status codes. */ + kStatusGroup_LPI2C = 9, /*!< Group number for LPI2C status codes. */ + kStatusGroup_UART = 10, /*!< Group number for UART status codes. */ + kStatusGroup_I2C = 11, /*!< Group number for UART status codes. */ + kStatusGroup_LPSCI = 12, /*!< Group number for LPSCI status codes. */ + kStatusGroup_LPUART = 13, /*!< Group number for LPUART status codes. */ + kStatusGroup_SPI = 14, /*!< Group number for SPI status code.*/ + kStatusGroup_XRDC = 15, /*!< Group number for XRDC status code.*/ + kStatusGroup_SEMA42 = 16, /*!< Group number for SEMA42 status code.*/ + kStatusGroup_SDHC = 17, /*!< Group number for SDHC status code */ + kStatusGroup_SDMMC = 18, /*!< Group number for SDMMC status code */ + kStatusGroup_SAI = 19, /*!< Group number for SAI status code */ + kStatusGroup_MCG = 20, /*!< Group number for MCG status codes. */ + kStatusGroup_SCG = 21, /*!< Group number for SCG status codes. */ + kStatusGroup_SDSPI = 22, /*!< Group number for SDSPI status codes. */ + kStatusGroup_FLEXIO_I2S = 23, /*!< Group number for FLEXIO I2S status codes */ + kStatusGroup_FLEXIO_MCULCD = 24, /*!< Group number for FLEXIO LCD status codes */ + kStatusGroup_FLASHIAP = 25, /*!< Group number for FLASHIAP status codes */ + kStatusGroup_FLEXCOMM_I2C = 26, /*!< Group number for FLEXCOMM I2C status codes */ + kStatusGroup_I2S = 27, /*!< Group number for I2S status codes */ + kStatusGroup_IUART = 28, /*!< Group number for IUART status codes */ + kStatusGroup_CSI = 29, /*!< Group number for CSI status codes */ + kStatusGroup_MIPI_DSI = 30, /*!< Group number for MIPI DSI status codes */ + kStatusGroup_SDRAMC = 35, /*!< Group number for SDRAMC status codes. */ + kStatusGroup_POWER = 39, /*!< Group number for POWER status codes. */ + kStatusGroup_ENET = 40, /*!< Group number for ENET status codes. */ + kStatusGroup_PHY = 41, /*!< Group number for PHY status codes. */ + kStatusGroup_TRGMUX = 42, /*!< Group number for TRGMUX status codes. */ + kStatusGroup_SMARTCARD = 43, /*!< Group number for SMARTCARD status codes. */ + kStatusGroup_LMEM = 44, /*!< Group number for LMEM status codes. */ + kStatusGroup_QSPI = 45, /*!< Group number for QSPI status codes. */ + kStatusGroup_DMA = 50, /*!< Group number for DMA status codes. */ + kStatusGroup_EDMA = 51, /*!< Group number for EDMA status codes. */ + kStatusGroup_DMAMGR = 52, /*!< Group number for DMAMGR status codes. */ + kStatusGroup_FLEXCAN = 53, /*!< Group number for FlexCAN status codes. */ + kStatusGroup_LTC = 54, /*!< Group number for LTC status codes. */ + kStatusGroup_FLEXIO_CAMERA = 55, /*!< Group number for FLEXIO CAMERA status codes. */ + kStatusGroup_LPC_SPI = 56, /*!< Group number for LPC_SPI status codes. */ + kStatusGroup_LPC_USART = 57, /*!< Group number for LPC_USART status codes. */ + kStatusGroup_DMIC = 58, /*!< Group number for DMIC status codes. */ + kStatusGroup_SDIF = 59, /*!< Group number for SDIF status codes.*/ + kStatusGroup_SPIFI = 60, /*!< Group number for SPIFI status codes. */ + kStatusGroup_OTP = 61, /*!< Group number for OTP status codes. */ + kStatusGroup_MCAN = 62, /*!< Group number for MCAN status codes. */ + kStatusGroup_CAAM = 63, /*!< Group number for CAAM status codes. */ + kStatusGroup_ECSPI = 64, /*!< Group number for ECSPI status codes. */ + kStatusGroup_USDHC = 65, /*!< Group number for USDHC status codes.*/ + kStatusGroup_LPC_I2C = 66, /*!< Group number for LPC_I2C status codes.*/ + kStatusGroup_DCP = 67, /*!< Group number for DCP status codes.*/ + kStatusGroup_MSCAN = 68, /*!< Group number for MSCAN status codes.*/ + kStatusGroup_ESAI = 69, /*!< Group number for ESAI status codes. */ + kStatusGroup_FLEXSPI = 70, /*!< Group number for FLEXSPI status codes. */ + kStatusGroup_MMDC = 71, /*!< Group number for MMDC status codes. */ + kStatusGroup_MICFIL = 72, /*!< Group number for MIC status codes. */ + kStatusGroup_SDMA = 73, /*!< Group number for SDMA status codes. */ + kStatusGroup_ICS = 74, /*!< Group number for ICS status codes. */ + kStatusGroup_SPDIF = 75, /*!< Group number for SPDIF status codes. */ + kStatusGroup_LPC_MINISPI = 76, /*!< Group number for LPC_MINISPI status codes. */ + kStatusGroup_NOTIFIER = 98, /*!< Group number for NOTIFIER status codes. */ + kStatusGroup_DebugConsole = 99, /*!< Group number for debug console status codes. */ + kStatusGroup_SEMC = 100, /*!< Group number for SEMC status codes. */ + kStatusGroup_ApplicationRangeStart = 101, /*!< Starting number for application groups. */ +}; + +/*! @brief Generic status return codes. */ +enum _generic_status +{ + kStatus_Success = MAKE_STATUS(kStatusGroup_Generic, 0), + kStatus_Fail = MAKE_STATUS(kStatusGroup_Generic, 1), + kStatus_ReadOnly = MAKE_STATUS(kStatusGroup_Generic, 2), + kStatus_OutOfRange = MAKE_STATUS(kStatusGroup_Generic, 3), + kStatus_InvalidArgument = MAKE_STATUS(kStatusGroup_Generic, 4), + kStatus_Timeout = MAKE_STATUS(kStatusGroup_Generic, 5), + kStatus_NoTransferInProgress = MAKE_STATUS(kStatusGroup_Generic, 6), +}; + +/*! @brief Type used for all status and error return values. */ +typedef int32_t status_t; + +/* + * The fsl_clock.h is included here because it needs MAKE_VERSION/MAKE_STATUS/status_t + * defined in previous of this file. + */ +#include "fsl_clock.h" + +/* + * Chip level peripheral reset API, for MCUs that implement peripheral reset control external to a peripheral + */ +#if ((defined(FSL_FEATURE_SOC_SYSCON_COUNT) && (FSL_FEATURE_SOC_SYSCON_COUNT > 0)) || \ + (defined(FSL_FEATURE_SOC_ASYNC_SYSCON_COUNT) && (FSL_FEATURE_SOC_ASYNC_SYSCON_COUNT > 0))) +#include "fsl_reset.h" +#endif + +/* + * Macro guard for whether to use default weak IRQ implementation in drivers + */ +#ifndef FSL_DRIVER_TRANSFER_DOUBLE_WEAK_IRQ +#define FSL_DRIVER_TRANSFER_DOUBLE_WEAK_IRQ 1 +#endif + +/*! @name Min/max macros */ +/* @{ */ +#if !defined(MIN) +#define MIN(a, b) ((a) < (b) ? (a) : (b)) +#endif + +#if !defined(MAX) +#define MAX(a, b) ((a) > (b) ? (a) : (b)) +#endif +/* @} */ + +/*! @brief Computes the number of elements in an array. */ +#if !defined(ARRAY_SIZE) +#define ARRAY_SIZE(x) (sizeof(x) / sizeof((x)[0])) +#endif + +/*! @name UINT16_MAX/UINT32_MAX value */ +/* @{ */ +#if !defined(UINT16_MAX) +#define UINT16_MAX ((uint16_t)-1) +#endif + +#if !defined(UINT32_MAX) +#define UINT32_MAX ((uint32_t)-1) +#endif +/* @} */ + +/*! @name Timer utilities */ +/* @{ */ +/*! Macro to convert a microsecond period to raw count value */ +#define USEC_TO_COUNT(us, clockFreqInHz) (uint64_t)((uint64_t)us * clockFreqInHz / 1000000U) +/*! Macro to convert a raw count value to microsecond */ +#define COUNT_TO_USEC(count, clockFreqInHz) (uint64_t)((uint64_t)count * 1000000U / clockFreqInHz) + +/*! Macro to convert a millisecond period to raw count value */ +#define MSEC_TO_COUNT(ms, clockFreqInHz) (uint64_t)((uint64_t)ms * clockFreqInHz / 1000U) +/*! Macro to convert a raw count value to millisecond */ +#define COUNT_TO_MSEC(count, clockFreqInHz) (uint64_t)((uint64_t)count * 1000U / clockFreqInHz) +/* @} */ + +/*! @name Alignment variable definition macros */ +/* @{ */ +#if (defined(__ICCARM__)) +/** + * Workaround to disable MISRA C message suppress warnings for IAR compiler. + * http://supp.iar.com/Support/?note=24725 + */ +_Pragma("diag_suppress=Pm120") +#define SDK_PRAGMA(x) _Pragma(#x) + _Pragma("diag_error=Pm120") +/*! Macro to define a variable with alignbytes alignment */ +#define SDK_ALIGN(var, alignbytes) SDK_PRAGMA(data_alignment = alignbytes) var +/*! Macro to define a variable with L1 d-cache line size alignment */ +#if defined(FSL_FEATURE_L1DCACHE_LINESIZE_BYTE) +#define SDK_L1DCACHE_ALIGN(var) SDK_PRAGMA(data_alignment = FSL_FEATURE_L1DCACHE_LINESIZE_BYTE) var +#endif +/*! Macro to define a variable with L2 cache line size alignment */ +#if defined(FSL_FEATURE_L2CACHE_LINESIZE_BYTE) +#define SDK_L2CACHE_ALIGN(var) SDK_PRAGMA(data_alignment = FSL_FEATURE_L2CACHE_LINESIZE_BYTE) var +#endif +#elif defined(__ARMCC_VERSION) +/*! Macro to define a variable with alignbytes alignment */ +#define SDK_ALIGN(var, alignbytes) __align(alignbytes) var +/*! Macro to define a variable with L1 d-cache line size alignment */ +#if defined(FSL_FEATURE_L1DCACHE_LINESIZE_BYTE) +#define SDK_L1DCACHE_ALIGN(var) __align(FSL_FEATURE_L1DCACHE_LINESIZE_BYTE) var +#endif +/*! Macro to define a variable with L2 cache line size alignment */ +#if defined(FSL_FEATURE_L2CACHE_LINESIZE_BYTE) +#define SDK_L2CACHE_ALIGN(var) __align(FSL_FEATURE_L2CACHE_LINESIZE_BYTE) var +#endif +#elif defined(__GNUC__) +/*! Macro to define a variable with alignbytes alignment */ +#define SDK_ALIGN(var, alignbytes) var __attribute__((aligned(alignbytes))) +/*! Macro to define a variable with L1 d-cache line size alignment */ +#if defined(FSL_FEATURE_L1DCACHE_LINESIZE_BYTE) +#define SDK_L1DCACHE_ALIGN(var) var __attribute__((aligned(FSL_FEATURE_L1DCACHE_LINESIZE_BYTE))) +#endif +/*! Macro to define a variable with L2 cache line size alignment */ +#if defined(FSL_FEATURE_L2CACHE_LINESIZE_BYTE) +#define SDK_L2CACHE_ALIGN(var) var __attribute__((aligned(FSL_FEATURE_L2CACHE_LINESIZE_BYTE))) +#endif +#else +#error Toolchain not supported +#define SDK_ALIGN(var, alignbytes) var +#if defined(FSL_FEATURE_L1DCACHE_LINESIZE_BYTE) +#define SDK_L1DCACHE_ALIGN(var) var +#endif +#if defined(FSL_FEATURE_L2CACHE_LINESIZE_BYTE) +#define SDK_L2CACHE_ALIGN(var) var +#endif +#endif + +/*! Macro to change a value to a given size aligned value */ +#define SDK_SIZEALIGN(var, alignbytes) \ + ((unsigned int)((var) + ((alignbytes)-1)) & (unsigned int)(~(unsigned int)((alignbytes)-1))) +/* @} */ + +/*! @name Non-cacheable region definition macros */ +/* For initialized non-zero non-cacheable variables, please using "AT_NONCACHEABLE_SECTION_INIT(var) ={xx};" or + * "AT_NONCACHEABLE_SECTION_ALIGN_INIT(var) ={xx};" in your projects to define them, for zero-inited non-cacheable variables, + * please using "AT_NONCACHEABLE_SECTION(var);" or "AT_NONCACHEABLE_SECTION_ALIGN(var);" to define them, these zero-inited variables + * will be initialized to zero in system startup. + */ +/* @{ */ +#if (defined(__ICCARM__)) +#if defined(FSL_FEATURE_L1ICACHE_LINESIZE_BYTE) +#define AT_NONCACHEABLE_SECTION(var) var @"NonCacheable" +#define AT_NONCACHEABLE_SECTION_ALIGN(var, alignbytes) SDK_PRAGMA(data_alignment = alignbytes) var @"NonCacheable" +#define AT_NONCACHEABLE_SECTION_INIT(var) var @"NonCacheable.init" +#define AT_NONCACHEABLE_SECTION_ALIGN_INIT(var, alignbytes) SDK_PRAGMA(data_alignment = alignbytes) var @"NonCacheable.init" +#else +#define AT_NONCACHEABLE_SECTION(var) var +#define AT_NONCACHEABLE_SECTION_ALIGN(var, alignbytes) SDK_PRAGMA(data_alignment = alignbytes) var +#define AT_NONCACHEABLE_SECTION_INIT(var) var +#define AT_NONCACHEABLE_SECTION_ALIGN_INIT(var, alignbytes) SDK_PRAGMA(data_alignment = alignbytes) var +#endif +#elif(defined(__ARMCC_VERSION)) +#if defined(FSL_FEATURE_L1ICACHE_LINESIZE_BYTE) +#define AT_NONCACHEABLE_SECTION(var) __attribute__((section("NonCacheable"), zero_init)) var +#define AT_NONCACHEABLE_SECTION_ALIGN(var, alignbytes) \ + __attribute__((section("NonCacheable"), zero_init)) __align(alignbytes) var +#define AT_NONCACHEABLE_SECTION_INIT(var) __attribute__((section("NonCacheable.init"))) var +#define AT_NONCACHEABLE_SECTION_ALIGN_INIT(var, alignbytes) \ + __attribute__((section("NonCacheable.init"))) __align(alignbytes) var +#else +#define AT_NONCACHEABLE_SECTION(var) var +#define AT_NONCACHEABLE_SECTION_ALIGN(var, alignbytes) __align(alignbytes) var +#define AT_NONCACHEABLE_SECTION_INIT(var) var +#define AT_NONCACHEABLE_SECTION_ALIGN_INIT(var, alignbytes) __align(alignbytes) var +#endif +#elif(defined(__GNUC__)) +/* For GCC, when the non-cacheable section is required, please define "__STARTUP_INITIALIZE_NONCACHEDATA" + * in your projects to make sure the non-cacheable section variables will be initialized in system startup. + */ +#if defined(FSL_FEATURE_L1ICACHE_LINESIZE_BYTE) +#define AT_NONCACHEABLE_SECTION_INIT(var) __attribute__((section("NonCacheable.init"))) var +#define AT_NONCACHEABLE_SECTION_ALIGN_INIT(var, alignbytes) \ + __attribute__((section("NonCacheable.init"))) var __attribute__((aligned(alignbytes))) +#define AT_NONCACHEABLE_SECTION(var) __attribute__((section("NonCacheable,\"aw\",%nobits @"))) var +#define AT_NONCACHEABLE_SECTION_ALIGN(var, alignbytes) \ + __attribute__((section("NonCacheable,\"aw\",%nobits @"))) var __attribute__((aligned(alignbytes))) +#else +#define AT_NONCACHEABLE_SECTION(var) var +#define AT_NONCACHEABLE_SECTION_ALIGN(var, alignbytes) var __attribute__((aligned(alignbytes))) +#define AT_NONCACHEABLE_SECTION_INIT(var) var +#define AT_NONCACHEABLE_SECTION_ALIGN_INIT(var, alignbytes) var __attribute__((aligned(alignbytes))) +#endif +#else +#error Toolchain not supported. +#define AT_NONCACHEABLE_SECTION(var) var +#define AT_NONCACHEABLE_SECTION_ALIGN(var, alignbytes) var +#define AT_NONCACHEABLE_SECTION_INIT(var) var +#define AT_NONCACHEABLE_SECTION_ALIGN_INIT(var, alignbytes) var +#endif +/* @} */ + +/*! @name Time sensitive region */ +/* @{ */ +#if defined(FSL_SDK_DRIVER_QUICK_ACCESS_ENABLE) && FSL_SDK_DRIVER_QUICK_ACCESS_ENABLE +#if (defined(__ICCARM__)) +#define AT_QUICKACCESS_SECTION_CODE(func) func @"CodeQuickAccess" +#define AT_QUICKACCESS_SECTION_DATA(func) func @"DataQuickAccess" +#elif(defined(__ARMCC_VERSION)) +#define AT_QUICKACCESS_SECTION_CODE(func) __attribute__((section("CodeQuickAccess"))) func +#define AT_QUICKACCESS_SECTION_DATA(func) __attribute__((section("DataQuickAccess"))) func +#elif(defined(__GNUC__)) +#define AT_QUICKACCESS_SECTION_CODE(func) __attribute__((section("CodeQuickAccess"))) func +#define AT_QUICKACCESS_SECTION_DATA(func) __attribute__((section("DataQuickAccess"))) func +#else +#error Toolchain not supported. +#endif /* defined(__ICCARM__) */ +#else +#if (defined(__ICCARM__)) +#define AT_QUICKACCESS_SECTION_CODE(func) func +#define AT_QUICKACCESS_SECTION_DATA(func) func +#elif(defined(__ARMCC_VERSION)) +#define AT_QUICKACCESS_SECTION_CODE(func) func +#define AT_QUICKACCESS_SECTION_DATA(func) func +#elif(defined(__GNUC__)) +#define AT_QUICKACCESS_SECTION_CODE(func) func +#define AT_QUICKACCESS_SECTION_DATA(func) func +#else +#error Toolchain not supported. +#endif +#endif /* __FSL_SDK_DRIVER_QUICK_ACCESS_ENABLE */ +/* @} */ + +/******************************************************************************* + * API + ******************************************************************************/ + +#if defined(__cplusplus) + extern "C" +{ +#endif + + /*! + * @brief Enable specific interrupt. + * + * Enable LEVEL1 interrupt. For some devices, there might be multiple interrupt + * levels. For example, there are NVIC and intmux. Here the interrupts connected + * to NVIC are the LEVEL1 interrupts, because they are routed to the core directly. + * The interrupts connected to intmux are the LEVEL2 interrupts, they are routed + * to NVIC first then routed to core. + * + * This function only enables the LEVEL1 interrupts. The number of LEVEL1 interrupts + * is indicated by the feature macro FSL_FEATURE_NUMBER_OF_LEVEL1_INT_VECTORS. + * + * @param interrupt The IRQ number. + * @retval kStatus_Success Interrupt enabled successfully + * @retval kStatus_Fail Failed to enable the interrupt + */ + static inline status_t EnableIRQ(IRQn_Type interrupt) + { + if (NotAvail_IRQn == interrupt) + { + return kStatus_Fail; + } + +#if defined(FSL_FEATURE_NUMBER_OF_LEVEL1_INT_VECTORS) && (FSL_FEATURE_NUMBER_OF_LEVEL1_INT_VECTORS > 0) + if (interrupt >= FSL_FEATURE_NUMBER_OF_LEVEL1_INT_VECTORS) + { + return kStatus_Fail; + } +#endif + +#if defined(__GIC_PRIO_BITS) + GIC_EnableIRQ(interrupt); +#else + NVIC_EnableIRQ(interrupt); +#endif + return kStatus_Success; + } + + /*! + * @brief Disable specific interrupt. + * + * Disable LEVEL1 interrupt. For some devices, there might be multiple interrupt + * levels. For example, there are NVIC and intmux. Here the interrupts connected + * to NVIC are the LEVEL1 interrupts, because they are routed to the core directly. + * The interrupts connected to intmux are the LEVEL2 interrupts, they are routed + * to NVIC first then routed to core. + * + * This function only disables the LEVEL1 interrupts. The number of LEVEL1 interrupts + * is indicated by the feature macro FSL_FEATURE_NUMBER_OF_LEVEL1_INT_VECTORS. + * + * @param interrupt The IRQ number. + * @retval kStatus_Success Interrupt disabled successfully + * @retval kStatus_Fail Failed to disable the interrupt + */ + static inline status_t DisableIRQ(IRQn_Type interrupt) + { + if (NotAvail_IRQn == interrupt) + { + return kStatus_Fail; + } + +#if defined(FSL_FEATURE_NUMBER_OF_LEVEL1_INT_VECTORS) && (FSL_FEATURE_NUMBER_OF_LEVEL1_INT_VECTORS > 0) + if (interrupt >= FSL_FEATURE_NUMBER_OF_LEVEL1_INT_VECTORS) + { + return kStatus_Fail; + } +#endif + +#if defined(__GIC_PRIO_BITS) + GIC_DisableIRQ(interrupt); +#else + NVIC_DisableIRQ(interrupt); +#endif + return kStatus_Success; + } + + /*! + * @brief Disable the global IRQ + * + * Disable the global interrupt and return the current primask register. User is required to provided the primask + * register for the EnableGlobalIRQ(). + * + * @return Current primask value. + */ + static inline uint32_t DisableGlobalIRQ(void) + { +#if defined(CPSR_I_Msk) + uint32_t cpsr = __get_CPSR() & CPSR_I_Msk; + + __disable_irq(); + + return cpsr; +#else + uint32_t regPrimask = __get_PRIMASK(); + + __disable_irq(); + + return regPrimask; +#endif + } + + /*! + * @brief Enaable the global IRQ + * + * Set the primask register with the provided primask value but not just enable the primask. The idea is for the + * convinience of integration of RTOS. some RTOS get its own management mechanism of primask. User is required to + * use the EnableGlobalIRQ() and DisableGlobalIRQ() in pair. + * + * @param primask value of primask register to be restored. The primask value is supposed to be provided by the + * DisableGlobalIRQ(). + */ + static inline void EnableGlobalIRQ(uint32_t primask) + { +#if defined(CPSR_I_Msk) + __set_CPSR((__get_CPSR() & ~CPSR_I_Msk) | primask); +#else + __set_PRIMASK(primask); +#endif + } + +#if defined(ENABLE_RAM_VECTOR_TABLE) + /*! + * @brief install IRQ handler + * + * @param irq IRQ number + * @param irqHandler IRQ handler address + * @return The old IRQ handler address + */ + uint32_t InstallIRQHandler(IRQn_Type irq, uint32_t irqHandler); +#endif /* ENABLE_RAM_VECTOR_TABLE. */ + +#if (defined(FSL_FEATURE_SOC_SYSCON_COUNT) && (FSL_FEATURE_SOC_SYSCON_COUNT > 0)) + /*! + * @brief Enable specific interrupt for wake-up from deep-sleep mode. + * + * Enable the interrupt for wake-up from deep sleep mode. + * Some interrupts are typically used in sleep mode only and will not occur during + * deep-sleep mode because relevant clocks are stopped. However, it is possible to enable + * those clocks (significantly increasing power consumption in the reduced power mode), + * making these wake-ups possible. + * + * @note This function also enables the interrupt in the NVIC (EnableIRQ() is called internally). + * + * @param interrupt The IRQ number. + */ + void EnableDeepSleepIRQ(IRQn_Type interrupt); + + /*! + * @brief Disable specific interrupt for wake-up from deep-sleep mode. + * + * Disable the interrupt for wake-up from deep sleep mode. + * Some interrupts are typically used in sleep mode only and will not occur during + * deep-sleep mode because relevant clocks are stopped. However, it is possible to enable + * those clocks (significantly increasing power consumption in the reduced power mode), + * making these wake-ups possible. + * + * @note This function also disables the interrupt in the NVIC (DisableIRQ() is called internally). + * + * @param interrupt The IRQ number. + */ + void DisableDeepSleepIRQ(IRQn_Type interrupt); +#endif /* FSL_FEATURE_SOC_SYSCON_COUNT */ + + /*! + * @brief Allocate memory with given alignment and aligned size. + * + * This is provided to support the dynamically allocated memory + * used in cache-able region. + * @param size The length required to malloc. + * @param alignbytes The alignment size. + * @retval The allocated memory. + */ + void *SDK_Malloc(size_t size, size_t alignbytes); + + /*! + * @brief Free memory. + * + * @param ptr The memory to be release. + */ + void SDK_Free(void *ptr); + +#if defined(__cplusplus) +} +#endif + +/*! @} */ + +#endif /* _FSL_COMMON_H_ */ diff --git a/drivers/fsl_crc.c b/drivers/fsl_crc.c new file mode 100644 index 0000000..4c942a5 --- /dev/null +++ b/drivers/fsl_crc.c @@ -0,0 +1,292 @@ +/* + * The Clear BSD License + * Copyright (c) 2015-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: + * + * o Redistributions of source code must retain the above copyright notice, this list + * of conditions and the following disclaimer. + * + * o 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. + * + * o 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. + */ +#include "fsl_crc.h" + +/******************************************************************************* + * Definitions + ******************************************************************************/ + +/* Component ID definition, used by tools. */ +#ifndef FSL_COMPONENT_ID +#define FSL_COMPONENT_ID "platform.drivers.crc" +#endif + +/*! @internal @brief Has data register with name CRC. */ +#if defined(FSL_FEATURE_CRC_HAS_CRC_REG) && FSL_FEATURE_CRC_HAS_CRC_REG +#define DATA CRC +#define DATALL CRCLL +#endif + +#if defined(CRC_DRIVER_USE_CRC16_CCIT_FALSE_AS_DEFAULT) && CRC_DRIVER_USE_CRC16_CCIT_FALSE_AS_DEFAULT +/* @brief Default user configuration structure for CRC-16-CCITT */ +#define CRC_DRIVER_DEFAULT_POLYNOMIAL 0x1021U +/*< CRC-16-CCIT polynomial x**16 + x**12 + x**5 + x**0 */ +#define CRC_DRIVER_DEFAULT_SEED 0xFFFFU +/*< Default initial checksum */ +#define CRC_DRIVER_DEFAULT_REFLECT_IN false +/*< Default is no transpose */ +#define CRC_DRIVER_DEFAULT_REFLECT_OUT false +/*< Default is transpose bytes */ +#define CRC_DRIVER_DEFAULT_COMPLEMENT_CHECKSUM false +/*< Default is without complement of CRC data register read data */ +#define CRC_DRIVER_DEFAULT_CRC_BITS kCrcBits16 +/*< Default is 16-bit CRC protocol */ +#define CRC_DRIVER_DEFAULT_CRC_RESULT kCrcFinalChecksum +/*< Default is resutl type is final checksum */ +#endif /* CRC_DRIVER_USE_CRC16_CCIT_FALSE_AS_DEFAULT */ + +/*! @brief CRC type of transpose of read write data */ +typedef enum _crc_transpose_type +{ + kCrcTransposeNone = 0U, /*! No transpose */ + kCrcTransposeBits = 1U, /*! Tranpose bits in bytes */ + kCrcTransposeBitsAndBytes = 2U, /*! Transpose bytes and bits in bytes */ + kCrcTransposeBytes = 3U, /*! Transpose bytes */ +} crc_transpose_type_t; + +/*! +* @brief CRC module configuration. +* +* This structure holds the configuration for the CRC module. +*/ +typedef struct _crc_module_config +{ + uint32_t polynomial; /*!< CRC Polynomial, MSBit first.@n + Example polynomial: 0x1021 = 1_0000_0010_0001 = x^12+x^5+1 */ + uint32_t seed; /*!< Starting checksum value */ + crc_transpose_type_t readTranspose; /*!< Type of transpose when reading CRC result. */ + crc_transpose_type_t writeTranspose; /*!< Type of transpose when writing CRC input data. */ + bool complementChecksum; /*!< True if the result shall be complement of the actual checksum. */ + crc_bits_t crcBits; /*!< Selects 16- or 32- bit CRC protocol. */ +} crc_module_config_t; + +/******************************************************************************* + * Code + ******************************************************************************/ + +/*! + * @brief Returns transpose type for CRC protocol reflect in parameter. + * + * This functions helps to set writeTranspose member of crc_config_t structure. Reflect in is CRC protocol parameter. + * + * @param enable True or false for the selected CRC protocol Reflect In (refin) parameter. + */ +static inline crc_transpose_type_t CRC_GetTransposeTypeFromReflectIn(bool enable) +{ + return ((enable) ? kCrcTransposeBitsAndBytes : kCrcTransposeBytes); +} + +/*! + * @brief Returns transpose type for CRC protocol reflect out parameter. + * + * This functions helps to set readTranspose member of crc_config_t structure. Reflect out is CRC protocol parameter. + * + * @param enable True or false for the selected CRC protocol Reflect Out (refout) parameter. + */ +static inline crc_transpose_type_t CRC_GetTransposeTypeFromReflectOut(bool enable) +{ + return ((enable) ? kCrcTransposeBitsAndBytes : kCrcTransposeNone); +} + +/*! + * @brief Starts checksum computation. + * + * Configures the CRC module for the specified CRC protocol. @n + * Starts the checksum computation by writing the seed value + * + * @param base CRC peripheral address. + * @param config Pointer to protocol configuration structure. + */ +static void CRC_ConfigureAndStart(CRC_Type *base, const crc_module_config_t *config) +{ + uint32_t crcControl; + + /* pre-compute value for CRC control registger based on user configuraton without WAS field */ + crcControl = 0 | CRC_CTRL_TOT(config->writeTranspose) | CRC_CTRL_TOTR(config->readTranspose) | + CRC_CTRL_FXOR(config->complementChecksum) | CRC_CTRL_TCRC(config->crcBits); + + /* make sure the control register is clear - WAS is deasserted, and protocol is set */ + base->CTRL = crcControl; + + /* write polynomial register */ + base->GPOLY = config->polynomial; + + /* write pre-computed control register value along with WAS to start checksum computation */ + base->CTRL = crcControl | CRC_CTRL_WAS(true); + + /* write seed (initial checksum) */ + base->DATA = config->seed; + + /* deassert WAS by writing pre-computed CRC control register value */ + base->CTRL = crcControl; +} + +/*! + * @brief Starts final checksum computation. + * + * Configures the CRC module for the specified CRC protocol. @n + * Starts final checksum computation by writing the seed value. + * @note CRC_Get16bitResult() or CRC_Get32bitResult() return final checksum + * (output reflection and xor functions are applied). + * + * @param base CRC peripheral address. + * @param protocolConfig Pointer to protocol configuration structure. + */ +static void CRC_SetProtocolConfig(CRC_Type *base, const crc_config_t *protocolConfig) +{ + crc_module_config_t moduleConfig; + /* convert protocol to CRC peripheral module configuration, prepare for final checksum */ + moduleConfig.polynomial = protocolConfig->polynomial; + moduleConfig.seed = protocolConfig->seed; + moduleConfig.readTranspose = CRC_GetTransposeTypeFromReflectOut(protocolConfig->reflectOut); + moduleConfig.writeTranspose = CRC_GetTransposeTypeFromReflectIn(protocolConfig->reflectIn); + moduleConfig.complementChecksum = protocolConfig->complementChecksum; + moduleConfig.crcBits = protocolConfig->crcBits; + + CRC_ConfigureAndStart(base, &moduleConfig); +} + +/*! + * @brief Starts intermediate checksum computation. + * + * Configures the CRC module for the specified CRC protocol. @n + * Starts intermediate checksum computation by writing the seed value. + * @note CRC_Get16bitResult() or CRC_Get32bitResult() return intermediate checksum (raw data register value). + * + * @param base CRC peripheral address. + * @param protocolConfig Pointer to protocol configuration structure. + */ +static void CRC_SetRawProtocolConfig(CRC_Type *base, const crc_config_t *protocolConfig) +{ + crc_module_config_t moduleConfig; + /* convert protocol to CRC peripheral module configuration, prepare for intermediate checksum */ + moduleConfig.polynomial = protocolConfig->polynomial; + moduleConfig.seed = protocolConfig->seed; + moduleConfig.readTranspose = + kCrcTransposeNone; /* intermediate checksum does no transpose of data register read value */ + moduleConfig.writeTranspose = CRC_GetTransposeTypeFromReflectIn(protocolConfig->reflectIn); + moduleConfig.complementChecksum = false; /* intermediate checksum does no xor of data register read value */ + moduleConfig.crcBits = protocolConfig->crcBits; + + CRC_ConfigureAndStart(base, &moduleConfig); +} + +void CRC_Init(CRC_Type *base, const crc_config_t *config) +{ +#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) + /* ungate clock */ + CLOCK_EnableClock(kCLOCK_Crc0); +#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */ + /* configure CRC module and write the seed */ + if (config->crcResult == kCrcFinalChecksum) + { + CRC_SetProtocolConfig(base, config); + } + else + { + CRC_SetRawProtocolConfig(base, config); + } +} + +void CRC_GetDefaultConfig(crc_config_t *config) +{ + static const crc_config_t crc16ccit = { + CRC_DRIVER_DEFAULT_POLYNOMIAL, CRC_DRIVER_DEFAULT_SEED, + CRC_DRIVER_DEFAULT_REFLECT_IN, CRC_DRIVER_DEFAULT_REFLECT_OUT, + CRC_DRIVER_DEFAULT_COMPLEMENT_CHECKSUM, CRC_DRIVER_DEFAULT_CRC_BITS, + CRC_DRIVER_DEFAULT_CRC_RESULT, + }; + + *config = crc16ccit; +} + +void CRC_WriteData(CRC_Type *base, const uint8_t *data, size_t dataSize) +{ + const uint32_t *data32; + + /* 8-bit reads and writes till source address is aligned 4 bytes */ + while ((dataSize) && ((uint32_t)data & 3U)) + { + base->ACCESS8BIT.DATALL = *data; + data++; + dataSize--; + } + + /* use 32-bit reads and writes as long as possible */ + data32 = (const uint32_t *)data; + while (dataSize >= sizeof(uint32_t)) + { + base->DATA = *data32; + data32++; + dataSize -= sizeof(uint32_t); + } + + data = (const uint8_t *)data32; + + /* 8-bit reads and writes till end of data buffer */ + while (dataSize) + { + base->ACCESS8BIT.DATALL = *data; + data++; + dataSize--; + } +} + +uint32_t CRC_Get32bitResult(CRC_Type *base) +{ + return base->DATA; +} + +uint16_t CRC_Get16bitResult(CRC_Type *base) +{ + uint32_t retval; + uint32_t totr; /* type of transpose read bitfield */ + + retval = base->DATA; + totr = (base->CTRL & CRC_CTRL_TOTR_MASK) >> CRC_CTRL_TOTR_SHIFT; + + /* check transpose type to get 16-bit out of 32-bit register */ + if (totr >= 2U) + { + /* transpose of bytes for read is set, the result CRC is in CRC_DATA[HU:HL] */ + retval &= 0xFFFF0000U; + retval = retval >> 16U; + } + else + { + /* no transpose of bytes for read, the result CRC is in CRC_DATA[LU:LL] */ + retval &= 0x0000FFFFU; + } + return (uint16_t)retval; +} diff --git a/drivers/fsl_crc.h b/drivers/fsl_crc.h new file mode 100644 index 0000000..7a2e8ab --- /dev/null +++ b/drivers/fsl_crc.h @@ -0,0 +1,197 @@ +/* + * The Clear BSD License + * Copyright (c) 2015-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: + * + * o Redistributions of source code must retain the above copyright notice, this list + * of conditions and the following disclaimer. + * + * o 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. + * + * o 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_CRC_H_ +#define _FSL_CRC_H_ + +#include "fsl_common.h" + +/*! + * @addtogroup crc + * @{ + */ + +/******************************************************************************* + * Definitions + ******************************************************************************/ + +/*! @name Driver version */ +/*@{*/ +/*! @brief CRC driver version. Version 2.0.1. + * + * Current version: 2.0.1 + * + * Change log: + * - Version 2.0.1 + * - move DATA and DATALL macro definition from header file to source file + */ +#define FSL_CRC_DRIVER_VERSION (MAKE_VERSION(2, 0, 1)) +/*@}*/ + +#ifndef CRC_DRIVER_CUSTOM_DEFAULTS +/*! @brief Default configuration structure filled by CRC_GetDefaultConfig(). Use CRC16-CCIT-FALSE as defeault. */ +#define CRC_DRIVER_USE_CRC16_CCIT_FALSE_AS_DEFAULT 1 +#endif + +/*! @brief CRC bit width */ +typedef enum _crc_bits +{ + kCrcBits16 = 0U, /*!< Generate 16-bit CRC code */ + kCrcBits32 = 1U /*!< Generate 32-bit CRC code */ +} crc_bits_t; + +/*! @brief CRC result type */ +typedef enum _crc_result +{ + kCrcFinalChecksum = 0U, /*!< CRC data register read value is the final checksum. + Reflect out and final xor protocol features are applied. */ + kCrcIntermediateChecksum = 1U /*!< CRC data register read value is intermediate checksum (raw value). + Reflect out and final xor protocol feature are not applied. + Intermediate checksum can be used as a seed for CRC_Init() + to continue adding data to this checksum. */ +} crc_result_t; + +/*! +* @brief CRC protocol configuration. +* +* This structure holds the configuration for the CRC protocol. +* +*/ +typedef struct _crc_config +{ + uint32_t polynomial; /*!< CRC Polynomial, MSBit first. + Example polynomial: 0x1021 = 1_0000_0010_0001 = x^12+x^5+1 */ + uint32_t seed; /*!< Starting checksum value */ + bool reflectIn; /*!< Reflect bits on input. */ + bool reflectOut; /*!< Reflect bits on output. */ + bool complementChecksum; /*!< True if the result shall be complement of the actual checksum. */ + crc_bits_t crcBits; /*!< Selects 16- or 32- bit CRC protocol. */ + crc_result_t crcResult; /*!< Selects final or intermediate checksum return from CRC_Get16bitResult() or + CRC_Get32bitResult() */ +} crc_config_t; + +/******************************************************************************* + * API + ******************************************************************************/ +#if defined(__cplusplus) +extern "C" { +#endif + +/*! + * @brief Enables and configures the CRC peripheral module. + * + * This function enables the clock gate in the SIM module for the CRC peripheral. + * It also configures the CRC module and starts a checksum computation by writing the seed. + * + * @param base CRC peripheral address. + * @param config CRC module configuration structure. + */ +void CRC_Init(CRC_Type *base, const crc_config_t *config); + +/*! + * @brief Disables the CRC peripheral module. + * + * This function disables the clock gate in the SIM module for the CRC peripheral. + * + * @param base CRC peripheral address. + */ +static inline void CRC_Deinit(CRC_Type *base) +{ +#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) + /* gate clock */ + CLOCK_DisableClock(kCLOCK_Crc0); +#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */ +} + +/*! + * @brief Loads default values to the CRC protocol configuration structure. + * + * Loads default values to the CRC protocol configuration structure. The default values are as follows. + * @code + * config->polynomial = 0x1021; + * config->seed = 0xFFFF; + * config->reflectIn = false; + * config->reflectOut = false; + * config->complementChecksum = false; + * config->crcBits = kCrcBits16; + * config->crcResult = kCrcFinalChecksum; + * @endcode + * + * @param config CRC protocol configuration structure. + */ +void CRC_GetDefaultConfig(crc_config_t *config); + +/*! + * @brief Writes data to the CRC module. + * + * Writes input data buffer bytes to the CRC data register. + * The configured type of transpose is applied. + * + * @param base CRC peripheral address. + * @param data Input data stream, MSByte in data[0]. + * @param dataSize Size in bytes of the input data buffer. + */ +void CRC_WriteData(CRC_Type *base, const uint8_t *data, size_t dataSize); + +/*! + * @brief Reads the 32-bit checksum from the CRC module. + * + * Reads the CRC data register (either an intermediate or the final checksum). + * The configured type of transpose and complement is applied. + * + * @param base CRC peripheral address. + * @return An intermediate or the final 32-bit checksum, after configured transpose and complement operations. + */ +uint32_t CRC_Get32bitResult(CRC_Type *base); + +/*! + * @brief Reads a 16-bit checksum from the CRC module. + * + * Reads the CRC data register (either an intermediate or the final checksum). + * The configured type of transpose and complement is applied. + * + * @param base CRC peripheral address. + * @return An intermediate or the final 16-bit checksum, after configured transpose and complement operations. + */ +uint16_t CRC_Get16bitResult(CRC_Type *base); + +#if defined(__cplusplus) +} +#endif + +/*! + *@} + */ + +#endif /* _FSL_CRC_H_ */ diff --git a/drivers/fsl_dac.c b/drivers/fsl_dac.c new file mode 100644 index 0000000..74ac6eb --- /dev/null +++ b/drivers/fsl_dac.c @@ -0,0 +1,230 @@ +/* + * The Clear BSD License + * Copyright (c) 2015, 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: + * + * o Redistributions of source code must retain the above copyright notice, this list + * of conditions and the following disclaimer. + * + * o 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. + * + * o 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. + */ + +#include "fsl_dac.h" + +/* Component ID definition, used by tools. */ +#ifndef FSL_COMPONENT_ID +#define FSL_COMPONENT_ID "platform.drivers.dac" +#endif + + +/******************************************************************************* + * Prototypes + ******************************************************************************/ +/*! + * @brief Get instance number for DAC module. + * + * @param base DAC peripheral base address + */ +static uint32_t DAC_GetInstance(DAC_Type *base); + +/******************************************************************************* + * Variables + ******************************************************************************/ +/*! @brief Pointers to DAC bases for each instance. */ +static DAC_Type *const s_dacBases[] = DAC_BASE_PTRS; +#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) +/*! @brief Pointers to DAC clocks for each instance. */ +static const clock_ip_name_t s_dacClocks[] = DAC_CLOCKS; +#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */ + +/******************************************************************************* + * Codes + ******************************************************************************/ +static uint32_t DAC_GetInstance(DAC_Type *base) +{ + uint32_t instance; + + /* Find the instance index from base address mappings. */ + for (instance = 0; instance < ARRAY_SIZE(s_dacBases); instance++) + { + if (s_dacBases[instance] == base) + { + break; + } + } + + assert(instance < ARRAY_SIZE(s_dacBases)); + + return instance; +} + +void DAC_Init(DAC_Type *base, const dac_config_t *config) +{ + assert(NULL != config); + + uint8_t tmp8; + +#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) + /* Enable the clock. */ + CLOCK_EnableClock(s_dacClocks[DAC_GetInstance(base)]); +#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */ + + /* Configure. */ + /* DACx_C0. */ + tmp8 = base->C0 & ~(DAC_C0_DACRFS_MASK | DAC_C0_LPEN_MASK); + if (kDAC_ReferenceVoltageSourceVref2 == config->referenceVoltageSource) + { + tmp8 |= DAC_C0_DACRFS_MASK; + } + if (config->enableLowPowerMode) + { + tmp8 |= DAC_C0_LPEN_MASK; + } + base->C0 = tmp8; + + /* DAC_Enable(base, true); */ + /* Tip: The DAC output can be enabled till then after user sets their own available data in application. */ +} + +void DAC_Deinit(DAC_Type *base) +{ + DAC_Enable(base, false); + +#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) + /* Disable the clock. */ + CLOCK_DisableClock(s_dacClocks[DAC_GetInstance(base)]); +#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */ +} + +void DAC_GetDefaultConfig(dac_config_t *config) +{ + assert(NULL != config); + + config->referenceVoltageSource = kDAC_ReferenceVoltageSourceVref2; + config->enableLowPowerMode = false; +} + +void DAC_SetBufferConfig(DAC_Type *base, const dac_buffer_config_t *config) +{ + assert(NULL != config); + + uint8_t tmp8; + + /* DACx_C0. */ + tmp8 = base->C0 & ~(DAC_C0_DACTRGSEL_MASK); + if (kDAC_BufferTriggerBySoftwareMode == config->triggerMode) + { + tmp8 |= DAC_C0_DACTRGSEL_MASK; + } + base->C0 = tmp8; + + /* DACx_C1. */ + tmp8 = base->C1 & + ~( +#if defined(FSL_FEATURE_DAC_HAS_WATERMARK_SELECTION) && FSL_FEATURE_DAC_HAS_WATERMARK_SELECTION + DAC_C1_DACBFWM_MASK | +#endif /* FSL_FEATURE_DAC_HAS_WATERMARK_SELECTION */ + DAC_C1_DACBFMD_MASK); +#if defined(FSL_FEATURE_DAC_HAS_WATERMARK_SELECTION) && FSL_FEATURE_DAC_HAS_WATERMARK_SELECTION + tmp8 |= DAC_C1_DACBFWM(config->watermark); +#endif /* FSL_FEATURE_DAC_HAS_WATERMARK_SELECTION */ + tmp8 |= DAC_C1_DACBFMD(config->workMode); + base->C1 = tmp8; + + /* DACx_C2. */ + tmp8 = base->C2 & ~DAC_C2_DACBFUP_MASK; + tmp8 |= DAC_C2_DACBFUP(config->upperLimit); + base->C2 = tmp8; +} + +void DAC_GetDefaultBufferConfig(dac_buffer_config_t *config) +{ + assert(NULL != config); + + config->triggerMode = kDAC_BufferTriggerBySoftwareMode; +#if defined(FSL_FEATURE_DAC_HAS_WATERMARK_SELECTION) && FSL_FEATURE_DAC_HAS_WATERMARK_SELECTION + config->watermark = kDAC_BufferWatermark1Word; +#endif /* FSL_FEATURE_DAC_HAS_WATERMARK_SELECTION */ + config->workMode = kDAC_BufferWorkAsNormalMode; + config->upperLimit = DAC_DATL_COUNT - 1U; +} + +void DAC_SetBufferValue(DAC_Type *base, uint8_t index, uint16_t value) +{ + assert(index < DAC_DATL_COUNT); + + base->DAT[index].DATL = (uint8_t)(0xFFU & value); /* Low 8-bit. */ + base->DAT[index].DATH = (uint8_t)((0xF00U & value) >> 8); /* High 4-bit. */ +} + +void DAC_SetBufferReadPointer(DAC_Type *base, uint8_t index) +{ + assert(index < DAC_DATL_COUNT); + + uint8_t tmp8 = base->C2 & ~DAC_C2_DACBFRP_MASK; + + tmp8 |= DAC_C2_DACBFRP(index); + base->C2 = tmp8; +} + +void DAC_EnableBufferInterrupts(DAC_Type *base, uint32_t mask) +{ + mask &= ( +#if defined(FSL_FEATURE_DAC_HAS_WATERMARK_DETECTION) && FSL_FEATURE_DAC_HAS_WATERMARK_DETECTION + DAC_C0_DACBWIEN_MASK | +#endif /* FSL_FEATURE_DAC_HAS_WATERMARK_DETECTION */ + DAC_C0_DACBTIEN_MASK | DAC_C0_DACBBIEN_MASK); + base->C0 |= ((uint8_t)mask); /* Write 1 to enable. */ +} + +void DAC_DisableBufferInterrupts(DAC_Type *base, uint32_t mask) +{ + mask &= ( +#if defined(FSL_FEATURE_DAC_HAS_WATERMARK_DETECTION) && FSL_FEATURE_DAC_HAS_WATERMARK_DETECTION + DAC_C0_DACBWIEN_MASK | +#endif /* FSL_FEATURE_DAC_HAS_WATERMARK_DETECTION */ + DAC_C0_DACBTIEN_MASK | DAC_C0_DACBBIEN_MASK); + base->C0 &= (uint8_t)(~((uint8_t)mask)); /* Write 0 to disable. */ +} + +uint32_t DAC_GetBufferStatusFlags(DAC_Type *base) +{ + return (uint32_t)(base->SR & ( +#if defined(FSL_FEATURE_DAC_HAS_WATERMARK_DETECTION) && FSL_FEATURE_DAC_HAS_WATERMARK_DETECTION + DAC_SR_DACBFWMF_MASK | +#endif /* FSL_FEATURE_DAC_HAS_WATERMARK_DETECTION */ + DAC_SR_DACBFRPTF_MASK | DAC_SR_DACBFRPBF_MASK)); +} + +void DAC_ClearBufferStatusFlags(DAC_Type *base, uint32_t mask) +{ + mask &= ( +#if defined(FSL_FEATURE_DAC_HAS_WATERMARK_DETECTION) && FSL_FEATURE_DAC_HAS_WATERMARK_DETECTION + DAC_SR_DACBFWMF_MASK | +#endif /* FSL_FEATURE_DAC_HAS_WATERMARK_DETECTION */ + DAC_SR_DACBFRPTF_MASK | DAC_SR_DACBFRPBF_MASK); + base->SR &= (uint8_t)(~((uint8_t)mask)); /* Write 0 to clear flags. */ +} diff --git a/drivers/fsl_dac.h b/drivers/fsl_dac.h new file mode 100644 index 0000000..2fd2afe --- /dev/null +++ b/drivers/fsl_dac.h @@ -0,0 +1,382 @@ +/* + * The Clear BSD License + * Copyright (c) 2015, 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: + * + * o Redistributions of source code must retain the above copyright notice, this list + * of conditions and the following disclaimer. + * + * o 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. + * + * o 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_DAC_H_ +#define _FSL_DAC_H_ + +#include "fsl_common.h" + +/*! + * @addtogroup dac + * @{ + */ + + +/******************************************************************************* + * Definitions + ******************************************************************************/ + +/*! @name Driver version */ +/*@{*/ +/*! @brief DAC driver version 2.0.1. */ +#define FSL_DAC_DRIVER_VERSION (MAKE_VERSION(2, 0, 1)) +/*@}*/ + +/*! + * @brief DAC buffer flags. + */ +enum _dac_buffer_status_flags +{ +#if defined(FSL_FEATURE_DAC_HAS_WATERMARK_DETECTION) && FSL_FEATURE_DAC_HAS_WATERMARK_DETECTION + kDAC_BufferWatermarkFlag = DAC_SR_DACBFWMF_MASK, /*!< DAC Buffer Watermark Flag. */ +#endif /* FSL_FEATURE_DAC_HAS_WATERMARK_DETECTION */ + kDAC_BufferReadPointerTopPositionFlag = DAC_SR_DACBFRPTF_MASK, /*!< DAC Buffer Read Pointer Top Position Flag. */ + kDAC_BufferReadPointerBottomPositionFlag = DAC_SR_DACBFRPBF_MASK, /*!< DAC Buffer Read Pointer Bottom Position + Flag. */ +}; + +/*! + * @brief DAC buffer interrupts. + */ +enum _dac_buffer_interrupt_enable +{ +#if defined(FSL_FEATURE_DAC_HAS_WATERMARK_DETECTION) && FSL_FEATURE_DAC_HAS_WATERMARK_DETECTION + kDAC_BufferWatermarkInterruptEnable = DAC_C0_DACBWIEN_MASK, /*!< DAC Buffer Watermark Interrupt Enable. */ +#endif /* FSL_FEATURE_DAC_HAS_WATERMARK_DETECTION */ + kDAC_BufferReadPointerTopInterruptEnable = DAC_C0_DACBTIEN_MASK, /*!< DAC Buffer Read Pointer Top Flag Interrupt + Enable. */ + kDAC_BufferReadPointerBottomInterruptEnable = DAC_C0_DACBBIEN_MASK, /*!< DAC Buffer Read Pointer Bottom Flag + Interrupt Enable */ +}; + +/*! + * @brief DAC reference voltage source. + */ +typedef enum _dac_reference_voltage_source +{ + kDAC_ReferenceVoltageSourceVref1 = 0U, /*!< The DAC selects DACREF_1 as the reference voltage. */ + kDAC_ReferenceVoltageSourceVref2 = 1U, /*!< The DAC selects DACREF_2 as the reference voltage. */ +} dac_reference_voltage_source_t; + +/*! + * @brief DAC buffer trigger mode. + */ +typedef enum _dac_buffer_trigger_mode +{ + kDAC_BufferTriggerByHardwareMode = 0U, /*!< The DAC hardware trigger is selected. */ + kDAC_BufferTriggerBySoftwareMode = 1U, /*!< The DAC software trigger is selected. */ +} dac_buffer_trigger_mode_t; + +#if defined(FSL_FEATURE_DAC_HAS_WATERMARK_SELECTION) && FSL_FEATURE_DAC_HAS_WATERMARK_SELECTION +/*! + * @brief DAC buffer watermark. + */ +typedef enum _dac_buffer_watermark +{ +#if defined(FSL_FEATURE_DAC_HAS_WATERMARK_1_WORD) && FSL_FEATURE_DAC_HAS_WATERMARK_1_WORD + kDAC_BufferWatermark1Word = 0U, /*!< 1 word away from the upper limit. */ +#endif /* FSL_FEATURE_DAC_HAS_WATERMARK_1_WORD */ +#if defined(FSL_FEATURE_DAC_HAS_WATERMARK_2_WORDS) && FSL_FEATURE_DAC_HAS_WATERMARK_2_WORDS + kDAC_BufferWatermark2Word = 1U, /*!< 2 words away from the upper limit. */ +#endif /* FSL_FEATURE_DAC_HAS_WATERMARK_2_WORDS */ +#if defined(FSL_FEATURE_DAC_HAS_WATERMARK_3_WORDS) && FSL_FEATURE_DAC_HAS_WATERMARK_3_WORDS + kDAC_BufferWatermark3Word = 2U, /*!< 3 words away from the upper limit. */ +#endif /* FSL_FEATURE_DAC_HAS_WATERMARK_3_WORDS */ +#if defined(FSL_FEATURE_DAC_HAS_WATERMARK_4_WORDS) && FSL_FEATURE_DAC_HAS_WATERMARK_4_WORDS + kDAC_BufferWatermark4Word = 3U, /*!< 4 words away from the upper limit. */ +#endif /* FSL_FEATURE_DAC_HAS_WATERMARK_4_WORDS */ +} dac_buffer_watermark_t; +#endif /* FSL_FEATURE_DAC_HAS_WATERMARK_SELECTION */ + +/*! + * @brief DAC buffer work mode. + */ +typedef enum _dac_buffer_work_mode +{ + kDAC_BufferWorkAsNormalMode = 0U, /*!< Normal mode. */ +#if defined(FSL_FEATURE_DAC_HAS_BUFFER_SWING_MODE) && FSL_FEATURE_DAC_HAS_BUFFER_SWING_MODE + kDAC_BufferWorkAsSwingMode, /*!< Swing mode. */ +#endif /* FSL_FEATURE_DAC_HAS_BUFFER_SWING_MODE */ + kDAC_BufferWorkAsOneTimeScanMode, /*!< One-Time Scan mode. */ +#if defined(FSL_FEATURE_DAC_HAS_BUFFER_FIFO_MODE) && FSL_FEATURE_DAC_HAS_BUFFER_FIFO_MODE + kDAC_BufferWorkAsFIFOMode, /*!< FIFO mode. */ +#endif /* FSL_FEATURE_DAC_HAS_BUFFER_FIFO_MODE */ +} dac_buffer_work_mode_t; + +/*! + * @brief DAC module configuration. + */ +typedef struct _dac_config +{ + dac_reference_voltage_source_t referenceVoltageSource; /*!< Select the DAC reference voltage source. */ + bool enableLowPowerMode; /*!< Enable the low-power mode. */ +} dac_config_t; + +/*! + * @brief DAC buffer configuration. + */ +typedef struct _dac_buffer_config +{ + dac_buffer_trigger_mode_t triggerMode; /*!< Select the buffer's trigger mode. */ +#if defined(FSL_FEATURE_DAC_HAS_WATERMARK_SELECTION) && FSL_FEATURE_DAC_HAS_WATERMARK_SELECTION + dac_buffer_watermark_t watermark; /*!< Select the buffer's watermark. */ +#endif /* FSL_FEATURE_DAC_HAS_WATERMARK_SELECTION */ + dac_buffer_work_mode_t workMode; /*!< Select the buffer's work mode. */ + uint8_t upperLimit; /*!< Set the upper limit for the buffer index. + Normally, 0-15 is available for a buffer with 16 items. */ +} dac_buffer_config_t; + +/******************************************************************************* + * API + ******************************************************************************/ +#if defined(__cplusplus) +extern "C" { +#endif + +/*! + * @name Initialization + * @{ + */ + +/*! + * @brief Initializes the DAC module. + * + * This function initializes the DAC module including the following operations. + * - Enabling the clock for DAC module. + * - Configuring the DAC converter with a user configuration. + * - Enabling the DAC module. + * + * @param base DAC peripheral base address. + * @param config Pointer to the configuration structure. See "dac_config_t". + */ +void DAC_Init(DAC_Type *base, const dac_config_t *config); + +/*! + * @brief De-initializes the DAC module. + * + * This function de-initializes the DAC module including the following operations. + * - Disabling the DAC module. + * - Disabling the clock for the DAC module. + * + * @param base DAC peripheral base address. + */ +void DAC_Deinit(DAC_Type *base); + +/*! + * @brief Initializes the DAC user configuration structure. + * + * This function initializes the user configuration structure to a default value. The default values are as follows. + * @code + * config->referenceVoltageSource = kDAC_ReferenceVoltageSourceVref2; + * config->enableLowPowerMode = false; + * @endcode + * @param config Pointer to the configuration structure. See "dac_config_t". + */ +void DAC_GetDefaultConfig(dac_config_t *config); + +/*! + * @brief Enables the DAC module. + * + * @param base DAC peripheral base address. + * @param enable Enables or disables the feature. + */ +static inline void DAC_Enable(DAC_Type *base, bool enable) +{ + if (enable) + { + base->C0 |= DAC_C0_DACEN_MASK; + } + else + { + base->C0 &= ~DAC_C0_DACEN_MASK; + } +} + +/* @} */ + +/*! + * @name Buffer + * @{ + */ + +/*! + * @brief Enables the DAC buffer. + * + * @param base DAC peripheral base address. + * @param enable Enables or disables the feature. + */ +static inline void DAC_EnableBuffer(DAC_Type *base, bool enable) +{ + if (enable) + { + base->C1 |= DAC_C1_DACBFEN_MASK; + } + else + { + base->C1 &= ~DAC_C1_DACBFEN_MASK; + } +} + +/*! + * @brief Configures the CMP buffer. + * + * @param base DAC peripheral base address. + * @param config Pointer to the configuration structure. See "dac_buffer_config_t". + */ +void DAC_SetBufferConfig(DAC_Type *base, const dac_buffer_config_t *config); + +/*! + * @brief Initializes the DAC buffer configuration structure. + * + * This function initializes the DAC buffer configuration structure to default values. The default values are as follows. + * @code + * config->triggerMode = kDAC_BufferTriggerBySoftwareMode; + * config->watermark = kDAC_BufferWatermark1Word; + * config->workMode = kDAC_BufferWorkAsNormalMode; + * config->upperLimit = DAC_DATL_COUNT - 1U; + * @endcode + * @param config Pointer to the configuration structure. See "dac_buffer_config_t". + */ +void DAC_GetDefaultBufferConfig(dac_buffer_config_t *config); + +/*! + * @brief Enables the DMA for DAC buffer. + * + * @param base DAC peripheral base address. + * @param enable Enables or disables the feature. + */ +static inline void DAC_EnableBufferDMA(DAC_Type *base, bool enable) +{ + if (enable) + { + base->C1 |= DAC_C1_DMAEN_MASK; + } + else + { + base->C1 &= ~DAC_C1_DMAEN_MASK; + } +} + +/*! + * @brief Sets the value for items in the buffer. + * + * @param base DAC peripheral base address. + * @param index Setting the index for items in the buffer. The available index should not exceed the size of the DAC buffer. + * @param value Setting the value for items in the buffer. 12-bits are available. + */ +void DAC_SetBufferValue(DAC_Type *base, uint8_t index, uint16_t value); + +/*! + * @brief Triggers the buffer using software and updates the read pointer of the DAC buffer. + * + * This function triggers the function using software. The read pointer of the DAC buffer is updated with one step + * after this function is called. Changing the read pointer depends on the buffer's work mode. + * + * @param base DAC peripheral base address. + */ +static inline void DAC_DoSoftwareTriggerBuffer(DAC_Type *base) +{ + base->C0 |= DAC_C0_DACSWTRG_MASK; +} + +/*! + * @brief Gets the current read pointer of the DAC buffer. + * + * This function gets the current read pointer of the DAC buffer. + * The current output value depends on the item indexed by the read pointer. It is updated either + * by a software trigger or a hardware trigger. + * + * @param base DAC peripheral base address. + * + * @return The current read pointer of the DAC buffer. + */ +static inline uint8_t DAC_GetBufferReadPointer(DAC_Type *base) +{ + return ((base->C2 & DAC_C2_DACBFRP_MASK) >> DAC_C2_DACBFRP_SHIFT); +} + +/*! + * @brief Sets the current read pointer of the DAC buffer. + * + * This function sets the current read pointer of the DAC buffer. + * The current output value depends on the item indexed by the read pointer. It is updated either by a + * software trigger or a hardware trigger. After the read pointer changes, the DAC output value also changes. + * + * @param base DAC peripheral base address. + * @param index Setting an index value for the pointer. + */ +void DAC_SetBufferReadPointer(DAC_Type *base, uint8_t index); + +/*! + * @brief Enables interrupts for the DAC buffer. + * + * @param base DAC peripheral base address. + * @param mask Mask value for interrupts. See "_dac_buffer_interrupt_enable". + */ +void DAC_EnableBufferInterrupts(DAC_Type *base, uint32_t mask); + +/*! + * @brief Disables interrupts for the DAC buffer. + * + * @param base DAC peripheral base address. + * @param mask Mask value for interrupts. See "_dac_buffer_interrupt_enable". + */ +void DAC_DisableBufferInterrupts(DAC_Type *base, uint32_t mask); + +/*! + * @brief Gets the flags of events for the DAC buffer. + * + * @param base DAC peripheral base address. + * + * @return Mask value for the asserted flags. See "_dac_buffer_status_flags". + */ +uint32_t DAC_GetBufferStatusFlags(DAC_Type *base); + +/*! + * @brief Clears the flags of events for the DAC buffer. + * + * @param base DAC peripheral base address. + * @param mask Mask value for flags. See "_dac_buffer_status_flags_t". + */ +void DAC_ClearBufferStatusFlags(DAC_Type *base, uint32_t mask); + +/* @} */ + +#if defined(__cplusplus) +} +#endif +/*! + * @} + */ +#endif /* _FSL_DAC_H_ */ diff --git a/drivers/fsl_dmamux.c b/drivers/fsl_dmamux.c new file mode 100644 index 0000000..155531d --- /dev/null +++ b/drivers/fsl_dmamux.c @@ -0,0 +1,103 @@ +/* + * The Clear BSD License + * Copyright (c) 2015, 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: + * + * o Redistributions of source code must retain the above copyright notice, this list + * of conditions and the following disclaimer. + * + * o 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. + * + * o 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. + */ + +#include "fsl_dmamux.h" + +/******************************************************************************* + * Definitions + ******************************************************************************/ + +/* Component ID definition, used by tools. */ +#ifndef FSL_COMPONENT_ID +#define FSL_COMPONENT_ID "platform.drivers.dmamux" +#endif + + +/******************************************************************************* + * Prototypes + ******************************************************************************/ + +/*! + * @brief Get instance number for DMAMUX. + * + * @param base DMAMUX peripheral base address. + */ +static uint32_t DMAMUX_GetInstance(DMAMUX_Type *base); + +/******************************************************************************* + * Variables + ******************************************************************************/ + +/*! @brief Array to map DMAMUX instance number to base pointer. */ +static DMAMUX_Type *const s_dmamuxBases[] = DMAMUX_BASE_PTRS; + +#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) +/*! @brief Array to map DMAMUX instance number to clock name. */ +static const clock_ip_name_t s_dmamuxClockName[] = DMAMUX_CLOCKS; +#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */ + +/******************************************************************************* + * Code + ******************************************************************************/ +static uint32_t DMAMUX_GetInstance(DMAMUX_Type *base) +{ + uint32_t instance; + + /* Find the instance index from base address mappings. */ + for (instance = 0; instance < ARRAY_SIZE(s_dmamuxBases); instance++) + { + if (s_dmamuxBases[instance] == base) + { + break; + } + } + + assert(instance < ARRAY_SIZE(s_dmamuxBases)); + + return instance; +} + +void DMAMUX_Init(DMAMUX_Type *base) +{ +#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) + CLOCK_EnableClock(s_dmamuxClockName[DMAMUX_GetInstance(base)]); +#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */ +} + +void DMAMUX_Deinit(DMAMUX_Type *base) +{ +#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) + CLOCK_DisableClock(s_dmamuxClockName[DMAMUX_GetInstance(base)]); +#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */ +} diff --git a/drivers/fsl_dmamux.h b/drivers/fsl_dmamux.h new file mode 100644 index 0000000..17f32ee --- /dev/null +++ b/drivers/fsl_dmamux.h @@ -0,0 +1,204 @@ +/* + * The Clear BSD License + * Copyright (c) 2015, 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: + * + * o Redistributions of source code must retain the above copyright notice, this list + * of conditions and the following disclaimer. + * + * o 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. + * + * o 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_DMAMUX_H_ +#define _FSL_DMAMUX_H_ + +#include "fsl_common.h" + +/*! + * @addtogroup dmamux + * @{ + */ + + +/******************************************************************************* + * Definitions + ******************************************************************************/ + +/*! @name Driver version */ +/*@{*/ +/*! @brief DMAMUX driver version 2.0.2. */ +#define FSL_DMAMUX_DRIVER_VERSION (MAKE_VERSION(2, 0, 2)) +/*@}*/ + +/******************************************************************************* + * API + ******************************************************************************/ + +#if defined(__cplusplus) +extern "C" { +#endif /* __cplusplus */ + +/*! + * @name DMAMUX Initialization and de-initialization + * @{ + */ + +/*! + * @brief Initializes the DMAMUX peripheral. + * + * This function ungates the DMAMUX clock. + * + * @param base DMAMUX peripheral base address. + * + */ +void DMAMUX_Init(DMAMUX_Type *base); + +/*! + * @brief Deinitializes the DMAMUX peripheral. + * + * This function gates the DMAMUX clock. + * + * @param base DMAMUX peripheral base address. + */ +void DMAMUX_Deinit(DMAMUX_Type *base); + +/* @} */ +/*! + * @name DMAMUX Channel Operation + * @{ + */ + +/*! + * @brief Enables the DMAMUX channel. + * + * This function enables the DMAMUX channel. + * + * @param base DMAMUX peripheral base address. + * @param channel DMAMUX channel number. + */ +static inline void DMAMUX_EnableChannel(DMAMUX_Type *base, uint32_t channel) +{ + assert(channel < FSL_FEATURE_DMAMUX_MODULE_CHANNEL); + + base->CHCFG[channel] |= DMAMUX_CHCFG_ENBL_MASK; +} + +/*! + * @brief Disables the DMAMUX channel. + * + * This function disables the DMAMUX channel. + * + * @note The user must disable the DMAMUX channel before configuring it. + * @param base DMAMUX peripheral base address. + * @param channel DMAMUX channel number. + */ +static inline void DMAMUX_DisableChannel(DMAMUX_Type *base, uint32_t channel) +{ + assert(channel < FSL_FEATURE_DMAMUX_MODULE_CHANNEL); + + base->CHCFG[channel] &= ~DMAMUX_CHCFG_ENBL_MASK; +} + +/*! + * @brief Configures the DMAMUX channel source. + * + * @param base DMAMUX peripheral base address. + * @param channel DMAMUX channel number. + * @param source Channel source, which is used to trigger the DMA transfer. + */ +static inline void DMAMUX_SetSource(DMAMUX_Type *base, uint32_t channel, uint32_t source) +{ + assert(channel < FSL_FEATURE_DMAMUX_MODULE_CHANNEL); + + base->CHCFG[channel] = ((base->CHCFG[channel] & ~DMAMUX_CHCFG_SOURCE_MASK) | DMAMUX_CHCFG_SOURCE(source)); +} + +#if defined(FSL_FEATURE_DMAMUX_HAS_TRIG) && FSL_FEATURE_DMAMUX_HAS_TRIG > 0U +/*! + * @brief Enables the DMAMUX period trigger. + * + * This function enables the DMAMUX period trigger feature. + * + * @param base DMAMUX peripheral base address. + * @param channel DMAMUX channel number. + */ +static inline void DMAMUX_EnablePeriodTrigger(DMAMUX_Type *base, uint32_t channel) +{ + assert(channel < FSL_FEATURE_DMAMUX_MODULE_CHANNEL); + + base->CHCFG[channel] |= DMAMUX_CHCFG_TRIG_MASK; +} + +/*! + * @brief Disables the DMAMUX period trigger. + * + * This function disables the DMAMUX period trigger. + * + * @param base DMAMUX peripheral base address. + * @param channel DMAMUX channel number. + */ +static inline void DMAMUX_DisablePeriodTrigger(DMAMUX_Type *base, uint32_t channel) +{ + assert(channel < FSL_FEATURE_DMAMUX_MODULE_CHANNEL); + + base->CHCFG[channel] &= ~DMAMUX_CHCFG_TRIG_MASK; +} +#endif /* FSL_FEATURE_DMAMUX_HAS_TRIG */ + +#if (defined(FSL_FEATURE_DMAMUX_HAS_A_ON) && FSL_FEATURE_DMAMUX_HAS_A_ON) +/*! + * @brief Enables the DMA channel to be always ON. + * + * This function enables the DMAMUX channel always ON feature. + * + * @param base DMAMUX peripheral base address. + * @param channel DMAMUX channel number. + * @param enable Switcher of the always ON feature. "true" means enabled, "false" means disabled. + */ +static inline void DMAMUX_EnableAlwaysOn(DMAMUX_Type *base, uint32_t channel, bool enable) +{ + assert(channel < FSL_FEATURE_DMAMUX_MODULE_CHANNEL); + + if (enable) + { + base->CHCFG[channel] |= DMAMUX_CHCFG_A_ON_MASK; + } + else + { + base->CHCFG[channel] &= ~DMAMUX_CHCFG_A_ON_MASK; + } +} +#endif /* FSL_FEATURE_DMAMUX_HAS_A_ON */ + +/* @} */ + +#if defined(__cplusplus) +} +#endif /* __cplusplus */ + +/* @} */ + +#endif /* _FSL_DMAMUX_H_ */ diff --git a/drivers/fsl_dspi.c b/drivers/fsl_dspi.c new file mode 100644 index 0000000..620335b --- /dev/null +++ b/drivers/fsl_dspi.c @@ -0,0 +1,1807 @@ +/* + * The Clear BSD License + * Copyright (c) 2015, 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: + * + * o Redistributions of source code must retain the above copyright notice, this list + * of conditions and the following disclaimer. + * + * o 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. + * + * o 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. + */ + +#include "fsl_dspi.h" + +/******************************************************************************* + * Definitions + ******************************************************************************/ + +/* Component ID definition, used by tools. */ +#ifndef FSL_COMPONENT_ID +#define FSL_COMPONENT_ID "platform.drivers.dspi" +#endif + +/*! @brief Typedef for master interrupt handler. */ +typedef void (*dspi_master_isr_t)(SPI_Type *base, dspi_master_handle_t *handle); + +/*! @brief Typedef for slave interrupt handler. */ +typedef void (*dspi_slave_isr_t)(SPI_Type *base, dspi_slave_handle_t *handle); + +/******************************************************************************* + * Prototypes + ******************************************************************************/ +/*! + * @brief Configures the DSPI peripheral chip select polarity. + * + * This function takes in the desired peripheral chip select (Pcs) and it's corresponding desired polarity and + * configures the Pcs signal to operate with the desired characteristic. + * + * @param base DSPI peripheral address. + * @param pcs The particular peripheral chip select (parameter value is of type dspi_which_pcs_t) for which we wish to + * apply the active high or active low characteristic. + * @param activeLowOrHigh The setting for either "active high, inactive low (0)" or "active low, inactive high(1)" of + * type dspi_pcs_polarity_config_t. + */ +static void DSPI_SetOnePcsPolarity(SPI_Type *base, dspi_which_pcs_t pcs, dspi_pcs_polarity_config_t activeLowOrHigh); + +/*! + * @brief Master fill up the TX FIFO with data. + * This is not a public API. + */ +static void DSPI_MasterTransferFillUpTxFifo(SPI_Type *base, dspi_master_handle_t *handle); + +/*! + * @brief Master finish up a transfer. + * It would call back if there is callback function and set the state to idle. + * This is not a public API. + */ +static void DSPI_MasterTransferComplete(SPI_Type *base, dspi_master_handle_t *handle); + +/*! + * @brief Slave fill up the TX FIFO with data. + * This is not a public API. + */ +static void DSPI_SlaveTransferFillUpTxFifo(SPI_Type *base, dspi_slave_handle_t *handle); + +/*! + * @brief Slave finish up a transfer. + * It would call back if there is callback function and set the state to idle. + * This is not a public API. + */ +static void DSPI_SlaveTransferComplete(SPI_Type *base, dspi_slave_handle_t *handle); + +/*! + * @brief DSPI common interrupt handler. + * + * @param base DSPI peripheral address. + * @param handle pointer to g_dspiHandle which stores the transfer state. + */ +static void DSPI_CommonIRQHandler(SPI_Type *base, void *param); + +/*! + * @brief Master prepare the transfer. + * Basically it set up dspi_master_handle . + * This is not a public API. + */ +static void DSPI_MasterTransferPrepare(SPI_Type *base, dspi_master_handle_t *handle, dspi_transfer_t *transfer); + +/******************************************************************************* + * Variables + ******************************************************************************/ + +/* Defines constant value arrays for the baud rate pre-scalar and scalar divider values.*/ +static const uint32_t s_baudratePrescaler[] = {2, 3, 5, 7}; +static const uint32_t s_baudrateScaler[] = {2, 4, 6, 8, 16, 32, 64, 128, + 256, 512, 1024, 2048, 4096, 8192, 16384, 32768}; + +static const uint32_t s_delayPrescaler[] = {1, 3, 5, 7}; +static const uint32_t s_delayScaler[] = {2, 4, 8, 16, 32, 64, 128, 256, + 512, 1024, 2048, 4096, 8192, 16384, 32768, 65536}; + +/*! @brief Pointers to dspi bases for each instance. */ +static SPI_Type *const s_dspiBases[] = SPI_BASE_PTRS; + +/*! @brief Pointers to dspi IRQ number for each instance. */ +static IRQn_Type const s_dspiIRQ[] = SPI_IRQS; + +#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) +/*! @brief Pointers to dspi clocks for each instance. */ +static clock_ip_name_t const s_dspiClock[] = DSPI_CLOCKS; +#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */ + +/*! @brief Pointers to dspi handles for each instance. */ +static void *g_dspiHandle[ARRAY_SIZE(s_dspiBases)]; + +/*! @brief Pointer to master IRQ handler for each instance. */ +static dspi_master_isr_t s_dspiMasterIsr; + +/*! @brief Pointer to slave IRQ handler for each instance. */ +static dspi_slave_isr_t s_dspiSlaveIsr; + +/* @brief Dummy data for each instance. This data is used when user's tx buffer is NULL*/ +volatile uint8_t g_dspiDummyData[ARRAY_SIZE(s_dspiBases)] = {0}; +/********************************************************************************************************************** +* Code +*********************************************************************************************************************/ +uint32_t DSPI_GetInstance(SPI_Type *base) +{ + uint32_t instance; + + /* Find the instance index from base address mappings. */ + for (instance = 0; instance < ARRAY_SIZE(s_dspiBases); instance++) + { + if (s_dspiBases[instance] == base) + { + break; + } + } + + assert(instance < ARRAY_SIZE(s_dspiBases)); + + return instance; +} + +void DSPI_SetDummyData(SPI_Type *base, uint8_t dummyData) +{ + uint32_t instance = DSPI_GetInstance(base); + g_dspiDummyData[instance] = dummyData; +} + +void DSPI_MasterInit(SPI_Type *base, const dspi_master_config_t *masterConfig, uint32_t srcClock_Hz) +{ + assert(masterConfig); + + uint32_t temp; +#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) + /* enable DSPI clock */ + CLOCK_EnableClock(s_dspiClock[DSPI_GetInstance(base)]); +#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */ + + DSPI_Enable(base, true); + DSPI_StopTransfer(base); + + DSPI_SetMasterSlaveMode(base, kDSPI_Master); + + temp = base->MCR & (~(SPI_MCR_CONT_SCKE_MASK | SPI_MCR_MTFE_MASK | SPI_MCR_ROOE_MASK | SPI_MCR_SMPL_PT_MASK | + SPI_MCR_DIS_TXF_MASK | SPI_MCR_DIS_RXF_MASK)); + + base->MCR = temp | SPI_MCR_CONT_SCKE(masterConfig->enableContinuousSCK) | + SPI_MCR_MTFE(masterConfig->enableModifiedTimingFormat) | + SPI_MCR_ROOE(masterConfig->enableRxFifoOverWrite) | SPI_MCR_SMPL_PT(masterConfig->samplePoint) | + SPI_MCR_DIS_TXF(false) | SPI_MCR_DIS_RXF(false); + + DSPI_SetOnePcsPolarity(base, masterConfig->whichPcs, masterConfig->pcsActiveHighOrLow); + + if (0 == DSPI_MasterSetBaudRate(base, masterConfig->whichCtar, masterConfig->ctarConfig.baudRate, srcClock_Hz)) + { + assert(false); + } + + temp = base->CTAR[masterConfig->whichCtar] & + ~(SPI_CTAR_FMSZ_MASK | SPI_CTAR_CPOL_MASK | SPI_CTAR_CPHA_MASK | SPI_CTAR_LSBFE_MASK); + + base->CTAR[masterConfig->whichCtar] = + temp | SPI_CTAR_FMSZ(masterConfig->ctarConfig.bitsPerFrame - 1) | SPI_CTAR_CPOL(masterConfig->ctarConfig.cpol) | + SPI_CTAR_CPHA(masterConfig->ctarConfig.cpha) | SPI_CTAR_LSBFE(masterConfig->ctarConfig.direction); + + DSPI_MasterSetDelayTimes(base, masterConfig->whichCtar, kDSPI_PcsToSck, srcClock_Hz, + masterConfig->ctarConfig.pcsToSckDelayInNanoSec); + DSPI_MasterSetDelayTimes(base, masterConfig->whichCtar, kDSPI_LastSckToPcs, srcClock_Hz, + masterConfig->ctarConfig.lastSckToPcsDelayInNanoSec); + DSPI_MasterSetDelayTimes(base, masterConfig->whichCtar, kDSPI_BetweenTransfer, srcClock_Hz, + masterConfig->ctarConfig.betweenTransferDelayInNanoSec); + + DSPI_SetDummyData(base, DSPI_DUMMY_DATA); + DSPI_StartTransfer(base); +} + +void DSPI_MasterGetDefaultConfig(dspi_master_config_t *masterConfig) +{ + assert(masterConfig); + + masterConfig->whichCtar = kDSPI_Ctar0; + masterConfig->ctarConfig.baudRate = 500000; + masterConfig->ctarConfig.bitsPerFrame = 8; + masterConfig->ctarConfig.cpol = kDSPI_ClockPolarityActiveHigh; + masterConfig->ctarConfig.cpha = kDSPI_ClockPhaseFirstEdge; + masterConfig->ctarConfig.direction = kDSPI_MsbFirst; + + masterConfig->ctarConfig.pcsToSckDelayInNanoSec = 1000; + masterConfig->ctarConfig.lastSckToPcsDelayInNanoSec = 1000; + masterConfig->ctarConfig.betweenTransferDelayInNanoSec = 1000; + + masterConfig->whichPcs = kDSPI_Pcs0; + masterConfig->pcsActiveHighOrLow = kDSPI_PcsActiveLow; + + masterConfig->enableContinuousSCK = false; + masterConfig->enableRxFifoOverWrite = false; + masterConfig->enableModifiedTimingFormat = false; + masterConfig->samplePoint = kDSPI_SckToSin0Clock; +} + +void DSPI_SlaveInit(SPI_Type *base, const dspi_slave_config_t *slaveConfig) +{ + assert(slaveConfig); + + uint32_t temp = 0; + +#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) + /* enable DSPI clock */ + CLOCK_EnableClock(s_dspiClock[DSPI_GetInstance(base)]); +#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */ + + DSPI_Enable(base, true); + DSPI_StopTransfer(base); + + DSPI_SetMasterSlaveMode(base, kDSPI_Slave); + + temp = base->MCR & (~(SPI_MCR_CONT_SCKE_MASK | SPI_MCR_MTFE_MASK | SPI_MCR_ROOE_MASK | SPI_MCR_SMPL_PT_MASK | + SPI_MCR_DIS_TXF_MASK | SPI_MCR_DIS_RXF_MASK)); + + base->MCR = temp | SPI_MCR_CONT_SCKE(slaveConfig->enableContinuousSCK) | + SPI_MCR_MTFE(slaveConfig->enableModifiedTimingFormat) | + SPI_MCR_ROOE(slaveConfig->enableRxFifoOverWrite) | SPI_MCR_SMPL_PT(slaveConfig->samplePoint) | + SPI_MCR_DIS_TXF(false) | SPI_MCR_DIS_RXF(false); + + DSPI_SetOnePcsPolarity(base, kDSPI_Pcs0, kDSPI_PcsActiveLow); + + temp = base->CTAR[slaveConfig->whichCtar] & + ~(SPI_CTAR_FMSZ_MASK | SPI_CTAR_CPOL_MASK | SPI_CTAR_CPHA_MASK | SPI_CTAR_LSBFE_MASK); + + base->CTAR[slaveConfig->whichCtar] = temp | SPI_CTAR_SLAVE_FMSZ(slaveConfig->ctarConfig.bitsPerFrame - 1) | + SPI_CTAR_SLAVE_CPOL(slaveConfig->ctarConfig.cpol) | + SPI_CTAR_SLAVE_CPHA(slaveConfig->ctarConfig.cpha); + + DSPI_SetDummyData(base, DSPI_DUMMY_DATA); + + DSPI_StartTransfer(base); +} + +void DSPI_SlaveGetDefaultConfig(dspi_slave_config_t *slaveConfig) +{ + assert(slaveConfig); + + slaveConfig->whichCtar = kDSPI_Ctar0; + slaveConfig->ctarConfig.bitsPerFrame = 8; + slaveConfig->ctarConfig.cpol = kDSPI_ClockPolarityActiveHigh; + slaveConfig->ctarConfig.cpha = kDSPI_ClockPhaseFirstEdge; + + slaveConfig->enableContinuousSCK = false; + slaveConfig->enableRxFifoOverWrite = false; + slaveConfig->enableModifiedTimingFormat = false; + slaveConfig->samplePoint = kDSPI_SckToSin0Clock; +} + +void DSPI_Deinit(SPI_Type *base) +{ + DSPI_StopTransfer(base); + DSPI_Enable(base, false); + +#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) + /* disable DSPI clock */ + CLOCK_DisableClock(s_dspiClock[DSPI_GetInstance(base)]); +#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */ +} + +static void DSPI_SetOnePcsPolarity(SPI_Type *base, dspi_which_pcs_t pcs, dspi_pcs_polarity_config_t activeLowOrHigh) +{ + uint32_t temp; + + temp = base->MCR; + + if (activeLowOrHigh == kDSPI_PcsActiveLow) + { + temp |= SPI_MCR_PCSIS(pcs); + } + else + { + temp &= ~SPI_MCR_PCSIS(pcs); + } + + base->MCR = temp; +} + +uint32_t DSPI_MasterSetBaudRate(SPI_Type *base, + dspi_ctar_selection_t whichCtar, + uint32_t baudRate_Bps, + uint32_t srcClock_Hz) +{ + /* for master mode configuration, if slave mode detected, return 0*/ + if (!DSPI_IsMaster(base)) + { + return 0; + } + uint32_t temp; + uint32_t prescaler, bestPrescaler; + uint32_t scaler, bestScaler; + uint32_t dbr, bestDbr; + uint32_t realBaudrate, bestBaudrate; + uint32_t diff, min_diff; + uint32_t baudrate = baudRate_Bps; + + /* find combination of prescaler and scaler resulting in baudrate closest to the requested value */ + min_diff = 0xFFFFFFFFU; + bestPrescaler = 0; + bestScaler = 0; + bestDbr = 1; + bestBaudrate = 0; /* required to avoid compilation warning */ + + /* In all for loops, if min_diff = 0, the exit for loop*/ + for (prescaler = 0; (prescaler < 4) && min_diff; prescaler++) + { + for (scaler = 0; (scaler < 16) && min_diff; scaler++) + { + for (dbr = 1; (dbr < 3) && min_diff; dbr++) + { + realBaudrate = ((srcClock_Hz * dbr) / (s_baudratePrescaler[prescaler] * (s_baudrateScaler[scaler]))); + + /* calculate the baud rate difference based on the conditional statement that states that the calculated + * baud rate must not exceed the desired baud rate. + */ + if (baudrate >= realBaudrate) + { + diff = baudrate - realBaudrate; + if (min_diff > diff) + { + /* a better match found */ + min_diff = diff; + bestPrescaler = prescaler; + bestScaler = scaler; + bestBaudrate = realBaudrate; + bestDbr = dbr; + } + } + } + } + } + + /* write the best dbr, prescalar, and baud rate scalar to the CTAR */ + temp = base->CTAR[whichCtar] & ~(SPI_CTAR_DBR_MASK | SPI_CTAR_PBR_MASK | SPI_CTAR_BR_MASK); + + base->CTAR[whichCtar] = temp | ((bestDbr - 1) << SPI_CTAR_DBR_SHIFT) | (bestPrescaler << SPI_CTAR_PBR_SHIFT) | + (bestScaler << SPI_CTAR_BR_SHIFT); + + /* return the actual calculated baud rate */ + return bestBaudrate; +} + +void DSPI_MasterSetDelayScaler( + SPI_Type *base, dspi_ctar_selection_t whichCtar, uint32_t prescaler, uint32_t scaler, dspi_delay_type_t whichDelay) +{ + /* these settings are only relevant in master mode */ + if (DSPI_IsMaster(base)) + { + switch (whichDelay) + { + case kDSPI_PcsToSck: + base->CTAR[whichCtar] = (base->CTAR[whichCtar] & (~SPI_CTAR_PCSSCK_MASK) & (~SPI_CTAR_CSSCK_MASK)) | + SPI_CTAR_PCSSCK(prescaler) | SPI_CTAR_CSSCK(scaler); + break; + case kDSPI_LastSckToPcs: + base->CTAR[whichCtar] = (base->CTAR[whichCtar] & (~SPI_CTAR_PASC_MASK) & (~SPI_CTAR_ASC_MASK)) | + SPI_CTAR_PASC(prescaler) | SPI_CTAR_ASC(scaler); + break; + case kDSPI_BetweenTransfer: + base->CTAR[whichCtar] = (base->CTAR[whichCtar] & (~SPI_CTAR_PDT_MASK) & (~SPI_CTAR_DT_MASK)) | + SPI_CTAR_PDT(prescaler) | SPI_CTAR_DT(scaler); + break; + default: + break; + } + } +} + +uint32_t DSPI_MasterSetDelayTimes(SPI_Type *base, + dspi_ctar_selection_t whichCtar, + dspi_delay_type_t whichDelay, + uint32_t srcClock_Hz, + uint32_t delayTimeInNanoSec) +{ + /* for master mode configuration, if slave mode detected, return 0 */ + if (!DSPI_IsMaster(base)) + { + return 0; + } + + uint32_t prescaler, bestPrescaler; + uint32_t scaler, bestScaler; + uint32_t realDelay, bestDelay; + uint32_t diff, min_diff; + uint32_t initialDelayNanoSec; + + /* find combination of prescaler and scaler resulting in the delay closest to the + * requested value + */ + min_diff = 0xFFFFFFFFU; + /* Initialize prescaler and scaler to their max values to generate the max delay */ + bestPrescaler = 0x3; + bestScaler = 0xF; + bestDelay = (((1000000000U * 4) / srcClock_Hz) * s_delayPrescaler[bestPrescaler] * s_delayScaler[bestScaler]) / 4; + + /* First calculate the initial, default delay */ + initialDelayNanoSec = 1000000000U / srcClock_Hz * 2; + + /* If the initial, default delay is already greater than the desired delay, then + * set the delays to their initial value (0) and return the delay. In other words, + * there is no way to decrease the delay value further. + */ + if (initialDelayNanoSec >= delayTimeInNanoSec) + { + DSPI_MasterSetDelayScaler(base, whichCtar, 0, 0, whichDelay); + return initialDelayNanoSec; + } + + /* In all for loops, if min_diff = 0, the exit for loop */ + for (prescaler = 0; (prescaler < 4) && min_diff; prescaler++) + { + for (scaler = 0; (scaler < 16) && min_diff; scaler++) + { + realDelay = ((4000000000U / srcClock_Hz) * s_delayPrescaler[prescaler] * s_delayScaler[scaler]) / 4; + + /* calculate the delay difference based on the conditional statement + * that states that the calculated delay must not be less then the desired delay + */ + if (realDelay >= delayTimeInNanoSec) + { + diff = realDelay - delayTimeInNanoSec; + if (min_diff > diff) + { + /* a better match found */ + min_diff = diff; + bestPrescaler = prescaler; + bestScaler = scaler; + bestDelay = realDelay; + } + } + } + } + + /* write the best dbr, prescalar, and baud rate scalar to the CTAR */ + DSPI_MasterSetDelayScaler(base, whichCtar, bestPrescaler, bestScaler, whichDelay); + + /* return the actual calculated baud rate */ + return bestDelay; +} + +void DSPI_GetDefaultDataCommandConfig(dspi_command_data_config_t *command) +{ + assert(command); + + command->isPcsContinuous = false; + command->whichCtar = kDSPI_Ctar0; + command->whichPcs = kDSPI_Pcs0; + command->isEndOfQueue = false; + command->clearTransferCount = false; +} + +void DSPI_MasterWriteDataBlocking(SPI_Type *base, dspi_command_data_config_t *command, uint16_t data) +{ + assert(command); + + /* First, clear Transmit Complete Flag (TCF) */ + DSPI_ClearStatusFlags(base, kDSPI_TxCompleteFlag); + + while (!(DSPI_GetStatusFlags(base) & kDSPI_TxFifoFillRequestFlag)) + { + DSPI_ClearStatusFlags(base, kDSPI_TxFifoFillRequestFlag); + } + + base->PUSHR = SPI_PUSHR_CONT(command->isPcsContinuous) | SPI_PUSHR_CTAS(command->whichCtar) | + SPI_PUSHR_PCS(command->whichPcs) | SPI_PUSHR_EOQ(command->isEndOfQueue) | + SPI_PUSHR_CTCNT(command->clearTransferCount) | SPI_PUSHR_TXDATA(data); + DSPI_ClearStatusFlags(base, kDSPI_TxFifoFillRequestFlag); + + /* Wait till TCF sets */ + while (!(DSPI_GetStatusFlags(base) & kDSPI_TxCompleteFlag)) + { + } +} + +void DSPI_MasterWriteCommandDataBlocking(SPI_Type *base, uint32_t data) +{ + /* First, clear Transmit Complete Flag (TCF) */ + DSPI_ClearStatusFlags(base, kDSPI_TxCompleteFlag); + + while (!(DSPI_GetStatusFlags(base) & kDSPI_TxFifoFillRequestFlag)) + { + DSPI_ClearStatusFlags(base, kDSPI_TxFifoFillRequestFlag); + } + + base->PUSHR = data; + + DSPI_ClearStatusFlags(base, kDSPI_TxFifoFillRequestFlag); + + /* Wait till TCF sets */ + while (!(DSPI_GetStatusFlags(base) & kDSPI_TxCompleteFlag)) + { + } +} + +void DSPI_SlaveWriteDataBlocking(SPI_Type *base, uint32_t data) +{ + /* First, clear Transmit Complete Flag (TCF) */ + DSPI_ClearStatusFlags(base, kDSPI_TxCompleteFlag); + + while (!(DSPI_GetStatusFlags(base) & kDSPI_TxFifoFillRequestFlag)) + { + DSPI_ClearStatusFlags(base, kDSPI_TxFifoFillRequestFlag); + } + + base->PUSHR_SLAVE = data; + + DSPI_ClearStatusFlags(base, kDSPI_TxFifoFillRequestFlag); + + /* Wait till TCF sets */ + while (!(DSPI_GetStatusFlags(base) & kDSPI_TxCompleteFlag)) + { + } +} + +void DSPI_EnableInterrupts(SPI_Type *base, uint32_t mask) +{ + if (mask & SPI_RSER_TFFF_RE_MASK) + { + base->RSER &= ~SPI_RSER_TFFF_DIRS_MASK; + } + if (mask & SPI_RSER_RFDF_RE_MASK) + { + base->RSER &= ~SPI_RSER_RFDF_DIRS_MASK; + } + base->RSER |= mask; +} + +/*Transactional APIs -- Master*/ + +void DSPI_MasterTransferCreateHandle(SPI_Type *base, + dspi_master_handle_t *handle, + dspi_master_transfer_callback_t callback, + void *userData) +{ + assert(handle); + + /* Zero the handle. */ + memset(handle, 0, sizeof(*handle)); + + g_dspiHandle[DSPI_GetInstance(base)] = handle; + + handle->callback = callback; + handle->userData = userData; +} + +status_t DSPI_MasterTransferBlocking(SPI_Type *base, dspi_transfer_t *transfer) +{ + assert(transfer); + + uint16_t wordToSend = 0; + uint16_t wordReceived = 0; + uint8_t dummyData = g_dspiDummyData[DSPI_GetInstance(base)]; + uint8_t bitsPerFrame; + + uint32_t command; + uint32_t lastCommand; + + uint8_t *txData; + uint8_t *rxData; + uint32_t remainingSendByteCount; + uint32_t remainingReceiveByteCount; + + uint32_t fifoSize; + dspi_command_data_config_t commandStruct; + + /* If the transfer count is zero, then return immediately.*/ + if (transfer->dataSize == 0) + { + return kStatus_InvalidArgument; + } + + DSPI_StopTransfer(base); + DSPI_DisableInterrupts(base, kDSPI_AllInterruptEnable); + DSPI_FlushFifo(base, true, true); + DSPI_ClearStatusFlags(base, kDSPI_AllStatusFlag); + + /*Calculate the command and lastCommand*/ + commandStruct.whichPcs = + (dspi_which_pcs_t)(1U << ((transfer->configFlags & DSPI_MASTER_PCS_MASK) >> DSPI_MASTER_PCS_SHIFT)); + commandStruct.isEndOfQueue = false; + commandStruct.clearTransferCount = false; + commandStruct.whichCtar = + (dspi_ctar_selection_t)((transfer->configFlags & DSPI_MASTER_CTAR_MASK) >> DSPI_MASTER_CTAR_SHIFT); + commandStruct.isPcsContinuous = (bool)(transfer->configFlags & kDSPI_MasterPcsContinuous); + + command = DSPI_MasterGetFormattedCommand(&(commandStruct)); + + commandStruct.isEndOfQueue = true; + commandStruct.isPcsContinuous = (bool)(transfer->configFlags & kDSPI_MasterActiveAfterTransfer); + lastCommand = DSPI_MasterGetFormattedCommand(&(commandStruct)); + + /*Calculate the bitsPerFrame*/ + bitsPerFrame = ((base->CTAR[commandStruct.whichCtar] & SPI_CTAR_FMSZ_MASK) >> SPI_CTAR_FMSZ_SHIFT) + 1; + + txData = transfer->txData; + rxData = transfer->rxData; + remainingSendByteCount = transfer->dataSize; + remainingReceiveByteCount = transfer->dataSize; + + if ((base->MCR & SPI_MCR_DIS_RXF_MASK) || (base->MCR & SPI_MCR_DIS_TXF_MASK)) + { + fifoSize = 1; + } + else + { + fifoSize = FSL_FEATURE_DSPI_FIFO_SIZEn(base); + } + + DSPI_StartTransfer(base); + + if (bitsPerFrame <= 8) + { + while (remainingSendByteCount > 0) + { + if (remainingSendByteCount == 1) + { + while (!(DSPI_GetStatusFlags(base) & kDSPI_TxFifoFillRequestFlag)) + { + DSPI_ClearStatusFlags(base, kDSPI_TxFifoFillRequestFlag); + } + + if (txData != NULL) + { + base->PUSHR = (*txData) | (lastCommand); + txData++; + } + else + { + base->PUSHR = (lastCommand) | (dummyData); + } + DSPI_ClearStatusFlags(base, kDSPI_TxFifoFillRequestFlag); + remainingSendByteCount--; + + while (remainingReceiveByteCount > 0) + { + if (DSPI_GetStatusFlags(base) & kDSPI_RxFifoDrainRequestFlag) + { + if (rxData != NULL) + { + /* Read data from POPR*/ + *(rxData) = DSPI_ReadData(base); + rxData++; + } + else + { + DSPI_ReadData(base); + } + remainingReceiveByteCount--; + + DSPI_ClearStatusFlags(base, kDSPI_RxFifoDrainRequestFlag); + } + } + } + else + { + /*Wait until Tx Fifo is not full*/ + while (!(DSPI_GetStatusFlags(base) & kDSPI_TxFifoFillRequestFlag)) + { + DSPI_ClearStatusFlags(base, kDSPI_TxFifoFillRequestFlag); + } + if (txData != NULL) + { + base->PUSHR = command | (uint16_t)(*txData); + txData++; + } + else + { + base->PUSHR = command | dummyData; + } + remainingSendByteCount--; + + DSPI_ClearStatusFlags(base, kDSPI_TxFifoFillRequestFlag); + + while ((remainingReceiveByteCount - remainingSendByteCount) >= fifoSize) + { + if (DSPI_GetStatusFlags(base) & kDSPI_RxFifoDrainRequestFlag) + { + if (rxData != NULL) + { + *(rxData) = DSPI_ReadData(base); + rxData++; + } + else + { + DSPI_ReadData(base); + } + remainingReceiveByteCount--; + + DSPI_ClearStatusFlags(base, kDSPI_RxFifoDrainRequestFlag); + } + } + } + } + } + else + { + while (remainingSendByteCount > 0) + { + if (remainingSendByteCount <= 2) + { + while (!(DSPI_GetStatusFlags(base) & kDSPI_TxFifoFillRequestFlag)) + { + DSPI_ClearStatusFlags(base, kDSPI_TxFifoFillRequestFlag); + } + + if (txData != NULL) + { + wordToSend = *(txData); + ++txData; + + if (remainingSendByteCount > 1) + { + wordToSend |= (unsigned)(*(txData)) << 8U; + ++txData; + } + } + else + { + wordToSend = dummyData; + } + + base->PUSHR = lastCommand | wordToSend; + + DSPI_ClearStatusFlags(base, kDSPI_TxFifoFillRequestFlag); + remainingSendByteCount = 0; + + while (remainingReceiveByteCount > 0) + { + if (DSPI_GetStatusFlags(base) & kDSPI_RxFifoDrainRequestFlag) + { + wordReceived = DSPI_ReadData(base); + + if (remainingReceiveByteCount != 1) + { + if (rxData != NULL) + { + *(rxData) = wordReceived; + ++rxData; + *(rxData) = wordReceived >> 8; + ++rxData; + } + remainingReceiveByteCount -= 2; + } + else + { + if (rxData != NULL) + { + *(rxData) = wordReceived; + ++rxData; + } + remainingReceiveByteCount--; + } + DSPI_ClearStatusFlags(base, kDSPI_RxFifoDrainRequestFlag); + } + } + } + else + { + /*Wait until Tx Fifo is not full*/ + while (!(DSPI_GetStatusFlags(base) & kDSPI_TxFifoFillRequestFlag)) + { + DSPI_ClearStatusFlags(base, kDSPI_TxFifoFillRequestFlag); + } + + if (txData != NULL) + { + wordToSend = *(txData); + ++txData; + wordToSend |= (unsigned)(*(txData)) << 8U; + ++txData; + } + else + { + wordToSend = dummyData; + } + base->PUSHR = command | wordToSend; + remainingSendByteCount -= 2; + + DSPI_ClearStatusFlags(base, kDSPI_TxFifoFillRequestFlag); + + while (((remainingReceiveByteCount - remainingSendByteCount) / 2) >= fifoSize) + { + if (DSPI_GetStatusFlags(base) & kDSPI_RxFifoDrainRequestFlag) + { + wordReceived = DSPI_ReadData(base); + + if (rxData != NULL) + { + *rxData = wordReceived; + ++rxData; + *rxData = wordReceived >> 8; + ++rxData; + } + remainingReceiveByteCount -= 2; + + DSPI_ClearStatusFlags(base, kDSPI_RxFifoDrainRequestFlag); + } + } + } + } + } + + return kStatus_Success; +} + +static void DSPI_MasterTransferPrepare(SPI_Type *base, dspi_master_handle_t *handle, dspi_transfer_t *transfer) +{ + assert(handle); + assert(transfer); + + dspi_command_data_config_t commandStruct; + + DSPI_StopTransfer(base); + DSPI_FlushFifo(base, true, true); + DSPI_ClearStatusFlags(base, kDSPI_AllStatusFlag); + + commandStruct.whichPcs = + (dspi_which_pcs_t)(1U << ((transfer->configFlags & DSPI_MASTER_PCS_MASK) >> DSPI_MASTER_PCS_SHIFT)); + commandStruct.isEndOfQueue = false; + commandStruct.clearTransferCount = false; + commandStruct.whichCtar = + (dspi_ctar_selection_t)((transfer->configFlags & DSPI_MASTER_CTAR_MASK) >> DSPI_MASTER_CTAR_SHIFT); + commandStruct.isPcsContinuous = (bool)(transfer->configFlags & kDSPI_MasterPcsContinuous); + handle->command = DSPI_MasterGetFormattedCommand(&(commandStruct)); + + commandStruct.isEndOfQueue = true; + commandStruct.isPcsContinuous = (bool)(transfer->configFlags & kDSPI_MasterActiveAfterTransfer); + handle->lastCommand = DSPI_MasterGetFormattedCommand(&(commandStruct)); + + handle->bitsPerFrame = ((base->CTAR[commandStruct.whichCtar] & SPI_CTAR_FMSZ_MASK) >> SPI_CTAR_FMSZ_SHIFT) + 1; + + if ((base->MCR & SPI_MCR_DIS_RXF_MASK) || (base->MCR & SPI_MCR_DIS_TXF_MASK)) + { + handle->fifoSize = 1; + } + else + { + handle->fifoSize = FSL_FEATURE_DSPI_FIFO_SIZEn(base); + } + handle->txData = transfer->txData; + handle->rxData = transfer->rxData; + handle->remainingSendByteCount = transfer->dataSize; + handle->remainingReceiveByteCount = transfer->dataSize; + handle->totalByteCount = transfer->dataSize; +} + +status_t DSPI_MasterTransferNonBlocking(SPI_Type *base, dspi_master_handle_t *handle, dspi_transfer_t *transfer) +{ + assert(handle); + assert(transfer); + + /* If the transfer count is zero, then return immediately.*/ + if (transfer->dataSize == 0) + { + return kStatus_InvalidArgument; + } + + /* Check that we're not busy.*/ + if (handle->state == kDSPI_Busy) + { + return kStatus_DSPI_Busy; + } + + handle->state = kDSPI_Busy; + + /* Disable the NVIC for DSPI peripheral. */ + DisableIRQ(s_dspiIRQ[DSPI_GetInstance(base)]); + + DSPI_MasterTransferPrepare(base, handle, transfer); + + /* RX FIFO Drain request: RFDF_RE to enable RFDF interrupt + * Since SPI is a synchronous interface, we only need to enable the RX interrupt. + * The IRQ handler will get the status of RX and TX interrupt flags. + */ + s_dspiMasterIsr = DSPI_MasterTransferHandleIRQ; + + DSPI_EnableInterrupts(base, kDSPI_RxFifoDrainRequestInterruptEnable); + DSPI_StartTransfer(base); + + /* Fill up the Tx FIFO to trigger the transfer. */ + DSPI_MasterTransferFillUpTxFifo(base, handle); + + /* Enable the NVIC for DSPI peripheral. */ + EnableIRQ(s_dspiIRQ[DSPI_GetInstance(base)]); + + return kStatus_Success; +} + +status_t DSPI_MasterHalfDuplexTransferBlocking(SPI_Type *base, dspi_half_duplex_transfer_t *xfer) +{ + assert(xfer); + + dspi_transfer_t tempXfer = {0}; + status_t status; + + if (xfer->isTransmitFirst) + { + tempXfer.txData = xfer->txData; + tempXfer.rxData = NULL; + tempXfer.dataSize = xfer->txDataSize; + } + else + { + tempXfer.txData = NULL; + tempXfer.rxData = xfer->rxData; + tempXfer.dataSize = xfer->rxDataSize; + } + /* If the pcs pin keep assert between transmit and receive. */ + if (xfer->isPcsAssertInTransfer) + { + tempXfer.configFlags = (xfer->configFlags) | kDSPI_MasterActiveAfterTransfer; + } + else + { + tempXfer.configFlags = (xfer->configFlags) & (uint32_t)(~kDSPI_MasterActiveAfterTransfer); + } + + status = DSPI_MasterTransferBlocking(base, &tempXfer); + if (status != kStatus_Success) + { + return status; + } + + if (xfer->isTransmitFirst) + { + tempXfer.txData = NULL; + tempXfer.rxData = xfer->rxData; + tempXfer.dataSize = xfer->rxDataSize; + } + else + { + tempXfer.txData = xfer->txData; + tempXfer.rxData = NULL; + tempXfer.dataSize = xfer->txDataSize; + } + tempXfer.configFlags = xfer->configFlags; + + /* DSPI transfer blocking. */ + status = DSPI_MasterTransferBlocking(base, &tempXfer); + + return status; +} + +status_t DSPI_MasterHalfDuplexTransferNonBlocking(SPI_Type *base, + dspi_master_handle_t *handle, + dspi_half_duplex_transfer_t *xfer) +{ + assert(xfer); + assert(handle); + dspi_transfer_t tempXfer = {0}; + status_t status; + + if (xfer->isTransmitFirst) + { + tempXfer.txData = xfer->txData; + tempXfer.rxData = NULL; + tempXfer.dataSize = xfer->txDataSize; + } + else + { + tempXfer.txData = NULL; + tempXfer.rxData = xfer->rxData; + tempXfer.dataSize = xfer->rxDataSize; + } + /* If the pcs pin keep assert between transmit and receive. */ + if (xfer->isPcsAssertInTransfer) + { + tempXfer.configFlags = (xfer->configFlags) | kDSPI_MasterActiveAfterTransfer; + } + else + { + tempXfer.configFlags = (xfer->configFlags) & (uint32_t)(~kDSPI_MasterActiveAfterTransfer); + } + + status = DSPI_MasterTransferBlocking(base, &tempXfer); + if (status != kStatus_Success) + { + return status; + } + + if (xfer->isTransmitFirst) + { + tempXfer.txData = NULL; + tempXfer.rxData = xfer->rxData; + tempXfer.dataSize = xfer->rxDataSize; + } + else + { + tempXfer.txData = xfer->txData; + tempXfer.rxData = NULL; + tempXfer.dataSize = xfer->txDataSize; + } + tempXfer.configFlags = xfer->configFlags; + + status = DSPI_MasterTransferNonBlocking(base, handle, &tempXfer); + + return status; +} + +status_t DSPI_MasterTransferGetCount(SPI_Type *base, dspi_master_handle_t *handle, size_t *count) +{ + assert(handle); + + if (!count) + { + return kStatus_InvalidArgument; + } + + /* Catch when there is not an active transfer. */ + if (handle->state != kDSPI_Busy) + { + *count = 0; + return kStatus_NoTransferInProgress; + } + + *count = handle->totalByteCount - handle->remainingReceiveByteCount; + return kStatus_Success; +} + +static void DSPI_MasterTransferComplete(SPI_Type *base, dspi_master_handle_t *handle) +{ + assert(handle); + + /* Disable interrupt requests*/ + DSPI_DisableInterrupts(base, kDSPI_RxFifoDrainRequestInterruptEnable | kDSPI_TxFifoFillRequestInterruptEnable); + + status_t status = 0; + if (handle->state == kDSPI_Error) + { + status = kStatus_DSPI_Error; + } + else + { + status = kStatus_Success; + } + + handle->state = kDSPI_Idle; + + if (handle->callback) + { + handle->callback(base, handle, status, handle->userData); + } +} + +static void DSPI_MasterTransferFillUpTxFifo(SPI_Type *base, dspi_master_handle_t *handle) +{ + assert(handle); + + uint16_t wordToSend = 0; + uint8_t dummyData = g_dspiDummyData[DSPI_GetInstance(base)]; + + /* If bits/frame is greater than one byte */ + if (handle->bitsPerFrame > 8) + { + /* Fill the fifo until it is full or until the send word count is 0 or until the difference + * between the remainingReceiveByteCount and remainingSendByteCount equals the FIFO depth. + * The reason for checking the difference is to ensure we only send as much as the + * RX FIFO can receive. + * For this case where bitsPerFrame > 8, each entry in the FIFO contains 2 bytes of the + * send data, hence the difference between the remainingReceiveByteCount and + * remainingSendByteCount must be divided by 2 to convert this difference into a + * 16-bit (2 byte) value. + */ + while ((DSPI_GetStatusFlags(base) & kDSPI_TxFifoFillRequestFlag) && + ((handle->remainingReceiveByteCount - handle->remainingSendByteCount) / 2 < handle->fifoSize)) + { + if (handle->remainingSendByteCount <= 2) + { + if (handle->txData) + { + if (handle->remainingSendByteCount == 1) + { + wordToSend = *(handle->txData); + } + else + { + wordToSend = *(handle->txData); + ++handle->txData; /* increment to next data byte */ + wordToSend |= (unsigned)(*(handle->txData)) << 8U; + } + } + else + { + wordToSend = dummyData; + } + handle->remainingSendByteCount = 0; + base->PUSHR = handle->lastCommand | wordToSend; + } + /* For all words except the last word */ + else + { + if (handle->txData) + { + wordToSend = *(handle->txData); + ++handle->txData; /* increment to next data byte */ + wordToSend |= (unsigned)(*(handle->txData)) << 8U; + ++handle->txData; /* increment to next data byte */ + } + else + { + wordToSend = dummyData; + } + handle->remainingSendByteCount -= 2; /* decrement remainingSendByteCount by 2 */ + base->PUSHR = handle->command | wordToSend; + } + + /* Try to clear the TFFF; if the TX FIFO is full this will clear */ + DSPI_ClearStatusFlags(base, kDSPI_TxFifoFillRequestFlag); + + /* exit loop if send count is zero, else update local variables for next loop. + * If this is the first time write to the PUSHR, write only once. + */ + if ((handle->remainingSendByteCount == 0) || (handle->remainingSendByteCount == handle->totalByteCount - 2)) + { + break; + } + } /* End of TX FIFO fill while loop */ + } + /* Optimized for bits/frame less than or equal to one byte. */ + else + { + /* Fill the fifo until it is full or until the send word count is 0 or until the difference + * between the remainingReceiveByteCount and remainingSendByteCount equals the FIFO depth. + * The reason for checking the difference is to ensure we only send as much as the + * RX FIFO can receive. + */ + while ((DSPI_GetStatusFlags(base) & kDSPI_TxFifoFillRequestFlag) && + ((handle->remainingReceiveByteCount - handle->remainingSendByteCount) < handle->fifoSize)) + { + if (handle->txData) + { + wordToSend = *(handle->txData); + ++handle->txData; + } + else + { + wordToSend = dummyData; + } + + if (handle->remainingSendByteCount == 1) + { + base->PUSHR = handle->lastCommand | wordToSend; + } + else + { + base->PUSHR = handle->command | wordToSend; + } + + /* Try to clear the TFFF; if the TX FIFO is full this will clear */ + DSPI_ClearStatusFlags(base, kDSPI_TxFifoFillRequestFlag); + + --handle->remainingSendByteCount; + + /* exit loop if send count is zero, else update local variables for next loop + * If this is the first time write to the PUSHR, write only once. + */ + if ((handle->remainingSendByteCount == 0) || (handle->remainingSendByteCount == handle->totalByteCount - 1)) + { + break; + } + } + } +} + +void DSPI_MasterTransferAbort(SPI_Type *base, dspi_master_handle_t *handle) +{ + assert(handle); + + DSPI_StopTransfer(base); + + /* Disable interrupt requests*/ + DSPI_DisableInterrupts(base, kDSPI_RxFifoDrainRequestInterruptEnable | kDSPI_TxFifoFillRequestInterruptEnable); + + handle->state = kDSPI_Idle; +} + +void DSPI_MasterTransferHandleIRQ(SPI_Type *base, dspi_master_handle_t *handle) +{ + assert(handle); + + /* RECEIVE IRQ handler: Check read buffer only if there are remaining bytes to read. */ + if (handle->remainingReceiveByteCount) + { + /* Check read buffer.*/ + uint16_t wordReceived; /* Maximum supported data bit length in master mode is 16-bits */ + + /* If bits/frame is greater than one byte */ + if (handle->bitsPerFrame > 8) + { + while (DSPI_GetStatusFlags(base) & kDSPI_RxFifoDrainRequestFlag) + { + wordReceived = DSPI_ReadData(base); + /* clear the rx fifo drain request, needed for non-DMA applications as this flag + * will remain set even if the rx fifo is empty. By manually clearing this flag, it + * either remain clear if no more data is in the fifo, or it will set if there is + * more data in the fifo. + */ + DSPI_ClearStatusFlags(base, kDSPI_RxFifoDrainRequestFlag); + + /* Store read bytes into rx buffer only if a buffer pointer was provided */ + if (handle->rxData) + { + /* For the last word received, if there is an extra byte due to the odd transfer + * byte count, only save the last byte and discard the upper byte + */ + if (handle->remainingReceiveByteCount == 1) + { + *handle->rxData = wordReceived; /* Write first data byte */ + --handle->remainingReceiveByteCount; + } + else + { + *handle->rxData = wordReceived; /* Write first data byte */ + ++handle->rxData; /* increment to next data byte */ + *handle->rxData = wordReceived >> 8; /* Write second data byte */ + ++handle->rxData; /* increment to next data byte */ + handle->remainingReceiveByteCount -= 2; + } + } + else + { + if (handle->remainingReceiveByteCount == 1) + { + --handle->remainingReceiveByteCount; + } + else + { + handle->remainingReceiveByteCount -= 2; + } + } + if (handle->remainingReceiveByteCount == 0) + { + break; + } + } /* End of RX FIFO drain while loop */ + } + /* Optimized for bits/frame less than or equal to one byte. */ + else + { + while (DSPI_GetStatusFlags(base) & kDSPI_RxFifoDrainRequestFlag) + { + wordReceived = DSPI_ReadData(base); + /* clear the rx fifo drain request, needed for non-DMA applications as this flag + * will remain set even if the rx fifo is empty. By manually clearing this flag, it + * either remain clear if no more data is in the fifo, or it will set if there is + * more data in the fifo. + */ + DSPI_ClearStatusFlags(base, kDSPI_RxFifoDrainRequestFlag); + + /* Store read bytes into rx buffer only if a buffer pointer was provided */ + if (handle->rxData) + { + *handle->rxData = wordReceived; + ++handle->rxData; + } + + --handle->remainingReceiveByteCount; + + if (handle->remainingReceiveByteCount == 0) + { + break; + } + } /* End of RX FIFO drain while loop */ + } + } + + /* Check write buffer. We always have to send a word in order to keep the transfer + * moving. So if the caller didn't provide a send buffer, we just send a zero. + */ + if (handle->remainingSendByteCount) + { + DSPI_MasterTransferFillUpTxFifo(base, handle); + } + + /* Check if we're done with this transfer.*/ + if ((handle->remainingSendByteCount == 0) && (handle->remainingReceiveByteCount == 0)) + { + /* Complete the transfer and disable the interrupts */ + DSPI_MasterTransferComplete(base, handle); + } +} + +/*Transactional APIs -- Slave*/ +void DSPI_SlaveTransferCreateHandle(SPI_Type *base, + dspi_slave_handle_t *handle, + dspi_slave_transfer_callback_t callback, + void *userData) +{ + assert(handle); + + /* Zero the handle. */ + memset(handle, 0, sizeof(*handle)); + + g_dspiHandle[DSPI_GetInstance(base)] = handle; + + handle->callback = callback; + handle->userData = userData; +} + +status_t DSPI_SlaveTransferNonBlocking(SPI_Type *base, dspi_slave_handle_t *handle, dspi_transfer_t *transfer) +{ + assert(handle); + assert(transfer); + + /* If receive length is zero */ + if (transfer->dataSize == 0) + { + return kStatus_InvalidArgument; + } + + /* If both send buffer and receive buffer is null */ + if ((!(transfer->txData)) && (!(transfer->rxData))) + { + return kStatus_InvalidArgument; + } + + /* Check that we're not busy.*/ + if (handle->state == kDSPI_Busy) + { + return kStatus_DSPI_Busy; + } + handle->state = kDSPI_Busy; + + /* Enable the NVIC for DSPI peripheral. */ + EnableIRQ(s_dspiIRQ[DSPI_GetInstance(base)]); + + /* Store transfer information */ + handle->txData = transfer->txData; + handle->rxData = transfer->rxData; + handle->remainingSendByteCount = transfer->dataSize; + handle->remainingReceiveByteCount = transfer->dataSize; + handle->totalByteCount = transfer->dataSize; + + handle->errorCount = 0; + + uint8_t whichCtar = (transfer->configFlags & DSPI_SLAVE_CTAR_MASK) >> DSPI_SLAVE_CTAR_SHIFT; + handle->bitsPerFrame = + (((base->CTAR_SLAVE[whichCtar]) & SPI_CTAR_SLAVE_FMSZ_MASK) >> SPI_CTAR_SLAVE_FMSZ_SHIFT) + 1; + + DSPI_StopTransfer(base); + + DSPI_FlushFifo(base, true, true); + DSPI_ClearStatusFlags(base, kDSPI_AllStatusFlag); + + s_dspiSlaveIsr = DSPI_SlaveTransferHandleIRQ; + + /* Enable RX FIFO drain request, the slave only use this interrupt */ + DSPI_EnableInterrupts(base, kDSPI_RxFifoDrainRequestInterruptEnable); + + if (handle->rxData) + { + /* RX FIFO overflow request enable */ + DSPI_EnableInterrupts(base, kDSPI_RxFifoOverflowInterruptEnable); + } + if (handle->txData) + { + /* TX FIFO underflow request enable */ + DSPI_EnableInterrupts(base, kDSPI_TxFifoUnderflowInterruptEnable); + } + + DSPI_StartTransfer(base); + + /* Prepare data to transmit */ + DSPI_SlaveTransferFillUpTxFifo(base, handle); + + return kStatus_Success; +} + +status_t DSPI_SlaveTransferGetCount(SPI_Type *base, dspi_slave_handle_t *handle, size_t *count) +{ + assert(handle); + + if (!count) + { + return kStatus_InvalidArgument; + } + + /* Catch when there is not an active transfer. */ + if (handle->state != kDSPI_Busy) + { + *count = 0; + return kStatus_NoTransferInProgress; + } + + *count = handle->totalByteCount - handle->remainingReceiveByteCount; + return kStatus_Success; +} + +static void DSPI_SlaveTransferFillUpTxFifo(SPI_Type *base, dspi_slave_handle_t *handle) +{ + assert(handle); + + uint16_t transmitData = 0; + uint8_t dummyPattern = g_dspiDummyData[DSPI_GetInstance(base)]; + + /* Service the transmitter, if transmit buffer provided, transmit the data, + * else transmit dummy pattern + */ + while (DSPI_GetStatusFlags(base) & kDSPI_TxFifoFillRequestFlag) + { + /* Transmit data */ + if (handle->remainingSendByteCount > 0) + { + /* Have data to transmit, update the transmit data and push to FIFO */ + if (handle->bitsPerFrame <= 8) + { + /* bits/frame is 1 byte */ + if (handle->txData) + { + /* Update transmit data and transmit pointer */ + transmitData = *handle->txData; + handle->txData++; + } + else + { + transmitData = dummyPattern; + } + + /* Decrease remaining dataSize */ + --handle->remainingSendByteCount; + } + /* bits/frame is 2 bytes */ + else + { + /* With multibytes per frame transmission, the transmit frame contains data from + * transmit buffer until sent dataSize matches user request. Other bytes will set to + * dummy pattern value. + */ + if (handle->txData) + { + /* Update first byte of transmit data and transmit pointer */ + transmitData = *handle->txData; + handle->txData++; + + if (handle->remainingSendByteCount == 1) + { + /* Decrease remaining dataSize */ + --handle->remainingSendByteCount; + /* Update second byte of transmit data to second byte of dummy pattern */ + transmitData = transmitData | (uint16_t)(((uint16_t)dummyPattern) << 8); + } + else + { + /* Update second byte of transmit data and transmit pointer */ + transmitData = transmitData | (uint16_t)((uint16_t)(*handle->txData) << 8); + handle->txData++; + handle->remainingSendByteCount -= 2; + } + } + else + { + if (handle->remainingSendByteCount == 1) + { + --handle->remainingSendByteCount; + } + else + { + handle->remainingSendByteCount -= 2; + } + transmitData = (uint16_t)((uint16_t)(dummyPattern) << 8) | dummyPattern; + } + } + } + else + { + break; + } + + /* Write the data to the DSPI data register */ + base->PUSHR_SLAVE = transmitData; + + /* Try to clear TFFF by writing a one to it; it will not clear if TX FIFO not full */ + DSPI_ClearStatusFlags(base, kDSPI_TxFifoFillRequestFlag); + } +} + +static void DSPI_SlaveTransferComplete(SPI_Type *base, dspi_slave_handle_t *handle) +{ + assert(handle); + + /* Disable interrupt requests */ + DSPI_DisableInterrupts(base, kDSPI_TxFifoUnderflowInterruptEnable | kDSPI_TxFifoFillRequestInterruptEnable | + kDSPI_RxFifoOverflowInterruptEnable | kDSPI_RxFifoDrainRequestInterruptEnable); + + /* The transfer is complete. */ + handle->txData = NULL; + handle->rxData = NULL; + handle->remainingReceiveByteCount = 0; + handle->remainingSendByteCount = 0; + + status_t status = 0; + if (handle->state == kDSPI_Error) + { + status = kStatus_DSPI_Error; + } + else + { + status = kStatus_Success; + } + + handle->state = kDSPI_Idle; + + if (handle->callback) + { + handle->callback(base, handle, status, handle->userData); + } +} + +void DSPI_SlaveTransferAbort(SPI_Type *base, dspi_slave_handle_t *handle) +{ + assert(handle); + + DSPI_StopTransfer(base); + + /* Disable interrupt requests */ + DSPI_DisableInterrupts(base, kDSPI_TxFifoUnderflowInterruptEnable | kDSPI_TxFifoFillRequestInterruptEnable | + kDSPI_RxFifoOverflowInterruptEnable | kDSPI_RxFifoDrainRequestInterruptEnable); + + handle->state = kDSPI_Idle; + handle->remainingSendByteCount = 0; + handle->remainingReceiveByteCount = 0; +} + +void DSPI_SlaveTransferHandleIRQ(SPI_Type *base, dspi_slave_handle_t *handle) +{ + assert(handle); + + uint8_t dummyPattern = g_dspiDummyData[DSPI_GetInstance(base)]; + uint32_t dataReceived; + uint32_t dataSend = 0; + + /* Because SPI protocol is synchronous, the number of bytes that that slave received from the + * master is the actual number of bytes that the slave transmitted to the master. So we only + * monitor the received dataSize to know when the transfer is complete. + */ + if (handle->remainingReceiveByteCount > 0) + { + while (DSPI_GetStatusFlags(base) & kDSPI_RxFifoDrainRequestFlag) + { + /* Have received data in the buffer. */ + dataReceived = base->POPR; + /*Clear the rx fifo drain request, needed for non-DMA applications as this flag + * will remain set even if the rx fifo is empty. By manually clearing this flag, it + * either remain clear if no more data is in the fifo, or it will set if there is + * more data in the fifo. + */ + DSPI_ClearStatusFlags(base, kDSPI_RxFifoDrainRequestFlag); + + /* If bits/frame is one byte */ + if (handle->bitsPerFrame <= 8) + { + if (handle->rxData) + { + /* Receive buffer is not null, store data into it */ + *handle->rxData = dataReceived; + ++handle->rxData; + } + /* Descrease remaining receive byte count */ + --handle->remainingReceiveByteCount; + + if (handle->remainingSendByteCount > 0) + { + if (handle->txData) + { + dataSend = *handle->txData; + ++handle->txData; + } + else + { + dataSend = dummyPattern; + } + + --handle->remainingSendByteCount; + /* Write the data to the DSPI data register */ + base->PUSHR_SLAVE = dataSend; + } + } + else /* If bits/frame is 2 bytes */ + { + /* With multibytes frame receiving, we only receive till the received dataSize + * matches user request. Other bytes will be ignored. + */ + if (handle->rxData) + { + /* Receive buffer is not null, store first byte into it */ + *handle->rxData = dataReceived; + ++handle->rxData; + + if (handle->remainingReceiveByteCount == 1) + { + /* Decrease remaining receive byte count */ + --handle->remainingReceiveByteCount; + } + else + { + /* Receive buffer is not null, store second byte into it */ + *handle->rxData = dataReceived >> 8; + ++handle->rxData; + handle->remainingReceiveByteCount -= 2; + } + } + /* If no handle->rxData*/ + else + { + if (handle->remainingReceiveByteCount == 1) + { + /* Decrease remaining receive byte count */ + --handle->remainingReceiveByteCount; + } + else + { + handle->remainingReceiveByteCount -= 2; + } + } + + if (handle->remainingSendByteCount > 0) + { + if (handle->txData) + { + dataSend = *handle->txData; + ++handle->txData; + + if (handle->remainingSendByteCount == 1) + { + --handle->remainingSendByteCount; + dataSend |= (uint16_t)((uint16_t)(dummyPattern) << 8); + } + else + { + dataSend |= (uint32_t)(*handle->txData) << 8; + ++handle->txData; + handle->remainingSendByteCount -= 2; + } + } + /* If no handle->txData*/ + else + { + if (handle->remainingSendByteCount == 1) + { + --handle->remainingSendByteCount; + } + else + { + handle->remainingSendByteCount -= 2; + } + dataSend = (uint16_t)((uint16_t)(dummyPattern) << 8) | dummyPattern; + } + /* Write the data to the DSPI data register */ + base->PUSHR_SLAVE = dataSend; + } + } + /* Try to clear TFFF by writing a one to it; it will not clear if TX FIFO not full */ + DSPI_ClearStatusFlags(base, kDSPI_TxFifoFillRequestFlag); + + if (handle->remainingReceiveByteCount == 0) + { + break; + } + } + } + /* Check if remaining receive byte count matches user request */ + if ((handle->remainingReceiveByteCount == 0) || (handle->state == kDSPI_Error)) + { + /* Other cases, stop the transfer. */ + DSPI_SlaveTransferComplete(base, handle); + return; + } + + /* Catch tx fifo underflow conditions, service only if tx under flow interrupt enabled */ + if ((DSPI_GetStatusFlags(base) & kDSPI_TxFifoUnderflowFlag) && (base->RSER & SPI_RSER_TFUF_RE_MASK)) + { + DSPI_ClearStatusFlags(base, kDSPI_TxFifoUnderflowFlag); + /* Change state to error and clear flag */ + if (handle->txData) + { + handle->state = kDSPI_Error; + } + handle->errorCount++; + } + /* Catch rx fifo overflow conditions, service only if rx over flow interrupt enabled */ + if ((DSPI_GetStatusFlags(base) & kDSPI_RxFifoOverflowFlag) && (base->RSER & SPI_RSER_RFOF_RE_MASK)) + { + DSPI_ClearStatusFlags(base, kDSPI_RxFifoOverflowFlag); + /* Change state to error and clear flag */ + if (handle->txData) + { + handle->state = kDSPI_Error; + } + handle->errorCount++; + } +} + +static void DSPI_CommonIRQHandler(SPI_Type *base, void *param) +{ + if (DSPI_IsMaster(base)) + { + s_dspiMasterIsr(base, (dspi_master_handle_t *)param); + } + else + { + s_dspiSlaveIsr(base, (dspi_slave_handle_t *)param); + } +/* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +#if defined(SPI0) +void SPI0_DriverIRQHandler(void) +{ + assert(g_dspiHandle[0]); + DSPI_CommonIRQHandler(SPI0, g_dspiHandle[0]); +} +#endif + +#if defined(SPI1) +void SPI1_DriverIRQHandler(void) +{ + assert(g_dspiHandle[1]); + DSPI_CommonIRQHandler(SPI1, g_dspiHandle[1]); +} +#endif + +#if defined(SPI2) +void SPI2_DriverIRQHandler(void) +{ + assert(g_dspiHandle[2]); + DSPI_CommonIRQHandler(SPI2, g_dspiHandle[2]); +} +#endif + +#if defined(SPI3) +void SPI3_DriverIRQHandler(void) +{ + assert(g_dspiHandle[3]); + DSPI_CommonIRQHandler(SPI3, g_dspiHandle[3]); +} +#endif + +#if defined(SPI4) +void SPI4_DriverIRQHandler(void) +{ + assert(g_dspiHandle[4]); + DSPI_CommonIRQHandler(SPI4, g_dspiHandle[4]); +} +#endif + +#if defined(SPI5) +void SPI5_DriverIRQHandler(void) +{ + assert(g_dspiHandle[5]); + DSPI_CommonIRQHandler(SPI5, g_dspiHandle[5]); +} +#endif + +#if (FSL_FEATURE_SOC_DSPI_COUNT > 6) +#error "Should write the SPIx_DriverIRQHandler function that instance greater than 5 !" +#endif diff --git a/drivers/fsl_dspi.h b/drivers/fsl_dspi.h new file mode 100644 index 0000000..39bac8b --- /dev/null +++ b/drivers/fsl_dspi.h @@ -0,0 +1,1248 @@ +/* + * The Clear BSD License + * Copyright (c) 2015, 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: + * + * o Redistributions of source code must retain the above copyright notice, this list + * of conditions and the following disclaimer. + * + * o 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. + * + * o 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_DSPI_H_ +#define _FSL_DSPI_H_ + +#include "fsl_common.h" + +/*! + * @addtogroup dspi_driver + * @{ + */ + +/********************************************************************************************************************** + * Definitions + *********************************************************************************************************************/ + +/*! @name Driver version */ +/*@{*/ +/*! @brief DSPI driver version 2.2.0. */ +#define FSL_DSPI_DRIVER_VERSION (MAKE_VERSION(2, 2, 0)) +/*@}*/ + +#ifndef DSPI_DUMMY_DATA +/*! @brief DSPI dummy data if there is no Tx data.*/ +#define DSPI_DUMMY_DATA (0x00U) /*!< Dummy data used for Tx if there is no txData. */ +#endif + +/*! @brief Global variable for dummy data value setting. */ +extern volatile uint8_t g_dspiDummyData[]; + +/*! @brief Status for the DSPI driver.*/ +enum _dspi_status +{ + kStatus_DSPI_Busy = MAKE_STATUS(kStatusGroup_DSPI, 0), /*!< DSPI transfer is busy.*/ + kStatus_DSPI_Error = MAKE_STATUS(kStatusGroup_DSPI, 1), /*!< DSPI driver error. */ + kStatus_DSPI_Idle = MAKE_STATUS(kStatusGroup_DSPI, 2), /*!< DSPI is idle.*/ + kStatus_DSPI_OutOfRange = MAKE_STATUS(kStatusGroup_DSPI, 3) /*!< DSPI transfer out of range. */ +}; + +/*! @brief DSPI status flags in SPIx_SR register.*/ +enum _dspi_flags +{ + kDSPI_TxCompleteFlag = SPI_SR_TCF_MASK, /*!< Transfer Complete Flag. */ + kDSPI_EndOfQueueFlag = SPI_SR_EOQF_MASK, /*!< End of Queue Flag.*/ + kDSPI_TxFifoUnderflowFlag = SPI_SR_TFUF_MASK, /*!< Transmit FIFO Underflow Flag.*/ + kDSPI_TxFifoFillRequestFlag = SPI_SR_TFFF_MASK, /*!< Transmit FIFO Fill Flag.*/ + kDSPI_RxFifoOverflowFlag = SPI_SR_RFOF_MASK, /*!< Receive FIFO Overflow Flag.*/ + kDSPI_RxFifoDrainRequestFlag = SPI_SR_RFDF_MASK, /*!< Receive FIFO Drain Flag.*/ + kDSPI_TxAndRxStatusFlag = SPI_SR_TXRXS_MASK, /*!< The module is in Stopped/Running state.*/ + kDSPI_AllStatusFlag = SPI_SR_TCF_MASK | SPI_SR_EOQF_MASK | SPI_SR_TFUF_MASK | SPI_SR_TFFF_MASK | SPI_SR_RFOF_MASK | + SPI_SR_RFDF_MASK | SPI_SR_TXRXS_MASK /*!< All statuses above.*/ +}; + +/*! @brief DSPI interrupt source.*/ +enum _dspi_interrupt_enable +{ + kDSPI_TxCompleteInterruptEnable = SPI_RSER_TCF_RE_MASK, /*!< TCF interrupt enable.*/ + kDSPI_EndOfQueueInterruptEnable = SPI_RSER_EOQF_RE_MASK, /*!< EOQF interrupt enable.*/ + kDSPI_TxFifoUnderflowInterruptEnable = SPI_RSER_TFUF_RE_MASK, /*!< TFUF interrupt enable.*/ + kDSPI_TxFifoFillRequestInterruptEnable = SPI_RSER_TFFF_RE_MASK, /*!< TFFF interrupt enable, DMA disable.*/ + kDSPI_RxFifoOverflowInterruptEnable = SPI_RSER_RFOF_RE_MASK, /*!< RFOF interrupt enable.*/ + kDSPI_RxFifoDrainRequestInterruptEnable = SPI_RSER_RFDF_RE_MASK, /*!< RFDF interrupt enable, DMA disable.*/ + kDSPI_AllInterruptEnable = SPI_RSER_TCF_RE_MASK | SPI_RSER_EOQF_RE_MASK | SPI_RSER_TFUF_RE_MASK | + SPI_RSER_TFFF_RE_MASK | SPI_RSER_RFOF_RE_MASK | SPI_RSER_RFDF_RE_MASK + /*!< All above interrupts enable.*/ +}; + +/*! @brief DSPI DMA source.*/ +enum _dspi_dma_enable +{ + kDSPI_TxDmaEnable = (SPI_RSER_TFFF_RE_MASK | SPI_RSER_TFFF_DIRS_MASK), /*!< TFFF flag generates DMA requests. + No Tx interrupt request. */ + kDSPI_RxDmaEnable = (SPI_RSER_RFDF_RE_MASK | SPI_RSER_RFDF_DIRS_MASK) /*!< RFDF flag generates DMA requests. + No Rx interrupt request. */ +}; + +/*! @brief DSPI master or slave mode configuration.*/ +typedef enum _dspi_master_slave_mode +{ + kDSPI_Master = 1U, /*!< DSPI peripheral operates in master mode.*/ + kDSPI_Slave = 0U /*!< DSPI peripheral operates in slave mode.*/ +} dspi_master_slave_mode_t; + +/*! + * @brief DSPI Sample Point: Controls when the DSPI master samples SIN in the Modified Transfer Format. This field is + * valid + * only when the CPHA bit in the CTAR register is 0. + */ +typedef enum _dspi_master_sample_point +{ + kDSPI_SckToSin0Clock = 0U, /*!< 0 system clocks between SCK edge and SIN sample.*/ + kDSPI_SckToSin1Clock = 1U, /*!< 1 system clock between SCK edge and SIN sample.*/ + kDSPI_SckToSin2Clock = 2U /*!< 2 system clocks between SCK edge and SIN sample.*/ +} dspi_master_sample_point_t; + +/*! @brief DSPI Peripheral Chip Select (Pcs) configuration (which Pcs to configure).*/ +typedef enum _dspi_which_pcs_config +{ + kDSPI_Pcs0 = 1U << 0, /*!< Pcs[0] */ + kDSPI_Pcs1 = 1U << 1, /*!< Pcs[1] */ + kDSPI_Pcs2 = 1U << 2, /*!< Pcs[2] */ + kDSPI_Pcs3 = 1U << 3, /*!< Pcs[3] */ + kDSPI_Pcs4 = 1U << 4, /*!< Pcs[4] */ + kDSPI_Pcs5 = 1U << 5 /*!< Pcs[5] */ +} dspi_which_pcs_t; + +/*! @brief DSPI Peripheral Chip Select (Pcs) Polarity configuration.*/ +typedef enum _dspi_pcs_polarity_config +{ + kDSPI_PcsActiveHigh = 0U, /*!< Pcs Active High (idles low). */ + kDSPI_PcsActiveLow = 1U /*!< Pcs Active Low (idles high). */ +} dspi_pcs_polarity_config_t; + +/*! @brief DSPI Peripheral Chip Select (Pcs) Polarity.*/ +enum _dspi_pcs_polarity +{ + kDSPI_Pcs0ActiveLow = 1U << 0, /*!< Pcs0 Active Low (idles high). */ + kDSPI_Pcs1ActiveLow = 1U << 1, /*!< Pcs1 Active Low (idles high). */ + kDSPI_Pcs2ActiveLow = 1U << 2, /*!< Pcs2 Active Low (idles high). */ + kDSPI_Pcs3ActiveLow = 1U << 3, /*!< Pcs3 Active Low (idles high). */ + kDSPI_Pcs4ActiveLow = 1U << 4, /*!< Pcs4 Active Low (idles high). */ + kDSPI_Pcs5ActiveLow = 1U << 5, /*!< Pcs5 Active Low (idles high). */ + kDSPI_PcsAllActiveLow = 0xFFU /*!< Pcs0 to Pcs5 Active Low (idles high). */ +}; + +/*! @brief DSPI clock polarity configuration for a given CTAR.*/ +typedef enum _dspi_clock_polarity +{ + kDSPI_ClockPolarityActiveHigh = 0U, /*!< CPOL=0. Active-high DSPI clock (idles low).*/ + kDSPI_ClockPolarityActiveLow = 1U /*!< CPOL=1. Active-low DSPI clock (idles high).*/ +} dspi_clock_polarity_t; + +/*! @brief DSPI clock phase configuration for a given CTAR.*/ +typedef enum _dspi_clock_phase +{ + kDSPI_ClockPhaseFirstEdge = 0U, /*!< CPHA=0. Data is captured on the leading edge of the SCK and changed on the + following edge.*/ + kDSPI_ClockPhaseSecondEdge = 1U /*!< CPHA=1. Data is changed on the leading edge of the SCK and captured on the + following edge.*/ +} dspi_clock_phase_t; + +/*! @brief DSPI data shifter direction options for a given CTAR.*/ +typedef enum _dspi_shift_direction +{ + kDSPI_MsbFirst = 0U, /*!< Data transfers start with most significant bit.*/ + kDSPI_LsbFirst = 1U /*!< Data transfers start with least significant bit. + Shifting out of LSB is not supported for slave */ +} dspi_shift_direction_t; + +/*! @brief DSPI delay type selection.*/ +typedef enum _dspi_delay_type +{ + kDSPI_PcsToSck = 1U, /*!< Pcs-to-SCK delay. */ + kDSPI_LastSckToPcs, /*!< The last SCK edge to Pcs delay. */ + kDSPI_BetweenTransfer /*!< Delay between transfers. */ +} dspi_delay_type_t; + +/*! @brief DSPI Clock and Transfer Attributes Register (CTAR) selection.*/ +typedef enum _dspi_ctar_selection +{ + kDSPI_Ctar0 = 0U, /*!< CTAR0 selection option for master or slave mode; note that CTAR0 and CTAR0_SLAVE are the + same register address. */ + kDSPI_Ctar1 = 1U, /*!< CTAR1 selection option for master mode only. */ + kDSPI_Ctar2 = 2U, /*!< CTAR2 selection option for master mode only; note that some devices do not support CTAR2. */ + kDSPI_Ctar3 = 3U, /*!< CTAR3 selection option for master mode only; note that some devices do not support CTAR3. */ + kDSPI_Ctar4 = 4U, /*!< CTAR4 selection option for master mode only; note that some devices do not support CTAR4. */ + kDSPI_Ctar5 = 5U, /*!< CTAR5 selection option for master mode only; note that some devices do not support CTAR5. */ + kDSPI_Ctar6 = 6U, /*!< CTAR6 selection option for master mode only; note that some devices do not support CTAR6. */ + kDSPI_Ctar7 = 7U /*!< CTAR7 selection option for master mode only; note that some devices do not support CTAR7. */ +} dspi_ctar_selection_t; + +#define DSPI_MASTER_CTAR_SHIFT (0U) /*!< DSPI master CTAR shift macro; used internally. */ +#define DSPI_MASTER_CTAR_MASK (0x0FU) /*!< DSPI master CTAR mask macro; used internally. */ +#define DSPI_MASTER_PCS_SHIFT (4U) /*!< DSPI master PCS shift macro; used internally. */ +#define DSPI_MASTER_PCS_MASK (0xF0U) /*!< DSPI master PCS mask macro; used internally. */ +/*! @brief Use this enumeration for the DSPI master transfer configFlags. */ +enum _dspi_transfer_config_flag_for_master +{ + kDSPI_MasterCtar0 = 0U << DSPI_MASTER_CTAR_SHIFT, /*!< DSPI master transfer use CTAR0 setting. */ + kDSPI_MasterCtar1 = 1U << DSPI_MASTER_CTAR_SHIFT, /*!< DSPI master transfer use CTAR1 setting. */ + kDSPI_MasterCtar2 = 2U << DSPI_MASTER_CTAR_SHIFT, /*!< DSPI master transfer use CTAR2 setting. */ + kDSPI_MasterCtar3 = 3U << DSPI_MASTER_CTAR_SHIFT, /*!< DSPI master transfer use CTAR3 setting. */ + kDSPI_MasterCtar4 = 4U << DSPI_MASTER_CTAR_SHIFT, /*!< DSPI master transfer use CTAR4 setting. */ + kDSPI_MasterCtar5 = 5U << DSPI_MASTER_CTAR_SHIFT, /*!< DSPI master transfer use CTAR5 setting. */ + kDSPI_MasterCtar6 = 6U << DSPI_MASTER_CTAR_SHIFT, /*!< DSPI master transfer use CTAR6 setting. */ + kDSPI_MasterCtar7 = 7U << DSPI_MASTER_CTAR_SHIFT, /*!< DSPI master transfer use CTAR7 setting. */ + + kDSPI_MasterPcs0 = 0U << DSPI_MASTER_PCS_SHIFT, /*!< DSPI master transfer use PCS0 signal. */ + kDSPI_MasterPcs1 = 1U << DSPI_MASTER_PCS_SHIFT, /*!< DSPI master transfer use PCS1 signal. */ + kDSPI_MasterPcs2 = 2U << DSPI_MASTER_PCS_SHIFT, /*!< DSPI master transfer use PCS2 signal.*/ + kDSPI_MasterPcs3 = 3U << DSPI_MASTER_PCS_SHIFT, /*!< DSPI master transfer use PCS3 signal. */ + kDSPI_MasterPcs4 = 4U << DSPI_MASTER_PCS_SHIFT, /*!< DSPI master transfer use PCS4 signal. */ + kDSPI_MasterPcs5 = 5U << DSPI_MASTER_PCS_SHIFT, /*!< DSPI master transfer use PCS5 signal. */ + + kDSPI_MasterPcsContinuous = 1U << 20, /*!< Indicates whether the PCS signal is continuous. */ + kDSPI_MasterActiveAfterTransfer = + 1U << 21, /*!< Indicates whether the PCS signal is active after the last frame transfer.*/ +}; + +#define DSPI_SLAVE_CTAR_SHIFT (0U) /*!< DSPI slave CTAR shift macro; used internally. */ +#define DSPI_SLAVE_CTAR_MASK (0x07U) /*!< DSPI slave CTAR mask macro; used internally. */ +/*! @brief Use this enumeration for the DSPI slave transfer configFlags. */ +enum _dspi_transfer_config_flag_for_slave +{ + kDSPI_SlaveCtar0 = 0U << DSPI_SLAVE_CTAR_SHIFT, /*!< DSPI slave transfer use CTAR0 setting. */ + /*!< DSPI slave can only use PCS0. */ +}; + +/*! @brief DSPI transfer state, which is used for DSPI transactional API state machine. */ +enum _dspi_transfer_state +{ + kDSPI_Idle = 0x0U, /*!< Nothing in the transmitter/receiver. */ + kDSPI_Busy, /*!< Transfer queue is not finished. */ + kDSPI_Error /*!< Transfer error. */ +}; + +/*! @brief DSPI master command date configuration used for the SPIx_PUSHR.*/ +typedef struct _dspi_command_data_config +{ + bool isPcsContinuous; /*!< Option to enable the continuous assertion of the chip select between transfers.*/ + dspi_ctar_selection_t whichCtar; /*!< The desired Clock and Transfer Attributes + Register (CTAR) to use for CTAS.*/ + dspi_which_pcs_t whichPcs; /*!< The desired PCS signal to use for the data transfer.*/ + bool isEndOfQueue; /*!< Signals that the current transfer is the last in the queue.*/ + bool clearTransferCount; /*!< Clears the SPI Transfer Counter (SPI_TCNT) before transmission starts.*/ +} dspi_command_data_config_t; + +/*! @brief DSPI master ctar configuration structure.*/ +typedef struct _dspi_master_ctar_config +{ + uint32_t baudRate; /*!< Baud Rate for DSPI. */ + uint32_t bitsPerFrame; /*!< Bits per frame, minimum 4, maximum 16.*/ + dspi_clock_polarity_t cpol; /*!< Clock polarity. */ + dspi_clock_phase_t cpha; /*!< Clock phase. */ + dspi_shift_direction_t direction; /*!< MSB or LSB data shift direction. */ + + uint32_t pcsToSckDelayInNanoSec; /*!< PCS to SCK delay time in nanoseconds; setting to 0 sets the minimum + delay. It also sets the boundary value if out of range.*/ + uint32_t lastSckToPcsDelayInNanoSec; /*!< The last SCK to PCS delay time in nanoseconds; setting to 0 sets the + minimum delay. It also sets the boundary value if out of range.*/ + + uint32_t betweenTransferDelayInNanoSec; /*!< After the SCK delay time in nanoseconds; setting to 0 sets the minimum + delay. It also sets the boundary value if out of range.*/ +} dspi_master_ctar_config_t; + +/*! @brief DSPI master configuration structure.*/ +typedef struct _dspi_master_config +{ + dspi_ctar_selection_t whichCtar; /*!< The desired CTAR to use. */ + dspi_master_ctar_config_t ctarConfig; /*!< Set the ctarConfig to the desired CTAR. */ + + dspi_which_pcs_t whichPcs; /*!< The desired Peripheral Chip Select (pcs). */ + dspi_pcs_polarity_config_t pcsActiveHighOrLow; /*!< The desired PCS active high or low. */ + + bool enableContinuousSCK; /*!< CONT_SCKE, continuous SCK enable. Note that the continuous SCK is only + supported for CPHA = 1.*/ + bool enableRxFifoOverWrite; /*!< ROOE, receive FIFO overflow overwrite enable. If ROOE = 0, the incoming + data is ignored and the data from the transfer that generated the overflow + is also ignored. If ROOE = 1, the incoming data is shifted to the + shift register. */ + + bool enableModifiedTimingFormat; /*!< Enables a modified transfer format to be used if true.*/ + dspi_master_sample_point_t samplePoint; /*!< Controls when the module master samples SIN in the Modified Transfer + Format. It's valid only when CPHA=0. */ +} dspi_master_config_t; + +/*! @brief DSPI slave ctar configuration structure.*/ +typedef struct _dspi_slave_ctar_config +{ + uint32_t bitsPerFrame; /*!< Bits per frame, minimum 4, maximum 16.*/ + dspi_clock_polarity_t cpol; /*!< Clock polarity. */ + dspi_clock_phase_t cpha; /*!< Clock phase. */ + /*!< Slave only supports MSB and does not support LSB.*/ +} dspi_slave_ctar_config_t; + +/*! @brief DSPI slave configuration structure.*/ +typedef struct _dspi_slave_config +{ + dspi_ctar_selection_t whichCtar; /*!< The desired CTAR to use. */ + dspi_slave_ctar_config_t ctarConfig; /*!< Set the ctarConfig to the desired CTAR. */ + + bool enableContinuousSCK; /*!< CONT_SCKE, continuous SCK enable. Note that the continuous SCK is only + supported for CPHA = 1.*/ + bool enableRxFifoOverWrite; /*!< ROOE, receive FIFO overflow overwrite enable. If ROOE = 0, the incoming + data is ignored and the data from the transfer that generated the overflow + is also ignored. If ROOE = 1, the incoming data is shifted to the + shift register. */ + bool enableModifiedTimingFormat; /*!< Enables a modified transfer format to be used if true.*/ + dspi_master_sample_point_t samplePoint; /*!< Controls when the module master samples SIN in the Modified Transfer + Format. It's valid only when CPHA=0. */ +} dspi_slave_config_t; + +/*! +* @brief Forward declaration of the _dspi_master_handle typedefs. +*/ +typedef struct _dspi_master_handle dspi_master_handle_t; + +/*! +* @brief Forward declaration of the _dspi_slave_handle typedefs. +*/ +typedef struct _dspi_slave_handle dspi_slave_handle_t; + +/*! + * @brief Completion callback function pointer type. + * + * @param base DSPI peripheral address. + * @param handle Pointer to the handle for the DSPI master. + * @param status Success or error code describing whether the transfer completed. + * @param userData Arbitrary pointer-dataSized value passed from the application. + */ +typedef void (*dspi_master_transfer_callback_t)(SPI_Type *base, + dspi_master_handle_t *handle, + status_t status, + void *userData); +/*! + * @brief Completion callback function pointer type. + * + * @param base DSPI peripheral address. + * @param handle Pointer to the handle for the DSPI slave. + * @param status Success or error code describing whether the transfer completed. + * @param userData Arbitrary pointer-dataSized value passed from the application. + */ +typedef void (*dspi_slave_transfer_callback_t)(SPI_Type *base, + dspi_slave_handle_t *handle, + status_t status, + void *userData); + +/*! @brief DSPI master/slave transfer structure.*/ +typedef struct _dspi_transfer +{ + uint8_t *txData; /*!< Send buffer. */ + uint8_t *rxData; /*!< Receive buffer. */ + volatile size_t dataSize; /*!< Transfer bytes. */ + + uint32_t + configFlags; /*!< Transfer transfer configuration flags; set from _dspi_transfer_config_flag_for_master if the + transfer is used for master or _dspi_transfer_config_flag_for_slave enumeration if the transfer + is used for slave.*/ +} dspi_transfer_t; + +/*! @brief DSPI half-duplex(master) transfer structure */ +typedef struct _dspi_half_duplex_transfer +{ + uint8_t *txData; /*!< Send buffer */ + uint8_t *rxData; /*!< Receive buffer */ + size_t txDataSize; /*!< Transfer bytes for transmit */ + size_t rxDataSize; /*!< Transfer bytes */ + uint32_t configFlags; /*!< Transfer configuration flags; set from _dspi_transfer_config_flag_for_master. */ + bool isPcsAssertInTransfer; /*!< If Pcs pin keep assert between transmit and receive. true for assert and false for + deassert. */ + bool isTransmitFirst; /*!< True for transmit first and false for receive first. */ +} dspi_half_duplex_transfer_t; + +/*! @brief DSPI master transfer handle structure used for transactional API. */ +struct _dspi_master_handle +{ + uint32_t bitsPerFrame; /*!< The desired number of bits per frame. */ + volatile uint32_t command; /*!< The desired data command. */ + volatile uint32_t lastCommand; /*!< The desired last data command. */ + + uint8_t fifoSize; /*!< FIFO dataSize. */ + + volatile bool + isPcsActiveAfterTransfer; /*!< Indicates whether the PCS signal is active after the last frame transfer.*/ + volatile bool isThereExtraByte; /*!< Indicates whether there are extra bytes.*/ + + uint8_t *volatile txData; /*!< Send buffer. */ + uint8_t *volatile rxData; /*!< Receive buffer. */ + volatile size_t remainingSendByteCount; /*!< A number of bytes remaining to send.*/ + volatile size_t remainingReceiveByteCount; /*!< A number of bytes remaining to receive.*/ + size_t totalByteCount; /*!< A number of transfer bytes*/ + + volatile uint8_t state; /*!< DSPI transfer state, see _dspi_transfer_state.*/ + + dspi_master_transfer_callback_t callback; /*!< Completion callback. */ + void *userData; /*!< Callback user data. */ +}; + +/*! @brief DSPI slave transfer handle structure used for the transactional API. */ +struct _dspi_slave_handle +{ + uint32_t bitsPerFrame; /*!< The desired number of bits per frame. */ + volatile bool isThereExtraByte; /*!< Indicates whether there are extra bytes.*/ + + uint8_t *volatile txData; /*!< Send buffer. */ + uint8_t *volatile rxData; /*!< Receive buffer. */ + volatile size_t remainingSendByteCount; /*!< A number of bytes remaining to send.*/ + volatile size_t remainingReceiveByteCount; /*!< A number of bytes remaining to receive.*/ + size_t totalByteCount; /*!< A number of transfer bytes*/ + + volatile uint8_t state; /*!< DSPI transfer state.*/ + + volatile uint32_t errorCount; /*!< Error count for slave transfer.*/ + + dspi_slave_transfer_callback_t callback; /*!< Completion callback. */ + void *userData; /*!< Callback user data. */ +}; + +/********************************************************************************************************************** + * API + *********************************************************************************************************************/ +#if defined(__cplusplus) +extern "C" { +#endif /*_cplusplus*/ + +/*! + * @name Initialization and deinitialization + * @{ + */ + +/*! + * @brief Initializes the DSPI master. + * + * This function initializes the DSPI master configuration. This is an example use case. + * @code + * dspi_master_config_t masterConfig; + * masterConfig.whichCtar = kDSPI_Ctar0; + * masterConfig.ctarConfig.baudRate = 500000000U; + * masterConfig.ctarConfig.bitsPerFrame = 8; + * masterConfig.ctarConfig.cpol = kDSPI_ClockPolarityActiveHigh; + * masterConfig.ctarConfig.cpha = kDSPI_ClockPhaseFirstEdge; + * masterConfig.ctarConfig.direction = kDSPI_MsbFirst; + * masterConfig.ctarConfig.pcsToSckDelayInNanoSec = 1000000000U / masterConfig.ctarConfig.baudRate ; + * masterConfig.ctarConfig.lastSckToPcsDelayInNanoSec = 1000000000U / masterConfig.ctarConfig.baudRate ; + * masterConfig.ctarConfig.betweenTransferDelayInNanoSec = 1000000000U / masterConfig.ctarConfig.baudRate ; + * masterConfig.whichPcs = kDSPI_Pcs0; + * masterConfig.pcsActiveHighOrLow = kDSPI_PcsActiveLow; + * masterConfig.enableContinuousSCK = false; + * masterConfig.enableRxFifoOverWrite = false; + * masterConfig.enableModifiedTimingFormat = false; + * masterConfig.samplePoint = kDSPI_SckToSin0Clock; + * DSPI_MasterInit(base, &masterConfig, srcClock_Hz); + * @endcode + * + * @param base DSPI peripheral address. + * @param masterConfig Pointer to the structure dspi_master_config_t. + * @param srcClock_Hz Module source input clock in Hertz. + */ +void DSPI_MasterInit(SPI_Type *base, const dspi_master_config_t *masterConfig, uint32_t srcClock_Hz); + +/*! + * @brief Sets the dspi_master_config_t structure to default values. + * + * The purpose of this API is to get the configuration structure initialized for the DSPI_MasterInit(). + * Users may use the initialized structure unchanged in the DSPI_MasterInit() or modify the structure + * before calling the DSPI_MasterInit(). + * Example: + * @code + * dspi_master_config_t masterConfig; + * DSPI_MasterGetDefaultConfig(&masterConfig); + * @endcode + * @param masterConfig pointer to dspi_master_config_t structure + */ +void DSPI_MasterGetDefaultConfig(dspi_master_config_t *masterConfig); + +/*! + * @brief DSPI slave configuration. + * + * This function initializes the DSPI slave configuration. This is an example use case. + * @code + * dspi_slave_config_t slaveConfig; + * slaveConfig->whichCtar = kDSPI_Ctar0; + * slaveConfig->ctarConfig.bitsPerFrame = 8; + * slaveConfig->ctarConfig.cpol = kDSPI_ClockPolarityActiveHigh; + * slaveConfig->ctarConfig.cpha = kDSPI_ClockPhaseFirstEdge; + * slaveConfig->enableContinuousSCK = false; + * slaveConfig->enableRxFifoOverWrite = false; + * slaveConfig->enableModifiedTimingFormat = false; + * slaveConfig->samplePoint = kDSPI_SckToSin0Clock; + * DSPI_SlaveInit(base, &slaveConfig); + * @endcode + * + * @param base DSPI peripheral address. + * @param slaveConfig Pointer to the structure dspi_master_config_t. + */ +void DSPI_SlaveInit(SPI_Type *base, const dspi_slave_config_t *slaveConfig); + +/*! + * @brief Sets the dspi_slave_config_t structure to a default value. + * + * The purpose of this API is to get the configuration structure initialized for the DSPI_SlaveInit(). + * Users may use the initialized structure unchanged in the DSPI_SlaveInit() or modify the structure + * before calling the DSPI_SlaveInit(). + * This is an example. + * @code + * dspi_slave_config_t slaveConfig; + * DSPI_SlaveGetDefaultConfig(&slaveConfig); + * @endcode + * @param slaveConfig Pointer to the dspi_slave_config_t structure. + */ +void DSPI_SlaveGetDefaultConfig(dspi_slave_config_t *slaveConfig); + +/*! + * @brief De-initializes the DSPI peripheral. Call this API to disable the DSPI clock. + * @param base DSPI peripheral address. + */ +void DSPI_Deinit(SPI_Type *base); + +/*! + * @brief Enables the DSPI peripheral and sets the MCR MDIS to 0. + * + * @param base DSPI peripheral address. + * @param enable Pass true to enable module, false to disable module. + */ +static inline void DSPI_Enable(SPI_Type *base, bool enable) +{ + if (enable) + { + base->MCR &= ~SPI_MCR_MDIS_MASK; + } + else + { + base->MCR |= SPI_MCR_MDIS_MASK; + } +} + +/*! + *@} +*/ + +/*! + * @name Status + * @{ + */ + +/*! + * @brief Gets the DSPI status flag state. + * @param base DSPI peripheral address. + * @return DSPI status (in SR register). + */ +static inline uint32_t DSPI_GetStatusFlags(SPI_Type *base) +{ + return (base->SR); +} + +/*! + * @brief Clears the DSPI status flag. + * + * This function clears the desired status bit by using a write-1-to-clear. The user passes in the base and the + * desired status bit to clear. The list of status bits is defined in the dspi_status_and_interrupt_request_t. The + * function uses these bit positions in its algorithm to clear the desired flag state. + * This is an example. + * @code + * DSPI_ClearStatusFlags(base, kDSPI_TxCompleteFlag|kDSPI_EndOfQueueFlag); + * @endcode + * + * @param base DSPI peripheral address. + * @param statusFlags The status flag used from the type dspi_flags. + */ +static inline void DSPI_ClearStatusFlags(SPI_Type *base, uint32_t statusFlags) +{ + base->SR = statusFlags; /*!< The status flags are cleared by writing 1 (w1c).*/ +} + +/*! + *@} +*/ + +/*! + * @name Interrupts + * @{ + */ + +/*! + * @brief Enables the DSPI interrupts. + * + * This function configures the various interrupt masks of the DSPI. The parameters are a base and an interrupt mask. + * Note, for Tx Fill and Rx FIFO drain requests, enable the interrupt request and disable the DMA request. + * Do not use this API(write to RSER register) while DSPI is in running state. + * + * @code + * DSPI_EnableInterrupts(base, kDSPI_TxCompleteInterruptEnable | kDSPI_EndOfQueueInterruptEnable ); + * @endcode + * + * @param base DSPI peripheral address. + * @param mask The interrupt mask; use the enum _dspi_interrupt_enable. + */ +void DSPI_EnableInterrupts(SPI_Type *base, uint32_t mask); + +/*! + * @brief Disables the DSPI interrupts. + * + * @code + * DSPI_DisableInterrupts(base, kDSPI_TxCompleteInterruptEnable | kDSPI_EndOfQueueInterruptEnable ); + * @endcode + * + * @param base DSPI peripheral address. + * @param mask The interrupt mask; use the enum _dspi_interrupt_enable. + */ +static inline void DSPI_DisableInterrupts(SPI_Type *base, uint32_t mask) +{ + base->RSER &= ~mask; +} + +/*! + *@} +*/ + +/*! + * @name DMA Control + * @{ + */ + +/*! + * @brief Enables the DSPI DMA request. + * + * This function configures the Rx and Tx DMA mask of the DSPI. The parameters are a base and a DMA mask. + * @code + * DSPI_EnableDMA(base, kDSPI_TxDmaEnable | kDSPI_RxDmaEnable); + * @endcode + * + * @param base DSPI peripheral address. + * @param mask The interrupt mask; use the enum dspi_dma_enable. + */ +static inline void DSPI_EnableDMA(SPI_Type *base, uint32_t mask) +{ + base->RSER |= mask; +} + +/*! + * @brief Disables the DSPI DMA request. + * + * This function configures the Rx and Tx DMA mask of the DSPI. The parameters are a base and a DMA mask. + * @code + * SPI_DisableDMA(base, kDSPI_TxDmaEnable | kDSPI_RxDmaEnable); + * @endcode + * + * @param base DSPI peripheral address. + * @param mask The interrupt mask; use the enum dspi_dma_enable. + */ +static inline void DSPI_DisableDMA(SPI_Type *base, uint32_t mask) +{ + base->RSER &= ~mask; +} + +/*! + * @brief Gets the DSPI master PUSHR data register address for the DMA operation. + * + * This function gets the DSPI master PUSHR data register address because this value is needed for the DMA operation. + * + * @param base DSPI peripheral address. + * @return The DSPI master PUSHR data register address. + */ +static inline uint32_t DSPI_MasterGetTxRegisterAddress(SPI_Type *base) +{ + return (uint32_t) & (base->PUSHR); +} + +/*! + * @brief Gets the DSPI slave PUSHR data register address for the DMA operation. + * + * This function gets the DSPI slave PUSHR data register address as this value is needed for the DMA operation. + * + * @param base DSPI peripheral address. + * @return The DSPI slave PUSHR data register address. + */ +static inline uint32_t DSPI_SlaveGetTxRegisterAddress(SPI_Type *base) +{ + return (uint32_t) & (base->PUSHR_SLAVE); +} + +/*! + * @brief Gets the DSPI POPR data register address for the DMA operation. + * + * This function gets the DSPI POPR data register address as this value is needed for the DMA operation. + * + * @param base DSPI peripheral address. + * @return The DSPI POPR data register address. + */ +static inline uint32_t DSPI_GetRxRegisterAddress(SPI_Type *base) +{ + return (uint32_t) & (base->POPR); +} + +/*! + *@} +*/ + +/*! + * @name Bus Operations + * @{ + */ +/*! + * @brief Get instance number for DSPI module. + * + * @param base DSPI peripheral base address. + */ +uint32_t DSPI_GetInstance(SPI_Type *base); + +/*! + * @brief Configures the DSPI for master or slave. + * + * @param base DSPI peripheral address. + * @param mode Mode setting (master or slave) of type dspi_master_slave_mode_t. + */ +static inline void DSPI_SetMasterSlaveMode(SPI_Type *base, dspi_master_slave_mode_t mode) +{ + base->MCR = (base->MCR & (~SPI_MCR_MSTR_MASK)) | SPI_MCR_MSTR(mode); +} + +/*! + * @brief Returns whether the DSPI module is in master mode. + * + * @param base DSPI peripheral address. + * @return Returns true if the module is in master mode or false if the module is in slave mode. + */ +static inline bool DSPI_IsMaster(SPI_Type *base) +{ + return (bool)((base->MCR) & SPI_MCR_MSTR_MASK); +} +/*! + * @brief Starts the DSPI transfers and clears HALT bit in MCR. + * + * This function sets the module to start data transfer in either master or slave mode. + * + * @param base DSPI peripheral address. + */ +static inline void DSPI_StartTransfer(SPI_Type *base) +{ + base->MCR &= ~SPI_MCR_HALT_MASK; +} +/*! + * @brief Stops DSPI transfers and sets the HALT bit in MCR. + * + * This function stops data transfers in either master or slave modes. + * + * @param base DSPI peripheral address. + */ +static inline void DSPI_StopTransfer(SPI_Type *base) +{ + base->MCR |= SPI_MCR_HALT_MASK; +} + +/*! + * @brief Enables or disables the DSPI FIFOs. + * + * This function allows the caller to disable/enable the Tx and Rx FIFOs independently. + * Note that to disable, pass in a logic 0 (false) for the particular FIFO configuration. To enable, + * pass in a logic 1 (true). + * + * @param base DSPI peripheral address. + * @param enableTxFifo Disables (false) the TX FIFO; Otherwise, enables (true) the TX FIFO + * @param enableRxFifo Disables (false) the RX FIFO; Otherwise, enables (true) the RX FIFO + */ +static inline void DSPI_SetFifoEnable(SPI_Type *base, bool enableTxFifo, bool enableRxFifo) +{ + base->MCR = (base->MCR & (~(SPI_MCR_DIS_RXF_MASK | SPI_MCR_DIS_TXF_MASK))) | SPI_MCR_DIS_TXF(!enableTxFifo) | + SPI_MCR_DIS_RXF(!enableRxFifo); +} + +/*! + * @brief Flushes the DSPI FIFOs. + * + * @param base DSPI peripheral address. + * @param flushTxFifo Flushes (true) the Tx FIFO; Otherwise, does not flush (false) the Tx FIFO + * @param flushRxFifo Flushes (true) the Rx FIFO; Otherwise, does not flush (false) the Rx FIFO + */ +static inline void DSPI_FlushFifo(SPI_Type *base, bool flushTxFifo, bool flushRxFifo) +{ + base->MCR = (base->MCR & (~(SPI_MCR_CLR_TXF_MASK | SPI_MCR_CLR_RXF_MASK))) | SPI_MCR_CLR_TXF(flushTxFifo) | + SPI_MCR_CLR_RXF(flushRxFifo); +} + +/*! + * @brief Configures the DSPI peripheral chip select polarity simultaneously. + * For example, PCS0 and PCS1 are set to active low and other PCS is set to active high. Note that the number of + * PCSs is specific to the device. + * @code + * DSPI_SetAllPcsPolarity(base, kDSPI_Pcs0ActiveLow | kDSPI_Pcs1ActiveLow); + @endcode + * @param base DSPI peripheral address. + * @param mask The PCS polarity mask; use the enum _dspi_pcs_polarity. + */ +static inline void DSPI_SetAllPcsPolarity(SPI_Type *base, uint32_t mask) +{ + base->MCR = (base->MCR & ~SPI_MCR_PCSIS_MASK) | SPI_MCR_PCSIS(mask); +} + +/*! + * @brief Sets the DSPI baud rate in bits per second. + * + * This function takes in the desired baudRate_Bps (baud rate) and calculates the nearest possible baud rate without + * exceeding the desired baud rate, and returns the calculated baud rate in bits-per-second. It requires that the + * caller also provide the frequency of the module source clock (in Hertz). + * + * @param base DSPI peripheral address. + * @param whichCtar The desired Clock and Transfer Attributes Register (CTAR) of the type dspi_ctar_selection_t + * @param baudRate_Bps The desired baud rate in bits per second + * @param srcClock_Hz Module source input clock in Hertz + * @return The actual calculated baud rate + */ +uint32_t DSPI_MasterSetBaudRate(SPI_Type *base, + dspi_ctar_selection_t whichCtar, + uint32_t baudRate_Bps, + uint32_t srcClock_Hz); + +/*! + * @brief Manually configures the delay prescaler and scaler for a particular CTAR. + * + * This function configures the PCS to SCK delay pre-scalar (PcsSCK) and scalar (CSSCK), after SCK delay pre-scalar + * (PASC) and scalar (ASC), and the delay after transfer pre-scalar (PDT) and scalar (DT). + * + * These delay names are available in the type dspi_delay_type_t. + * + * The user passes the delay to the configuration along with the prescaler and scaler value. + * This allows the user to directly set the prescaler/scaler values if pre-calculated or + * to manually increment either value. + * + * @param base DSPI peripheral address. + * @param whichCtar The desired Clock and Transfer Attributes Register (CTAR) of type dspi_ctar_selection_t. + * @param prescaler The prescaler delay value (can be an integer 0, 1, 2, or 3). + * @param scaler The scaler delay value (can be any integer between 0 to 15). + * @param whichDelay The desired delay to configure; must be of type dspi_delay_type_t + */ +void DSPI_MasterSetDelayScaler( + SPI_Type *base, dspi_ctar_selection_t whichCtar, uint32_t prescaler, uint32_t scaler, dspi_delay_type_t whichDelay); + +/*! + * @brief Calculates the delay prescaler and scaler based on the desired delay input in nanoseconds. + * + * This function calculates the values for the following. + * PCS to SCK delay pre-scalar (PCSSCK) and scalar (CSSCK), or + * After SCK delay pre-scalar (PASC) and scalar (ASC), or + * Delay after transfer pre-scalar (PDT) and scalar (DT). + * + * These delay names are available in the type dspi_delay_type_t. + * + * The user passes which delay to configure along with the desired delay value in nanoseconds. The function + * calculates the values needed for the prescaler and scaler. Note that returning the calculated delay as an exact + * delay match may not be possible. In this case, the closest match is calculated without going below the desired + * delay value input. + * It is possible to input a very large delay value that exceeds the capability of the part, in which case the maximum + * supported delay is returned. The higher-level peripheral driver alerts the user of an out of range delay + * input. + * + * @param base DSPI peripheral address. + * @param whichCtar The desired Clock and Transfer Attributes Register (CTAR) of type dspi_ctar_selection_t. + * @param whichDelay The desired delay to configure, must be of type dspi_delay_type_t + * @param srcClock_Hz Module source input clock in Hertz + * @param delayTimeInNanoSec The desired delay value in nanoseconds. + * @return The actual calculated delay value. + */ +uint32_t DSPI_MasterSetDelayTimes(SPI_Type *base, + dspi_ctar_selection_t whichCtar, + dspi_delay_type_t whichDelay, + uint32_t srcClock_Hz, + uint32_t delayTimeInNanoSec); + +/*! + * @brief Writes data into the data buffer for master mode. + * + * In master mode, the 16-bit data is appended to the 16-bit command info. The command portion + * provides characteristics of the data, such as the optional continuous chip select + * operation between transfers, the desired Clock and Transfer Attributes register to use for the + * associated SPI frame, the desired PCS signal to use for the data transfer, whether the current + * transfer is the last in the queue, and whether to clear the transfer count (normally needed when + * sending the first frame of a data packet). This is an example. + * @code + * dspi_command_data_config_t commandConfig; + * commandConfig.isPcsContinuous = true; + * commandConfig.whichCtar = kDSPICtar0; + * commandConfig.whichPcs = kDSPIPcs0; + * commandConfig.clearTransferCount = false; + * commandConfig.isEndOfQueue = false; + * DSPI_MasterWriteData(base, &commandConfig, dataWord); + @endcode + * + * @param base DSPI peripheral address. + * @param command Pointer to the command structure. + * @param data The data word to be sent. + */ +static inline void DSPI_MasterWriteData(SPI_Type *base, dspi_command_data_config_t *command, uint16_t data) +{ + base->PUSHR = SPI_PUSHR_CONT(command->isPcsContinuous) | SPI_PUSHR_CTAS(command->whichCtar) | + SPI_PUSHR_PCS(command->whichPcs) | SPI_PUSHR_EOQ(command->isEndOfQueue) | + SPI_PUSHR_CTCNT(command->clearTransferCount) | SPI_PUSHR_TXDATA(data); +} + +/*! + * @brief Sets the dspi_command_data_config_t structure to default values. + * + * The purpose of this API is to get the configuration structure initialized for use in the DSPI_MasterWrite_xx(). + * Users may use the initialized structure unchanged in the DSPI_MasterWrite_xx() or modify the structure + * before calling the DSPI_MasterWrite_xx(). + * This is an example. + * @code + * dspi_command_data_config_t command; + * DSPI_GetDefaultDataCommandConfig(&command); + * @endcode + * @param command Pointer to the dspi_command_data_config_t structure. + */ +void DSPI_GetDefaultDataCommandConfig(dspi_command_data_config_t *command); + +/*! + * @brief Writes data into the data buffer master mode and waits till complete to return. + * + * In master mode, the 16-bit data is appended to the 16-bit command info. The command portion + * provides characteristics of the data, such as the optional continuous chip select + * operation between transfers, the desired Clock and Transfer Attributes register to use for the + * associated SPI frame, the desired PCS signal to use for the data transfer, whether the current + * transfer is the last in the queue, and whether to clear the transfer count (normally needed when + * sending the first frame of a data packet). This is an example. + * @code + * dspi_command_config_t commandConfig; + * commandConfig.isPcsContinuous = true; + * commandConfig.whichCtar = kDSPICtar0; + * commandConfig.whichPcs = kDSPIPcs1; + * commandConfig.clearTransferCount = false; + * commandConfig.isEndOfQueue = false; + * DSPI_MasterWriteDataBlocking(base, &commandConfig, dataWord); + * @endcode + * + * Note that this function does not return until after the transmit is complete. Also note that the DSPI must be + * enabled and running to transmit data (MCR[MDIS] & [HALT] = 0). Because the SPI is a synchronous protocol, + * the received data is available when the transmit completes. + * + * @param base DSPI peripheral address. + * @param command Pointer to the command structure. + * @param data The data word to be sent. + */ +void DSPI_MasterWriteDataBlocking(SPI_Type *base, dspi_command_data_config_t *command, uint16_t data); + +/*! + * @brief Returns the DSPI command word formatted to the PUSHR data register bit field. + * + * This function allows the caller to pass in the data command structure and returns the command word formatted + * according to the DSPI PUSHR register bit field placement. The user can then "OR" the returned command word with the + * desired data to send and use the function DSPI_HAL_WriteCommandDataMastermode or + * DSPI_HAL_WriteCommandDataMastermodeBlocking to write the entire 32-bit command data word to the PUSHR. This helps + * improve performance in cases where the command structure is constant. For example, the user calls this function + * before starting a transfer to generate the command word. When they are ready to transmit the data, they OR + * this formatted command word with the desired data to transmit. This process increases transmit performance when + * compared to calling send functions, such as DSPI_HAL_WriteDataMastermode, which format the command word each time a + * data word is to be sent. + * + * @param command Pointer to the command structure. + * @return The command word formatted to the PUSHR data register bit field. + */ +static inline uint32_t DSPI_MasterGetFormattedCommand(dspi_command_data_config_t *command) +{ + /* Format the 16-bit command word according to the PUSHR data register bit field*/ + return (uint32_t)(SPI_PUSHR_CONT(command->isPcsContinuous) | SPI_PUSHR_CTAS(command->whichCtar) | + SPI_PUSHR_PCS(command->whichPcs) | SPI_PUSHR_EOQ(command->isEndOfQueue) | + SPI_PUSHR_CTCNT(command->clearTransferCount)); +} + +/*! + * @brief Writes a 32-bit data word (16-bit command appended with 16-bit data) into the data + * buffer master mode and waits till complete to return. + * + * In this function, the user must append the 16-bit data to the 16-bit command information and then provide the total +* 32-bit word + * as the data to send. + * The command portion provides characteristics of the data, such as the optional continuous chip select operation + * between transfers, the desired Clock and Transfer Attributes register to use for the associated SPI frame, the +* desired PCS + * signal to use for the data transfer, whether the current transfer is the last in the queue, and whether to clear the + * transfer count (normally needed when sending the first frame of a data packet). The user is responsible for + * appending this command with the data to send. This is an example: + * @code + * dataWord = <16-bit command> | <16-bit data>; + * DSPI_MasterWriteCommandDataBlocking(base, dataWord); + * @endcode + * + * Note that this function does not return until after the transmit is complete. Also note that the DSPI must be + * enabled and running to transmit data (MCR[MDIS] & [HALT] = 0). + * Because the SPI is a synchronous protocol, the received data is available when the transmit completes. + * + * For a blocking polling transfer, see methods below. + * Option 1: +* uint32_t command_to_send = DSPI_MasterGetFormattedCommand(&command); +* uint32_t data0 = command_to_send | data_need_to_send_0; +* uint32_t data1 = command_to_send | data_need_to_send_1; +* uint32_t data2 = command_to_send | data_need_to_send_2; +* +* DSPI_MasterWriteCommandDataBlocking(base,data0); +* DSPI_MasterWriteCommandDataBlocking(base,data1); +* DSPI_MasterWriteCommandDataBlocking(base,data2); +* +* Option 2: +* DSPI_MasterWriteDataBlocking(base,&command,data_need_to_send_0); +* DSPI_MasterWriteDataBlocking(base,&command,data_need_to_send_1); +* DSPI_MasterWriteDataBlocking(base,&command,data_need_to_send_2); +* + * @param base DSPI peripheral address. + * @param data The data word (command and data combined) to be sent. + */ +void DSPI_MasterWriteCommandDataBlocking(SPI_Type *base, uint32_t data); + +/*! + * @brief Writes data into the data buffer in slave mode. + * + * In slave mode, up to 16-bit words may be written. + * + * @param base DSPI peripheral address. + * @param data The data to send. + */ +static inline void DSPI_SlaveWriteData(SPI_Type *base, uint32_t data) +{ + base->PUSHR_SLAVE = data; +} + +/*! + * @brief Writes data into the data buffer in slave mode, waits till data was transmitted, and returns. + * + * In slave mode, up to 16-bit words may be written. The function first clears the transmit complete flag, writes data + * into data register, and finally waits until the data is transmitted. + * + * @param base DSPI peripheral address. + * @param data The data to send. + */ +void DSPI_SlaveWriteDataBlocking(SPI_Type *base, uint32_t data); + +/*! + * @brief Reads data from the data buffer. + * + * @param base DSPI peripheral address. + * @return The data from the read data buffer. + */ +static inline uint32_t DSPI_ReadData(SPI_Type *base) +{ + return (base->POPR); +} + +/*! + * @brief Set up the dummy data. + * + * @param base DSPI peripheral address. + * @param dummyData Data to be transferred when tx buffer is NULL. + */ +void DSPI_SetDummyData(SPI_Type *base, uint8_t dummyData); + +/*! + *@} +*/ + +/*! + * @name Transactional + * @{ + */ +/*Transactional APIs*/ + +/*! + * @brief Initializes the DSPI master handle. + * + * This function initializes the DSPI handle, which can be used for other DSPI transactional APIs. Usually, for a + * specified DSPI instance, call this API once to get the initialized handle. + * + * @param base DSPI peripheral base address. + * @param handle DSPI handle pointer to dspi_master_handle_t. + * @param callback DSPI callback. + * @param userData Callback function parameter. + */ +void DSPI_MasterTransferCreateHandle(SPI_Type *base, + dspi_master_handle_t *handle, + dspi_master_transfer_callback_t callback, + void *userData); + +/*! + * @brief DSPI master transfer data using polling. + * + * This function transfers data using polling. This is a blocking function, which does not return until all transfers + * have been completed. + * + * @param base DSPI peripheral base address. + * @param transfer Pointer to the dspi_transfer_t structure. + * @return status of status_t. + */ +status_t DSPI_MasterTransferBlocking(SPI_Type *base, dspi_transfer_t *transfer); + +/*! + * @brief DSPI master transfer data using interrupts. + * + * This function transfers data using interrupts. This is a non-blocking function, which returns right away. When all + * data is transferred, the callback function is called. + + * @param base DSPI peripheral base address. + * @param handle Pointer to the dspi_master_handle_t structure which stores the transfer state. + * @param transfer Pointer to the dspi_transfer_t structure. + * @return status of status_t. + */ +status_t DSPI_MasterTransferNonBlocking(SPI_Type *base, dspi_master_handle_t *handle, dspi_transfer_t *transfer); + +/*! + * @brief Transfers a block of data using a polling method. + * + * This function will do a half-duplex transfer for DSPI master, This is a blocking function, + * which does not retuen until all transfer have been completed. And data transfer will be half-duplex, + * users can set transmit first or receive first. + * + * @param base DSPI base pointer + * @param xfer pointer to dspi_half_duplex_transfer_t structure + * @return status of status_t. + */ +status_t DSPI_MasterHalfDuplexTransferBlocking(SPI_Type *base, dspi_half_duplex_transfer_t *xfer); + +/*! + * @brief Performs a non-blocking DSPI interrupt transfer. + * + * This function transfers data using interrupts, the transfer mechanism is half-duplex. This is a non-blocking + * function, + * which returns right away. When all data is transferred, the callback function is called. + * + * @param base DSPI peripheral base address. + * @param handle pointer to dspi_master_handle_t structure which stores the transfer state + * @param xfer pointer to dspi_half_duplex_transfer_t structure + * @return status of status_t. + */ +status_t DSPI_MasterHalfDuplexTransferNonBlocking(SPI_Type *base, + dspi_master_handle_t *handle, + dspi_half_duplex_transfer_t *xfer); + +/*! + * @brief Gets the master transfer count. + * + * This function gets the master transfer count. + * + * @param base DSPI peripheral base address. + * @param handle Pointer to the dspi_master_handle_t structure which stores the transfer state. + * @param count The number of bytes transferred by using the non-blocking transaction. + * @return status of status_t. + */ +status_t DSPI_MasterTransferGetCount(SPI_Type *base, dspi_master_handle_t *handle, size_t *count); + +/*! + * @brief DSPI master aborts a transfer using an interrupt. + * + * This function aborts a transfer using an interrupt. + * + * @param base DSPI peripheral base address. + * @param handle Pointer to the dspi_master_handle_t structure which stores the transfer state. + */ +void DSPI_MasterTransferAbort(SPI_Type *base, dspi_master_handle_t *handle); + +/*! + * @brief DSPI Master IRQ handler function. + * + * This function processes the DSPI transmit and receive IRQ. + + * @param base DSPI peripheral base address. + * @param handle Pointer to the dspi_master_handle_t structure which stores the transfer state. + */ +void DSPI_MasterTransferHandleIRQ(SPI_Type *base, dspi_master_handle_t *handle); + +/*! + * @brief Initializes the DSPI slave handle. + * + * This function initializes the DSPI handle, which can be used for other DSPI transactional APIs. Usually, for a + * specified DSPI instance, call this API once to get the initialized handle. + * + * @param handle DSPI handle pointer to the dspi_slave_handle_t. + * @param base DSPI peripheral base address. + * @param callback DSPI callback. + * @param userData Callback function parameter. + */ +void DSPI_SlaveTransferCreateHandle(SPI_Type *base, + dspi_slave_handle_t *handle, + dspi_slave_transfer_callback_t callback, + void *userData); + +/*! + * @brief DSPI slave transfers data using an interrupt. + * + * This function transfers data using an interrupt. This is a non-blocking function, which returns right away. When all + * data is transferred, the callback function is called. + * + * @param base DSPI peripheral base address. + * @param handle Pointer to the dspi_slave_handle_t structure which stores the transfer state. + * @param transfer Pointer to the dspi_transfer_t structure. + * @return status of status_t. + */ +status_t DSPI_SlaveTransferNonBlocking(SPI_Type *base, dspi_slave_handle_t *handle, dspi_transfer_t *transfer); + +/*! + * @brief Gets the slave transfer count. + * + * This function gets the slave transfer count. + * + * @param base DSPI peripheral base address. + * @param handle Pointer to the dspi_master_handle_t structure which stores the transfer state. + * @param count The number of bytes transferred by using the non-blocking transaction. + * @return status of status_t. + */ +status_t DSPI_SlaveTransferGetCount(SPI_Type *base, dspi_slave_handle_t *handle, size_t *count); + +/*! + * @brief DSPI slave aborts a transfer using an interrupt. + * + * This function aborts a transfer using an interrupt. + * + * @param base DSPI peripheral base address. + * @param handle Pointer to the dspi_slave_handle_t structure which stores the transfer state. + */ +void DSPI_SlaveTransferAbort(SPI_Type *base, dspi_slave_handle_t *handle); + +/*! + * @brief DSPI Master IRQ handler function. + * + * This function processes the DSPI transmit and receive IRQ. + * + * @param base DSPI peripheral base address. + * @param handle Pointer to the dspi_slave_handle_t structure which stores the transfer state. + */ +void DSPI_SlaveTransferHandleIRQ(SPI_Type *base, dspi_slave_handle_t *handle); + +/*! + *@} +*/ + +#if defined(__cplusplus) +} +#endif /*_cplusplus*/ + /*! + *@} + */ + +#endif /*_FSL_DSPI_H_*/ diff --git a/drivers/fsl_dspi_edma.c b/drivers/fsl_dspi_edma.c new file mode 100644 index 0000000..bbd560e --- /dev/null +++ b/drivers/fsl_dspi_edma.c @@ -0,0 +1,1446 @@ +/* + * The Clear BSD License + * Copyright (c) 2015, 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: + * + * o Redistributions of source code must retain the above copyright notice, this list + * of conditions and the following disclaimer. + * + * o 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. + * + * o 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. + */ + +#include "fsl_dspi_edma.h" + +/*********************************************************************************************************************** +* Definitions +***********************************************************************************************************************/ + +/* Component ID definition, used by tools. */ +#ifndef FSL_COMPONENT_ID +#define FSL_COMPONENT_ID "platform.drivers.dspi_edma" +#endif + +/*! +* @brief Structure definition for dspi_master_edma_private_handle_t. The structure is private. +*/ +typedef struct _dspi_master_edma_private_handle +{ + SPI_Type *base; /*!< DSPI peripheral base address. */ + dspi_master_edma_handle_t *handle; /*!< dspi_master_edma_handle_t handle */ +} dspi_master_edma_private_handle_t; + +/*! +* @brief Structure definition for dspi_slave_edma_private_handle_t. The structure is private. +*/ +typedef struct _dspi_slave_edma_private_handle +{ + SPI_Type *base; /*!< DSPI peripheral base address. */ + dspi_slave_edma_handle_t *handle; /*!< dspi_master_edma_handle_t handle */ +} dspi_slave_edma_private_handle_t; + +/*********************************************************************************************************************** +* Prototypes +***********************************************************************************************************************/ +/*! +* @brief EDMA_DspiMasterCallback after the DSPI master transfer completed by using EDMA. +* This is not a public API. +*/ +static void EDMA_DspiMasterCallback(edma_handle_t *edmaHandle, + void *g_dspiEdmaPrivateHandle, + bool transferDone, + uint32_t tcds); + +/*! +* @brief EDMA_DspiSlaveCallback after the DSPI slave transfer completed by using EDMA. +* This is not a public API. +*/ +static void EDMA_DspiSlaveCallback(edma_handle_t *edmaHandle, + void *g_dspiEdmaPrivateHandle, + bool transferDone, + uint32_t tcds); + +/*********************************************************************************************************************** +* Variables +***********************************************************************************************************************/ + +/*! @brief Pointers to dspi edma handles for each instance. */ +static dspi_master_edma_private_handle_t s_dspiMasterEdmaPrivateHandle[FSL_FEATURE_SOC_DSPI_COUNT]; +static dspi_slave_edma_private_handle_t s_dspiSlaveEdmaPrivateHandle[FSL_FEATURE_SOC_DSPI_COUNT]; + +/*********************************************************************************************************************** +* Code +***********************************************************************************************************************/ + +void DSPI_MasterTransferCreateHandleEDMA(SPI_Type *base, + dspi_master_edma_handle_t *handle, + dspi_master_edma_transfer_callback_t callback, + void *userData, + edma_handle_t *edmaRxRegToRxDataHandle, + edma_handle_t *edmaTxDataToIntermediaryHandle, + edma_handle_t *edmaIntermediaryToTxRegHandle) +{ + assert(handle); + assert(edmaRxRegToRxDataHandle); +#if (!(defined(FSL_FEATURE_DSPI_HAS_GASKET) && FSL_FEATURE_DSPI_HAS_GASKET)) + assert(edmaTxDataToIntermediaryHandle); +#endif + assert(edmaIntermediaryToTxRegHandle); + + /* Zero the handle. */ + memset(handle, 0, sizeof(*handle)); + + uint32_t instance = DSPI_GetInstance(base); + + s_dspiMasterEdmaPrivateHandle[instance].base = base; + s_dspiMasterEdmaPrivateHandle[instance].handle = handle; + + handle->callback = callback; + handle->userData = userData; + + handle->edmaRxRegToRxDataHandle = edmaRxRegToRxDataHandle; + handle->edmaTxDataToIntermediaryHandle = edmaTxDataToIntermediaryHandle; + handle->edmaIntermediaryToTxRegHandle = edmaIntermediaryToTxRegHandle; +} + +status_t DSPI_MasterTransferEDMA(SPI_Type *base, dspi_master_edma_handle_t *handle, dspi_transfer_t *transfer) +{ + assert(handle); + assert(transfer); + + /* If the transfer count is zero, then return immediately.*/ + if (transfer->dataSize == 0) + { + return kStatus_InvalidArgument; + } + + /* If both send buffer and receive buffer is null */ + if ((!(transfer->txData)) && (!(transfer->rxData))) + { + return kStatus_InvalidArgument; + } + + /* Check that we're not busy.*/ + if (handle->state == kDSPI_Busy) + { + return kStatus_DSPI_Busy; + } + + handle->state = kDSPI_Busy; + + uint32_t instance = DSPI_GetInstance(base); + uint16_t wordToSend = 0; + uint8_t dummyData = g_dspiDummyData[DSPI_GetInstance(base)]; + uint8_t dataAlreadyFed = 0; + uint8_t dataFedMax = 2; + + uint32_t rxAddr = DSPI_GetRxRegisterAddress(base); + uint32_t txAddr = DSPI_MasterGetTxRegisterAddress(base); + + edma_tcd_t *softwareTCD = (edma_tcd_t *)((uint32_t)(&handle->dspiSoftwareTCD[1]) & (~0x1FU)); + + edma_transfer_config_t transferConfigA; + edma_transfer_config_t transferConfigB; + + handle->txBuffIfNull = ((uint32_t)dummyData << 8) | dummyData; + + dspi_command_data_config_t commandStruct; + DSPI_StopTransfer(base); + DSPI_FlushFifo(base, true, true); + DSPI_ClearStatusFlags(base, kDSPI_AllStatusFlag); + + commandStruct.whichPcs = + (dspi_which_pcs_t)(1U << ((transfer->configFlags & DSPI_MASTER_PCS_MASK) >> DSPI_MASTER_PCS_SHIFT)); + commandStruct.isEndOfQueue = false; + commandStruct.clearTransferCount = false; + commandStruct.whichCtar = + (dspi_ctar_selection_t)((transfer->configFlags & DSPI_MASTER_CTAR_MASK) >> DSPI_MASTER_CTAR_SHIFT); + commandStruct.isPcsContinuous = (bool)(transfer->configFlags & kDSPI_MasterPcsContinuous); + handle->command = DSPI_MasterGetFormattedCommand(&(commandStruct)); + + commandStruct.isEndOfQueue = true; + commandStruct.isPcsContinuous = (bool)(transfer->configFlags & kDSPI_MasterActiveAfterTransfer); + handle->lastCommand = DSPI_MasterGetFormattedCommand(&(commandStruct)); + + handle->bitsPerFrame = ((base->CTAR[commandStruct.whichCtar] & SPI_CTAR_FMSZ_MASK) >> SPI_CTAR_FMSZ_SHIFT) + 1; + + if ((base->MCR & SPI_MCR_DIS_RXF_MASK) || (base->MCR & SPI_MCR_DIS_TXF_MASK)) + { + handle->fifoSize = 1; + } + else + { + handle->fifoSize = FSL_FEATURE_DSPI_FIFO_SIZEn(base); + } + handle->txData = transfer->txData; + handle->rxData = transfer->rxData; + handle->remainingSendByteCount = transfer->dataSize; + handle->remainingReceiveByteCount = transfer->dataSize; + handle->totalByteCount = transfer->dataSize; + + /* If using a shared RX/TX DMA request, then this limits the amount of data we can transfer + * due to the linked channel. The max bytes is 511 if 8-bit/frame or 1022 if 16-bit/frame + */ + uint32_t limited_size = 0; + if (1 == FSL_FEATURE_DSPI_HAS_SEPARATE_DMA_RX_TX_REQn(base)) + { + limited_size = 32767u; + } + else + { + limited_size = 511u; + } + + if (handle->bitsPerFrame > 8) + { + if (transfer->dataSize > (limited_size << 1u)) + { + handle->state = kDSPI_Idle; + return kStatus_DSPI_OutOfRange; + } + } + else + { + if (transfer->dataSize > limited_size) + { + handle->state = kDSPI_Idle; + return kStatus_DSPI_OutOfRange; + } + } + + /*The data size should be even if the bitsPerFrame is greater than 8 (that is 2 bytes per frame in dspi) */ + if ((handle->bitsPerFrame > 8) && (transfer->dataSize & 0x1)) + { + handle->state = kDSPI_Idle; + return kStatus_InvalidArgument; + } + + DSPI_DisableDMA(base, kDSPI_RxDmaEnable | kDSPI_TxDmaEnable); + + EDMA_SetCallback(handle->edmaRxRegToRxDataHandle, EDMA_DspiMasterCallback, + &s_dspiMasterEdmaPrivateHandle[instance]); + + /* + (1)For DSPI instances with shared RX/TX DMA requests: Rx DMA request -> channel_A -> channel_B-> channel_C. + channel_A minor link to channel_B , channel_B minor link to channel_C. + + Already pushed 1 or 2 data in SPI_PUSHR , then start the DMA tansfer. + channel_A:SPI_POPR to rxData, + channel_B:next txData to handle->command (low 16 bits), + channel_C:handle->command (32 bits) to SPI_PUSHR, and use the scatter/gather to transfer the last data + (handle->lastCommand to SPI_PUSHR). + + (2)For DSPI instances with separate RX and TX DMA requests: + Rx DMA request -> channel_A + Tx DMA request -> channel_C -> channel_B . + channel_C major link to channel_B. + So need prepare the first data in "intermediary" before the DMA + transfer and then channel_B is used to prepare the next data to "intermediary" + + channel_A:SPI_POPR to rxData, + channel_C: handle->command (32 bits) to SPI_PUSHR, + channel_B: next txData to handle->command (low 16 bits), and use the scatter/gather to prepare the last data + (handle->lastCommand to handle->Command). + */ + + /*If dspi has separate dma request , prepare the first data in "intermediary" . + else (dspi has shared dma request) , send first 2 data if there is fifo or send first 1 data if there is no fifo*/ + if (1 == FSL_FEATURE_DSPI_HAS_SEPARATE_DMA_RX_TX_REQn(base)) + { + /* For DSPI instances with separate RX/TX DMA requests, we'll use the TX DMA request to + * trigger the TX DMA channel and RX DMA request to trigger the RX DMA channel + */ + + /*Prepare the firt data*/ + if (handle->bitsPerFrame > 8) + { + /* If it's the last word */ + if (handle->remainingSendByteCount <= 2) + { + if (handle->txData) + { + wordToSend = *(handle->txData); + ++handle->txData; /* increment to next data byte */ + wordToSend |= (unsigned)(*(handle->txData)) << 8U; + } + else + { + wordToSend = ((uint32_t)dummyData << 8) | dummyData; + } + handle->lastCommand = (handle->lastCommand & 0xffff0000U) | wordToSend; + handle->command = handle->lastCommand; + } + else /* For all words except the last word , frame > 8bits */ + { + if (handle->txData) + { + wordToSend = *(handle->txData); + ++handle->txData; /* increment to next data byte */ + wordToSend |= (unsigned)(*(handle->txData)) << 8U; + ++handle->txData; /* increment to next data byte */ + } + else + { + wordToSend = ((uint32_t)dummyData << 8) | dummyData; + } + handle->command = (handle->command & 0xffff0000U) | wordToSend; + } + } + else /* Optimized for bits/frame less than or equal to one byte. */ + { + if (handle->txData) + { + wordToSend = *(handle->txData); + ++handle->txData; /* increment to next data word*/ + } + else + { + wordToSend = dummyData; + } + + if (handle->remainingSendByteCount == 1) + { + handle->lastCommand = (handle->lastCommand & 0xffff0000U) | wordToSend; + handle->command = handle->lastCommand; + } + else + { + handle->command = (handle->command & 0xffff0000U) | wordToSend; + } + } + } + + else /*dspi has shared dma request*/ + { + /* For DSPI instances with shared RX/TX DMA requests, we'll use the RX DMA request to + * trigger ongoing transfers and will link to the TX DMA channel from the RX DMA channel. + */ + + /* If bits/frame is greater than one byte */ + if (handle->bitsPerFrame > 8) + { + while (DSPI_GetStatusFlags(base) & kDSPI_TxFifoFillRequestFlag) + { + if (handle->remainingSendByteCount <= 2) + { + if (handle->txData) + { + wordToSend = *(handle->txData); + ++handle->txData; + wordToSend |= (unsigned)(*(handle->txData)) << 8U; + } + else + { + wordToSend = ((uint32_t)dummyData << 8) | dummyData; + } + handle->remainingSendByteCount = 0; + base->PUSHR = (handle->lastCommand & 0xffff0000U) | wordToSend; + } + /* For all words except the last word */ + else + { + if (handle->txData) + { + wordToSend = *(handle->txData); + ++handle->txData; + wordToSend |= (unsigned)(*(handle->txData)) << 8U; + ++handle->txData; + } + else + { + wordToSend = ((uint32_t)dummyData << 8) | dummyData; + } + handle->remainingSendByteCount -= 2; + base->PUSHR = (handle->command & 0xffff0000U) | wordToSend; + } + + /* Try to clear the TFFF; if the TX FIFO is full this will clear */ + DSPI_ClearStatusFlags(base, kDSPI_TxFifoFillRequestFlag); + + dataAlreadyFed += 2; + + /* exit loop if send count is zero, else update local variables for next loop */ + if ((handle->remainingSendByteCount == 0) || (dataAlreadyFed == (dataFedMax * 2))) + { + break; + } + } /* End of TX FIFO fill while loop */ + } + else /* Optimized for bits/frame less than or equal to one byte. */ + { + while (DSPI_GetStatusFlags(base) & kDSPI_TxFifoFillRequestFlag) + { + if (handle->txData) + { + wordToSend = *(handle->txData); + ++handle->txData; + } + else + { + wordToSend = dummyData; + } + + if (handle->remainingSendByteCount == 1) + { + base->PUSHR = (handle->lastCommand & 0xffff0000U) | wordToSend; + } + else + { + base->PUSHR = (handle->command & 0xffff0000U) | wordToSend; + } + + /* Try to clear the TFFF; if the TX FIFO is full this will clear */ + DSPI_ClearStatusFlags(base, kDSPI_TxFifoFillRequestFlag); + + --handle->remainingSendByteCount; + + dataAlreadyFed++; + + /* exit loop if send count is zero, else update local variables for next loop */ + if ((handle->remainingSendByteCount == 0) || (dataAlreadyFed == dataFedMax)) + { + break; + } + } /* End of TX FIFO fill while loop */ + } + } + + /***channel_A *** used for carry the data from Rx_Data_Register(POPR) to User_Receive_Buffer(rxData)*/ + EDMA_ResetChannel(handle->edmaRxRegToRxDataHandle->base, handle->edmaRxRegToRxDataHandle->channel); + + transferConfigA.srcAddr = (uint32_t)rxAddr; + transferConfigA.srcOffset = 0; + + if (handle->rxData) + { + transferConfigA.destAddr = (uint32_t) & (handle->rxData[0]); + transferConfigA.destOffset = 1; + } + else + { + transferConfigA.destAddr = (uint32_t) & (handle->rxBuffIfNull); + transferConfigA.destOffset = 0; + } + + transferConfigA.destTransferSize = kEDMA_TransferSize1Bytes; + + if (handle->bitsPerFrame <= 8) + { + transferConfigA.srcTransferSize = kEDMA_TransferSize1Bytes; + transferConfigA.minorLoopBytes = 1; + transferConfigA.majorLoopCounts = handle->remainingReceiveByteCount; + } + else + { + transferConfigA.srcTransferSize = kEDMA_TransferSize2Bytes; + transferConfigA.minorLoopBytes = 2; + transferConfigA.majorLoopCounts = handle->remainingReceiveByteCount / 2; + } + + /* Store the initially configured eDMA minor byte transfer count into the DSPI handle */ + handle->nbytes = transferConfigA.minorLoopBytes; + + EDMA_SetTransferConfig(handle->edmaRxRegToRxDataHandle->base, handle->edmaRxRegToRxDataHandle->channel, + &transferConfigA, NULL); + EDMA_EnableChannelInterrupts(handle->edmaRxRegToRxDataHandle->base, handle->edmaRxRegToRxDataHandle->channel, + kEDMA_MajorInterruptEnable); + + /*Calculate the last data : handle->lastCommand*/ + if (((handle->remainingSendByteCount > 0) && (1 != FSL_FEATURE_DSPI_HAS_SEPARATE_DMA_RX_TX_REQn(base))) || + ((((handle->remainingSendByteCount > 1) && (handle->bitsPerFrame <= 8)) || + ((handle->remainingSendByteCount > 2) && (handle->bitsPerFrame > 8))) && + (1 == FSL_FEATURE_DSPI_HAS_SEPARATE_DMA_RX_TX_REQn(base)))) + { + if (handle->txData) + { + uint32_t bufferIndex = 0; + + if (1 == FSL_FEATURE_DSPI_HAS_SEPARATE_DMA_RX_TX_REQn(base)) + { + if (handle->bitsPerFrame <= 8) + { + bufferIndex = handle->remainingSendByteCount - 1; + } + else + { + bufferIndex = handle->remainingSendByteCount - 2; + } + } + else + { + bufferIndex = handle->remainingSendByteCount; + } + + if (handle->bitsPerFrame <= 8) + { + handle->lastCommand = (handle->lastCommand & 0xffff0000U) | handle->txData[bufferIndex - 1]; + } + else + { + handle->lastCommand = (handle->lastCommand & 0xffff0000U) | + ((uint32_t)handle->txData[bufferIndex - 1] << 8) | + handle->txData[bufferIndex - 2]; + } + } + else + { + if (handle->bitsPerFrame <= 8) + { + wordToSend = dummyData; + } + else + { + wordToSend = ((uint32_t)dummyData << 8) | dummyData; + } + handle->lastCommand = (handle->lastCommand & 0xffff0000U) | wordToSend; + } + } + +/* The feature of GASKET is that the SPI supports 8-bit or 16-bit writes to the PUSH TX FIFO, + * allowing a single write to the command word followed by multiple writes to the transmit word. + * The TX FIFO will save the last command word written, and convert a 8-bit/16-bit write to the + * transmit word into a 32-bit write that pushes both the command word and transmit word into + * the TX FIFO (PUSH TX FIFO Register In Master Mode) + * So, if this feature is supported, we can use use one channel to carry the receive data from + * receive regsiter to user data buffer, use the other channel to carry the data from user data buffer + * to transmit register,and use the scatter/gather function to prepare the last data. + * That is to say, if GASKET feature is supported, we can use only two channels for tansferring data. + */ +#if defined(FSL_FEATURE_DSPI_HAS_GASKET) && FSL_FEATURE_DSPI_HAS_GASKET + /* For DSPI instances with separate RX and TX DMA requests: use the scatter/gather to prepare the last data + * (handle->lastCommand) to PUSHR register. + */ + + EDMA_ResetChannel(handle->edmaIntermediaryToTxRegHandle->base, handle->edmaIntermediaryToTxRegHandle->channel); + + if ((1 == FSL_FEATURE_DSPI_HAS_SEPARATE_DMA_RX_TX_REQn(base)) || + ((handle->remainingSendByteCount > 0) && (1 != FSL_FEATURE_DSPI_HAS_SEPARATE_DMA_RX_TX_REQn(base)))) + { + transferConfigB.srcAddr = (uint32_t) & (handle->lastCommand); + transferConfigB.destAddr = (uint32_t)txAddr; + transferConfigB.srcTransferSize = kEDMA_TransferSize4Bytes; + transferConfigB.destTransferSize = kEDMA_TransferSize4Bytes; + transferConfigB.srcOffset = 0; + transferConfigB.destOffset = 0; + transferConfigB.minorLoopBytes = 4; + transferConfigB.majorLoopCounts = 1; + + EDMA_TcdReset(softwareTCD); + EDMA_TcdSetTransferConfig(softwareTCD, &transferConfigB, NULL); + } + + /*User_Send_Buffer(txData) to PUSHR register. */ + if (((handle->remainingSendByteCount > 2) && (handle->bitsPerFrame <= 8)) || + ((handle->remainingSendByteCount > 4) && (handle->bitsPerFrame > 8))) + { + if (handle->txData) + { + if (1 == FSL_FEATURE_DSPI_HAS_SEPARATE_DMA_RX_TX_REQn(base)) + { + /* For DSPI with separate RX and TX DMA requests, one frame data has been carry + * to handle->command, so need to reduce the pointer of txData. + */ + transferConfigB.srcAddr = + (uint32_t)((uint8_t *)(handle->txData) - ((handle->bitsPerFrame <= 8) ? (1U) : (2U))); + transferConfigB.srcOffset = 1; + } + else + { + /* For DSPI with shared RX and TX DMA requests, one or two frame data have been carry + * to PUSHR register, so no need to change the pointer of txData. + */ + transferConfigB.srcAddr = (uint32_t)((uint8_t *)(handle->txData)); + transferConfigB.srcOffset = 1; + } + } + else + { + transferConfigB.srcAddr = (uint32_t)(&handle->txBuffIfNull); + transferConfigB.srcOffset = 0; + } + + transferConfigB.destAddr = (uint32_t)txAddr; + transferConfigB.destOffset = 0; + + transferConfigB.srcTransferSize = kEDMA_TransferSize1Bytes; + + if (handle->bitsPerFrame <= 8) + { + transferConfigB.destTransferSize = kEDMA_TransferSize1Bytes; + transferConfigB.minorLoopBytes = 1; + + transferConfigB.majorLoopCounts = handle->remainingSendByteCount - 1; + } + else + { + transferConfigB.destTransferSize = kEDMA_TransferSize2Bytes; + transferConfigB.minorLoopBytes = 2; + transferConfigB.majorLoopCounts = (handle->remainingSendByteCount / 2) - 1; + } + + EDMA_SetTransferConfig(handle->edmaIntermediaryToTxRegHandle->base, + handle->edmaIntermediaryToTxRegHandle->channel, &transferConfigB, softwareTCD); + } + /* If only one word to transmit, only carry the lastcommand. */ + else + { + EDMA_SetTransferConfig(handle->edmaIntermediaryToTxRegHandle->base, + handle->edmaIntermediaryToTxRegHandle->channel, &transferConfigB, NULL); + } + + /*Start the EDMA channel_A , channel_C. */ + EDMA_StartTransfer(handle->edmaRxRegToRxDataHandle); + EDMA_StartTransfer(handle->edmaIntermediaryToTxRegHandle); + + /* Set the channel link. + * For DSPI instances with shared TX and RX DMA requests, setup channel minor link, first receive data from the + * receive register, and then carry transmit data to PUSHER register. + * For DSPI instance with separate TX and RX DMA requests, there is no need to set up channel link. + */ + if (1 != FSL_FEATURE_DSPI_HAS_SEPARATE_DMA_RX_TX_REQn(base)) + { + /*Set channel priority*/ + uint8_t channelPriorityLow = handle->edmaRxRegToRxDataHandle->channel; + uint8_t channelPriorityHigh = handle->edmaIntermediaryToTxRegHandle->channel; + uint8_t t = 0; + + if (channelPriorityLow > channelPriorityHigh) + { + t = channelPriorityLow; + channelPriorityLow = channelPriorityHigh; + channelPriorityHigh = t; + } + + edma_channel_Preemption_config_t preemption_config_t; + preemption_config_t.enableChannelPreemption = true; + preemption_config_t.enablePreemptAbility = true; + preemption_config_t.channelPriority = channelPriorityLow; + + EDMA_SetChannelPreemptionConfig(handle->edmaRxRegToRxDataHandle->base, handle->edmaRxRegToRxDataHandle->channel, + &preemption_config_t); + + preemption_config_t.channelPriority = channelPriorityHigh; + EDMA_SetChannelPreemptionConfig(handle->edmaIntermediaryToTxRegHandle->base, + handle->edmaIntermediaryToTxRegHandle->channel, &preemption_config_t); + /*if there is Rx DMA request , carry the 32bits data (handle->command) to user data first , then link to + channelC to carry the next data to PUSHER register.(txData to PUSHER) */ + if (handle->remainingSendByteCount > 0) + { + EDMA_SetChannelLink(handle->edmaRxRegToRxDataHandle->base, handle->edmaRxRegToRxDataHandle->channel, + kEDMA_MinorLink, handle->edmaIntermediaryToTxRegHandle->channel); + } + } + + DSPI_EnableDMA(base, kDSPI_RxDmaEnable | kDSPI_TxDmaEnable); + + /* Setup control info to PUSHER register. */ + *((uint16_t *)&(base->PUSHR) + 1) = (handle->command >> 16U); +#else + + /***channel_B *** used for carry the data from User_Send_Buffer to "intermediary" because the SPIx_PUSHR should + write the 32bits at once time . Then use channel_C to carry the "intermediary" to SPIx_PUSHR. Note that the + SPIx_PUSHR upper 16 bits are the "command" and the low 16bits are data */ + + EDMA_ResetChannel(handle->edmaTxDataToIntermediaryHandle->base, handle->edmaTxDataToIntermediaryHandle->channel); + + /*For DSPI instances with separate RX and TX DMA requests: use the scatter/gather to prepare the last data + * (handle->lastCommand) to handle->Command*/ + if (1 == FSL_FEATURE_DSPI_HAS_SEPARATE_DMA_RX_TX_REQn(base)) + { + transferConfigB.srcAddr = (uint32_t) & (handle->lastCommand); + transferConfigB.destAddr = (uint32_t) & (handle->command); + transferConfigB.srcTransferSize = kEDMA_TransferSize4Bytes; + transferConfigB.destTransferSize = kEDMA_TransferSize4Bytes; + transferConfigB.srcOffset = 0; + transferConfigB.destOffset = 0; + transferConfigB.minorLoopBytes = 4; + transferConfigB.majorLoopCounts = 1; + + EDMA_TcdReset(softwareTCD); + EDMA_TcdSetTransferConfig(softwareTCD, &transferConfigB, NULL); + } + + /*User_Send_Buffer(txData) to intermediary(handle->command)*/ + if (((((handle->remainingSendByteCount > 2) && (handle->bitsPerFrame <= 8)) || + ((handle->remainingSendByteCount > 4) && (handle->bitsPerFrame > 8))) && + (1 == FSL_FEATURE_DSPI_HAS_SEPARATE_DMA_RX_TX_REQn(base))) || + (1 != FSL_FEATURE_DSPI_HAS_SEPARATE_DMA_RX_TX_REQn(base))) + { + if (handle->txData) + { + transferConfigB.srcAddr = (uint32_t)(handle->txData); + transferConfigB.srcOffset = 1; + } + else + { + transferConfigB.srcAddr = (uint32_t)(&handle->txBuffIfNull); + transferConfigB.srcOffset = 0; + } + + transferConfigB.destAddr = (uint32_t)(&handle->command); + transferConfigB.destOffset = 0; + + transferConfigB.srcTransferSize = kEDMA_TransferSize1Bytes; + + if (handle->bitsPerFrame <= 8) + { + transferConfigB.destTransferSize = kEDMA_TransferSize1Bytes; + transferConfigB.minorLoopBytes = 1; + + if (1 == FSL_FEATURE_DSPI_HAS_SEPARATE_DMA_RX_TX_REQn(base)) + { + transferConfigB.majorLoopCounts = handle->remainingSendByteCount - 2; + } + else + { + /*Only enable channel_B minorlink to channel_C , so need to add one count due to the last time is + majorlink , the majorlink would not trigger the channel_C*/ + transferConfigB.majorLoopCounts = handle->remainingSendByteCount + 1; + } + } + else + { + transferConfigB.destTransferSize = kEDMA_TransferSize2Bytes; + transferConfigB.minorLoopBytes = 2; + if (1 == FSL_FEATURE_DSPI_HAS_SEPARATE_DMA_RX_TX_REQn(base)) + { + transferConfigB.majorLoopCounts = handle->remainingSendByteCount / 2 - 2; + } + else + { + /*Only enable channel_B minorlink to channel_C , so need to add one count due to the last time is + * majorlink*/ + transferConfigB.majorLoopCounts = handle->remainingSendByteCount / 2 + 1; + } + } + + if (1 == FSL_FEATURE_DSPI_HAS_SEPARATE_DMA_RX_TX_REQn(base)) + { + EDMA_SetTransferConfig(handle->edmaTxDataToIntermediaryHandle->base, + handle->edmaTxDataToIntermediaryHandle->channel, &transferConfigB, softwareTCD); + EDMA_EnableAutoStopRequest(handle->edmaIntermediaryToTxRegHandle->base, + handle->edmaIntermediaryToTxRegHandle->channel, false); + } + else + { + EDMA_SetTransferConfig(handle->edmaTxDataToIntermediaryHandle->base, + handle->edmaTxDataToIntermediaryHandle->channel, &transferConfigB, NULL); + } + } + else + { + EDMA_SetTransferConfig(handle->edmaTxDataToIntermediaryHandle->base, + handle->edmaTxDataToIntermediaryHandle->channel, &transferConfigB, NULL); + } + + /***channel_C ***carry the "intermediary" to SPIx_PUSHR. used the edma Scatter Gather function on channel_C to + handle the last data */ + + edma_transfer_config_t transferConfigC; + EDMA_ResetChannel(handle->edmaIntermediaryToTxRegHandle->base, handle->edmaIntermediaryToTxRegHandle->channel); + + /*For DSPI instances with shared RX/TX DMA requests: use the scatter/gather to prepare the last data + * (handle->lastCommand) to SPI_PUSHR*/ + if (((1 != FSL_FEATURE_DSPI_HAS_SEPARATE_DMA_RX_TX_REQn(base)) && (handle->remainingSendByteCount > 0))) + { + transferConfigC.srcAddr = (uint32_t) & (handle->lastCommand); + transferConfigC.destAddr = (uint32_t)txAddr; + transferConfigC.srcTransferSize = kEDMA_TransferSize4Bytes; + transferConfigC.destTransferSize = kEDMA_TransferSize4Bytes; + transferConfigC.srcOffset = 0; + transferConfigC.destOffset = 0; + transferConfigC.minorLoopBytes = 4; + transferConfigC.majorLoopCounts = 1; + + EDMA_TcdReset(softwareTCD); + EDMA_TcdSetTransferConfig(softwareTCD, &transferConfigC, NULL); + } + + if (((handle->remainingSendByteCount > 1) && (handle->bitsPerFrame <= 8)) || + ((handle->remainingSendByteCount > 2) && (handle->bitsPerFrame > 8)) || + (1 == FSL_FEATURE_DSPI_HAS_SEPARATE_DMA_RX_TX_REQn(base))) + { + transferConfigC.srcAddr = (uint32_t)(&(handle->command)); + transferConfigC.destAddr = (uint32_t)txAddr; + + transferConfigC.srcTransferSize = kEDMA_TransferSize4Bytes; + transferConfigC.destTransferSize = kEDMA_TransferSize4Bytes; + transferConfigC.srcOffset = 0; + transferConfigC.destOffset = 0; + transferConfigC.minorLoopBytes = 4; + if (1 != FSL_FEATURE_DSPI_HAS_SEPARATE_DMA_RX_TX_REQn(base)) + { + if (handle->bitsPerFrame <= 8) + { + transferConfigC.majorLoopCounts = handle->remainingSendByteCount - 1; + } + else + { + transferConfigC.majorLoopCounts = handle->remainingSendByteCount / 2 - 1; + } + + EDMA_SetTransferConfig(handle->edmaIntermediaryToTxRegHandle->base, + handle->edmaIntermediaryToTxRegHandle->channel, &transferConfigC, softwareTCD); + } + else + { + transferConfigC.majorLoopCounts = 1; + + EDMA_SetTransferConfig(handle->edmaIntermediaryToTxRegHandle->base, + handle->edmaIntermediaryToTxRegHandle->channel, &transferConfigC, NULL); + } + + EDMA_EnableAutoStopRequest(handle->edmaIntermediaryToTxRegHandle->base, + handle->edmaIntermediaryToTxRegHandle->channel, false); + } + else + { + EDMA_SetTransferConfig(handle->edmaIntermediaryToTxRegHandle->base, + handle->edmaIntermediaryToTxRegHandle->channel, &transferConfigC, NULL); + } + + /*Start the EDMA channel_A , channel_B , channel_C transfer*/ + EDMA_StartTransfer(handle->edmaRxRegToRxDataHandle); + EDMA_StartTransfer(handle->edmaTxDataToIntermediaryHandle); + EDMA_StartTransfer(handle->edmaIntermediaryToTxRegHandle); + + /*Set channel priority*/ + uint8_t channelPriorityLow = handle->edmaRxRegToRxDataHandle->channel; + uint8_t channelPriorityMid = handle->edmaTxDataToIntermediaryHandle->channel; + uint8_t channelPriorityHigh = handle->edmaIntermediaryToTxRegHandle->channel; + uint8_t t = 0; + if (channelPriorityLow > channelPriorityMid) + { + t = channelPriorityLow; + channelPriorityLow = channelPriorityMid; + channelPriorityMid = t; + } + + if (channelPriorityLow > channelPriorityHigh) + { + t = channelPriorityLow; + channelPriorityLow = channelPriorityHigh; + channelPriorityHigh = t; + } + + if (channelPriorityMid > channelPriorityHigh) + { + t = channelPriorityMid; + channelPriorityMid = channelPriorityHigh; + channelPriorityHigh = t; + } + edma_channel_Preemption_config_t preemption_config_t; + preemption_config_t.enableChannelPreemption = true; + preemption_config_t.enablePreemptAbility = true; + preemption_config_t.channelPriority = channelPriorityLow; + + if (1 != FSL_FEATURE_DSPI_HAS_SEPARATE_DMA_RX_TX_REQn(base)) + { + EDMA_SetChannelPreemptionConfig(handle->edmaRxRegToRxDataHandle->base, handle->edmaRxRegToRxDataHandle->channel, + &preemption_config_t); + + preemption_config_t.channelPriority = channelPriorityMid; + EDMA_SetChannelPreemptionConfig(handle->edmaTxDataToIntermediaryHandle->base, + handle->edmaTxDataToIntermediaryHandle->channel, &preemption_config_t); + + preemption_config_t.channelPriority = channelPriorityHigh; + EDMA_SetChannelPreemptionConfig(handle->edmaIntermediaryToTxRegHandle->base, + handle->edmaIntermediaryToTxRegHandle->channel, &preemption_config_t); + } + else + { + EDMA_SetChannelPreemptionConfig(handle->edmaIntermediaryToTxRegHandle->base, + handle->edmaIntermediaryToTxRegHandle->channel, &preemption_config_t); + + preemption_config_t.channelPriority = channelPriorityMid; + EDMA_SetChannelPreemptionConfig(handle->edmaTxDataToIntermediaryHandle->base, + handle->edmaTxDataToIntermediaryHandle->channel, &preemption_config_t); + + preemption_config_t.channelPriority = channelPriorityHigh; + EDMA_SetChannelPreemptionConfig(handle->edmaRxRegToRxDataHandle->base, handle->edmaRxRegToRxDataHandle->channel, + &preemption_config_t); + } + + /*Set the channel link.*/ + if (1 == FSL_FEATURE_DSPI_HAS_SEPARATE_DMA_RX_TX_REQn(base)) + { + /*if there is Tx DMA request , carry the 32bits data (handle->command) to PUSHR first , then link to channelB + to prepare the next 32bits data (txData to handle->command) */ + if (handle->remainingSendByteCount > 1) + { + EDMA_SetChannelLink(handle->edmaIntermediaryToTxRegHandle->base, + handle->edmaIntermediaryToTxRegHandle->channel, kEDMA_MajorLink, + handle->edmaTxDataToIntermediaryHandle->channel); + } + + DSPI_EnableDMA(base, kDSPI_RxDmaEnable | kDSPI_TxDmaEnable); + } + else + { + if (handle->remainingSendByteCount > 0) + { + EDMA_SetChannelLink(handle->edmaRxRegToRxDataHandle->base, handle->edmaRxRegToRxDataHandle->channel, + kEDMA_MinorLink, handle->edmaTxDataToIntermediaryHandle->channel); + + EDMA_SetChannelLink(handle->edmaTxDataToIntermediaryHandle->base, + handle->edmaTxDataToIntermediaryHandle->channel, kEDMA_MinorLink, + handle->edmaIntermediaryToTxRegHandle->channel); + } + + DSPI_EnableDMA(base, kDSPI_RxDmaEnable); + } +#endif + DSPI_StartTransfer(base); + + return kStatus_Success; +} + +status_t DSPI_MasterHalfDuplexTransferEDMA(SPI_Type *base, + dspi_master_edma_handle_t *handle, + dspi_half_duplex_transfer_t *xfer) +{ + assert(xfer); + assert(handle); + dspi_transfer_t tempXfer = {0}; + status_t status; + + if (xfer->isTransmitFirst) + { + tempXfer.txData = xfer->txData; + tempXfer.rxData = NULL; + tempXfer.dataSize = xfer->txDataSize; + } + else + { + tempXfer.txData = NULL; + tempXfer.rxData = xfer->rxData; + tempXfer.dataSize = xfer->rxDataSize; + } + /* If the pcs pin keep assert between transmit and receive. */ + if (xfer->isPcsAssertInTransfer) + { + tempXfer.configFlags = (xfer->configFlags) | kDSPI_MasterActiveAfterTransfer; + } + else + { + tempXfer.configFlags = (xfer->configFlags) & (uint32_t)(~kDSPI_MasterActiveAfterTransfer); + } + + status = DSPI_MasterTransferBlocking(base, &tempXfer); + if (status != kStatus_Success) + { + return status; + } + + if (xfer->isTransmitFirst) + { + tempXfer.txData = NULL; + tempXfer.rxData = xfer->rxData; + tempXfer.dataSize = xfer->rxDataSize; + } + else + { + tempXfer.txData = xfer->txData; + tempXfer.rxData = NULL; + tempXfer.dataSize = xfer->txDataSize; + } + tempXfer.configFlags = xfer->configFlags; + + status = DSPI_MasterTransferEDMA(base, handle, &tempXfer); + + return status; +} +static void EDMA_DspiMasterCallback(edma_handle_t *edmaHandle, + void *g_dspiEdmaPrivateHandle, + bool transferDone, + uint32_t tcds) +{ + assert(edmaHandle); + assert(g_dspiEdmaPrivateHandle); + + dspi_master_edma_private_handle_t *dspiEdmaPrivateHandle; + + dspiEdmaPrivateHandle = (dspi_master_edma_private_handle_t *)g_dspiEdmaPrivateHandle; + + DSPI_DisableDMA((dspiEdmaPrivateHandle->base), kDSPI_RxDmaEnable | kDSPI_TxDmaEnable); + + dspiEdmaPrivateHandle->handle->state = kDSPI_Idle; + + if (dspiEdmaPrivateHandle->handle->callback) + { + dspiEdmaPrivateHandle->handle->callback(dspiEdmaPrivateHandle->base, dspiEdmaPrivateHandle->handle, + kStatus_Success, dspiEdmaPrivateHandle->handle->userData); + } +} + +void DSPI_MasterTransferAbortEDMA(SPI_Type *base, dspi_master_edma_handle_t *handle) +{ + assert(handle); + + DSPI_StopTransfer(base); + + DSPI_DisableDMA(base, kDSPI_RxDmaEnable | kDSPI_TxDmaEnable); + + EDMA_AbortTransfer(handle->edmaRxRegToRxDataHandle); + EDMA_AbortTransfer(handle->edmaTxDataToIntermediaryHandle); + EDMA_AbortTransfer(handle->edmaIntermediaryToTxRegHandle); + + handle->state = kDSPI_Idle; +} + +status_t DSPI_MasterTransferGetCountEDMA(SPI_Type *base, dspi_master_edma_handle_t *handle, size_t *count) +{ + assert(handle); + + if (!count) + { + return kStatus_InvalidArgument; + } + + /* Catch when there is not an active transfer. */ + if (handle->state != kDSPI_Busy) + { + *count = 0; + return kStatus_NoTransferInProgress; + } + + size_t bytes; + + bytes = (uint32_t)handle->nbytes * EDMA_GetRemainingMajorLoopCount(handle->edmaRxRegToRxDataHandle->base, + handle->edmaRxRegToRxDataHandle->channel); + + *count = handle->totalByteCount - bytes; + + return kStatus_Success; +} + +void DSPI_SlaveTransferCreateHandleEDMA(SPI_Type *base, + dspi_slave_edma_handle_t *handle, + dspi_slave_edma_transfer_callback_t callback, + void *userData, + edma_handle_t *edmaRxRegToRxDataHandle, + edma_handle_t *edmaTxDataToTxRegHandle) +{ + assert(handle); + assert(edmaRxRegToRxDataHandle); + assert(edmaTxDataToTxRegHandle); + + /* Zero the handle. */ + memset(handle, 0, sizeof(*handle)); + + uint32_t instance = DSPI_GetInstance(base); + + s_dspiSlaveEdmaPrivateHandle[instance].base = base; + s_dspiSlaveEdmaPrivateHandle[instance].handle = handle; + + handle->callback = callback; + handle->userData = userData; + + handle->edmaRxRegToRxDataHandle = edmaRxRegToRxDataHandle; + handle->edmaTxDataToTxRegHandle = edmaTxDataToTxRegHandle; +} + +status_t DSPI_SlaveTransferEDMA(SPI_Type *base, dspi_slave_edma_handle_t *handle, dspi_transfer_t *transfer) +{ + assert(handle); + assert(transfer); + + /* If send/receive length is zero */ + if (transfer->dataSize == 0) + { + return kStatus_InvalidArgument; + } + + /* If both send buffer and receive buffer is null */ + if ((!(transfer->txData)) && (!(transfer->rxData))) + { + return kStatus_InvalidArgument; + } + + /* Check that we're not busy.*/ + if (handle->state == kDSPI_Busy) + { + return kStatus_DSPI_Busy; + } + + handle->state = kDSPI_Busy; + + uint32_t instance = DSPI_GetInstance(base); + uint8_t whichCtar = (transfer->configFlags & DSPI_SLAVE_CTAR_MASK) >> DSPI_SLAVE_CTAR_SHIFT; + handle->bitsPerFrame = + (((base->CTAR_SLAVE[whichCtar]) & SPI_CTAR_SLAVE_FMSZ_MASK) >> SPI_CTAR_SLAVE_FMSZ_SHIFT) + 1; + + /* If using a shared RX/TX DMA request, then this limits the amount of data we can transfer + * due to the linked channel. The max bytes is 511 if 8-bit/frame or 1022 if 16-bit/frame + */ + uint32_t limited_size = 0; + if (1 == FSL_FEATURE_DSPI_HAS_SEPARATE_DMA_RX_TX_REQn(base)) + { + limited_size = 32767u; + } + else + { + limited_size = 511u; + } + + if (handle->bitsPerFrame > 8) + { + if (transfer->dataSize > (limited_size << 1u)) + { + handle->state = kDSPI_Idle; + return kStatus_DSPI_OutOfRange; + } + } + else + { + if (transfer->dataSize > limited_size) + { + handle->state = kDSPI_Idle; + return kStatus_DSPI_OutOfRange; + } + } + + /*The data size should be even if the bitsPerFrame is greater than 8 (that is 2 bytes per frame in dspi) */ + if ((handle->bitsPerFrame > 8) && (transfer->dataSize & 0x1)) + { + handle->state = kDSPI_Idle; + return kStatus_InvalidArgument; + } + + EDMA_SetCallback(handle->edmaRxRegToRxDataHandle, EDMA_DspiSlaveCallback, &s_dspiSlaveEdmaPrivateHandle[instance]); + + /* Store transfer information */ + handle->txData = transfer->txData; + handle->rxData = transfer->rxData; + handle->remainingSendByteCount = transfer->dataSize; + handle->remainingReceiveByteCount = transfer->dataSize; + handle->totalByteCount = transfer->dataSize; + + uint16_t wordToSend = 0; + uint8_t dummyData = g_dspiDummyData[DSPI_GetInstance(base)]; + uint8_t dataAlreadyFed = 0; + uint8_t dataFedMax = 2; + + uint32_t rxAddr = DSPI_GetRxRegisterAddress(base); + uint32_t txAddr = DSPI_SlaveGetTxRegisterAddress(base); + + edma_transfer_config_t transferConfigA; + edma_transfer_config_t transferConfigC; + + DSPI_StopTransfer(base); + + DSPI_FlushFifo(base, true, true); + DSPI_ClearStatusFlags(base, kDSPI_AllStatusFlag); + + DSPI_DisableDMA(base, kDSPI_RxDmaEnable | kDSPI_TxDmaEnable); + + DSPI_StartTransfer(base); + + /*if dspi has separate dma request , need not prepare data first . + else (dspi has shared dma request) , send first 2 data into fifo if there is fifo or send first 1 data to + slaveGetTxRegister if there is no fifo*/ + if (1 != FSL_FEATURE_DSPI_HAS_SEPARATE_DMA_RX_TX_REQn(base)) + { + /* For DSPI instances with shared RX/TX DMA requests, we'll use the RX DMA request to + * trigger ongoing transfers and will link to the TX DMA channel from the RX DMA channel. + */ + /* If bits/frame is greater than one byte */ + if (handle->bitsPerFrame > 8) + { + while (DSPI_GetStatusFlags(base) & kDSPI_TxFifoFillRequestFlag) + { + if (handle->txData) + { + wordToSend = *(handle->txData); + ++handle->txData; /* Increment to next data byte */ + + wordToSend |= (unsigned)(*(handle->txData)) << 8U; + ++handle->txData; /* Increment to next data byte */ + } + else + { + wordToSend = ((uint32_t)dummyData << 8) | dummyData; + } + handle->remainingSendByteCount -= 2; /* decrement remainingSendByteCount by 2 */ + base->PUSHR_SLAVE = wordToSend; + + /* Try to clear the TFFF; if the TX FIFO is full this will clear */ + DSPI_ClearStatusFlags(base, kDSPI_TxFifoFillRequestFlag); + + dataAlreadyFed += 2; + + /* Exit loop if send count is zero, else update local variables for next loop */ + if ((handle->remainingSendByteCount == 0) || (dataAlreadyFed == (dataFedMax * 2))) + { + break; + } + } /* End of TX FIFO fill while loop */ + } + else /* Optimized for bits/frame less than or equal to one byte. */ + { + while (DSPI_GetStatusFlags(base) & kDSPI_TxFifoFillRequestFlag) + { + if (handle->txData) + { + wordToSend = *(handle->txData); + /* Increment to next data word*/ + ++handle->txData; + } + else + { + wordToSend = dummyData; + } + + base->PUSHR_SLAVE = wordToSend; + + /* Try to clear the TFFF; if the TX FIFO is full this will clear */ + DSPI_ClearStatusFlags(base, kDSPI_TxFifoFillRequestFlag); + /* Decrement remainingSendByteCount*/ + --handle->remainingSendByteCount; + + dataAlreadyFed++; + + /* Exit loop if send count is zero, else update local variables for next loop */ + if ((handle->remainingSendByteCount == 0) || (dataAlreadyFed == dataFedMax)) + { + break; + } + } /* End of TX FIFO fill while loop */ + } + } + + /***channel_A *** used for carry the data from Rx_Data_Register(POPR) to User_Receive_Buffer*/ + if (handle->remainingReceiveByteCount > 0) + { + EDMA_ResetChannel(handle->edmaRxRegToRxDataHandle->base, handle->edmaRxRegToRxDataHandle->channel); + + transferConfigA.srcAddr = (uint32_t)rxAddr; + transferConfigA.srcOffset = 0; + + if (handle->rxData) + { + transferConfigA.destAddr = (uint32_t) & (handle->rxData[0]); + transferConfigA.destOffset = 1; + } + else + { + transferConfigA.destAddr = (uint32_t) & (handle->rxBuffIfNull); + transferConfigA.destOffset = 0; + } + + transferConfigA.destTransferSize = kEDMA_TransferSize1Bytes; + + if (handle->bitsPerFrame <= 8) + { + transferConfigA.srcTransferSize = kEDMA_TransferSize1Bytes; + transferConfigA.minorLoopBytes = 1; + transferConfigA.majorLoopCounts = handle->remainingReceiveByteCount; + } + else + { + transferConfigA.srcTransferSize = kEDMA_TransferSize2Bytes; + transferConfigA.minorLoopBytes = 2; + transferConfigA.majorLoopCounts = handle->remainingReceiveByteCount / 2; + } + + /* Store the initially configured eDMA minor byte transfer count into the DSPI handle */ + handle->nbytes = transferConfigA.minorLoopBytes; + + EDMA_SetTransferConfig(handle->edmaRxRegToRxDataHandle->base, handle->edmaRxRegToRxDataHandle->channel, + &transferConfigA, NULL); + EDMA_EnableChannelInterrupts(handle->edmaRxRegToRxDataHandle->base, handle->edmaRxRegToRxDataHandle->channel, + kEDMA_MajorInterruptEnable); + } + + if (handle->remainingSendByteCount > 0) + { + /***channel_C *** used for carry the data from User_Send_Buffer to Tx_Data_Register(PUSHR_SLAVE)*/ + EDMA_ResetChannel(handle->edmaTxDataToTxRegHandle->base, handle->edmaTxDataToTxRegHandle->channel); + + transferConfigC.destAddr = (uint32_t)txAddr; + transferConfigC.destOffset = 0; + + if (handle->txData) + { + transferConfigC.srcAddr = (uint32_t)(&(handle->txData[0])); + transferConfigC.srcOffset = 1; + } + else + { + transferConfigC.srcAddr = (uint32_t)(&handle->txBuffIfNull); + transferConfigC.srcOffset = 0; + if (handle->bitsPerFrame <= 8) + { + handle->txBuffIfNull = dummyData; + } + else + { + handle->txBuffIfNull = ((uint32_t)dummyData << 8) | dummyData; + } + } + + transferConfigC.srcTransferSize = kEDMA_TransferSize1Bytes; + + if (handle->bitsPerFrame <= 8) + { + transferConfigC.destTransferSize = kEDMA_TransferSize1Bytes; + transferConfigC.minorLoopBytes = 1; + transferConfigC.majorLoopCounts = handle->remainingSendByteCount; + } + else + { + transferConfigC.destTransferSize = kEDMA_TransferSize2Bytes; + transferConfigC.minorLoopBytes = 2; + transferConfigC.majorLoopCounts = handle->remainingSendByteCount / 2; + } + + EDMA_SetTransferConfig(handle->edmaTxDataToTxRegHandle->base, handle->edmaTxDataToTxRegHandle->channel, + &transferConfigC, NULL); + + EDMA_StartTransfer(handle->edmaTxDataToTxRegHandle); + } + + EDMA_StartTransfer(handle->edmaRxRegToRxDataHandle); + + /*Set channel priority*/ + uint8_t channelPriorityLow = handle->edmaRxRegToRxDataHandle->channel; + uint8_t channelPriorityHigh = handle->edmaTxDataToTxRegHandle->channel; + uint8_t t = 0; + + if (channelPriorityLow > channelPriorityHigh) + { + t = channelPriorityLow; + channelPriorityLow = channelPriorityHigh; + channelPriorityHigh = t; + } + + edma_channel_Preemption_config_t preemption_config_t; + preemption_config_t.enableChannelPreemption = true; + preemption_config_t.enablePreemptAbility = true; + preemption_config_t.channelPriority = channelPriorityLow; + + if (1 != FSL_FEATURE_DSPI_HAS_SEPARATE_DMA_RX_TX_REQn(base)) + { + EDMA_SetChannelPreemptionConfig(handle->edmaRxRegToRxDataHandle->base, handle->edmaRxRegToRxDataHandle->channel, + &preemption_config_t); + + preemption_config_t.channelPriority = channelPriorityHigh; + EDMA_SetChannelPreemptionConfig(handle->edmaTxDataToTxRegHandle->base, handle->edmaTxDataToTxRegHandle->channel, + &preemption_config_t); + } + else + { + EDMA_SetChannelPreemptionConfig(handle->edmaTxDataToTxRegHandle->base, handle->edmaTxDataToTxRegHandle->channel, + &preemption_config_t); + + preemption_config_t.channelPriority = channelPriorityHigh; + EDMA_SetChannelPreemptionConfig(handle->edmaRxRegToRxDataHandle->base, handle->edmaRxRegToRxDataHandle->channel, + &preemption_config_t); + } + + /*Set the channel link. + For DSPI instances with shared RX/TX DMA requests: Rx DMA request -> channel_A -> channel_C. + For DSPI instances with separate RX and TX DMA requests: + Rx DMA request -> channel_A + Tx DMA request -> channel_C */ + if (1 != FSL_FEATURE_DSPI_HAS_SEPARATE_DMA_RX_TX_REQn(base)) + { + if (handle->remainingSendByteCount > 0) + { + EDMA_SetChannelLink(handle->edmaRxRegToRxDataHandle->base, handle->edmaRxRegToRxDataHandle->channel, + kEDMA_MinorLink, handle->edmaTxDataToTxRegHandle->channel); + } + DSPI_EnableDMA(base, kDSPI_RxDmaEnable); + } + else + { + DSPI_EnableDMA(base, kDSPI_RxDmaEnable | kDSPI_TxDmaEnable); + } + + return kStatus_Success; +} + +static void EDMA_DspiSlaveCallback(edma_handle_t *edmaHandle, + void *g_dspiEdmaPrivateHandle, + bool transferDone, + uint32_t tcds) +{ + assert(edmaHandle); + assert(g_dspiEdmaPrivateHandle); + + dspi_slave_edma_private_handle_t *dspiEdmaPrivateHandle; + + dspiEdmaPrivateHandle = (dspi_slave_edma_private_handle_t *)g_dspiEdmaPrivateHandle; + + DSPI_DisableDMA((dspiEdmaPrivateHandle->base), kDSPI_RxDmaEnable | kDSPI_TxDmaEnable); + + dspiEdmaPrivateHandle->handle->state = kDSPI_Idle; + + if (dspiEdmaPrivateHandle->handle->callback) + { + dspiEdmaPrivateHandle->handle->callback(dspiEdmaPrivateHandle->base, dspiEdmaPrivateHandle->handle, + kStatus_Success, dspiEdmaPrivateHandle->handle->userData); + } +} + +void DSPI_SlaveTransferAbortEDMA(SPI_Type *base, dspi_slave_edma_handle_t *handle) +{ + assert(handle); + + DSPI_StopTransfer(base); + + DSPI_DisableDMA(base, kDSPI_RxDmaEnable | kDSPI_TxDmaEnable); + + EDMA_AbortTransfer(handle->edmaRxRegToRxDataHandle); + EDMA_AbortTransfer(handle->edmaTxDataToTxRegHandle); + + handle->state = kDSPI_Idle; +} + +status_t DSPI_SlaveTransferGetCountEDMA(SPI_Type *base, dspi_slave_edma_handle_t *handle, size_t *count) +{ + assert(handle); + + if (!count) + { + return kStatus_InvalidArgument; + } + + /* Catch when there is not an active transfer. */ + if (handle->state != kDSPI_Busy) + { + *count = 0; + return kStatus_NoTransferInProgress; + } + + size_t bytes; + + bytes = (uint32_t)handle->nbytes * EDMA_GetRemainingMajorLoopCount(handle->edmaRxRegToRxDataHandle->base, + handle->edmaRxRegToRxDataHandle->channel); + + *count = handle->totalByteCount - bytes; + + return kStatus_Success; +} diff --git a/drivers/fsl_dspi_edma.h b/drivers/fsl_dspi_edma.h new file mode 100644 index 0000000..aa9656c --- /dev/null +++ b/drivers/fsl_dspi_edma.h @@ -0,0 +1,306 @@ +/* + * The Clear BSD License + * Copyright (c) 2015, 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: + * + * o Redistributions of source code must retain the above copyright notice, this list + * of conditions and the following disclaimer. + * + * o 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. + * + * o 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_DSPI_EDMA_H_ +#define _FSL_DSPI_EDMA_H_ + +#include "fsl_dspi.h" +#include "fsl_edma.h" +/*! + * @addtogroup dspi_edma_driver + * @{ + */ + +/*********************************************************************************************************************** + * Definitions + **********************************************************************************************************************/ + +/*! @name Driver version */ +/*@{*/ +/*! @brief DSPI EDMA driver version 2.2.0. */ +#define FSL_DSPI_EDMA_DRIVER_VERSION (MAKE_VERSION(2, 2, 0)) +/*@}*/ + +/*! +* @brief Forward declaration of the DSPI eDMA master handle typedefs. +*/ +typedef struct _dspi_master_edma_handle dspi_master_edma_handle_t; + +/*! +* @brief Forward declaration of the DSPI eDMA slave handle typedefs. +*/ +typedef struct _dspi_slave_edma_handle dspi_slave_edma_handle_t; + +/*! + * @brief Completion callback function pointer type. + * + * @param base DSPI peripheral base address. + * @param handle A pointer to the handle for the DSPI master. + * @param status Success or error code describing whether the transfer completed. + * @param userData An arbitrary pointer-dataSized value passed from the application. + */ +typedef void (*dspi_master_edma_transfer_callback_t)(SPI_Type *base, + dspi_master_edma_handle_t *handle, + status_t status, + void *userData); +/*! + * @brief Completion callback function pointer type. + * + * @param base DSPI peripheral base address. + * @param handle A pointer to the handle for the DSPI slave. + * @param status Success or error code describing whether the transfer completed. + * @param userData An arbitrary pointer-dataSized value passed from the application. + */ +typedef void (*dspi_slave_edma_transfer_callback_t)(SPI_Type *base, + dspi_slave_edma_handle_t *handle, + status_t status, + void *userData); + +/*! @brief DSPI master eDMA transfer handle structure used for the transactional API. */ +struct _dspi_master_edma_handle +{ + uint32_t bitsPerFrame; /*!< The desired number of bits per frame. */ + volatile uint32_t command; /*!< The desired data command. */ + volatile uint32_t lastCommand; /*!< The desired last data command. */ + + uint8_t fifoSize; /*!< FIFO dataSize. */ + + volatile bool + isPcsActiveAfterTransfer; /*!< Indicates whether the PCS signal keeps active after the last frame transfer.*/ + + uint8_t nbytes; /*!< eDMA minor byte transfer count initially configured. */ + volatile uint8_t state; /*!< DSPI transfer state , _dspi_transfer_state.*/ + + uint8_t *volatile txData; /*!< Send buffer. */ + uint8_t *volatile rxData; /*!< Receive buffer. */ + volatile size_t remainingSendByteCount; /*!< A number of bytes remaining to send.*/ + volatile size_t remainingReceiveByteCount; /*!< A number of bytes remaining to receive.*/ + size_t totalByteCount; /*!< A number of transfer bytes*/ + + uint32_t rxBuffIfNull; /*!< Used if there is not rxData for DMA purpose.*/ + uint32_t txBuffIfNull; /*!< Used if there is not txData for DMA purpose.*/ + + dspi_master_edma_transfer_callback_t callback; /*!< Completion callback. */ + void *userData; /*!< Callback user data. */ + + edma_handle_t *edmaRxRegToRxDataHandle; /*!TCD[channel].SADDR = tcd->SADDR; + base->TCD[channel].SOFF = tcd->SOFF; + base->TCD[channel].ATTR = tcd->ATTR; + base->TCD[channel].NBYTES_MLNO = tcd->NBYTES; + base->TCD[channel].SLAST = tcd->SLAST; + base->TCD[channel].DADDR = tcd->DADDR; + base->TCD[channel].DOFF = tcd->DOFF; + base->TCD[channel].CITER_ELINKNO = tcd->CITER; + base->TCD[channel].DLAST_SGA = tcd->DLAST_SGA; + /* Clear DONE bit first, otherwise ESG cannot be set */ + base->TCD[channel].CSR = 0; + base->TCD[channel].CSR = tcd->CSR; + base->TCD[channel].BITER_ELINKNO = tcd->BITER; +} + +void EDMA_Init(DMA_Type *base, const edma_config_t *config) +{ + assert(config != NULL); + + uint32_t tmpreg; + +#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) + /* Ungate EDMA periphral clock */ + CLOCK_EnableClock(s_edmaClockName[EDMA_GetInstance(base)]); +#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */ + /* Configure EDMA peripheral according to the configuration structure. */ + tmpreg = base->CR; + tmpreg &= ~(DMA_CR_ERCA_MASK | DMA_CR_HOE_MASK | DMA_CR_CLM_MASK | DMA_CR_EDBG_MASK); + tmpreg |= (DMA_CR_ERCA(config->enableRoundRobinArbitration) | DMA_CR_HOE(config->enableHaltOnError) | + DMA_CR_CLM(config->enableContinuousLinkMode) | DMA_CR_EDBG(config->enableDebugMode) | DMA_CR_EMLM(true)); + base->CR = tmpreg; +} + +void EDMA_Deinit(DMA_Type *base) +{ +#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) + /* Gate EDMA periphral clock */ + CLOCK_DisableClock(s_edmaClockName[EDMA_GetInstance(base)]); +#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */ +} + +void EDMA_GetDefaultConfig(edma_config_t *config) +{ + assert(config != NULL); + + config->enableRoundRobinArbitration = false; + config->enableHaltOnError = true; + config->enableContinuousLinkMode = false; + config->enableDebugMode = false; +} + +void EDMA_ResetChannel(DMA_Type *base, uint32_t channel) +{ + assert(channel < FSL_FEATURE_EDMA_MODULE_CHANNEL); + + EDMA_TcdReset((edma_tcd_t *)&base->TCD[channel]); +} + +void EDMA_SetTransferConfig(DMA_Type *base, uint32_t channel, const edma_transfer_config_t *config, edma_tcd_t *nextTcd) +{ + assert(channel < FSL_FEATURE_EDMA_MODULE_CHANNEL); + assert(config != NULL); + assert(((uint32_t)nextTcd & 0x1FU) == 0); + + EDMA_TcdSetTransferConfig((edma_tcd_t *)&base->TCD[channel], config, nextTcd); +} + +void EDMA_SetMinorOffsetConfig(DMA_Type *base, uint32_t channel, const edma_minor_offset_config_t *config) +{ + assert(channel < FSL_FEATURE_EDMA_MODULE_CHANNEL); + assert(config != NULL); + + uint32_t tmpreg; + + tmpreg = base->TCD[channel].NBYTES_MLOFFYES; + tmpreg &= ~(DMA_NBYTES_MLOFFYES_SMLOE_MASK | DMA_NBYTES_MLOFFYES_DMLOE_MASK | DMA_NBYTES_MLOFFYES_MLOFF_MASK); + tmpreg |= + (DMA_NBYTES_MLOFFYES_SMLOE(config->enableSrcMinorOffset) | + DMA_NBYTES_MLOFFYES_DMLOE(config->enableDestMinorOffset) | DMA_NBYTES_MLOFFYES_MLOFF(config->minorOffset)); + base->TCD[channel].NBYTES_MLOFFYES = tmpreg; +} + +void EDMA_SetChannelLink(DMA_Type *base, uint32_t channel, edma_channel_link_type_t type, uint32_t linkedChannel) +{ + assert(channel < FSL_FEATURE_EDMA_MODULE_CHANNEL); + assert(linkedChannel < FSL_FEATURE_EDMA_MODULE_CHANNEL); + + EDMA_TcdSetChannelLink((edma_tcd_t *)&base->TCD[channel], type, linkedChannel); +} + +void EDMA_SetBandWidth(DMA_Type *base, uint32_t channel, edma_bandwidth_t bandWidth) +{ + assert(channel < FSL_FEATURE_EDMA_MODULE_CHANNEL); + + base->TCD[channel].CSR = (base->TCD[channel].CSR & (~DMA_CSR_BWC_MASK)) | DMA_CSR_BWC(bandWidth); +} + +void EDMA_SetModulo(DMA_Type *base, uint32_t channel, edma_modulo_t srcModulo, edma_modulo_t destModulo) +{ + assert(channel < FSL_FEATURE_EDMA_MODULE_CHANNEL); + + uint32_t tmpreg; + + tmpreg = base->TCD[channel].ATTR & (~(DMA_ATTR_SMOD_MASK | DMA_ATTR_DMOD_MASK)); + base->TCD[channel].ATTR = tmpreg | DMA_ATTR_DMOD(destModulo) | DMA_ATTR_SMOD(srcModulo); +} + +void EDMA_EnableChannelInterrupts(DMA_Type *base, uint32_t channel, uint32_t mask) +{ + assert(channel < FSL_FEATURE_EDMA_MODULE_CHANNEL); + + /* Enable error interrupt */ + if (mask & kEDMA_ErrorInterruptEnable) + { + base->EEI |= (0x1U << channel); + } + + /* Enable Major interrupt */ + if (mask & kEDMA_MajorInterruptEnable) + { + base->TCD[channel].CSR |= DMA_CSR_INTMAJOR_MASK; + } + + /* Enable Half major interrupt */ + if (mask & kEDMA_HalfInterruptEnable) + { + base->TCD[channel].CSR |= DMA_CSR_INTHALF_MASK; + } +} + +void EDMA_DisableChannelInterrupts(DMA_Type *base, uint32_t channel, uint32_t mask) +{ + assert(channel < FSL_FEATURE_EDMA_MODULE_CHANNEL); + + /* Disable error interrupt */ + if (mask & kEDMA_ErrorInterruptEnable) + { + base->EEI &= ~(0x1U << channel); + } + + /* Disable Major interrupt */ + if (mask & kEDMA_MajorInterruptEnable) + { + base->TCD[channel].CSR &= ~DMA_CSR_INTMAJOR_MASK; + } + + /* Disable Half major interrupt */ + if (mask & kEDMA_HalfInterruptEnable) + { + base->TCD[channel].CSR &= ~DMA_CSR_INTHALF_MASK; + } +} + +void EDMA_TcdReset(edma_tcd_t *tcd) +{ + assert(tcd != NULL); + assert(((uint32_t)tcd & 0x1FU) == 0); + + /* Reset channel TCD */ + tcd->SADDR = 0U; + tcd->SOFF = 0U; + tcd->ATTR = 0U; + tcd->NBYTES = 0U; + tcd->SLAST = 0U; + tcd->DADDR = 0U; + tcd->DOFF = 0U; + tcd->CITER = 0U; + tcd->DLAST_SGA = 0U; + /* Enable auto disable request feature */ + tcd->CSR = DMA_CSR_DREQ(true); + tcd->BITER = 0U; +} + +void EDMA_TcdSetTransferConfig(edma_tcd_t *tcd, const edma_transfer_config_t *config, edma_tcd_t *nextTcd) +{ + assert(tcd != NULL); + assert(((uint32_t)tcd & 0x1FU) == 0); + assert(config != NULL); + assert(((uint32_t)nextTcd & 0x1FU) == 0); + + /* source address */ + tcd->SADDR = config->srcAddr; + /* destination address */ + tcd->DADDR = config->destAddr; + /* Source data and destination data transfer size */ + tcd->ATTR = DMA_ATTR_SSIZE(config->srcTransferSize) | DMA_ATTR_DSIZE(config->destTransferSize); + /* Source address signed offset */ + tcd->SOFF = config->srcOffset; + /* Destination address signed offset */ + tcd->DOFF = config->destOffset; + /* Minor byte transfer count */ + tcd->NBYTES = config->minorLoopBytes; + /* Current major iteration count */ + tcd->CITER = config->majorLoopCounts; + /* Starting major iteration count */ + tcd->BITER = config->majorLoopCounts; + /* Enable scatter/gather processing */ + if (nextTcd != NULL) + { + tcd->DLAST_SGA = (uint32_t)nextTcd; + /* + Before call EDMA_TcdSetTransferConfig or EDMA_SetTransferConfig, + user must call EDMA_TcdReset or EDMA_ResetChannel which will set + DREQ, so must use "|" or "&" rather than "=". + + Clear the DREQ bit because scatter gather has been enabled, so the + previous transfer is not the last transfer, and channel request should + be enabled at the next transfer(the next TCD). + */ + tcd->CSR = (tcd->CSR | DMA_CSR_ESG_MASK) & ~DMA_CSR_DREQ_MASK; + } +} + +void EDMA_TcdSetMinorOffsetConfig(edma_tcd_t *tcd, const edma_minor_offset_config_t *config) +{ + assert(tcd != NULL); + assert(((uint32_t)tcd & 0x1FU) == 0); + + uint32_t tmpreg; + + tmpreg = tcd->NBYTES & + ~(DMA_NBYTES_MLOFFYES_SMLOE_MASK | DMA_NBYTES_MLOFFYES_DMLOE_MASK | DMA_NBYTES_MLOFFYES_MLOFF_MASK); + tmpreg |= + (DMA_NBYTES_MLOFFYES_SMLOE(config->enableSrcMinorOffset) | + DMA_NBYTES_MLOFFYES_DMLOE(config->enableDestMinorOffset) | DMA_NBYTES_MLOFFYES_MLOFF(config->minorOffset)); + tcd->NBYTES = tmpreg; +} + +void EDMA_TcdSetChannelLink(edma_tcd_t *tcd, edma_channel_link_type_t type, uint32_t linkedChannel) +{ + assert(tcd != NULL); + assert(((uint32_t)tcd & 0x1FU) == 0); + assert(linkedChannel < FSL_FEATURE_EDMA_MODULE_CHANNEL); + + if (type == kEDMA_MinorLink) /* Minor link config */ + { + uint32_t tmpreg; + + /* Enable minor link */ + tcd->CITER |= DMA_CITER_ELINKYES_ELINK_MASK; + tcd->BITER |= DMA_BITER_ELINKYES_ELINK_MASK; + /* Set likned channel */ + tmpreg = tcd->CITER & (~DMA_CITER_ELINKYES_LINKCH_MASK); + tmpreg |= DMA_CITER_ELINKYES_LINKCH(linkedChannel); + tcd->CITER = tmpreg; + tmpreg = tcd->BITER & (~DMA_BITER_ELINKYES_LINKCH_MASK); + tmpreg |= DMA_BITER_ELINKYES_LINKCH(linkedChannel); + tcd->BITER = tmpreg; + } + else if (type == kEDMA_MajorLink) /* Major link config */ + { + uint32_t tmpreg; + + /* Enable major link */ + tcd->CSR |= DMA_CSR_MAJORELINK_MASK; + /* Set major linked channel */ + tmpreg = tcd->CSR & (~DMA_CSR_MAJORLINKCH_MASK); + tcd->CSR = tmpreg | DMA_CSR_MAJORLINKCH(linkedChannel); + } + else /* Link none */ + { + tcd->CITER &= ~DMA_CITER_ELINKYES_ELINK_MASK; + tcd->BITER &= ~DMA_BITER_ELINKYES_ELINK_MASK; + tcd->CSR &= ~DMA_CSR_MAJORELINK_MASK; + } +} + +void EDMA_TcdSetModulo(edma_tcd_t *tcd, edma_modulo_t srcModulo, edma_modulo_t destModulo) +{ + assert(tcd != NULL); + assert(((uint32_t)tcd & 0x1FU) == 0); + + uint32_t tmpreg; + + tmpreg = tcd->ATTR & (~(DMA_ATTR_SMOD_MASK | DMA_ATTR_DMOD_MASK)); + tcd->ATTR = tmpreg | DMA_ATTR_DMOD(destModulo) | DMA_ATTR_SMOD(srcModulo); +} + +void EDMA_TcdEnableInterrupts(edma_tcd_t *tcd, uint32_t mask) +{ + assert(tcd != NULL); + + /* Enable Major interrupt */ + if (mask & kEDMA_MajorInterruptEnable) + { + tcd->CSR |= DMA_CSR_INTMAJOR_MASK; + } + + /* Enable Half major interrupt */ + if (mask & kEDMA_HalfInterruptEnable) + { + tcd->CSR |= DMA_CSR_INTHALF_MASK; + } +} + +void EDMA_TcdDisableInterrupts(edma_tcd_t *tcd, uint32_t mask) +{ + assert(tcd != NULL); + + /* Disable Major interrupt */ + if (mask & kEDMA_MajorInterruptEnable) + { + tcd->CSR &= ~DMA_CSR_INTMAJOR_MASK; + } + + /* Disable Half major interrupt */ + if (mask & kEDMA_HalfInterruptEnable) + { + tcd->CSR &= ~DMA_CSR_INTHALF_MASK; + } +} + +uint32_t EDMA_GetRemainingMajorLoopCount(DMA_Type *base, uint32_t channel) +{ + assert(channel < FSL_FEATURE_EDMA_MODULE_CHANNEL); + + uint32_t remainingCount = 0; + + if (DMA_CSR_DONE_MASK & base->TCD[channel].CSR) + { + remainingCount = 0; + } + else + { + /* Calculate the unfinished bytes */ + if (base->TCD[channel].CITER_ELINKNO & DMA_CITER_ELINKNO_ELINK_MASK) + { + remainingCount = + (base->TCD[channel].CITER_ELINKYES & DMA_CITER_ELINKYES_CITER_MASK) >> DMA_CITER_ELINKYES_CITER_SHIFT; + } + else + { + remainingCount = + (base->TCD[channel].CITER_ELINKNO & DMA_CITER_ELINKNO_CITER_MASK) >> DMA_CITER_ELINKNO_CITER_SHIFT; + } + } + + return remainingCount; +} + +uint32_t EDMA_GetChannelStatusFlags(DMA_Type *base, uint32_t channel) +{ + assert(channel < FSL_FEATURE_EDMA_MODULE_CHANNEL); + + uint32_t retval = 0; + + /* Get DONE bit flag */ + retval |= ((base->TCD[channel].CSR & DMA_CSR_DONE_MASK) >> DMA_CSR_DONE_SHIFT); + /* Get ERROR bit flag */ + retval |= (((base->ERR >> channel) & 0x1U) << 1U); + /* Get INT bit flag */ + retval |= (((base->INT >> channel) & 0x1U) << 2U); + + return retval; +} + +void EDMA_ClearChannelStatusFlags(DMA_Type *base, uint32_t channel, uint32_t mask) +{ + assert(channel < FSL_FEATURE_EDMA_MODULE_CHANNEL); + + /* Clear DONE bit flag */ + if (mask & kEDMA_DoneFlag) + { + base->CDNE = channel; + } + /* Clear ERROR bit flag */ + if (mask & kEDMA_ErrorFlag) + { + base->CERR = channel; + } + /* Clear INT bit flag */ + if (mask & kEDMA_InterruptFlag) + { + base->CINT = channel; + } +} + +static uint8_t Get_StartInstance(void) +{ + static uint8_t StartInstanceNum; + +#if defined(DMA0) + StartInstanceNum = EDMA_GetInstance(DMA0); +#elif defined(DMA1) + StartInstanceNum = EDMA_GetInstance(DMA1); +#elif defined(DMA2) + StartInstanceNum = EDMA_GetInstance(DMA2); +#elif defined(DMA3) + StartInstanceNum = EDMA_GetInstance(DMA3); +#endif + + return StartInstanceNum; +} + +void EDMA_CreateHandle(edma_handle_t *handle, DMA_Type *base, uint32_t channel) +{ + assert(handle != NULL); + assert(channel < FSL_FEATURE_EDMA_MODULE_CHANNEL); + + uint32_t edmaInstance; + uint32_t channelIndex; + uint8_t StartInstance; + edma_tcd_t *tcdRegs; + + /* Zero the handle */ + memset(handle, 0, sizeof(*handle)); + + handle->base = base; + handle->channel = channel; + /* Get the DMA instance number */ + edmaInstance = EDMA_GetInstance(base); + StartInstance = Get_StartInstance(); + channelIndex = ((edmaInstance - StartInstance) * FSL_FEATURE_EDMA_MODULE_CHANNEL) + channel; + s_EDMAHandle[channelIndex] = handle; + + /* Enable NVIC interrupt */ + EnableIRQ(s_edmaIRQNumber[edmaInstance][channel]); + + /* + Reset TCD registers to zero. Unlike the EDMA_TcdReset(DREQ will be set), + CSR will be 0. Because in order to suit EDMA busy check mechanism in + EDMA_SubmitTransfer, CSR must be set 0. + */ + tcdRegs = (edma_tcd_t *)&handle->base->TCD[handle->channel]; + tcdRegs->SADDR = 0; + tcdRegs->SOFF = 0; + tcdRegs->ATTR = 0; + tcdRegs->NBYTES = 0; + tcdRegs->SLAST = 0; + tcdRegs->DADDR = 0; + tcdRegs->DOFF = 0; + tcdRegs->CITER = 0; + tcdRegs->DLAST_SGA = 0; + tcdRegs->CSR = 0; + tcdRegs->BITER = 0; +} + +void EDMA_InstallTCDMemory(edma_handle_t *handle, edma_tcd_t *tcdPool, uint32_t tcdSize) +{ + assert(handle != NULL); + assert(((uint32_t)tcdPool & 0x1FU) == 0); + + /* Initialize tcd queue attibute. */ + handle->header = 0; + handle->tail = 0; + handle->tcdUsed = 0; + handle->tcdSize = tcdSize; + handle->flags = 0; + handle->tcdPool = tcdPool; +} + +void EDMA_SetCallback(edma_handle_t *handle, edma_callback callback, void *userData) +{ + assert(handle != NULL); + + handle->callback = callback; + handle->userData = userData; +} + +void EDMA_PrepareTransfer(edma_transfer_config_t *config, + void *srcAddr, + uint32_t srcWidth, + void *destAddr, + uint32_t destWidth, + uint32_t bytesEachRequest, + uint32_t transferBytes, + edma_transfer_type_t type) +{ + assert(config != NULL); + assert(srcAddr != NULL); + assert(destAddr != NULL); + assert((srcWidth == 1U) || (srcWidth == 2U) || (srcWidth == 4U) || (srcWidth == 16U) || (srcWidth == 32U)); + assert((destWidth == 1U) || (destWidth == 2U) || (destWidth == 4U) || (destWidth == 16U) || (destWidth == 32U)); + assert(transferBytes % bytesEachRequest == 0); + + config->destAddr = (uint32_t)destAddr; + config->srcAddr = (uint32_t)srcAddr; + config->minorLoopBytes = bytesEachRequest; + config->majorLoopCounts = transferBytes / bytesEachRequest; + switch (srcWidth) + { + case 1U: + config->srcTransferSize = kEDMA_TransferSize1Bytes; + break; + case 2U: + config->srcTransferSize = kEDMA_TransferSize2Bytes; + break; + case 4U: + config->srcTransferSize = kEDMA_TransferSize4Bytes; + break; + case 16U: + config->srcTransferSize = kEDMA_TransferSize16Bytes; + break; + case 32U: + config->srcTransferSize = kEDMA_TransferSize32Bytes; + break; + default: + break; + } + switch (destWidth) + { + case 1U: + config->destTransferSize = kEDMA_TransferSize1Bytes; + break; + case 2U: + config->destTransferSize = kEDMA_TransferSize2Bytes; + break; + case 4U: + config->destTransferSize = kEDMA_TransferSize4Bytes; + break; + case 16U: + config->destTransferSize = kEDMA_TransferSize16Bytes; + break; + case 32U: + config->destTransferSize = kEDMA_TransferSize32Bytes; + break; + default: + break; + } + switch (type) + { + case kEDMA_MemoryToMemory: + config->destOffset = destWidth; + config->srcOffset = srcWidth; + break; + case kEDMA_MemoryToPeripheral: + config->destOffset = 0U; + config->srcOffset = srcWidth; + break; + case kEDMA_PeripheralToMemory: + config->destOffset = destWidth; + config->srcOffset = 0U; + break; + default: + break; + } +} + +status_t EDMA_SubmitTransfer(edma_handle_t *handle, const edma_transfer_config_t *config) +{ + assert(handle != NULL); + assert(config != NULL); + + edma_tcd_t *tcdRegs = (edma_tcd_t *)&handle->base->TCD[handle->channel]; + + if (handle->tcdPool == NULL) + { + /* + Check if EDMA is busy: if the given channel started transfer, CSR will be not zero. Because + if it is the last transfer, DREQ will be set. If not, ESG will be set. So in order to suit + this check mechanism, EDMA_CreatHandle will clear CSR register. + */ + if ((tcdRegs->CSR != 0) && ((tcdRegs->CSR & DMA_CSR_DONE_MASK) == 0)) + { + return kStatus_EDMA_Busy; + } + else + { + EDMA_SetTransferConfig(handle->base, handle->channel, config, NULL); + /* Enable auto disable request feature */ + handle->base->TCD[handle->channel].CSR |= DMA_CSR_DREQ_MASK; + /* Enable major interrupt */ + handle->base->TCD[handle->channel].CSR |= DMA_CSR_INTMAJOR_MASK; + + return kStatus_Success; + } + } + else /* Use the TCD queue. */ + { + uint32_t primask; + uint32_t csr; + int8_t currentTcd; + int8_t previousTcd; + int8_t nextTcd; + + /* Check if tcd pool is full. */ + primask = DisableGlobalIRQ(); + if (handle->tcdUsed >= handle->tcdSize) + { + EnableGlobalIRQ(primask); + + return kStatus_EDMA_QueueFull; + } + currentTcd = handle->tail; + handle->tcdUsed++; + /* Calculate index of next TCD */ + nextTcd = currentTcd + 1U; + if (nextTcd == handle->tcdSize) + { + nextTcd = 0U; + } + /* Advance queue tail index */ + handle->tail = nextTcd; + EnableGlobalIRQ(primask); + /* Calculate index of previous TCD */ + previousTcd = currentTcd ? currentTcd - 1U : handle->tcdSize - 1U; + /* Configure current TCD block. */ + EDMA_TcdReset(&handle->tcdPool[currentTcd]); + EDMA_TcdSetTransferConfig(&handle->tcdPool[currentTcd], config, NULL); + /* Enable major interrupt */ + handle->tcdPool[currentTcd].CSR |= DMA_CSR_INTMAJOR_MASK; + /* Link current TCD with next TCD for identification of current TCD */ + handle->tcdPool[currentTcd].DLAST_SGA = (uint32_t)&handle->tcdPool[nextTcd]; + /* Chain from previous descriptor unless tcd pool size is 1(this descriptor is its own predecessor). */ + if (currentTcd != previousTcd) + { + /* Enable scatter/gather feature in the previous TCD block. */ + csr = (handle->tcdPool[previousTcd].CSR | DMA_CSR_ESG_MASK) & ~DMA_CSR_DREQ_MASK; + handle->tcdPool[previousTcd].CSR = csr; + /* + Check if the TCD blcok in the registers is the previous one (points to current TCD block). It + is used to check if the previous TCD linked has been loaded in TCD register. If so, it need to + link the TCD register in case link the current TCD with the dead chain when TCD loading occurs + before link the previous TCD block. + */ + if (tcdRegs->DLAST_SGA == (uint32_t)&handle->tcdPool[currentTcd]) + { + /* Clear the DREQ bits for the dynamic scatter gather */ + tcdRegs->CSR |= DMA_CSR_DREQ_MASK; + /* Enable scatter/gather also in the TCD registers. */ + csr = tcdRegs->CSR | DMA_CSR_ESG_MASK; + /* Must write the CSR register one-time, because the transfer maybe finished anytime. */ + tcdRegs->CSR = csr; + /* + It is very important to check the ESG bit! + Because this hardware design: if DONE bit is set, the ESG bit can not be set. So it can + be used to check if the dynamic TCD link operation is successful. If ESG bit is not set + and the DLAST_SGA is not the next TCD address(it means the dynamic TCD link succeed and + the current TCD block has been loaded into TCD registers), it means transfer finished + and TCD link operation fail, so must install TCD content into TCD registers and enable + transfer again. And if ESG is set, it means transfer has notfinished, so TCD dynamic + link succeed. + */ + if (tcdRegs->CSR & DMA_CSR_ESG_MASK) + { + tcdRegs->CSR &= ~DMA_CSR_DREQ_MASK; + return kStatus_Success; + } + /* + Check whether the current TCD block is already loaded in the TCD registers. It is another + condition when ESG bit is not set: it means the dynamic TCD link succeed and the current + TCD block has been loaded into TCD registers. + */ + if (tcdRegs->DLAST_SGA == (uint32_t)&handle->tcdPool[nextTcd]) + { + return kStatus_Success; + } + /* + If go to this, means the previous transfer finished, and the DONE bit is set. + So shall configure TCD registers. + */ + } + else if (tcdRegs->DLAST_SGA != 0) + { + /* The current TCD block has been linked successfully. */ + return kStatus_Success; + } + else + { + /* + DLAST_SGA is 0 and it means the first submit transfer, so shall configure + TCD registers. + */ + } + } + /* There is no live chain, TCD block need to be installed in TCD registers. */ + EDMA_InstallTCD(handle->base, handle->channel, &handle->tcdPool[currentTcd]); + /* Enable channel request again. */ + if (handle->flags & EDMA_TRANSFER_ENABLED_MASK) + { + handle->base->SERQ = DMA_SERQ_SERQ(handle->channel); + } + + return kStatus_Success; + } +} + +void EDMA_StartTransfer(edma_handle_t *handle) +{ + assert(handle != NULL); + + if (handle->tcdPool == NULL) + { + handle->base->SERQ = DMA_SERQ_SERQ(handle->channel); + } + else /* Use the TCD queue. */ + { + uint32_t primask; + edma_tcd_t *tcdRegs = (edma_tcd_t *)&handle->base->TCD[handle->channel]; + + handle->flags |= EDMA_TRANSFER_ENABLED_MASK; + + /* Check if there was at least one descriptor submitted since reset (TCD in registers is valid) */ + if (tcdRegs->DLAST_SGA != 0U) + { + primask = DisableGlobalIRQ(); + /* Check if channel request is actually disable. */ + if ((handle->base->ERQ & (1U << handle->channel)) == 0U) + { + /* Check if transfer is paused. */ + if ((!(tcdRegs->CSR & DMA_CSR_DONE_MASK)) || (tcdRegs->CSR & DMA_CSR_ESG_MASK)) + { + /* + Re-enable channel request must be as soon as possible, so must put it into + critical section to avoid task switching or interrupt service routine. + */ + handle->base->SERQ = DMA_SERQ_SERQ(handle->channel); + } + } + EnableGlobalIRQ(primask); + } + } +} + +void EDMA_StopTransfer(edma_handle_t *handle) +{ + assert(handle != NULL); + + handle->flags &= (~EDMA_TRANSFER_ENABLED_MASK); + handle->base->CERQ = DMA_CERQ_CERQ(handle->channel); +} + +void EDMA_AbortTransfer(edma_handle_t *handle) +{ + handle->base->CERQ = DMA_CERQ_CERQ(handle->channel); + /* + Clear CSR to release channel. Because if the given channel started transfer, + CSR will be not zero. Because if it is the last transfer, DREQ will be set. + If not, ESG will be set. + */ + handle->base->TCD[handle->channel].CSR = 0; + /* Cancel all next TCD transfer. */ + handle->base->TCD[handle->channel].DLAST_SGA = 0; + + /* Handle the tcd */ + if (handle->tcdPool != NULL) + { + handle->header = 0; + handle->tail = 0; + handle->tcdUsed = 0; + } +} + +void EDMA_HandleIRQ(edma_handle_t *handle) +{ + assert(handle != NULL); + + /* Clear EDMA interrupt flag */ + handle->base->CINT = handle->channel; + if ((handle->tcdPool == NULL) && (handle->callback != NULL)) + { + (handle->callback)(handle, handle->userData, true, 0); + } + else /* Use the TCD queue. Please refer to the API descriptions in the eDMA header file for detailed information. */ + { + uint32_t sga = handle->base->TCD[handle->channel].DLAST_SGA; + uint32_t sga_index; + int32_t tcds_done; + uint8_t new_header; + bool transfer_done; + + /* Check if transfer is already finished. */ + transfer_done = ((handle->base->TCD[handle->channel].CSR & DMA_CSR_DONE_MASK) != 0); + /* Get the offset of the next transfer TCD blcoks to be loaded into the eDMA engine. */ + sga -= (uint32_t)handle->tcdPool; + /* Get the index of the next transfer TCD blcoks to be loaded into the eDMA engine. */ + sga_index = sga / sizeof(edma_tcd_t); + /* Adjust header positions. */ + if (transfer_done) + { + /* New header shall point to the next TCD to be loaded (current one is already finished) */ + new_header = sga_index; + } + else + { + /* New header shall point to this descriptor currently loaded (not finished yet) */ + new_header = sga_index ? sga_index - 1U : handle->tcdSize - 1U; + } + /* Calculate the number of finished TCDs */ + if (new_header == handle->header) + { + if (handle->tcdUsed == handle->tcdSize) + { + tcds_done = handle->tcdUsed; + } + else + { + /* No TCD in the memory are going to be loaded or internal error occurs. */ + tcds_done = 0; + } + } + else + { + tcds_done = new_header - handle->header; + if (tcds_done < 0) + { + tcds_done += handle->tcdSize; + } + } + /* Advance header which points to the TCD to be loaded into the eDMA engine from memory. */ + handle->header = new_header; + /* Release TCD blocks. tcdUsed is the TCD number which can be used/loaded in the memory pool. */ + handle->tcdUsed -= tcds_done; + /* Invoke callback function. */ + if (handle->callback) + { + (handle->callback)(handle, handle->userData, transfer_done, tcds_done); + } + } +} + +/* 8 channels (Shared): kl28 */ +#if defined(FSL_FEATURE_EDMA_MODULE_CHANNEL) && FSL_FEATURE_EDMA_MODULE_CHANNEL == 8U + +#if defined(DMA0) +void DMA0_04_DriverIRQHandler(void) +{ + if ((EDMA_GetChannelStatusFlags(DMA0, 0U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[0]); + } + if ((EDMA_GetChannelStatusFlags(DMA0, 4U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[4]); + } + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA0_15_DriverIRQHandler(void) +{ + if ((EDMA_GetChannelStatusFlags(DMA0, 1U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[1]); + } + if ((EDMA_GetChannelStatusFlags(DMA0, 5U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[5]); + } + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA0_26_DriverIRQHandler(void) +{ + if ((EDMA_GetChannelStatusFlags(DMA0, 2U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[2]); + } + if ((EDMA_GetChannelStatusFlags(DMA0, 6U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[6]); + } + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA0_37_DriverIRQHandler(void) +{ + if ((EDMA_GetChannelStatusFlags(DMA0, 3U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[3]); + } + if ((EDMA_GetChannelStatusFlags(DMA0, 7U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[7]); + } + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} +#endif + +#if defined(DMA1) + +#if defined(DMA0) +void DMA1_04_DriverIRQHandler(void) +{ + if ((EDMA_GetChannelStatusFlags(DMA1, 0U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[8]); + } + if ((EDMA_GetChannelStatusFlags(DMA1, 4U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[12]); + } + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA1_15_DriverIRQHandler(void) +{ + if ((EDMA_GetChannelStatusFlags(DMA1, 1U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[9]); + } + if ((EDMA_GetChannelStatusFlags(DMA1, 5U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[13]); + } + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA1_26_DriverIRQHandler(void) +{ + if ((EDMA_GetChannelStatusFlags(DMA1, 2U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[10]); + } + if ((EDMA_GetChannelStatusFlags(DMA1, 6U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[14]); + } + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA1_37_DriverIRQHandler(void) +{ + if ((EDMA_GetChannelStatusFlags(DMA1, 3U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[11]); + } + if ((EDMA_GetChannelStatusFlags(DMA1, 7U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[15]); + } + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +#else +void DMA1_04_DriverIRQHandler(void) +{ + if ((EDMA_GetChannelStatusFlags(DMA1, 0U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[0]); + } + if ((EDMA_GetChannelStatusFlags(DMA1, 4U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[4]); + } + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA1_15_DriverIRQHandler(void) +{ + if ((EDMA_GetChannelStatusFlags(DMA1, 1U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[1]); + } + if ((EDMA_GetChannelStatusFlags(DMA1, 5U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[5]); + } + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA1_26_DriverIRQHandler(void) +{ + if ((EDMA_GetChannelStatusFlags(DMA1, 2U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[2]); + } + if ((EDMA_GetChannelStatusFlags(DMA1, 6U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[6]); + } + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA1_37_DriverIRQHandler(void) +{ + if ((EDMA_GetChannelStatusFlags(DMA1, 3U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[3]); + } + if ((EDMA_GetChannelStatusFlags(DMA1, 7U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[7]); + } + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} +#endif +#endif +#endif /* 8 channels (Shared) */ + +/* 16 channels (Shared): K32H844P */ +#if defined(FSL_FEATURE_EDMA_MODULE_CHANNEL) && FSL_FEATURE_EDMA_MODULE_CHANNEL == 16U + +void DMA0_08_DriverIRQHandler(void) +{ + if ((EDMA_GetChannelStatusFlags(DMA0, 0U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[0]); + } + if ((EDMA_GetChannelStatusFlags(DMA0, 8U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[8]); + } + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA0_19_DriverIRQHandler(void) +{ + if ((EDMA_GetChannelStatusFlags(DMA0, 1U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[1]); + } + if ((EDMA_GetChannelStatusFlags(DMA0, 9U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[9]); + } + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA0_210_DriverIRQHandler(void) +{ + if ((EDMA_GetChannelStatusFlags(DMA0, 2U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[2]); + } + if ((EDMA_GetChannelStatusFlags(DMA0, 10U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[10]); + } + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA0_311_DriverIRQHandler(void) +{ + if ((EDMA_GetChannelStatusFlags(DMA0, 3U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[3]); + } + if ((EDMA_GetChannelStatusFlags(DMA0, 11U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[11]); + } + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA0_412_DriverIRQHandler(void) +{ + if ((EDMA_GetChannelStatusFlags(DMA0, 4U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[4]); + } + if ((EDMA_GetChannelStatusFlags(DMA0, 12U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[12]); + } + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA0_513_DriverIRQHandler(void) +{ + if ((EDMA_GetChannelStatusFlags(DMA0, 5U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[5]); + } + if ((EDMA_GetChannelStatusFlags(DMA0, 13U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[13]); + } + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA0_614_DriverIRQHandler(void) +{ + if ((EDMA_GetChannelStatusFlags(DMA0, 6U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[6]); + } + if ((EDMA_GetChannelStatusFlags(DMA0, 14U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[14]); + } + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA0_715_DriverIRQHandler(void) +{ + if ((EDMA_GetChannelStatusFlags(DMA0, 7U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[7]); + } + if ((EDMA_GetChannelStatusFlags(DMA0, 15U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[15]); + } + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +#if defined(DMA1) +void DMA1_08_DriverIRQHandler(void) +{ + if ((EDMA_GetChannelStatusFlags(DMA1, 0U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[16]); + } + if ((EDMA_GetChannelStatusFlags(DMA1, 8U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[24]); + } + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA1_19_DriverIRQHandler(void) +{ + if ((EDMA_GetChannelStatusFlags(DMA1, 1U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[17]); + } + if ((EDMA_GetChannelStatusFlags(DMA1, 9U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[25]); + } + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA1_210_DriverIRQHandler(void) +{ + if ((EDMA_GetChannelStatusFlags(DMA1, 2U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[18]); + } + if ((EDMA_GetChannelStatusFlags(DMA1, 10U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[26]); + } + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA1_311_DriverIRQHandler(void) +{ + if ((EDMA_GetChannelStatusFlags(DMA1, 3U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[19]); + } + if ((EDMA_GetChannelStatusFlags(DMA1, 11U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[27]); + } + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA1_412_DriverIRQHandler(void) +{ + if ((EDMA_GetChannelStatusFlags(DMA1, 4U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[20]); + } + if ((EDMA_GetChannelStatusFlags(DMA1, 12U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[28]); + } + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA1_513_DriverIRQHandler(void) +{ + if ((EDMA_GetChannelStatusFlags(DMA1, 5U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[21]); + } + if ((EDMA_GetChannelStatusFlags(DMA1, 13U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[29]); + } + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA1_614_DriverIRQHandler(void) +{ + if ((EDMA_GetChannelStatusFlags(DMA1, 6U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[22]); + } + if ((EDMA_GetChannelStatusFlags(DMA1, 14U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[30]); + } + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA1_715_DriverIRQHandler(void) +{ + if ((EDMA_GetChannelStatusFlags(DMA1, 7U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[23]); + } + if ((EDMA_GetChannelStatusFlags(DMA1, 15U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[31]); + } + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} +#endif +#endif /* 16 channels (Shared) */ + +/* 32 channels (Shared): k80 */ +#if defined(FSL_FEATURE_EDMA_MODULE_CHANNEL) && FSL_FEATURE_EDMA_MODULE_CHANNEL == 32U + +void DMA0_DMA16_DriverIRQHandler(void) +{ + if ((EDMA_GetChannelStatusFlags(DMA0, 0U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[0]); + } + if ((EDMA_GetChannelStatusFlags(DMA0, 16U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[16]); + } + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA1_DMA17_DriverIRQHandler(void) +{ + if ((EDMA_GetChannelStatusFlags(DMA0, 1U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[1]); + } + if ((EDMA_GetChannelStatusFlags(DMA0, 17U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[17]); + } + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA2_DMA18_DriverIRQHandler(void) +{ + if ((EDMA_GetChannelStatusFlags(DMA0, 2U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[2]); + } + if ((EDMA_GetChannelStatusFlags(DMA0, 18U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[18]); + } + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA3_DMA19_DriverIRQHandler(void) +{ + if ((EDMA_GetChannelStatusFlags(DMA0, 3U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[3]); + } + if ((EDMA_GetChannelStatusFlags(DMA0, 19U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[19]); + } + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA4_DMA20_DriverIRQHandler(void) +{ + if ((EDMA_GetChannelStatusFlags(DMA0, 4U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[4]); + } + if ((EDMA_GetChannelStatusFlags(DMA0, 20U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[20]); + } + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA5_DMA21_DriverIRQHandler(void) +{ + if ((EDMA_GetChannelStatusFlags(DMA0, 5U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[5]); + } + if ((EDMA_GetChannelStatusFlags(DMA0, 21U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[21]); + } + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA6_DMA22_DriverIRQHandler(void) +{ + if ((EDMA_GetChannelStatusFlags(DMA0, 6U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[6]); + } + if ((EDMA_GetChannelStatusFlags(DMA0, 22U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[22]); + } + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA7_DMA23_DriverIRQHandler(void) +{ + if ((EDMA_GetChannelStatusFlags(DMA0, 7U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[7]); + } + if ((EDMA_GetChannelStatusFlags(DMA0, 23U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[23]); + } + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA8_DMA24_DriverIRQHandler(void) +{ + if ((EDMA_GetChannelStatusFlags(DMA0, 8U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[8]); + } + if ((EDMA_GetChannelStatusFlags(DMA0, 24U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[24]); + } + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA9_DMA25_DriverIRQHandler(void) +{ + if ((EDMA_GetChannelStatusFlags(DMA0, 9U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[9]); + } + if ((EDMA_GetChannelStatusFlags(DMA0, 25U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[25]); + } + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA10_DMA26_DriverIRQHandler(void) +{ + if ((EDMA_GetChannelStatusFlags(DMA0, 10U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[10]); + } + if ((EDMA_GetChannelStatusFlags(DMA0, 26U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[26]); + } + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA11_DMA27_DriverIRQHandler(void) +{ + if ((EDMA_GetChannelStatusFlags(DMA0, 11U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[11]); + } + if ((EDMA_GetChannelStatusFlags(DMA0, 27U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[27]); + } + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA12_DMA28_DriverIRQHandler(void) +{ + if ((EDMA_GetChannelStatusFlags(DMA0, 12U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[12]); + } + if ((EDMA_GetChannelStatusFlags(DMA0, 28U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[28]); + } + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA13_DMA29_DriverIRQHandler(void) +{ + if ((EDMA_GetChannelStatusFlags(DMA0, 13U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[13]); + } + if ((EDMA_GetChannelStatusFlags(DMA0, 29U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[29]); + } + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA14_DMA30_DriverIRQHandler(void) +{ + if ((EDMA_GetChannelStatusFlags(DMA0, 14U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[14]); + } + if ((EDMA_GetChannelStatusFlags(DMA0, 30U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[30]); + } + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA15_DMA31_DriverIRQHandler(void) +{ + if ((EDMA_GetChannelStatusFlags(DMA0, 15U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[15]); + } + if ((EDMA_GetChannelStatusFlags(DMA0, 31U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[31]); + } + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} +#endif /* 32 channels (Shared) */ + +/* 32 channels (Shared): MCIMX7U5_M4 */ +#if defined(FSL_FEATURE_EDMA_MODULE_CHANNEL) && FSL_FEATURE_EDMA_MODULE_CHANNEL == 32U + +void DMA0_0_4_DriverIRQHandler(void) +{ + if ((EDMA_GetChannelStatusFlags(DMA0, 0U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[0]); + } + if ((EDMA_GetChannelStatusFlags(DMA0, 4U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[4]); + } + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA0_1_5_DriverIRQHandler(void) +{ + if ((EDMA_GetChannelStatusFlags(DMA0, 1U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[1]); + } + if ((EDMA_GetChannelStatusFlags(DMA0, 5U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[5]); + } + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA0_2_6_DriverIRQHandler(void) +{ + if ((EDMA_GetChannelStatusFlags(DMA0, 2U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[2]); + } + if ((EDMA_GetChannelStatusFlags(DMA0, 6U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[6]); + } + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA0_3_7_DriverIRQHandler(void) +{ + if ((EDMA_GetChannelStatusFlags(DMA0, 3U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[3]); + } + if ((EDMA_GetChannelStatusFlags(DMA0, 7U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[7]); + } + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA0_8_12_DriverIRQHandler(void) +{ + if ((EDMA_GetChannelStatusFlags(DMA0, 8U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[8]); + } + if ((EDMA_GetChannelStatusFlags(DMA0, 12U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[12]); + } + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA0_9_13_DriverIRQHandler(void) +{ + if ((EDMA_GetChannelStatusFlags(DMA0, 9U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[9]); + } + if ((EDMA_GetChannelStatusFlags(DMA0, 13U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[13]); + } + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA0_10_14_DriverIRQHandler(void) +{ + if ((EDMA_GetChannelStatusFlags(DMA0, 10U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[10]); + } + if ((EDMA_GetChannelStatusFlags(DMA0, 14U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[14]); + } + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA0_11_15_DriverIRQHandler(void) +{ + if ((EDMA_GetChannelStatusFlags(DMA0, 11U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[11]); + } + if ((EDMA_GetChannelStatusFlags(DMA0, 15U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[15]); + } + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA0_16_20_DriverIRQHandler(void) +{ + if ((EDMA_GetChannelStatusFlags(DMA0, 16U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[16]); + } + if ((EDMA_GetChannelStatusFlags(DMA0, 20U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[20]); + } + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA0_17_21_DriverIRQHandler(void) +{ + if ((EDMA_GetChannelStatusFlags(DMA0, 17U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[17]); + } + if ((EDMA_GetChannelStatusFlags(DMA0, 21U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[21]); + } + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA0_18_22_DriverIRQHandler(void) +{ + if ((EDMA_GetChannelStatusFlags(DMA0, 18U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[18]); + } + if ((EDMA_GetChannelStatusFlags(DMA0, 22U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[22]); + } + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA0_19_23_DriverIRQHandler(void) +{ + if ((EDMA_GetChannelStatusFlags(DMA0, 19U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[19]); + } + if ((EDMA_GetChannelStatusFlags(DMA0, 23U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[23]); + } + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA0_24_28_DriverIRQHandler(void) +{ + if ((EDMA_GetChannelStatusFlags(DMA0, 24U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[24]); + } + if ((EDMA_GetChannelStatusFlags(DMA0, 28U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[28]); + } + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA0_25_29_DriverIRQHandler(void) +{ + if ((EDMA_GetChannelStatusFlags(DMA0, 25U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[25]); + } + if ((EDMA_GetChannelStatusFlags(DMA0, 29U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[29]); + } + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA0_26_30_DriverIRQHandler(void) +{ + if ((EDMA_GetChannelStatusFlags(DMA0, 26U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[26]); + } + if ((EDMA_GetChannelStatusFlags(DMA0, 30U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[30]); + } + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA0_27_31_DriverIRQHandler(void) +{ + if ((EDMA_GetChannelStatusFlags(DMA0, 27U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[27]); + } + if ((EDMA_GetChannelStatusFlags(DMA0, 31U) & kEDMA_InterruptFlag) != 0U) + { + EDMA_HandleIRQ(s_EDMAHandle[31]); + } + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} +#endif /* 32 channels (Shared): MCIMX7U5 */ + +/* 4 channels (No Shared): kv10 */ +#if defined(FSL_FEATURE_EDMA_MODULE_CHANNEL) && FSL_FEATURE_EDMA_MODULE_CHANNEL > 0 + +void DMA0_DriverIRQHandler(void) +{ + EDMA_HandleIRQ(s_EDMAHandle[0]); + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA1_DriverIRQHandler(void) +{ + EDMA_HandleIRQ(s_EDMAHandle[1]); + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA2_DriverIRQHandler(void) +{ + EDMA_HandleIRQ(s_EDMAHandle[2]); + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA3_DriverIRQHandler(void) +{ + EDMA_HandleIRQ(s_EDMAHandle[3]); + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +/* 8 channels (No Shared) */ +#if defined(FSL_FEATURE_EDMA_MODULE_CHANNEL) && FSL_FEATURE_EDMA_MODULE_CHANNEL > 4U + +void DMA4_DriverIRQHandler(void) +{ + EDMA_HandleIRQ(s_EDMAHandle[4]); + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA5_DriverIRQHandler(void) +{ + EDMA_HandleIRQ(s_EDMAHandle[5]); + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA6_DriverIRQHandler(void) +{ + EDMA_HandleIRQ(s_EDMAHandle[6]); + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA7_DriverIRQHandler(void) +{ + EDMA_HandleIRQ(s_EDMAHandle[7]); + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} +#endif /* FSL_FEATURE_EDMA_MODULE_CHANNEL == 8 */ + +/* 16 channels (No Shared) */ +#if defined(FSL_FEATURE_EDMA_MODULE_CHANNEL) && FSL_FEATURE_EDMA_MODULE_CHANNEL > 8U + +void DMA8_DriverIRQHandler(void) +{ + EDMA_HandleIRQ(s_EDMAHandle[8]); + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA9_DriverIRQHandler(void) +{ + EDMA_HandleIRQ(s_EDMAHandle[9]); + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA10_DriverIRQHandler(void) +{ + EDMA_HandleIRQ(s_EDMAHandle[10]); + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA11_DriverIRQHandler(void) +{ + EDMA_HandleIRQ(s_EDMAHandle[11]); + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA12_DriverIRQHandler(void) +{ + EDMA_HandleIRQ(s_EDMAHandle[12]); + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA13_DriverIRQHandler(void) +{ + EDMA_HandleIRQ(s_EDMAHandle[13]); + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA14_DriverIRQHandler(void) +{ + EDMA_HandleIRQ(s_EDMAHandle[14]); + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA15_DriverIRQHandler(void) +{ + EDMA_HandleIRQ(s_EDMAHandle[15]); + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} +#endif /* FSL_FEATURE_EDMA_MODULE_CHANNEL == 16 */ + +/* 32 channels (No Shared) */ +#if defined(FSL_FEATURE_EDMA_MODULE_CHANNEL) && FSL_FEATURE_EDMA_MODULE_CHANNEL > 16U + +void DMA16_DriverIRQHandler(void) +{ + EDMA_HandleIRQ(s_EDMAHandle[16]); + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA17_DriverIRQHandler(void) +{ + EDMA_HandleIRQ(s_EDMAHandle[17]); + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA18_DriverIRQHandler(void) +{ + EDMA_HandleIRQ(s_EDMAHandle[18]); + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA19_DriverIRQHandler(void) +{ + EDMA_HandleIRQ(s_EDMAHandle[19]); + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA20_DriverIRQHandler(void) +{ + EDMA_HandleIRQ(s_EDMAHandle[20]); + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA21_DriverIRQHandler(void) +{ + EDMA_HandleIRQ(s_EDMAHandle[21]); + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA22_DriverIRQHandler(void) +{ + EDMA_HandleIRQ(s_EDMAHandle[22]); + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA23_DriverIRQHandler(void) +{ + EDMA_HandleIRQ(s_EDMAHandle[23]); + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA24_DriverIRQHandler(void) +{ + EDMA_HandleIRQ(s_EDMAHandle[24]); + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA25_DriverIRQHandler(void) +{ + EDMA_HandleIRQ(s_EDMAHandle[25]); + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA26_DriverIRQHandler(void) +{ + EDMA_HandleIRQ(s_EDMAHandle[26]); + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA27_DriverIRQHandler(void) +{ + EDMA_HandleIRQ(s_EDMAHandle[27]); + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA28_DriverIRQHandler(void) +{ + EDMA_HandleIRQ(s_EDMAHandle[28]); + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA29_DriverIRQHandler(void) +{ + EDMA_HandleIRQ(s_EDMAHandle[29]); + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA30_DriverIRQHandler(void) +{ + EDMA_HandleIRQ(s_EDMAHandle[30]); + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void DMA31_DriverIRQHandler(void) +{ + EDMA_HandleIRQ(s_EDMAHandle[31]); + /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} +#endif /* FSL_FEATURE_EDMA_MODULE_CHANNEL == 32 */ + +#endif /* 4/8/16/32 channels (No Shared) */ diff --git a/drivers/fsl_edma.h b/drivers/fsl_edma.h new file mode 100644 index 0000000..03bc8db --- /dev/null +++ b/drivers/fsl_edma.h @@ -0,0 +1,957 @@ +/* + * The Clear BSD License + * Copyright (c) 2015, 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: + * + * o Redistributions of source code must retain the above copyright notice, this list + * of conditions and the following disclaimer. + * + * o 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. + * + * o 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_EDMA_H_ +#define _FSL_EDMA_H_ + +#include "fsl_common.h" + +/*! + * @addtogroup edma + * @{ + */ + +/******************************************************************************* + * Definitions + ******************************************************************************/ + +/*! @name Driver version */ +/*@{*/ +/*! @brief eDMA driver version */ +#define FSL_EDMA_DRIVER_VERSION (MAKE_VERSION(2, 1, 2)) /*!< Version 2.1.2. */ +/*@}*/ + +/*! @brief Compute the offset unit from DCHPRI3 */ +#define DMA_DCHPRI_INDEX(channel) (((channel) & ~0x03U) | (3 - ((channel)&0x03U))) + +/*! @brief Get the pointer of DCHPRIn */ +#define DMA_DCHPRIn(base, channel) ((volatile uint8_t *)&((base)->DCHPRI3))[DMA_DCHPRI_INDEX(channel)] + +/*! @brief eDMA transfer configuration */ +typedef enum _edma_transfer_size +{ + kEDMA_TransferSize1Bytes = 0x0U, /*!< Source/Destination data transfer size is 1 byte every time */ + kEDMA_TransferSize2Bytes = 0x1U, /*!< Source/Destination data transfer size is 2 bytes every time */ + kEDMA_TransferSize4Bytes = 0x2U, /*!< Source/Destination data transfer size is 4 bytes every time */ + kEDMA_TransferSize8Bytes = 0x3U, /*!< Source/Destination data transfer size is 8 bytes every time */ + kEDMA_TransferSize16Bytes = 0x4U, /*!< Source/Destination data transfer size is 16 bytes every time */ + kEDMA_TransferSize32Bytes = 0x5U, /*!< Source/Destination data transfer size is 32 bytes every time */ +} edma_transfer_size_t; + +/*! @brief eDMA modulo configuration */ +typedef enum _edma_modulo +{ + kEDMA_ModuloDisable = 0x0U, /*!< Disable modulo */ + kEDMA_Modulo2bytes, /*!< Circular buffer size is 2 bytes. */ + kEDMA_Modulo4bytes, /*!< Circular buffer size is 4 bytes. */ + kEDMA_Modulo8bytes, /*!< Circular buffer size is 8 bytes. */ + kEDMA_Modulo16bytes, /*!< Circular buffer size is 16 bytes. */ + kEDMA_Modulo32bytes, /*!< Circular buffer size is 32 bytes. */ + kEDMA_Modulo64bytes, /*!< Circular buffer size is 64 bytes. */ + kEDMA_Modulo128bytes, /*!< Circular buffer size is 128 bytes. */ + kEDMA_Modulo256bytes, /*!< Circular buffer size is 256 bytes. */ + kEDMA_Modulo512bytes, /*!< Circular buffer size is 512 bytes. */ + kEDMA_Modulo1Kbytes, /*!< Circular buffer size is 1 K bytes. */ + kEDMA_Modulo2Kbytes, /*!< Circular buffer size is 2 K bytes. */ + kEDMA_Modulo4Kbytes, /*!< Circular buffer size is 4 K bytes. */ + kEDMA_Modulo8Kbytes, /*!< Circular buffer size is 8 K bytes. */ + kEDMA_Modulo16Kbytes, /*!< Circular buffer size is 16 K bytes. */ + kEDMA_Modulo32Kbytes, /*!< Circular buffer size is 32 K bytes. */ + kEDMA_Modulo64Kbytes, /*!< Circular buffer size is 64 K bytes. */ + kEDMA_Modulo128Kbytes, /*!< Circular buffer size is 128 K bytes. */ + kEDMA_Modulo256Kbytes, /*!< Circular buffer size is 256 K bytes. */ + kEDMA_Modulo512Kbytes, /*!< Circular buffer size is 512 K bytes. */ + kEDMA_Modulo1Mbytes, /*!< Circular buffer size is 1 M bytes. */ + kEDMA_Modulo2Mbytes, /*!< Circular buffer size is 2 M bytes. */ + kEDMA_Modulo4Mbytes, /*!< Circular buffer size is 4 M bytes. */ + kEDMA_Modulo8Mbytes, /*!< Circular buffer size is 8 M bytes. */ + kEDMA_Modulo16Mbytes, /*!< Circular buffer size is 16 M bytes. */ + kEDMA_Modulo32Mbytes, /*!< Circular buffer size is 32 M bytes. */ + kEDMA_Modulo64Mbytes, /*!< Circular buffer size is 64 M bytes. */ + kEDMA_Modulo128Mbytes, /*!< Circular buffer size is 128 M bytes. */ + kEDMA_Modulo256Mbytes, /*!< Circular buffer size is 256 M bytes. */ + kEDMA_Modulo512Mbytes, /*!< Circular buffer size is 512 M bytes. */ + kEDMA_Modulo1Gbytes, /*!< Circular buffer size is 1 G bytes. */ + kEDMA_Modulo2Gbytes, /*!< Circular buffer size is 2 G bytes. */ +} edma_modulo_t; + +/*! @brief Bandwidth control */ +typedef enum _edma_bandwidth +{ + kEDMA_BandwidthStallNone = 0x0U, /*!< No eDMA engine stalls. */ + kEDMA_BandwidthStall4Cycle = 0x2U, /*!< eDMA engine stalls for 4 cycles after each read/write. */ + kEDMA_BandwidthStall8Cycle = 0x3U, /*!< eDMA engine stalls for 8 cycles after each read/write. */ +} edma_bandwidth_t; + +/*! @brief Channel link type */ +typedef enum _edma_channel_link_type +{ + kEDMA_LinkNone = 0x0U, /*!< No channel link */ + kEDMA_MinorLink, /*!< Channel link after each minor loop */ + kEDMA_MajorLink, /*!< Channel link while major loop count exhausted */ +} edma_channel_link_type_t; + +/*!@brief eDMA channel status flags. */ +enum _edma_channel_status_flags +{ + kEDMA_DoneFlag = 0x1U, /*!< DONE flag, set while transfer finished, CITER value exhausted*/ + kEDMA_ErrorFlag = 0x2U, /*!< eDMA error flag, an error occurred in a transfer */ + kEDMA_InterruptFlag = 0x4U, /*!< eDMA interrupt flag, set while an interrupt occurred of this channel */ +}; + +/*! @brief eDMA channel error status flags. */ +enum _edma_error_status_flags +{ + kEDMA_DestinationBusErrorFlag = DMA_ES_DBE_MASK, /*!< Bus error on destination address */ + kEDMA_SourceBusErrorFlag = DMA_ES_SBE_MASK, /*!< Bus error on the source address */ + kEDMA_ScatterGatherErrorFlag = DMA_ES_SGE_MASK, /*!< Error on the Scatter/Gather address, not 32byte aligned. */ + kEDMA_NbytesErrorFlag = DMA_ES_NCE_MASK, /*!< NBYTES/CITER configuration error */ + kEDMA_DestinationOffsetErrorFlag = DMA_ES_DOE_MASK, /*!< Destination offset not aligned with destination size */ + kEDMA_DestinationAddressErrorFlag = DMA_ES_DAE_MASK, /*!< Destination address not aligned with destination size */ + kEDMA_SourceOffsetErrorFlag = DMA_ES_SOE_MASK, /*!< Source offset not aligned with source size */ + kEDMA_SourceAddressErrorFlag = DMA_ES_SAE_MASK, /*!< Source address not aligned with source size*/ + kEDMA_ErrorChannelFlag = DMA_ES_ERRCHN_MASK, /*!< Error channel number of the cancelled channel number */ + kEDMA_ChannelPriorityErrorFlag = DMA_ES_CPE_MASK, /*!< Channel priority is not unique. */ + kEDMA_TransferCanceledFlag = DMA_ES_ECX_MASK, /*!< Transfer cancelled */ +#if defined(FSL_FEATURE_EDMA_CHANNEL_GROUP_COUNT) && FSL_FEATURE_EDMA_CHANNEL_GROUP_COUNT > 1 + kEDMA_GroupPriorityErrorFlag = DMA_ES_GPE_MASK, /*!< Group priority is not unique. */ +#endif + kEDMA_ValidFlag = DMA_ES_VLD_MASK, /*!< No error occurred, this bit is 0. Otherwise, it is 1. */ +}; + +/*! @brief eDMA interrupt source */ +typedef enum _edma_interrupt_enable +{ + kEDMA_ErrorInterruptEnable = 0x1U, /*!< Enable interrupt while channel error occurs. */ + kEDMA_MajorInterruptEnable = DMA_CSR_INTMAJOR_MASK, /*!< Enable interrupt while major count exhausted. */ + kEDMA_HalfInterruptEnable = DMA_CSR_INTHALF_MASK, /*!< Enable interrupt while major count to half value. */ +} edma_interrupt_enable_t; + +/*! @brief eDMA transfer type */ +typedef enum _edma_transfer_type +{ + kEDMA_MemoryToMemory = 0x0U, /*!< Transfer from memory to memory */ + kEDMA_PeripheralToMemory, /*!< Transfer from peripheral to memory */ + kEDMA_MemoryToPeripheral, /*!< Transfer from memory to peripheral */ +} edma_transfer_type_t; + +/*! @brief eDMA transfer status */ +enum _edma_transfer_status +{ + kStatus_EDMA_QueueFull = MAKE_STATUS(kStatusGroup_EDMA, 0), /*!< TCD queue is full. */ + kStatus_EDMA_Busy = MAKE_STATUS(kStatusGroup_EDMA, 1), /*!< Channel is busy and can't handle the + transfer request. */ +}; + +/*! @brief eDMA global configuration structure.*/ +typedef struct _edma_config +{ + bool enableContinuousLinkMode; /*!< Enable (true) continuous link mode. Upon minor loop completion, the channel + activates again if that channel has a minor loop channel link enabled and + the link channel is itself. */ + bool enableHaltOnError; /*!< Enable (true) transfer halt on error. Any error causes the HALT bit to set. + Subsequently, all service requests are ignored until the HALT bit is cleared.*/ + bool enableRoundRobinArbitration; /*!< Enable (true) round robin channel arbitration method or fixed priority + arbitration is used for channel selection */ + bool enableDebugMode; /*!< Enable(true) eDMA debug mode. When in debug mode, the eDMA stalls the start of + a new channel. Executing channels are allowed to complete. */ +} edma_config_t; + +/*! + * @brief eDMA transfer configuration + * + * This structure configures the source/destination transfer attribute. + */ +typedef struct _edma_transfer_config +{ + uint32_t srcAddr; /*!< Source data address. */ + uint32_t destAddr; /*!< Destination data address. */ + edma_transfer_size_t srcTransferSize; /*!< Source data transfer size. */ + edma_transfer_size_t destTransferSize; /*!< Destination data transfer size. */ + int16_t srcOffset; /*!< Sign-extended offset applied to the current source address to + form the next-state value as each source read is completed. */ + int16_t destOffset; /*!< Sign-extended offset applied to the current destination address to + form the next-state value as each destination write is completed. */ + uint32_t minorLoopBytes; /*!< Bytes to transfer in a minor loop*/ + uint32_t majorLoopCounts; /*!< Major loop iteration count. */ +} edma_transfer_config_t; + +/*! @brief eDMA channel priority configuration */ +typedef struct _edma_channel_Preemption_config +{ + bool enableChannelPreemption; /*!< If true: a channel can be suspended by other channel with higher priority */ + bool enablePreemptAbility; /*!< If true: a channel can suspend other channel with low priority */ + uint8_t channelPriority; /*!< Channel priority */ +} edma_channel_Preemption_config_t; + +/*! @brief eDMA minor offset configuration */ +typedef struct _edma_minor_offset_config +{ + bool enableSrcMinorOffset; /*!< Enable(true) or Disable(false) source minor loop offset. */ + bool enableDestMinorOffset; /*!< Enable(true) or Disable(false) destination minor loop offset. */ + uint32_t minorOffset; /*!< Offset for a minor loop mapping. */ +} edma_minor_offset_config_t; + +/*! + * @brief eDMA TCD. + * + * This structure is same as TCD register which is described in reference manual, + * and is used to configure the scatter/gather feature as a next hardware TCD. + */ +typedef struct _edma_tcd +{ + __IO uint32_t SADDR; /*!< SADDR register, used to save source address */ + __IO uint16_t SOFF; /*!< SOFF register, save offset bytes every transfer */ + __IO uint16_t ATTR; /*!< ATTR register, source/destination transfer size and modulo */ + __IO uint32_t NBYTES; /*!< Nbytes register, minor loop length in bytes */ + __IO uint32_t SLAST; /*!< SLAST register */ + __IO uint32_t DADDR; /*!< DADDR register, used for destination address */ + __IO uint16_t DOFF; /*!< DOFF register, used for destination offset */ + __IO uint16_t CITER; /*!< CITER register, current minor loop numbers, for unfinished minor loop.*/ + __IO uint32_t DLAST_SGA; /*!< DLASTSGA register, next stcd address used in scatter-gather mode */ + __IO uint16_t CSR; /*!< CSR register, for TCD control status */ + __IO uint16_t BITER; /*!< BITER register, begin minor loop count. */ +} edma_tcd_t; + +/*! @brief Callback for eDMA */ +struct _edma_handle; + +/*! @brief Define callback function for eDMA. + * + * This callback function is called in the EDMA interrupt handle. + * In normal mode, run into callback function means the transfer users need is done. + * In scatter gather mode, run into callback function means a transfer control block (tcd) is finished. Not + * all transfer finished, users can get the finished tcd numbers using interface EDMA_GetUnusedTCDNumber. + * + * @param handle EDMA handle pointer, users shall not touch the values inside. + * @param userData The callback user paramter pointer. Users can use this paramter to involve things users need to + * change in EDMA callback function. + * @param transferDone If the current loaded transfer done. In normal mode it means if all transfer done. In scatter + * gather mode, this paramter shows is the current transfer block in EDMA regsiter is done. As the + * load of core is different, it will be different if the new tcd loaded into EDMA registers while + * this callback called. If true, it always means new tcd still not loaded into registers, while + * false means new tcd already loaded into registers. + * @param tcds How many tcds are done from the last callback. This parameter only used in scatter gather mode. It + * tells user how many tcds are finished between the last callback and this. + */ +typedef void (*edma_callback)(struct _edma_handle *handle, void *userData, bool transferDone, uint32_t tcds); + +/*! @brief eDMA transfer handle structure */ +typedef struct _edma_handle +{ + edma_callback callback; /*!< Callback function for major count exhausted. */ + void *userData; /*!< Callback function parameter. */ + DMA_Type *base; /*!< eDMA peripheral base address. */ + edma_tcd_t *tcdPool; /*!< Pointer to memory stored TCDs. */ + uint8_t channel; /*!< eDMA channel number. */ + volatile int8_t header; /*!< The first TCD index. Should point to the next TCD to be loaded into the eDMA engine. */ + volatile int8_t tail; /*!< The last TCD index. Should point to the next TCD to be stored into the memory pool. */ + volatile int8_t tcdUsed; /*!< The number of used TCD slots. Should reflect the number of TCDs can be used/loaded in + the memory. */ + volatile int8_t tcdSize; /*!< The total number of TCD slots in the queue. */ + uint8_t flags; /*!< The status of the current channel. */ +} edma_handle_t; + +/******************************************************************************* + * APIs + ******************************************************************************/ +#if defined(__cplusplus) +extern "C" { +#endif /* __cplusplus */ + +/*! + * @name eDMA initialization and de-initialization + * @{ + */ + +/*! + * @brief Initializes the eDMA peripheral. + * + * This function ungates the eDMA clock and configures the eDMA peripheral according + * to the configuration structure. + * + * @param base eDMA peripheral base address. + * @param config A pointer to the configuration structure, see "edma_config_t". + * @note This function enables the minor loop map feature. + */ +void EDMA_Init(DMA_Type *base, const edma_config_t *config); + +/*! + * @brief Deinitializes the eDMA peripheral. + * + * This function gates the eDMA clock. + * + * @param base eDMA peripheral base address. + */ +void EDMA_Deinit(DMA_Type *base); + +/*! + * @brief Push content of TCD structure into hardware TCD register. + * + * @param base EDMA peripheral base address. + * @param channel EDMA channel number. + * @param tcd Point to TCD structure. + */ +void EDMA_InstallTCD(DMA_Type *base, uint32_t channel, edma_tcd_t *tcd); + +/*! + * @brief Gets the eDMA default configuration structure. + * + * This function sets the configuration structure to default values. + * The default configuration is set to the following values. + * @code + * config.enableContinuousLinkMode = false; + * config.enableHaltOnError = true; + * config.enableRoundRobinArbitration = false; + * config.enableDebugMode = false; + * @endcode + * + * @param config A pointer to the eDMA configuration structure. + */ +void EDMA_GetDefaultConfig(edma_config_t *config); + +/* @} */ +/*! + * @name eDMA Channel Operation + * @{ + */ + +/*! + * @brief Sets all TCD registers to default values. + * + * This function sets TCD registers for this channel to default values. + * + * @param base eDMA peripheral base address. + * @param channel eDMA channel number. + * @note This function must not be called while the channel transfer is ongoing + * or it causes unpredictable results. + * @note This function enables the auto stop request feature. + */ +void EDMA_ResetChannel(DMA_Type *base, uint32_t channel); + +/*! + * @brief Configures the eDMA transfer attribute. + * + * This function configures the transfer attribute, including source address, destination address, + * transfer size, address offset, and so on. It also configures the scatter gather feature if the + * user supplies the TCD address. + * Example: + * @code + * edma_transfer_t config; + * edma_tcd_t tcd; + * config.srcAddr = ..; + * config.destAddr = ..; + * ... + * EDMA_SetTransferConfig(DMA0, channel, &config, &stcd); + * @endcode + * + * @param base eDMA peripheral base address. + * @param channel eDMA channel number. + * @param config Pointer to eDMA transfer configuration structure. + * @param nextTcd Point to TCD structure. It can be NULL if users + * do not want to enable scatter/gather feature. + * @note If nextTcd is not NULL, it means scatter gather feature is enabled + * and DREQ bit is cleared in the previous transfer configuration, which + * is set in the eDMA_ResetChannel. + */ +void EDMA_SetTransferConfig(DMA_Type *base, + uint32_t channel, + const edma_transfer_config_t *config, + edma_tcd_t *nextTcd); + +/*! + * @brief Configures the eDMA minor offset feature. + * + * The minor offset means that the signed-extended value is added to the source address or destination + * address after each minor loop. + * + * @param base eDMA peripheral base address. + * @param channel eDMA channel number. + * @param config A pointer to the minor offset configuration structure. + */ +void EDMA_SetMinorOffsetConfig(DMA_Type *base, uint32_t channel, const edma_minor_offset_config_t *config); + +/*! + * @brief Configures the eDMA channel preemption feature. + * + * This function configures the channel preemption attribute and the priority of the channel. + * + * @param base eDMA peripheral base address. + * @param channel eDMA channel number + * @param config A pointer to the channel preemption configuration structure. + */ +static inline void EDMA_SetChannelPreemptionConfig(DMA_Type *base, + uint32_t channel, + const edma_channel_Preemption_config_t *config) +{ + assert(channel < FSL_FEATURE_EDMA_MODULE_CHANNEL); + assert(config != NULL); + + DMA_DCHPRIn(base, channel) = + (DMA_DCHPRI0_DPA(!config->enablePreemptAbility) | DMA_DCHPRI0_ECP(config->enableChannelPreemption) | + DMA_DCHPRI0_CHPRI(config->channelPriority)); +} + +/*! + * @brief Sets the channel link for the eDMA transfer. + * + * This function configures either the minor link or the major link mode. The minor link means that the channel link is + * triggered every time CITER decreases by 1. The major link means that the channel link is triggered when the CITER is + * exhausted. + * + * @param base eDMA peripheral base address. + * @param channel eDMA channel number. + * @param type A channel link type, which can be one of the following: + * @arg kEDMA_LinkNone + * @arg kEDMA_MinorLink + * @arg kEDMA_MajorLink + * @param linkedChannel The linked channel number. + * @note Users should ensure that DONE flag is cleared before calling this interface, or the configuration is invalid. + */ +void EDMA_SetChannelLink(DMA_Type *base, uint32_t channel, edma_channel_link_type_t type, uint32_t linkedChannel); + +/*! + * @brief Sets the bandwidth for the eDMA transfer. + * + * Because the eDMA processes the minor loop, it continuously generates read/write sequences + * until the minor count is exhausted. The bandwidth forces the eDMA to stall after the completion of + * each read/write access to control the bus request bandwidth seen by the crossbar switch. + * + * @param base eDMA peripheral base address. + * @param channel eDMA channel number. + * @param bandWidth A bandwidth setting, which can be one of the following: + * @arg kEDMABandwidthStallNone + * @arg kEDMABandwidthStall4Cycle + * @arg kEDMABandwidthStall8Cycle + */ +void EDMA_SetBandWidth(DMA_Type *base, uint32_t channel, edma_bandwidth_t bandWidth); + +/*! + * @brief Sets the source modulo and the destination modulo for the eDMA transfer. + * + * This function defines a specific address range specified to be the value after (SADDR + SOFF)/(DADDR + DOFF) + * calculation is performed or the original register value. It provides the ability to implement a circular data + * queue easily. + * + * @param base eDMA peripheral base address. + * @param channel eDMA channel number. + * @param srcModulo A source modulo value. + * @param destModulo A destination modulo value. + */ +void EDMA_SetModulo(DMA_Type *base, uint32_t channel, edma_modulo_t srcModulo, edma_modulo_t destModulo); + +#if defined(FSL_FEATURE_EDMA_ASYNCHRO_REQUEST_CHANNEL_COUNT) && FSL_FEATURE_EDMA_ASYNCHRO_REQUEST_CHANNEL_COUNT +/*! + * @brief Enables an async request for the eDMA transfer. + * + * @param base eDMA peripheral base address. + * @param channel eDMA channel number. + * @param enable The command to enable (true) or disable (false). + */ +static inline void EDMA_EnableAsyncRequest(DMA_Type *base, uint32_t channel, bool enable) +{ + assert(channel < FSL_FEATURE_DMAMUX_MODULE_CHANNEL); + + base->EARS = (base->EARS & (~(1U << channel))) | ((uint32_t)enable << channel); +} +#endif /* FSL_FEATURE_EDMA_ASYNCHRO_REQUEST_CHANNEL_COUNT */ + +/*! + * @brief Enables an auto stop request for the eDMA transfer. + * + * If enabling the auto stop request, the eDMA hardware automatically disables the hardware channel request. + * + * @param base eDMA peripheral base address. + * @param channel eDMA channel number. + * @param enable The command to enable (true) or disable (false). + */ +static inline void EDMA_EnableAutoStopRequest(DMA_Type *base, uint32_t channel, bool enable) +{ + assert(channel < FSL_FEATURE_DMAMUX_MODULE_CHANNEL); + + base->TCD[channel].CSR = (base->TCD[channel].CSR & (~DMA_CSR_DREQ_MASK)) | DMA_CSR_DREQ(enable); +} + +/*! + * @brief Enables the interrupt source for the eDMA transfer. + * + * @param base eDMA peripheral base address. + * @param channel eDMA channel number. + * @param mask The mask of interrupt source to be set. Users need to use + * the defined edma_interrupt_enable_t type. + */ +void EDMA_EnableChannelInterrupts(DMA_Type *base, uint32_t channel, uint32_t mask); + +/*! + * @brief Disables the interrupt source for the eDMA transfer. + * + * @param base eDMA peripheral base address. + * @param channel eDMA channel number. + * @param mask The mask of the interrupt source to be set. Use + * the defined edma_interrupt_enable_t type. + */ +void EDMA_DisableChannelInterrupts(DMA_Type *base, uint32_t channel, uint32_t mask); + +/* @} */ +/*! + * @name eDMA TCD Operation + * @{ + */ + +/*! + * @brief Sets all fields to default values for the TCD structure. + * + * This function sets all fields for this TCD structure to default value. + * + * @param tcd Pointer to the TCD structure. + * @note This function enables the auto stop request feature. + */ +void EDMA_TcdReset(edma_tcd_t *tcd); + +/*! + * @brief Configures the eDMA TCD transfer attribute. + * + * The TCD is a transfer control descriptor. The content of the TCD is the same as the hardware TCD registers. + * The STCD is used in the scatter-gather mode. + * This function configures the TCD transfer attribute, including source address, destination address, + * transfer size, address offset, and so on. It also configures the scatter gather feature if the + * user supplies the next TCD address. + * Example: + * @code + * edma_transfer_t config = { + * ... + * } + * edma_tcd_t tcd __aligned(32); + * edma_tcd_t nextTcd __aligned(32); + * EDMA_TcdSetTransferConfig(&tcd, &config, &nextTcd); + * @endcode + * + * @param tcd Pointer to the TCD structure. + * @param config Pointer to eDMA transfer configuration structure. + * @param nextTcd Pointer to the next TCD structure. It can be NULL if users + * do not want to enable scatter/gather feature. + * @note TCD address should be 32 bytes aligned or it causes an eDMA error. + * @note If the nextTcd is not NULL, the scatter gather feature is enabled + * and DREQ bit is cleared in the previous transfer configuration, which + * is set in the EDMA_TcdReset. + */ +void EDMA_TcdSetTransferConfig(edma_tcd_t *tcd, const edma_transfer_config_t *config, edma_tcd_t *nextTcd); + +/*! + * @brief Configures the eDMA TCD minor offset feature. + * + * A minor offset is a signed-extended value added to the source address or a destination + * address after each minor loop. + * + * @param tcd A point to the TCD structure. + * @param config A pointer to the minor offset configuration structure. + */ +void EDMA_TcdSetMinorOffsetConfig(edma_tcd_t *tcd, const edma_minor_offset_config_t *config); + +/*! + * @brief Sets the channel link for the eDMA TCD. + * + * This function configures either a minor link or a major link. The minor link means the channel link is + * triggered every time CITER decreases by 1. The major link means that the channel link is triggered when the CITER is + * exhausted. + * + * @note Users should ensure that DONE flag is cleared before calling this interface, or the configuration is invalid. + * @param tcd Point to the TCD structure. + * @param type Channel link type, it can be one of: + * @arg kEDMA_LinkNone + * @arg kEDMA_MinorLink + * @arg kEDMA_MajorLink + * @param linkedChannel The linked channel number. + */ +void EDMA_TcdSetChannelLink(edma_tcd_t *tcd, edma_channel_link_type_t type, uint32_t linkedChannel); + +/*! + * @brief Sets the bandwidth for the eDMA TCD. + * + * Because the eDMA processes the minor loop, it continuously generates read/write sequences + * until the minor count is exhausted. The bandwidth forces the eDMA to stall after the completion of + * each read/write access to control the bus request bandwidth seen by the crossbar switch. + * @param tcd A pointer to the TCD structure. + * @param bandWidth A bandwidth setting, which can be one of the following: + * @arg kEDMABandwidthStallNone + * @arg kEDMABandwidthStall4Cycle + * @arg kEDMABandwidthStall8Cycle + */ +static inline void EDMA_TcdSetBandWidth(edma_tcd_t *tcd, edma_bandwidth_t bandWidth) +{ + assert(tcd != NULL); + assert(((uint32_t)tcd & 0x1FU) == 0); + + tcd->CSR = (tcd->CSR & (~DMA_CSR_BWC_MASK)) | DMA_CSR_BWC(bandWidth); +} + +/*! + * @brief Sets the source modulo and the destination modulo for the eDMA TCD. + * + * This function defines a specific address range specified to be the value after (SADDR + SOFF)/(DADDR + DOFF) + * calculation is performed or the original register value. It provides the ability to implement a circular data + * queue easily. + * + * @param tcd A pointer to the TCD structure. + * @param srcModulo A source modulo value. + * @param destModulo A destination modulo value. + */ +void EDMA_TcdSetModulo(edma_tcd_t *tcd, edma_modulo_t srcModulo, edma_modulo_t destModulo); + +/*! + * @brief Sets the auto stop request for the eDMA TCD. + * + * If enabling the auto stop request, the eDMA hardware automatically disables the hardware channel request. + * + * @param tcd A pointer to the TCD structure. + * @param enable The command to enable (true) or disable (false). + */ +static inline void EDMA_TcdEnableAutoStopRequest(edma_tcd_t *tcd, bool enable) +{ + assert(tcd != NULL); + assert(((uint32_t)tcd & 0x1FU) == 0); + + tcd->CSR = (tcd->CSR & (~DMA_CSR_DREQ_MASK)) | DMA_CSR_DREQ(enable); +} + +/*! + * @brief Enables the interrupt source for the eDMA TCD. + * + * @param tcd Point to the TCD structure. + * @param mask The mask of interrupt source to be set. Users need to use + * the defined edma_interrupt_enable_t type. + */ +void EDMA_TcdEnableInterrupts(edma_tcd_t *tcd, uint32_t mask); + +/*! + * @brief Disables the interrupt source for the eDMA TCD. + * + * @param tcd Point to the TCD structure. + * @param mask The mask of interrupt source to be set. Users need to use + * the defined edma_interrupt_enable_t type. + */ +void EDMA_TcdDisableInterrupts(edma_tcd_t *tcd, uint32_t mask); + +/*! @} */ +/*! + * @name eDMA Channel Transfer Operation + * @{ + */ + +/*! + * @brief Enables the eDMA hardware channel request. + * + * This function enables the hardware channel request. + * + * @param base eDMA peripheral base address. + * @param channel eDMA channel number. + */ +static inline void EDMA_EnableChannelRequest(DMA_Type *base, uint32_t channel) +{ + assert(channel < FSL_FEATURE_DMAMUX_MODULE_CHANNEL); + + base->SERQ = DMA_SERQ_SERQ(channel); +} + +/*! + * @brief Disables the eDMA hardware channel request. + * + * This function disables the hardware channel request. + * + * @param base eDMA peripheral base address. + * @param channel eDMA channel number. + */ +static inline void EDMA_DisableChannelRequest(DMA_Type *base, uint32_t channel) +{ + assert(channel < FSL_FEATURE_DMAMUX_MODULE_CHANNEL); + + base->CERQ = DMA_CERQ_CERQ(channel); +} + +/*! + * @brief Starts the eDMA transfer by using the software trigger. + * + * This function starts a minor loop transfer. + * + * @param base eDMA peripheral base address. + * @param channel eDMA channel number. + */ +static inline void EDMA_TriggerChannelStart(DMA_Type *base, uint32_t channel) +{ + assert(channel < FSL_FEATURE_DMAMUX_MODULE_CHANNEL); + + base->SSRT = DMA_SSRT_SSRT(channel); +} + +/*! @} */ +/*! + * @name eDMA Channel Status Operation + * @{ + */ + +/*! + * @brief Gets the remaining major loop count from the eDMA current channel TCD. + * + * This function checks the TCD (Task Control Descriptor) status for a specified + * eDMA channel and returns the number of major loop count that has not finished. + * + * @param base eDMA peripheral base address. + * @param channel eDMA channel number. + * @return Major loop count which has not been transferred yet for the current TCD. + * @note 1. This function can only be used to get unfinished major loop count of transfer without + * the next TCD, or it might be inaccuracy. + * 2. The unfinished/remaining transfer bytes cannot be obtained directly from registers while + * the channel is running. + * Because to calculate the remaining bytes, the initial NBYTES configured in DMA_TCDn_NBYTES_MLNO + * register is needed while the eDMA IP does not support getting it while a channel is active. + * In another word, the NBYTES value reading is always the actual (decrementing) NBYTES value the dma_engine + * is working with while a channel is running. + * Consequently, to get the remaining transfer bytes, a software-saved initial value of NBYTES (for example + * copied before enabling the channel) is needed. The formula to calculate it is shown below: + * RemainingBytes = RemainingMajorLoopCount * NBYTES(initially configured) + */ +uint32_t EDMA_GetRemainingMajorLoopCount(DMA_Type *base, uint32_t channel); + +/*! + * @brief Gets the eDMA channel error status flags. + * + * @param base eDMA peripheral base address. + * @return The mask of error status flags. Users need to use the +* _edma_error_status_flags type to decode the return variables. + */ +static inline uint32_t EDMA_GetErrorStatusFlags(DMA_Type *base) +{ + return base->ES; +} + +/*! + * @brief Gets the eDMA channel status flags. + * + * @param base eDMA peripheral base address. + * @param channel eDMA channel number. + * @return The mask of channel status flags. Users need to use the + * _edma_channel_status_flags type to decode the return variables. + */ +uint32_t EDMA_GetChannelStatusFlags(DMA_Type *base, uint32_t channel); + +/*! + * @brief Clears the eDMA channel status flags. + * + * @param base eDMA peripheral base address. + * @param channel eDMA channel number. + * @param mask The mask of channel status to be cleared. Users need to use + * the defined _edma_channel_status_flags type. + */ +void EDMA_ClearChannelStatusFlags(DMA_Type *base, uint32_t channel, uint32_t mask); + +/*! @} */ +/*! + * @name eDMA Transactional Operation + */ + +/*! + * @brief Creates the eDMA handle. + * + * This function is called if using the transactional API for eDMA. This function + * initializes the internal state of the eDMA handle. + * + * @param handle eDMA handle pointer. The eDMA handle stores callback function and + * parameters. + * @param base eDMA peripheral base address. + * @param channel eDMA channel number. + */ +void EDMA_CreateHandle(edma_handle_t *handle, DMA_Type *base, uint32_t channel); + +/*! + * @brief Installs the TCDs memory pool into the eDMA handle. + * + * This function is called after the EDMA_CreateHandle to use scatter/gather feature. This function shall only be used + * while users need to use scatter gather mode. Scatter gather mode enables EDMA to load a new transfer control block + * (tcd) in hardware, and automatically reconfigure that DMA channel for a new transfer. + * Users need to preapre tcd memory and also configure tcds using interface EDMA_SubmitTransfer. + * + * @param handle eDMA handle pointer. + * @param tcdPool A memory pool to store TCDs. It must be 32 bytes aligned. + * @param tcdSize The number of TCD slots. + */ +void EDMA_InstallTCDMemory(edma_handle_t *handle, edma_tcd_t *tcdPool, uint32_t tcdSize); + +/*! + * @brief Installs a callback function for the eDMA transfer. + * + * This callback is called in the eDMA IRQ handler. Use the callback to do something after + * the current major loop transfer completes. This function will be called every time one tcd finished transfer. + * + * @param handle eDMA handle pointer. + * @param callback eDMA callback function pointer. + * @param userData A parameter for the callback function. + */ +void EDMA_SetCallback(edma_handle_t *handle, edma_callback callback, void *userData); + +/*! + * @brief Prepares the eDMA transfer structure. + * + * This function prepares the transfer configuration structure according to the user input. + * + * @param config The user configuration structure of type edma_transfer_t. + * @param srcAddr eDMA transfer source address. + * @param srcWidth eDMA transfer source address width(bytes). + * @param destAddr eDMA transfer destination address. + * @param destWidth eDMA transfer destination address width(bytes). + * @param bytesEachRequest eDMA transfer bytes per channel request. + * @param transferBytes eDMA transfer bytes to be transferred. + * @param type eDMA transfer type. + * @note The data address and the data width must be consistent. For example, if the SRC + * is 4 bytes, the source address must be 4 bytes aligned, or it results in + * source address error (SAE). + */ +void EDMA_PrepareTransfer(edma_transfer_config_t *config, + void *srcAddr, + uint32_t srcWidth, + void *destAddr, + uint32_t destWidth, + uint32_t bytesEachRequest, + uint32_t transferBytes, + edma_transfer_type_t type); + +/*! + * @brief Submits the eDMA transfer request. + * + * This function submits the eDMA transfer request according to the transfer configuration structure. + * In scatter gather mode, call this function will add a configured tcd to the circular list of tcd pool. + * The tcd pools is setup by call function EDMA_InstallTCDMemory before. + * + * @param handle eDMA handle pointer. + * @param config Pointer to eDMA transfer configuration structure. + * @retval kStatus_EDMA_Success It means submit transfer request succeed. + * @retval kStatus_EDMA_QueueFull It means TCD queue is full. Submit transfer request is not allowed. + * @retval kStatus_EDMA_Busy It means the given channel is busy, need to submit request later. + */ +status_t EDMA_SubmitTransfer(edma_handle_t *handle, const edma_transfer_config_t *config); + +/*! + * @brief eDMA starts transfer. + * + * This function enables the channel request. Users can call this function after submitting the transfer request + * or before submitting the transfer request. + * + * @param handle eDMA handle pointer. + */ +void EDMA_StartTransfer(edma_handle_t *handle); + +/*! + * @brief eDMA stops transfer. + * + * This function disables the channel request to pause the transfer. Users can call EDMA_StartTransfer() + * again to resume the transfer. + * + * @param handle eDMA handle pointer. + */ +void EDMA_StopTransfer(edma_handle_t *handle); + +/*! + * @brief eDMA aborts transfer. + * + * This function disables the channel request and clear transfer status bits. + * Users can submit another transfer after calling this API. + * + * @param handle DMA handle pointer. + */ +void EDMA_AbortTransfer(edma_handle_t *handle); + +/*! + * @brief Get unused TCD slot number. + * + * This function gets current tcd index which is run. If the TCD pool pointer is NULL, it will return 0. + * + * @param handle DMA handle pointer. + * @return The unused tcd slot number. + */ +static inline uint32_t EDMA_GetUnusedTCDNumber(edma_handle_t *handle) +{ + return (handle->tcdSize - handle->tcdUsed); +} + +/*! + * @brief Get the next tcd address. + * + * This function gets the next tcd address. If this is last TCD, return 0. + * + * @param handle DMA handle pointer. + * @return The next TCD address. + */ +static inline uint32_t EDMA_GetNextTCDAddress(edma_handle_t *handle) +{ + return (handle->base->TCD[handle->channel].DLAST_SGA); +} + +/*! + * @brief eDMA IRQ handler for the current major loop transfer completion. + * + * This function clears the channel major interrupt flag and calls + * the callback function if it is not NULL. + * + * Note: + * For the case using TCD queue, when the major iteration count is exhausted, additional operations are performed. + * These include the final address adjustments and reloading of the BITER field into the CITER. + * Assertion of an optional interrupt request also occurs at this time, as does a possible fetch of a new TCD from + * memory using the scatter/gather address pointer included in the descriptor (if scatter/gather is enabled). + * + * For instance, when the time interrupt of TCD[0] happens, the TCD[1] has already been loaded into the eDMA engine. + * As sga and sga_index are calculated based on the DLAST_SGA bitfield lies in the TCD_CSR register, the sga_index + * in this case should be 2 (DLAST_SGA of TCD[1] stores the address of TCD[2]). Thus, the "tcdUsed" updated should be + * (tcdUsed - 2U) which indicates the number of TCDs can be loaded in the memory pool (because TCD[0] and TCD[1] have + * been loaded into the eDMA engine at this point already.). + * + * For the last two continuous ISRs in a scatter/gather process, they both load the last TCD (The last ISR does not + * load a new TCD) from the memory pool to the eDMA engine when major loop completes. + * Therefore, ensure that the header and tcdUsed updated are identical for them. + * tcdUsed are both 0 in this case as no TCD to be loaded. + * + * See the "eDMA basic data flow" in the eDMA Functional description section of the Reference Manual for + * further details. + * + * @param handle eDMA handle pointer. + */ +void EDMA_HandleIRQ(edma_handle_t *handle); + +/* @} */ + +#if defined(__cplusplus) +} +#endif /* __cplusplus */ + +/* @} */ + +#endif /*_FSL_EDMA_H_*/ diff --git a/drivers/fsl_gpio.c b/drivers/fsl_gpio.c new file mode 100644 index 0000000..93f09bb --- /dev/null +++ b/drivers/fsl_gpio.c @@ -0,0 +1,235 @@ +/* + * The Clear BSD License + * Copyright (c) 2015, 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: + * + * o Redistributions of source code must retain the above copyright notice, this list + * of conditions and the following disclaimer. + * + * o 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. + * + * o 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. + */ + +#include "fsl_gpio.h" + +/* Component ID definition, used by tools. */ +#ifndef FSL_COMPONENT_ID +#define FSL_COMPONENT_ID "platform.drivers.gpio" +#endif + + +/******************************************************************************* + * Variables + ******************************************************************************/ + +#if !(defined(FSL_FEATURE_GPIO_HAS_NO_PORTINTERRUPT) && FSL_FEATURE_GPIO_HAS_NO_PORTINTERRUPT) +static PORT_Type *const s_portBases[] = PORT_BASE_PTRS; +static GPIO_Type *const s_gpioBases[] = GPIO_BASE_PTRS; +#endif + +#if defined(FSL_FEATURE_SOC_FGPIO_COUNT) && FSL_FEATURE_SOC_FGPIO_COUNT + +#if defined(FSL_FEATURE_PCC_HAS_FGPIO_CLOCK_GATE_CONTROL) && FSL_FEATURE_PCC_HAS_FGPIO_CLOCK_GATE_CONTROL + +#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) +/*! @brief Array to map FGPIO instance number to clock name. */ +static const clock_ip_name_t s_fgpioClockName[] = FGPIO_CLOCKS; +#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */ + +#endif /* FSL_FEATURE_PCC_HAS_FGPIO_CLOCK_GATE_CONTROL */ + +#endif /* FSL_FEATURE_SOC_FGPIO_COUNT */ + +/******************************************************************************* +* Prototypes +******************************************************************************/ +#if !(defined(FSL_FEATURE_GPIO_HAS_NO_PORTINTERRUPT) && FSL_FEATURE_GPIO_HAS_NO_PORTINTERRUPT) +/*! +* @brief Gets the GPIO instance according to the GPIO base +* +* @param base GPIO peripheral base pointer(PTA, PTB, PTC, etc.) +* @retval GPIO instance +*/ +static uint32_t GPIO_GetInstance(GPIO_Type *base); +#endif +/******************************************************************************* + * Code + ******************************************************************************/ +#if !(defined(FSL_FEATURE_GPIO_HAS_NO_PORTINTERRUPT) && FSL_FEATURE_GPIO_HAS_NO_PORTINTERRUPT) +static uint32_t GPIO_GetInstance(GPIO_Type *base) +{ + uint32_t instance; + + /* Find the instance index from base address mappings. */ + for (instance = 0; instance < ARRAY_SIZE(s_gpioBases); instance++) + { + if (s_gpioBases[instance] == base) + { + break; + } + } + + assert(instance < ARRAY_SIZE(s_gpioBases)); + + return instance; +} +#endif +void GPIO_PinInit(GPIO_Type *base, uint32_t pin, const gpio_pin_config_t *config) +{ + assert(config); + + if (config->pinDirection == kGPIO_DigitalInput) + { + base->PDDR &= ~(1U << pin); + } + else + { + GPIO_WritePinOutput(base, pin, config->outputLogic); + base->PDDR |= (1U << pin); + } +} + +#if !(defined(FSL_FEATURE_GPIO_HAS_NO_PORTINTERRUPT) && FSL_FEATURE_GPIO_HAS_NO_PORTINTERRUPT) +uint32_t GPIO_PortGetInterruptFlags(GPIO_Type *base) +{ + uint8_t instance; + PORT_Type *portBase; + instance = GPIO_GetInstance(base); + portBase = s_portBases[instance]; + return portBase->ISFR; +} + +void GPIO_PortClearInterruptFlags(GPIO_Type *base, uint32_t mask) +{ + uint8_t instance; + PORT_Type *portBase; + instance = GPIO_GetInstance(base); + portBase = s_portBases[instance]; + portBase->ISFR = mask; +} +#endif + +#if defined(FSL_FEATURE_GPIO_HAS_ATTRIBUTE_CHECKER) && FSL_FEATURE_GPIO_HAS_ATTRIBUTE_CHECKER +void GPIO_CheckAttributeBytes(GPIO_Type *base, gpio_checker_attribute_t attribute) +{ + base->GACR = ((uint32_t)attribute << GPIO_GACR_ACB0_SHIFT) | ((uint32_t)attribute << GPIO_GACR_ACB1_SHIFT) | + ((uint32_t)attribute << GPIO_GACR_ACB2_SHIFT) | ((uint32_t)attribute << GPIO_GACR_ACB3_SHIFT); +} +#endif + +#if defined(FSL_FEATURE_SOC_FGPIO_COUNT) && FSL_FEATURE_SOC_FGPIO_COUNT + +/******************************************************************************* + * Variables + ******************************************************************************/ +#if !(defined(FSL_FEATURE_GPIO_HAS_NO_PORTINTERRUPT) && FSL_FEATURE_GPIO_HAS_NO_PORTINTERRUPT) +static FGPIO_Type *const s_fgpioBases[] = FGPIO_BASE_PTRS; +#endif +/******************************************************************************* +* Prototypes +******************************************************************************/ +#if !(defined(FSL_FEATURE_GPIO_HAS_NO_PORTINTERRUPT) && FSL_FEATURE_GPIO_HAS_NO_PORTINTERRUPT) +/*! +* @brief Gets the FGPIO instance according to the GPIO base +* +* @param base FGPIO peripheral base pointer(PTA, PTB, PTC, etc.) +* @retval FGPIO instance +*/ +static uint32_t FGPIO_GetInstance(FGPIO_Type *base); +#endif +/******************************************************************************* + * Code + ******************************************************************************/ +#if !(defined(FSL_FEATURE_GPIO_HAS_NO_PORTINTERRUPT) && FSL_FEATURE_GPIO_HAS_NO_PORTINTERRUPT) +static uint32_t FGPIO_GetInstance(FGPIO_Type *base) +{ + uint32_t instance; + + /* Find the instance index from base address mappings. */ + for (instance = 0; instance < ARRAY_SIZE(s_fgpioBases); instance++) + { + if (s_fgpioBases[instance] == base) + { + break; + } + } + + assert(instance < ARRAY_SIZE(s_fgpioBases)); + + return instance; +} +#endif +#if defined(FSL_FEATURE_PCC_HAS_FGPIO_CLOCK_GATE_CONTROL) && FSL_FEATURE_PCC_HAS_FGPIO_CLOCK_GATE_CONTROL +void FGPIO_PortInit(FGPIO_Type *base) +{ +#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) + /* Ungate FGPIO periphral clock */ + CLOCK_EnableClock(s_fgpioClockName[FGPIO_GetInstance(base)]); +#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */ +} +#endif /* FSL_FEATURE_PCC_HAS_FGPIO_CLOCK_GATE_CONTROL */ + +void FGPIO_PinInit(FGPIO_Type *base, uint32_t pin, const gpio_pin_config_t *config) +{ + assert(config); + + if (config->pinDirection == kGPIO_DigitalInput) + { + base->PDDR &= ~(1U << pin); + } + else + { + FGPIO_WritePinOutput(base, pin, config->outputLogic); + base->PDDR |= (1U << pin); + } +} +#if !(defined(FSL_FEATURE_GPIO_HAS_NO_PORTINTERRUPT) && FSL_FEATURE_GPIO_HAS_NO_PORTINTERRUPT) +uint32_t FGPIO_PortGetInterruptFlags(FGPIO_Type *base) +{ + uint8_t instance; + instance = FGPIO_GetInstance(base); + PORT_Type *portBase; + portBase = s_portBases[instance]; + return portBase->ISFR; +} + +void FGPIO_PortClearInterruptFlags(FGPIO_Type *base, uint32_t mask) +{ + uint8_t instance; + instance = FGPIO_GetInstance(base); + PORT_Type *portBase; + portBase = s_portBases[instance]; + portBase->ISFR = mask; +} +#endif +#if defined(FSL_FEATURE_FGPIO_HAS_ATTRIBUTE_CHECKER) && FSL_FEATURE_FGPIO_HAS_ATTRIBUTE_CHECKER +void FGPIO_CheckAttributeBytes(FGPIO_Type *base, gpio_checker_attribute_t attribute) +{ + base->GACR = (attribute << FGPIO_GACR_ACB0_SHIFT) | (attribute << FGPIO_GACR_ACB1_SHIFT) | + (attribute << FGPIO_GACR_ACB2_SHIFT) | (attribute << FGPIO_GACR_ACB3_SHIFT); +} +#endif + +#endif /* FSL_FEATURE_SOC_FGPIO_COUNT */ diff --git a/drivers/fsl_gpio.h b/drivers/fsl_gpio.h new file mode 100644 index 0000000..794b472 --- /dev/null +++ b/drivers/fsl_gpio.h @@ -0,0 +1,594 @@ +/* + * The Clear BSD License + * Copyright (c) 2015, 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: + * + * o Redistributions of source code must retain the above copyright notice, this list + * of conditions and the following disclaimer. + * + * o 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. + * + * o 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_GPIO_H_ +#define _FSL_GPIO_H_ + +#include "fsl_common.h" + +/*! + * @addtogroup gpio + * @{ + */ + +/******************************************************************************* + * Definitions + ******************************************************************************/ + +/*! @name Driver version */ +/*@{*/ +/*! @brief GPIO driver version 2.2.1. */ +#define FSL_GPIO_DRIVER_VERSION (MAKE_VERSION(2, 2, 1)) +/*@}*/ + +/*! @brief GPIO direction definition */ +typedef enum _gpio_pin_direction +{ + kGPIO_DigitalInput = 0U, /*!< Set current pin as digital input*/ + kGPIO_DigitalOutput = 1U, /*!< Set current pin as digital output*/ +} gpio_pin_direction_t; + +#if defined(FSL_FEATURE_GPIO_HAS_ATTRIBUTE_CHECKER) && FSL_FEATURE_GPIO_HAS_ATTRIBUTE_CHECKER +/*! @brief GPIO checker attribute */ +typedef enum _gpio_checker_attribute +{ + kGPIO_UsernonsecureRWUsersecureRWPrivilegedsecureRW = + 0x00U, /*!< User nonsecure:Read+Write; User Secure:Read+Write; Privileged Secure:Read+Write */ + kGPIO_UsernonsecureRUsersecureRWPrivilegedsecureRW = + 0x01U, /*!< User nonsecure:Read; User Secure:Read+Write; Privileged Secure:Read+Write */ + kGPIO_UsernonsecureNUsersecureRWPrivilegedsecureRW = + 0x02U, /*!< User nonsecure:None; User Secure:Read+Write; Privileged Secure:Read+Write */ + kGPIO_UsernonsecureRUsersecureRPrivilegedsecureRW = + 0x03U, /*!< User nonsecure:Read; User Secure:Read; Privileged Secure:Read+Write */ + kGPIO_UsernonsecureNUsersecureRPrivilegedsecureRW = + 0x04U, /*!< User nonsecure:None; User Secure:Read; Privileged Secure:Read+Write */ + kGPIO_UsernonsecureNUsersecureNPrivilegedsecureRW = + 0x05U, /*!< User nonsecure:None; User Secure:None; Privileged Secure:Read+Write */ + kGPIO_UsernonsecureNUsersecureNPrivilegedsecureR = + 0x06U, /*!< User nonsecure:None; User Secure:None; Privileged Secure:Read */ + kGPIO_UsernonsecureNUsersecureNPrivilegedsecureN = + 0x07U, /*!< User nonsecure:None; User Secure:None; Privileged Secure:None */ + kGPIO_IgnoreAttributeCheck = 0x80U, /*!< Ignores the attribute check */ +} gpio_checker_attribute_t; +#endif + +/*! + * @brief The GPIO pin configuration structure. + * + * Each pin can only be configured as either an output pin or an input pin at a time. + * If configured as an input pin, leave the outputConfig unused. + * Note that in some use cases, the corresponding port property should be configured in advance + * with the PORT_SetPinConfig(). + */ +typedef struct _gpio_pin_config +{ + gpio_pin_direction_t pinDirection; /*!< GPIO direction, input or output */ + /* Output configurations; ignore if configured as an input pin */ + uint8_t outputLogic; /*!< Set a default output logic, which has no use in input */ +} gpio_pin_config_t; + +/*! @} */ + +/******************************************************************************* + * API + ******************************************************************************/ + +#if defined(__cplusplus) +extern "C" { +#endif + +/*! + * @addtogroup gpio_driver + * @{ + */ + +/*! @name GPIO Configuration */ +/*@{*/ + +/*! + * @brief Initializes a GPIO pin used by the board. + * + * To initialize the GPIO, define a pin configuration, as either input or output, in the user file. + * Then, call the GPIO_PinInit() function. + * + * This is an example to define an input pin or an output pin configuration. + * @code + * // Define a digital input pin configuration, + * gpio_pin_config_t config = + * { + * kGPIO_DigitalInput, + * 0, + * } + * //Define a digital output pin configuration, + * gpio_pin_config_t config = + * { + * kGPIO_DigitalOutput, + * 0, + * } + * @endcode + * + * @param base GPIO peripheral base pointer (GPIOA, GPIOB, GPIOC, and so on.) + * @param pin GPIO port pin number + * @param config GPIO pin configuration pointer + */ +void GPIO_PinInit(GPIO_Type *base, uint32_t pin, const gpio_pin_config_t *config); + +/*@}*/ + +/*! @name GPIO Output Operations */ +/*@{*/ + +/*! + * @brief Sets the output level of the multiple GPIO pins to the logic 1 or 0. + * + * @param base GPIO peripheral base pointer (GPIOA, GPIOB, GPIOC, and so on.) + * @param pin GPIO pin number + * @param output GPIO pin output logic level. + * - 0: corresponding pin output low-logic level. + * - 1: corresponding pin output high-logic level. + */ +static inline void GPIO_PinWrite(GPIO_Type *base, uint32_t pin, uint8_t output) +{ + if (output == 0U) + { + base->PCOR = 1U << pin; + } + else + { + base->PSOR = 1U << pin; + } +} + +/*! + * @brief Sets the output level of the multiple GPIO pins to the logic 1 or 0. + * @deprecated Do not use this function. It has been superceded by @ref GPIO_PinWrite. + */ +static inline void GPIO_WritePinOutput(GPIO_Type *base, uint32_t pin, uint8_t output) +{ + GPIO_PinWrite(base, pin, output); +} + +/*! + * @brief Sets the output level of the multiple GPIO pins to the logic 1. + * + * @param base GPIO peripheral base pointer (GPIOA, GPIOB, GPIOC, and so on.) + * @param mask GPIO pin number macro + */ +static inline void GPIO_PortSet(GPIO_Type *base, uint32_t mask) +{ + base->PSOR = mask; +} + +/*! + * @brief Sets the output level of the multiple GPIO pins to the logic 1. + * @deprecated Do not use this function. It has been superceded by @ref GPIO_PortSet. + */ +static inline void GPIO_SetPinsOutput(GPIO_Type *base, uint32_t mask) +{ + GPIO_PortSet(base, mask); +} + +/*! + * @brief Sets the output level of the multiple GPIO pins to the logic 0. + * + * @param base GPIO peripheral base pointer (GPIOA, GPIOB, GPIOC, and so on.) + * @param mask GPIO pin number macro + */ +static inline void GPIO_PortClear(GPIO_Type *base, uint32_t mask) +{ + base->PCOR = mask; +} + +/*! + * @brief Sets the output level of the multiple GPIO pins to the logic 0. + * @deprecated Do not use this function. It has been superceded by @ref GPIO_PortClear. + * + * @param base GPIO peripheral base pointer (GPIOA, GPIOB, GPIOC, and so on.) + * @param mask GPIO pin number macro + */ +static inline void GPIO_ClearPinsOutput(GPIO_Type *base, uint32_t mask) +{ + GPIO_PortClear(base, mask); +} + +/*! + * @brief Reverses the current output logic of the multiple GPIO pins. + * + * @param base GPIO peripheral base pointer (GPIOA, GPIOB, GPIOC, and so on.) + * @param mask GPIO pin number macro + */ +static inline void GPIO_PortToggle(GPIO_Type *base, uint32_t mask) +{ + base->PTOR = mask; +} + +/*! + * @brief Reverses the current output logic of the multiple GPIO pins. + * @deprecated Do not use this function. It has been superceded by @ref GPIO_PortToggle. + */ +static inline void GPIO_TogglePinsOutput(GPIO_Type *base, uint32_t mask) +{ + GPIO_PortToggle(base, mask); +} +/*@}*/ + +/*! @name GPIO Input Operations */ +/*@{*/ + +/*! + * @brief Reads the current input value of the GPIO port. + * + * @param base GPIO peripheral base pointer (GPIOA, GPIOB, GPIOC, and so on.) + * @param pin GPIO pin number + * @retval GPIO port input value + * - 0: corresponding pin input low-logic level. + * - 1: corresponding pin input high-logic level. + */ +static inline uint32_t GPIO_PinRead(GPIO_Type *base, uint32_t pin) +{ + return (((base->PDIR) >> pin) & 0x01U); +} + +/*! + * @brief Reads the current input value of the GPIO port. + * @deprecated Do not use this function. It has been superceded by @ref GPIO_PinRead. + */ +static inline uint32_t GPIO_ReadPinInput(GPIO_Type *base, uint32_t pin) +{ + return GPIO_PinRead(base, pin); +} + +/*@}*/ + +/*! @name GPIO Interrupt */ +/*@{*/ +#if !(defined(FSL_FEATURE_GPIO_HAS_NO_PORTINTERRUPT) && FSL_FEATURE_GPIO_HAS_NO_PORTINTERRUPT) + +/*! + * @brief Reads the GPIO port interrupt status flag. + * + * If a pin is configured to generate the DMA request, the corresponding flag + * is cleared automatically at the completion of the requested DMA transfer. + * Otherwise, the flag remains set until a logic one is written to that flag. + * If configured for a level sensitive interrupt that remains asserted, the flag + * is set again immediately. + * + * @param base GPIO peripheral base pointer (GPIOA, GPIOB, GPIOC, and so on.) + * @retval The current GPIO port interrupt status flag, for example, 0x00010001 means the + * pin 0 and 17 have the interrupt. + */ +uint32_t GPIO_PortGetInterruptFlags(GPIO_Type *base); + +/*! + * @brief Reads the GPIO port interrupt status flag. + * @deprecated Do not use this function. It has been superceded by @ref GPIO_PortGetInterruptFlags. + */ +static inline uint32_t GPIO_GetPinsInterruptFlags(GPIO_Type *base) +{ + return GPIO_PortGetInterruptFlags(base); +} + +/*! + * @brief Clears multiple GPIO pin interrupt status flags. + * + * @param base GPIO peripheral base pointer (GPIOA, GPIOB, GPIOC, and so on.) + * @param mask GPIO pin number macro + */ +void GPIO_PortClearInterruptFlags(GPIO_Type *base, uint32_t mask); + +/*! + * @brief Clears multiple GPIO pin interrupt status flags. + * @deprecated Do not use this function. It has been superceded by @ref GPIO_PortClearInterruptFlags. + */ +static inline void GPIO_ClearPinsInterruptFlags(GPIO_Type *base, uint32_t mask) +{ + GPIO_PortClearInterruptFlags(base, mask); +} +#endif +#if defined(FSL_FEATURE_GPIO_HAS_ATTRIBUTE_CHECKER) && FSL_FEATURE_GPIO_HAS_ATTRIBUTE_CHECKER +/*! + * @brief The GPIO module supports a device-specific number of data ports, organized as 32-bit + * words. Each 32-bit data port includes a GACR register, which defines the byte-level + * attributes required for a successful access to the GPIO programming model. The attribute controls for the 4 data + * bytes in the GACR follow a standard little endian + * data convention. + * + * @param base GPIO peripheral base pointer (GPIOA, GPIOB, GPIOC, and so on.) + * @param mask GPIO pin number macro + */ +void GPIO_CheckAttributeBytes(GPIO_Type *base, gpio_checker_attribute_t attribute); +#endif + +/*@}*/ +/*! @} */ + +/*! + * @addtogroup fgpio_driver + * @{ + */ + +/* + * Introduces the FGPIO feature. + * + * The FGPIO features are only support on some Kinetis MCUs. The FGPIO registers are aliased to the IOPORT + * interface. Accesses via the IOPORT interface occur in parallel with any instruction fetches and + * complete in a single cycle. This aliased Fast GPIO memory map is called FGPIO. + */ + +#if defined(FSL_FEATURE_SOC_FGPIO_COUNT) && FSL_FEATURE_SOC_FGPIO_COUNT + +/*! @name FGPIO Configuration */ +/*@{*/ + +/*! + * @brief Initializes the FGPIO peripheral. + * + * This function ungates the FGPIO clock. + * + * @param base FGPIO peripheral base pointer (FGPIOA, FGPIOB, FGPIOC, and so on.) + */ + void FGPIO_PortInit(FGPIO_Type *base); + +/*! + * @brief Initializes the FGPIO peripheral. + * @deprecated Do not use this function. It has been superceded by @ref FGPIO_PortInit. + */ + static inline void FGPIO_Init(FGPIO_Type *base) + { + FGPIO_PortInit(base); + } + +/*! + * @brief Initializes a FGPIO pin used by the board. + * + * To initialize the FGPIO driver, define a pin configuration, as either input or output, in the user file. + * Then, call the FGPIO_PinInit() function. + * + * This is an example to define an input pin or an output pin configuration: + * @code + * // Define a digital input pin configuration, + * gpio_pin_config_t config = + * { + * kGPIO_DigitalInput, + * 0, + * } + * //Define a digital output pin configuration, + * gpio_pin_config_t config = + * { + * kGPIO_DigitalOutput, + * 0, + * } + * @endcode + * + * @param base FGPIO peripheral base pointer (FGPIOA, FGPIOB, FGPIOC, and so on.) + * @param pin FGPIO port pin number + * @param config FGPIO pin configuration pointer + */ +void FGPIO_PinInit(FGPIO_Type *base, uint32_t pin, const gpio_pin_config_t *config); + +/*@}*/ + +/*! @name FGPIO Output Operations */ +/*@{*/ + +/*! + * @brief Sets the output level of the multiple FGPIO pins to the logic 1 or 0. + * + * @param base FGPIO peripheral base pointer (FGPIOA, FGPIOB, FGPIOC, and so on.) + * @param pin FGPIO pin number + * @param output FGPIOpin output logic level. + * - 0: corresponding pin output low-logic level. + * - 1: corresponding pin output high-logic level. + */ +static inline void FGPIO_PinWrite(FGPIO_Type *base, uint32_t pin, uint8_t output) +{ + if (output == 0U) + { + base->PCOR = 1 << pin; + } + else + { + base->PSOR = 1 << pin; + } +} + +/*! + * @brief Sets the output level of the multiple FGPIO pins to the logic 1 or 0. + * @deprecated Do not use this function. It has been superceded by @ref FGPIO_PinWrite. + */ +static inline void FGPIO_WritePinOutput(FGPIO_Type *base, uint32_t pin, uint8_t output) +{ + FGPIO_PinWrite(base, pin, output); +} + +/*! + * @brief Sets the output level of the multiple FGPIO pins to the logic 1. + * + * @param base FGPIO peripheral base pointer (FGPIOA, FGPIOB, FGPIOC, and so on.) + * @param mask FGPIO pin number macro + */ +static inline void FGPIO_PortSet(FGPIO_Type *base, uint32_t mask) +{ + base->PSOR = mask; +} + +/*! + * @brief Sets the output level of the multiple FGPIO pins to the logic 1. + * @deprecated Do not use this function. It has been superceded by @ref FGPIO_PortSet. + */ +static inline void FGPIO_SetPinsOutput(FGPIO_Type *base, uint32_t mask) +{ + FGPIO_PortSet(base, mask); +} + +/*! + * @brief Sets the output level of the multiple FGPIO pins to the logic 0. + * + * @param base FGPIO peripheral base pointer (FGPIOA, FGPIOB, FGPIOC, and so on.) + * @param mask FGPIO pin number macro + */ +static inline void FGPIO_PortClear(FGPIO_Type *base, uint32_t mask) +{ + base->PCOR = mask; +} + +/*! + * @brief Sets the output level of the multiple FGPIO pins to the logic 0. + * @deprecated Do not use this function. It has been superceded by @ref FGPIO_PortClear. + */ +static inline void FGPIO_ClearPinsOutput(FGPIO_Type *base, uint32_t mask) +{ + FGPIO_PortClear(base, mask); +} + +/*! + * @brief Reverses the current output logic of the multiple FGPIO pins. + * + * @param base FGPIO peripheral base pointer (FGPIOA, FGPIOB, FGPIOC, and so on.) + * @param mask FGPIO pin number macro + */ +static inline void FGPIO_PortToggle(FGPIO_Type *base, uint32_t mask) +{ + base->PTOR = mask; +} + +/*! + * @brief Reverses the current output logic of the multiple FGPIO pins. + * @deprecated Do not use this function. It has been superceded by @ref FGPIO_PortToggle. + */ +static inline void FGPIO_TogglePinsOutput(FGPIO_Type *base, uint32_t mask) +{ + FGPIO_PortToggle(base, mask); +} +/*@}*/ + +/*! @name FGPIO Input Operations */ +/*@{*/ + +/*! + * @brief Reads the current input value of the FGPIO port. + * + * @param base FGPIO peripheral base pointer (FGPIOA, FGPIOB, FGPIOC, and so on.) + * @param pin FGPIO pin number + * @retval FGPIO port input value + * - 0: corresponding pin input low-logic level. + * - 1: corresponding pin input high-logic level. + */ +static inline uint32_t FGPIO_PinRead(FGPIO_Type *base, uint32_t pin) +{ + return (((base->PDIR) >> pin) & 0x01U); +} + +/*! + * @brief Reads the current input value of the FGPIO port. + * @deprecated Do not use this function. It has been superceded by @ref FGPIO_PinRead + */ +static inline uint32_t FGPIO_ReadPinInput(FGPIO_Type *base, uint32_t pin) +{ + return FGPIO_PinRead(base, pin); +} +/*@}*/ + +/*! @name FGPIO Interrupt */ +/*@{*/ +#if !(defined(FSL_FEATURE_GPIO_HAS_NO_PORTINTERRUPT) && FSL_FEATURE_GPIO_HAS_NO_PORTINTERRUPT) + +/*! + * @brief Reads the FGPIO port interrupt status flag. + * + * If a pin is configured to generate the DMA request, the corresponding flag + * is cleared automatically at the completion of the requested DMA transfer. + * Otherwise, the flag remains set until a logic one is written to that flag. + * If configured for a level-sensitive interrupt that remains asserted, the flag + * is set again immediately. + * + * @param base FGPIO peripheral base pointer (FGPIOA, FGPIOB, FGPIOC, and so on.) + * @retval The current FGPIO port interrupt status flags, for example, 0x00010001 means the + * pin 0 and 17 have the interrupt. + */ +uint32_t FGPIO_PortGetInterruptFlags(FGPIO_Type *base); + +/*! + * @brief Reads the FGPIO port interrupt status flag. + * @deprecated Do not use this function. It has been superceded by @ref FGPIO_PortGetInterruptFlags. + */ +static inline uint32_t FGPIO_GetPinsInterruptFlags(FGPIO_Type *base) +{ + return FGPIO_PortGetInterruptFlags(base); +} + +/*! + * @brief Clears the multiple FGPIO pin interrupt status flag. + * + * @param base FGPIO peripheral base pointer (FGPIOA, FGPIOB, FGPIOC, and so on.) + * @param mask FGPIO pin number macro + */ +void FGPIO_PortClearInterruptFlags(FGPIO_Type *base, uint32_t mask); + +/*! + * @brief Clears the multiple FGPIO pin interrupt status flag. + * @deprecated Do not use this function. It has been superceded by @ref FGPIO_PortClearInterruptFlags. + */ +static inline void FGPIO_ClearPinsInterruptFlags(FGPIO_Type *base, uint32_t mask) +{ + FGPIO_PortClearInterruptFlags(base, mask); +} +#endif +#if defined(FSL_FEATURE_GPIO_HAS_ATTRIBUTE_CHECKER) && FSL_FEATURE_GPIO_HAS_ATTRIBUTE_CHECKER +/*! + * @brief The FGPIO module supports a device-specific number of data ports, organized as 32-bit + * words. Each 32-bit data port includes a GACR register, which defines the byte-level + * attributes required for a successful access to the GPIO programming model. The attribute controls for the 4 data + * bytes in the GACR follow a standard little endian + * data convention. + * + * @param base FGPIO peripheral base pointer (FGPIOA, FGPIOB, FGPIOC, and so on.) + * @param mask FGPIO pin number macro + */ +void FGPIO_CheckAttributeBytes(FGPIO_Type *base, gpio_checker_attribute_t attribute); +#endif + +/*@}*/ + +#endif /* FSL_FEATURE_SOC_FGPIO_COUNT */ + +#if defined(__cplusplus) +} +#endif + +/*! + * @} + */ + +#endif /* _FSL_GPIO_H_*/ diff --git a/drivers/fsl_i2c.c b/drivers/fsl_i2c.c new file mode 100644 index 0000000..d3da84a --- /dev/null +++ b/drivers/fsl_i2c.c @@ -0,0 +1,2005 @@ +/* + * The Clear BSD License + * Copyright (c) 2015, 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: + * + * o Redistributions of source code must retain the above copyright notice, this list + * of conditions and the following disclaimer. + * + * o 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. + * + * o 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. + */ +#include "fsl_i2c.h" + +/******************************************************************************* + * Definitions + ******************************************************************************/ + +/* Component ID definition, used by tools. */ +#ifndef FSL_COMPONENT_ID +#define FSL_COMPONENT_ID "platform.drivers.i2c" +#endif + + +/*! @brief i2c transfer state. */ +enum _i2c_transfer_states +{ + kIdleState = 0x0U, /*!< I2C bus idle. */ + kCheckAddressState = 0x1U, /*!< 7-bit address check state. */ + kSendCommandState = 0x2U, /*!< Send command byte phase. */ + kSendDataState = 0x3U, /*!< Send data transfer phase. */ + kReceiveDataBeginState = 0x4U, /*!< Receive data transfer phase begin. */ + kReceiveDataState = 0x5U, /*!< Receive data transfer phase. */ +}; + +/*! @brief Common sets of flags used by the driver. */ +enum _i2c_flag_constants +{ +/*! All flags which are cleared by the driver upon starting a transfer. */ +#if defined(FSL_FEATURE_I2C_HAS_START_STOP_DETECT) && FSL_FEATURE_I2C_HAS_START_STOP_DETECT + kClearFlags = kI2C_ArbitrationLostFlag | kI2C_IntPendingFlag | kI2C_StartDetectFlag | kI2C_StopDetectFlag, + kIrqFlags = kI2C_GlobalInterruptEnable | kI2C_StartStopDetectInterruptEnable, +#elif defined(FSL_FEATURE_I2C_HAS_STOP_DETECT) && FSL_FEATURE_I2C_HAS_STOP_DETECT + kClearFlags = kI2C_ArbitrationLostFlag | kI2C_IntPendingFlag | kI2C_StopDetectFlag, + kIrqFlags = kI2C_GlobalInterruptEnable | kI2C_StopDetectInterruptEnable, +#else + kClearFlags = kI2C_ArbitrationLostFlag | kI2C_IntPendingFlag, + kIrqFlags = kI2C_GlobalInterruptEnable, +#endif + +}; + +/*! @brief Typedef for interrupt handler. */ +typedef void (*i2c_isr_t)(I2C_Type *base, void *i2cHandle); + +/******************************************************************************* + * Prototypes + ******************************************************************************/ + +/*! +* @brief Set SCL/SDA hold time, this API receives SCL stop hold time, calculate the +* closest SCL divider and MULT value for the SDA hold time, SCL start and SCL stop +* hold time. To reduce the ROM size, SDA/SCL hold value mapping table is not provided, +* assume SCL divider = SCL stop hold value *2 to get the closest SCL divider value and MULT +* value, then the related SDA hold time, SCL start and SCL stop hold time is used. +* +* @param base I2C peripheral base address. +* @param sourceClock_Hz I2C functional clock frequency in Hertz. +* @param sclStopHoldTime_ns SCL stop hold time in ns. +*/ +static void I2C_SetHoldTime(I2C_Type *base, uint32_t sclStopHoldTime_ns, uint32_t sourceClock_Hz); + +/*! + * @brief Set up master transfer, send slave address and decide the initial + * transfer state. + * + * @param base I2C peripheral base address. + * @param handle pointer to i2c_master_handle_t structure which stores the transfer state. + * @param xfer pointer to i2c_master_transfer_t structure. + */ +static status_t I2C_InitTransferStateMachine(I2C_Type *base, i2c_master_handle_t *handle, i2c_master_transfer_t *xfer); + +/*! + * @brief Check and clear status operation. + * + * @param base I2C peripheral base address. + * @param status current i2c hardware status. + * @retval kStatus_Success No error found. + * @retval kStatus_I2C_ArbitrationLost Transfer error, arbitration lost. + * @retval kStatus_I2C_Nak Received Nak error. + */ +static status_t I2C_CheckAndClearError(I2C_Type *base, uint32_t status); + +/*! + * @brief Master run transfer state machine to perform a byte of transfer. + * + * @param base I2C peripheral base address. + * @param handle pointer to i2c_master_handle_t structure which stores the transfer state + * @param isDone input param to get whether the thing is done, true is done + * @retval kStatus_Success No error found. + * @retval kStatus_I2C_ArbitrationLost Transfer error, arbitration lost. + * @retval kStatus_I2C_Nak Received Nak error. + * @retval kStatus_I2C_Timeout Transfer error, wait signal timeout. + */ +static status_t I2C_MasterTransferRunStateMachine(I2C_Type *base, i2c_master_handle_t *handle, bool *isDone); + +/*! + * @brief I2C common interrupt handler. + * + * @param base I2C peripheral base address. + * @param handle pointer to i2c_master_handle_t structure which stores the transfer state + */ +static void I2C_TransferCommonIRQHandler(I2C_Type *base, void *handle); + +/******************************************************************************* + * Variables + ******************************************************************************/ + +/*! @brief Pointers to i2c bases for each instance. */ +I2C_Type *const s_i2cBases[] = I2C_BASE_PTRS; + +/*! @brief Pointers to i2c handles for each instance. */ +static void *s_i2cHandle[FSL_FEATURE_SOC_I2C_COUNT] = {NULL}; + +/*! @brief SCL clock divider used to calculate baudrate. */ +static const uint16_t s_i2cDividerTable[] = { + 20, 22, 24, 26, 28, 30, 34, 40, 28, 32, 36, 40, 44, 48, 56, 68, + 48, 56, 64, 72, 80, 88, 104, 128, 80, 96, 112, 128, 144, 160, 192, 240, + 160, 192, 224, 256, 288, 320, 384, 480, 320, 384, 448, 512, 576, 640, 768, 960, + 640, 768, 896, 1024, 1152, 1280, 1536, 1920, 1280, 1536, 1792, 2048, 2304, 2560, 3072, 3840}; + +/*! @brief Pointers to i2c IRQ number for each instance. */ +static const IRQn_Type s_i2cIrqs[] = I2C_IRQS; + +#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) +/*! @brief Pointers to i2c clocks for each instance. */ +static const clock_ip_name_t s_i2cClocks[] = I2C_CLOCKS; +#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */ + +/*! @brief Pointer to master IRQ handler for each instance. */ +static i2c_isr_t s_i2cMasterIsr; + +/*! @brief Pointer to slave IRQ handler for each instance. */ +static i2c_isr_t s_i2cSlaveIsr; + +/******************************************************************************* + * Codes + ******************************************************************************/ + +uint32_t I2C_GetInstance(I2C_Type *base) +{ + uint32_t instance; + + /* Find the instance index from base address mappings. */ + for (instance = 0; instance < ARRAY_SIZE(s_i2cBases); instance++) + { + if (s_i2cBases[instance] == base) + { + break; + } + } + + assert(instance < ARRAY_SIZE(s_i2cBases)); + + return instance; +} + +static void I2C_SetHoldTime(I2C_Type *base, uint32_t sclStopHoldTime_ns, uint32_t sourceClock_Hz) +{ + uint32_t multiplier; + uint32_t computedSclHoldTime; + uint32_t absError; + uint32_t bestError = UINT32_MAX; + uint32_t bestMult = 0u; + uint32_t bestIcr = 0u; + uint8_t mult; + uint8_t i; + + /* Search for the settings with the lowest error. Mult is the MULT field of the I2C_F register, + * and ranges from 0-2. It selects the multiplier factor for the divider. */ + /* SDA hold time = bus period (s) * mul * SDA hold value. */ + /* SCL start hold time = bus period (s) * mul * SCL start hold value. */ + /* SCL stop hold time = bus period (s) * mul * SCL stop hold value. */ + + for (mult = 0u; (mult <= 2u) && (bestError != 0); ++mult) + { + multiplier = 1u << mult; + + /* Scan table to find best match. */ + for (i = 0u; i < sizeof(s_i2cDividerTable) / sizeof(s_i2cDividerTable[0]); ++i) + { + /* Assume SCL hold(stop) value = s_i2cDividerTable[i]/2. */ + computedSclHoldTime = ((multiplier * s_i2cDividerTable[i]) * 500000U) / (sourceClock_Hz / 1000U); + absError = sclStopHoldTime_ns > computedSclHoldTime ? (sclStopHoldTime_ns - computedSclHoldTime) : + (computedSclHoldTime - sclStopHoldTime_ns); + + if (absError < bestError) + { + bestMult = mult; + bestIcr = i; + bestError = absError; + + /* If the error is 0, then we can stop searching because we won't find a better match. */ + if (absError == 0) + { + break; + } + } + } + } + + /* Set frequency register based on best settings. */ + base->F = I2C_F_MULT(bestMult) | I2C_F_ICR(bestIcr); +} + +static status_t I2C_InitTransferStateMachine(I2C_Type *base, i2c_master_handle_t *handle, i2c_master_transfer_t *xfer) +{ + status_t result = kStatus_Success; + i2c_direction_t direction = xfer->direction; + + /* Initialize the handle transfer information. */ + handle->transfer = *xfer; + + /* Save total transfer size. */ + handle->transferSize = xfer->dataSize; + + /* Initial transfer state. */ + if (handle->transfer.subaddressSize > 0) + { + if (xfer->direction == kI2C_Read) + { + direction = kI2C_Write; + } + } + + handle->state = kCheckAddressState; + + /* Clear all status before transfer. */ + I2C_MasterClearStatusFlags(base, kClearFlags); + + /* Handle no start option. */ + if (handle->transfer.flags & kI2C_TransferNoStartFlag) + { + /* No need to send start flag, directly go to send command or data */ + if (handle->transfer.subaddressSize > 0) + { + handle->state = kSendCommandState; + } + else + { + if (direction == kI2C_Write) + { + /* Next state, send data. */ + handle->state = kSendDataState; + } + else + { + /* Only support write with no stop signal. */ + return kStatus_InvalidArgument; + } + } + + /* Wait for TCF bit and manually trigger tx interrupt. */ + while (!(base->S & kI2C_TransferCompleteFlag)) + { + } + I2C_MasterTransferHandleIRQ(base, handle); + } + /* If repeated start is requested, send repeated start. */ + else if (handle->transfer.flags & kI2C_TransferRepeatedStartFlag) + { + result = I2C_MasterRepeatedStart(base, handle->transfer.slaveAddress, direction); + } + else /* For normal transfer, send start. */ + { + result = I2C_MasterStart(base, handle->transfer.slaveAddress, direction); + } + + return result; +} + +static status_t I2C_CheckAndClearError(I2C_Type *base, uint32_t status) +{ + status_t result = kStatus_Success; + + /* Check arbitration lost. */ + if (status & kI2C_ArbitrationLostFlag) + { + /* Clear arbitration lost flag. */ + base->S = kI2C_ArbitrationLostFlag; + result = kStatus_I2C_ArbitrationLost; + } + /* Check NAK */ + else if (status & kI2C_ReceiveNakFlag) + { + result = kStatus_I2C_Nak; + } + else + { + } + + return result; +} + +static status_t I2C_MasterTransferRunStateMachine(I2C_Type *base, i2c_master_handle_t *handle, bool *isDone) +{ + status_t result = kStatus_Success; + uint32_t statusFlags = base->S; + *isDone = false; + volatile uint8_t dummy = 0; + bool ignoreNak = ((handle->state == kSendDataState) && (handle->transfer.dataSize == 0U)) || + ((handle->state == kReceiveDataState) && (handle->transfer.dataSize == 1U)); + + /* Add this to avoid build warning. */ + dummy++; + + /* Check & clear error flags. */ + result = I2C_CheckAndClearError(base, statusFlags); + + /* Ignore Nak when it's appeared for last byte. */ + if ((result == kStatus_I2C_Nak) && ignoreNak) + { + result = kStatus_Success; + } + + /* Handle Check address state to check the slave address is Acked in slave + probe application. */ + if (handle->state == kCheckAddressState) + { + if (statusFlags & kI2C_ReceiveNakFlag) + { + result = kStatus_I2C_Addr_Nak; + } + else + { + if (handle->transfer.subaddressSize > 0) + { + handle->state = kSendCommandState; + } + else + { + if (handle->transfer.direction == kI2C_Write) + { + /* Next state, send data. */ + handle->state = kSendDataState; + } + else + { + /* Next state, receive data begin. */ + handle->state = kReceiveDataBeginState; + } + } + } + } + + if (result) + { + return result; + } + + /* Run state machine. */ + switch (handle->state) + { + /* Send I2C command. */ + case kSendCommandState: + if (handle->transfer.subaddressSize) + { + handle->transfer.subaddressSize--; + base->D = ((handle->transfer.subaddress) >> (8 * handle->transfer.subaddressSize)); + } + else + { + if (handle->transfer.direction == kI2C_Write) + { + /* Next state, send data. */ + handle->state = kSendDataState; + + /* Send first byte of data. */ + if (handle->transfer.dataSize > 0) + { + base->D = *handle->transfer.data; + handle->transfer.data++; + handle->transfer.dataSize--; + } + } + else + { + /* Send repeated start and slave address. */ + result = I2C_MasterRepeatedStart(base, handle->transfer.slaveAddress, kI2C_Read); + + /* Next state, receive data begin. */ + handle->state = kReceiveDataBeginState; + } + } + break; + + /* Send I2C data. */ + case kSendDataState: + /* Send one byte of data. */ + if (handle->transfer.dataSize > 0) + { + base->D = *handle->transfer.data; + handle->transfer.data++; + handle->transfer.dataSize--; + } + else + { + *isDone = true; + } + break; + + /* Start I2C data receive. */ + case kReceiveDataBeginState: + base->C1 &= ~(I2C_C1_TX_MASK | I2C_C1_TXAK_MASK); + + /* Send nak at the last receive byte. */ + if (handle->transfer.dataSize == 1) + { + base->C1 |= I2C_C1_TXAK_MASK; + } + + /* Read dummy to release the bus. */ + dummy = base->D; + + /* Next state, receive data. */ + handle->state = kReceiveDataState; + break; + + /* Receive I2C data. */ + case kReceiveDataState: + /* Receive one byte of data. */ + if (handle->transfer.dataSize--) + { + if (handle->transfer.dataSize == 0) + { + *isDone = true; + + /* Send stop if kI2C_TransferNoStop is not asserted. */ + if (!(handle->transfer.flags & kI2C_TransferNoStopFlag)) + { + result = I2C_MasterStop(base); + } + else + { + base->C1 |= I2C_C1_TX_MASK; + } + } + + /* Send NAK at the last receive byte. */ + if (handle->transfer.dataSize == 1) + { + base->C1 |= I2C_C1_TXAK_MASK; + } + + /* Read the data byte into the transfer buffer. */ + *handle->transfer.data = base->D; + handle->transfer.data++; + } + break; + + default: + break; + } + + return result; +} + +static void I2C_TransferCommonIRQHandler(I2C_Type *base, void *handle) +{ + /* Check if master interrupt. */ + if ((base->S & kI2C_ArbitrationLostFlag) || (base->C1 & I2C_C1_MST_MASK)) + { + s_i2cMasterIsr(base, handle); + } + else + { + s_i2cSlaveIsr(base, handle); + } + __DSB(); +} + +void I2C_MasterInit(I2C_Type *base, const i2c_master_config_t *masterConfig, uint32_t srcClock_Hz) +{ + assert(masterConfig && srcClock_Hz); + + /* Temporary register for filter read. */ + uint8_t fltReg; +#if defined(FSL_FEATURE_I2C_HAS_DOUBLE_BUFFER_ENABLE) && FSL_FEATURE_I2C_HAS_DOUBLE_BUFFER_ENABLE + uint8_t s2Reg; +#endif +#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) + /* Enable I2C clock. */ + CLOCK_EnableClock(s_i2cClocks[I2C_GetInstance(base)]); +#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */ + + /* Reset the module. */ + base->A1 = 0; + base->F = 0; + base->C1 = 0; + base->S = 0xFFU; + base->C2 = 0; +#if defined(FSL_FEATURE_I2C_HAS_START_STOP_DETECT) && FSL_FEATURE_I2C_HAS_START_STOP_DETECT + base->FLT = 0x50U; +#elif defined(FSL_FEATURE_I2C_HAS_STOP_DETECT) && FSL_FEATURE_I2C_HAS_STOP_DETECT + base->FLT = 0x40U; +#endif + base->RA = 0; + + /* Disable I2C prior to configuring it. */ + base->C1 &= ~(I2C_C1_IICEN_MASK); + + /* Clear all flags. */ + I2C_MasterClearStatusFlags(base, kClearFlags); + + /* Configure baud rate. */ + I2C_MasterSetBaudRate(base, masterConfig->baudRate_Bps, srcClock_Hz); + + /* Read out the FLT register. */ + fltReg = base->FLT; + +#if defined(FSL_FEATURE_I2C_HAS_STOP_HOLD_OFF) && FSL_FEATURE_I2C_HAS_STOP_HOLD_OFF + /* Configure the stop / hold enable. */ + fltReg &= ~(I2C_FLT_SHEN_MASK); + fltReg |= I2C_FLT_SHEN(masterConfig->enableStopHold); +#endif + + /* Configure the glitch filter value. */ + fltReg &= ~(I2C_FLT_FLT_MASK); + fltReg |= I2C_FLT_FLT(masterConfig->glitchFilterWidth); + + /* Write the register value back to the filter register. */ + base->FLT = fltReg; + +/* Enable/Disable double buffering. */ +#if defined(FSL_FEATURE_I2C_HAS_DOUBLE_BUFFER_ENABLE) && FSL_FEATURE_I2C_HAS_DOUBLE_BUFFER_ENABLE + s2Reg = base->S2 & (~I2C_S2_DFEN_MASK); + base->S2 = s2Reg | I2C_S2_DFEN(masterConfig->enableDoubleBuffering); +#endif + + /* Enable the I2C peripheral based on the configuration. */ + base->C1 = I2C_C1_IICEN(masterConfig->enableMaster); +} + +void I2C_MasterDeinit(I2C_Type *base) +{ + /* Disable I2C module. */ + I2C_Enable(base, false); + +#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) + /* Disable I2C clock. */ + CLOCK_DisableClock(s_i2cClocks[I2C_GetInstance(base)]); +#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */ +} + +void I2C_MasterGetDefaultConfig(i2c_master_config_t *masterConfig) +{ + assert(masterConfig); + + /* Default baud rate at 100kbps. */ + masterConfig->baudRate_Bps = 100000U; + +/* Default stop hold enable is disabled. */ +#if defined(FSL_FEATURE_I2C_HAS_STOP_HOLD_OFF) && FSL_FEATURE_I2C_HAS_STOP_HOLD_OFF + masterConfig->enableStopHold = false; +#endif + + /* Default glitch filter value is no filter. */ + masterConfig->glitchFilterWidth = 0U; + +/* Default enable double buffering. */ +#if defined(FSL_FEATURE_I2C_HAS_DOUBLE_BUFFER_ENABLE) && FSL_FEATURE_I2C_HAS_DOUBLE_BUFFER_ENABLE + masterConfig->enableDoubleBuffering = true; +#endif + + /* Enable the I2C peripheral. */ + masterConfig->enableMaster = true; +} + +void I2C_EnableInterrupts(I2C_Type *base, uint32_t mask) +{ +#ifdef I2C_HAS_STOP_DETECT + uint8_t fltReg; +#endif + + if (mask & kI2C_GlobalInterruptEnable) + { + base->C1 |= I2C_C1_IICIE_MASK; + } + +#if defined(FSL_FEATURE_I2C_HAS_STOP_DETECT) && FSL_FEATURE_I2C_HAS_STOP_DETECT + if (mask & kI2C_StopDetectInterruptEnable) + { + fltReg = base->FLT; + + /* Keep STOPF flag. */ + fltReg &= ~I2C_FLT_STOPF_MASK; + + /* Stop detect enable. */ + fltReg |= I2C_FLT_STOPIE_MASK; + base->FLT = fltReg; + } +#endif /* FSL_FEATURE_I2C_HAS_STOP_DETECT */ + +#if defined(FSL_FEATURE_I2C_HAS_START_STOP_DETECT) && FSL_FEATURE_I2C_HAS_START_STOP_DETECT + if (mask & kI2C_StartStopDetectInterruptEnable) + { + fltReg = base->FLT; + + /* Keep STARTF and STOPF flags. */ + fltReg &= ~(I2C_FLT_STOPF_MASK | I2C_FLT_STARTF_MASK); + + /* Start and stop detect enable. */ + fltReg |= I2C_FLT_SSIE_MASK; + base->FLT = fltReg; + } +#endif /* FSL_FEATURE_I2C_HAS_START_STOP_DETECT */ +} + +void I2C_DisableInterrupts(I2C_Type *base, uint32_t mask) +{ + if (mask & kI2C_GlobalInterruptEnable) + { + base->C1 &= ~I2C_C1_IICIE_MASK; + } + +#if defined(FSL_FEATURE_I2C_HAS_STOP_DETECT) && FSL_FEATURE_I2C_HAS_STOP_DETECT + if (mask & kI2C_StopDetectInterruptEnable) + { + base->FLT &= ~(I2C_FLT_STOPIE_MASK | I2C_FLT_STOPF_MASK); + } +#endif /* FSL_FEATURE_I2C_HAS_STOP_DETECT */ + +#if defined(FSL_FEATURE_I2C_HAS_START_STOP_DETECT) && FSL_FEATURE_I2C_HAS_START_STOP_DETECT + if (mask & kI2C_StartStopDetectInterruptEnable) + { + base->FLT &= ~(I2C_FLT_SSIE_MASK | I2C_FLT_STOPF_MASK | I2C_FLT_STARTF_MASK); + } +#endif /* FSL_FEATURE_I2C_HAS_START_STOP_DETECT */ +} + +void I2C_MasterSetBaudRate(I2C_Type *base, uint32_t baudRate_Bps, uint32_t srcClock_Hz) +{ + uint32_t multiplier; + uint32_t computedRate; + uint32_t absError; + uint32_t bestError = UINT32_MAX; + uint32_t bestMult = 0u; + uint32_t bestIcr = 0u; + uint8_t mult; + uint8_t i; + + /* Search for the settings with the lowest error. Mult is the MULT field of the I2C_F register, + * and ranges from 0-2. It selects the multiplier factor for the divider. */ + for (mult = 0u; (mult <= 2u) && (bestError != 0); ++mult) + { + multiplier = 1u << mult; + + /* Scan table to find best match. */ + for (i = 0u; i < sizeof(s_i2cDividerTable) / sizeof(uint16_t); ++i) + { + computedRate = srcClock_Hz / (multiplier * s_i2cDividerTable[i]); + absError = baudRate_Bps > computedRate ? (baudRate_Bps - computedRate) : (computedRate - baudRate_Bps); + + if (absError < bestError) + { + bestMult = mult; + bestIcr = i; + bestError = absError; + + /* If the error is 0, then we can stop searching because we won't find a better match. */ + if (absError == 0) + { + break; + } + } + } + } + + /* Set frequency register based on best settings. */ + base->F = I2C_F_MULT(bestMult) | I2C_F_ICR(bestIcr); +} + +status_t I2C_MasterStart(I2C_Type *base, uint8_t address, i2c_direction_t direction) +{ + status_t result = kStatus_Success; + uint32_t statusFlags = I2C_MasterGetStatusFlags(base); + + /* Return an error if the bus is already in use. */ + if (statusFlags & kI2C_BusBusyFlag) + { + result = kStatus_I2C_Busy; + } + else + { + /* Send the START signal. */ + base->C1 |= I2C_C1_MST_MASK | I2C_C1_TX_MASK; + +#if defined(FSL_FEATURE_I2C_HAS_DOUBLE_BUFFERING) && FSL_FEATURE_I2C_HAS_DOUBLE_BUFFERING +#if I2C_WAIT_TIMEOUT + uint32_t waitTimes = I2C_WAIT_TIMEOUT; + while ((!(base->S2 & I2C_S2_EMPTY_MASK)) && (--waitTimes)) + { + } + if (waitTimes == 0) + { + return kStatus_I2C_Timeout; + } +#else + while (!(base->S2 & I2C_S2_EMPTY_MASK)) + { + } +#endif +#endif /* FSL_FEATURE_I2C_HAS_DOUBLE_BUFFERING */ + + base->D = (((uint32_t)address) << 1U | ((direction == kI2C_Read) ? 1U : 0U)); + } + + return result; +} + +status_t I2C_MasterRepeatedStart(I2C_Type *base, uint8_t address, i2c_direction_t direction) +{ + status_t result = kStatus_Success; + uint8_t savedMult; + uint32_t statusFlags = I2C_MasterGetStatusFlags(base); + uint8_t timeDelay = 6; + + /* Return an error if the bus is already in use, but not by us. */ + if ((statusFlags & kI2C_BusBusyFlag) && ((base->C1 & I2C_C1_MST_MASK) == 0)) + { + result = kStatus_I2C_Busy; + } + else + { + savedMult = base->F; + base->F = savedMult & (~I2C_F_MULT_MASK); + + /* We are already in a transfer, so send a repeated start. */ + base->C1 |= I2C_C1_RSTA_MASK | I2C_C1_TX_MASK; + + /* Restore the multiplier factor. */ + base->F = savedMult; + + /* Add some delay to wait the Re-Start signal. */ + while (timeDelay--) + { + __NOP(); + } + +#if defined(FSL_FEATURE_I2C_HAS_DOUBLE_BUFFERING) && FSL_FEATURE_I2C_HAS_DOUBLE_BUFFERING +#if I2C_WAIT_TIMEOUT + uint32_t waitTimes = I2C_WAIT_TIMEOUT; + while ((!(base->S2 & I2C_S2_EMPTY_MASK)) && (--waitTimes)) + { + } + if (waitTimes == 0) + { + return kStatus_I2C_Timeout; + } +#else + while (!(base->S2 & I2C_S2_EMPTY_MASK)) + { + } +#endif +#endif /* FSL_FEATURE_I2C_HAS_DOUBLE_BUFFERING */ + + base->D = (((uint32_t)address) << 1U | ((direction == kI2C_Read) ? 1U : 0U)); + } + + return result; +} + +status_t I2C_MasterStop(I2C_Type *base) +{ + status_t result = kStatus_Success; + + /* Issue the STOP command on the bus. */ + base->C1 &= ~(I2C_C1_MST_MASK | I2C_C1_TX_MASK | I2C_C1_TXAK_MASK); + +#if I2C_WAIT_TIMEOUT + uint32_t waitTimes = I2C_WAIT_TIMEOUT; + /* Wait until bus not busy. */ + while ((base->S & kI2C_BusBusyFlag) && (--waitTimes)) + { + } + + if (waitTimes == 0) + { + result = kStatus_I2C_Timeout; + } +#else + /* Wait until data transfer complete. */ + while (base->S & kI2C_BusBusyFlag) + { + } +#endif + + return result; +} + +uint32_t I2C_MasterGetStatusFlags(I2C_Type *base) +{ + uint32_t statusFlags = base->S; + +#ifdef I2C_HAS_STOP_DETECT + /* Look up the STOPF bit from the filter register. */ + if (base->FLT & I2C_FLT_STOPF_MASK) + { + statusFlags |= kI2C_StopDetectFlag; + } +#endif + +#if defined(FSL_FEATURE_I2C_HAS_START_STOP_DETECT) && FSL_FEATURE_I2C_HAS_START_STOP_DETECT + /* Look up the STARTF bit from the filter register. */ + if (base->FLT & I2C_FLT_STARTF_MASK) + { + statusFlags |= kI2C_StartDetectFlag; + } +#endif /* FSL_FEATURE_I2C_HAS_START_STOP_DETECT */ + + return statusFlags; +} + +status_t I2C_MasterWriteBlocking(I2C_Type *base, const uint8_t *txBuff, size_t txSize, uint32_t flags) +{ + status_t result = kStatus_Success; + uint8_t statusFlags = 0; + +#if I2C_WAIT_TIMEOUT + uint32_t waitTimes = I2C_WAIT_TIMEOUT; + /* Wait until the data register is ready for transmit. */ + while ((!(base->S & kI2C_TransferCompleteFlag)) && (--waitTimes)) + { + } + if (waitTimes == 0) + { + return kStatus_I2C_Timeout; + } +#else + /* Wait until the data register is ready for transmit. */ + while (!(base->S & kI2C_TransferCompleteFlag)) + { + } +#endif + + /* Clear the IICIF flag. */ + base->S = kI2C_IntPendingFlag; + + /* Setup the I2C peripheral to transmit data. */ + base->C1 |= I2C_C1_TX_MASK; + + while (txSize--) + { + /* Send a byte of data. */ + base->D = *txBuff++; + +#if I2C_WAIT_TIMEOUT + waitTimes = I2C_WAIT_TIMEOUT; + /* Wait until data transfer complete. */ + while ((!(base->S & kI2C_IntPendingFlag)) && (--waitTimes)) + { + } + if (waitTimes == 0) + { + return kStatus_I2C_Timeout; + } +#else + /* Wait until data transfer complete. */ + while (!(base->S & kI2C_IntPendingFlag)) + { + } +#endif + statusFlags = base->S; + + /* Clear the IICIF flag. */ + base->S = kI2C_IntPendingFlag; + + /* Check if arbitration lost or no acknowledgement (NAK), return failure status. */ + if (statusFlags & kI2C_ArbitrationLostFlag) + { + base->S = kI2C_ArbitrationLostFlag; + result = kStatus_I2C_ArbitrationLost; + } + + if ((statusFlags & kI2C_ReceiveNakFlag) && txSize) + { + base->S = kI2C_ReceiveNakFlag; + result = kStatus_I2C_Nak; + } + + if (result != kStatus_Success) + { + /* Breaking out of the send loop. */ + break; + } + } + + if (((result == kStatus_Success) && (!(flags & kI2C_TransferNoStopFlag))) || (result == kStatus_I2C_Nak)) + { + /* Clear the IICIF flag. */ + base->S = kI2C_IntPendingFlag; + + /* Send stop. */ + result = I2C_MasterStop(base); + } + + return result; +} + +status_t I2C_MasterReadBlocking(I2C_Type *base, uint8_t *rxBuff, size_t rxSize, uint32_t flags) +{ + status_t result = kStatus_Success; + volatile uint8_t dummy = 0; + + /* Add this to avoid build warning. */ + dummy++; + +#if I2C_WAIT_TIMEOUT + uint32_t waitTimes = I2C_WAIT_TIMEOUT; + /* Wait until the data register is ready for transmit. */ + while ((!(base->S & kI2C_TransferCompleteFlag)) && (--waitTimes)) + { + } + if (waitTimes == 0) + { + return kStatus_I2C_Timeout; + } +#else + /* Wait until the data register is ready for transmit. */ + while (!(base->S & kI2C_TransferCompleteFlag)) + { + } +#endif + + /* Clear the IICIF flag. */ + base->S = kI2C_IntPendingFlag; + + /* Setup the I2C peripheral to receive data. */ + base->C1 &= ~(I2C_C1_TX_MASK | I2C_C1_TXAK_MASK); + + /* If rxSize equals 1, configure to send NAK. */ + if (rxSize == 1) + { + /* Issue NACK on read. */ + base->C1 |= I2C_C1_TXAK_MASK; + } + + /* Do dummy read. */ + dummy = base->D; + + while ((rxSize--)) + { +#if I2C_WAIT_TIMEOUT + waitTimes = I2C_WAIT_TIMEOUT; + /* Wait until data transfer complete. */ + while ((!(base->S & kI2C_IntPendingFlag)) && (--waitTimes)) + { + } + if (waitTimes == 0) + { + return kStatus_I2C_Timeout; + } +#else + /* Wait until data transfer complete. */ + while (!(base->S & kI2C_IntPendingFlag)) + { + } +#endif + /* Clear the IICIF flag. */ + base->S = kI2C_IntPendingFlag; + + /* Single byte use case. */ + if (rxSize == 0) + { + if (!(flags & kI2C_TransferNoStopFlag)) + { + /* Issue STOP command before reading last byte. */ + result = I2C_MasterStop(base); + } + else + { + /* Change direction to Tx to avoid extra clocks. */ + base->C1 |= I2C_C1_TX_MASK; + } + } + + if (rxSize == 1) + { + /* Issue NACK on read. */ + base->C1 |= I2C_C1_TXAK_MASK; + } + + /* Read from the data register. */ + *rxBuff++ = base->D; + } + + return result; +} + +status_t I2C_MasterTransferBlocking(I2C_Type *base, i2c_master_transfer_t *xfer) +{ + assert(xfer); + + i2c_direction_t direction = xfer->direction; + status_t result = kStatus_Success; + + /* Clear all status before transfer. */ + I2C_MasterClearStatusFlags(base, kClearFlags); + +#if I2C_WAIT_TIMEOUT + uint32_t waitTimes = I2C_WAIT_TIMEOUT; + /* Wait until the data register is ready for transmit. */ + while ((!(base->S & kI2C_TransferCompleteFlag)) && (--waitTimes)) + { + } + if (waitTimes == 0) + { + return kStatus_I2C_Timeout; + } +#else + /* Wait until the data register is ready for transmit. */ + while (!(base->S & kI2C_TransferCompleteFlag)) + { + } +#endif + + /* Change to send write address when it's a read operation with command. */ + if ((xfer->subaddressSize > 0) && (xfer->direction == kI2C_Read)) + { + direction = kI2C_Write; + } + + /* Handle no start option, only support write with no start signal. */ + if (xfer->flags & kI2C_TransferNoStartFlag) + { + if (direction == kI2C_Read) + { + return kStatus_InvalidArgument; + } + } + /* If repeated start is requested, send repeated start. */ + else if (xfer->flags & kI2C_TransferRepeatedStartFlag) + { + result = I2C_MasterRepeatedStart(base, xfer->slaveAddress, direction); + } + else /* For normal transfer, send start. */ + { + result = I2C_MasterStart(base, xfer->slaveAddress, direction); + } + + if (!(xfer->flags & kI2C_TransferNoStartFlag)) + { + /* Return if error. */ + if (result) + { + return result; + } + +#if I2C_WAIT_TIMEOUT + waitTimes = I2C_WAIT_TIMEOUT; + /* Wait until data transfer complete. */ + while ((!(base->S & kI2C_IntPendingFlag)) && (--waitTimes)) + { + } + if (waitTimes == 0) + { + return kStatus_I2C_Timeout; + } +#else + /* Wait until data transfer complete. */ + while (!(base->S & kI2C_IntPendingFlag)) + { + } +#endif + /* Check if there's transfer error. */ + result = I2C_CheckAndClearError(base, base->S); + + /* Return if error. */ + if (result) + { + if (result == kStatus_I2C_Nak) + { + result = kStatus_I2C_Addr_Nak; + + I2C_MasterStop(base); + } + + return result; + } + } + + /* Send subaddress. */ + if (xfer->subaddressSize) + { + do + { + /* Clear interrupt pending flag. */ + base->S = kI2C_IntPendingFlag; + + xfer->subaddressSize--; + base->D = ((xfer->subaddress) >> (8 * xfer->subaddressSize)); + +#if I2C_WAIT_TIMEOUT + waitTimes = I2C_WAIT_TIMEOUT; + /* Wait until data transfer complete. */ + while ((!(base->S & kI2C_IntPendingFlag)) && (--waitTimes)) + { + } + if (waitTimes == 0) + { + return kStatus_I2C_Timeout; + } +#else + /* Wait until data transfer complete. */ + while (!(base->S & kI2C_IntPendingFlag)) + { + } +#endif + + /* Check if there's transfer error. */ + result = I2C_CheckAndClearError(base, base->S); + + if (result) + { + if (result == kStatus_I2C_Nak) + { + I2C_MasterStop(base); + } + + return result; + } + + } while (xfer->subaddressSize > 0); + + if (xfer->direction == kI2C_Read) + { + /* Clear pending flag. */ + base->S = kI2C_IntPendingFlag; + + /* Send repeated start and slave address. */ + result = I2C_MasterRepeatedStart(base, xfer->slaveAddress, kI2C_Read); + + /* Return if error. */ + if (result) + { + return result; + } + +#if I2C_WAIT_TIMEOUT + waitTimes = I2C_WAIT_TIMEOUT; + /* Wait until data transfer complete. */ + while ((!(base->S & kI2C_IntPendingFlag)) && (--waitTimes)) + { + } + if (waitTimes == 0) + { + return kStatus_I2C_Timeout; + } +#else + /* Wait until data transfer complete. */ + while (!(base->S & kI2C_IntPendingFlag)) + { + } +#endif + + /* Check if there's transfer error. */ + result = I2C_CheckAndClearError(base, base->S); + + if (result) + { + if (result == kStatus_I2C_Nak) + { + result = kStatus_I2C_Addr_Nak; + + I2C_MasterStop(base); + } + + return result; + } + } + } + + /* Transmit data. */ + if ((xfer->direction == kI2C_Write) && (xfer->dataSize > 0)) + { + /* Send Data. */ + result = I2C_MasterWriteBlocking(base, xfer->data, xfer->dataSize, xfer->flags); + } + + /* Receive Data. */ + if ((xfer->direction == kI2C_Read) && (xfer->dataSize > 0)) + { + result = I2C_MasterReadBlocking(base, xfer->data, xfer->dataSize, xfer->flags); + } + + return result; +} + +void I2C_MasterTransferCreateHandle(I2C_Type *base, + i2c_master_handle_t *handle, + i2c_master_transfer_callback_t callback, + void *userData) +{ + assert(handle); + + uint32_t instance = I2C_GetInstance(base); + + /* Zero handle. */ + memset(handle, 0, sizeof(*handle)); + + /* Set callback and userData. */ + handle->completionCallback = callback; + handle->userData = userData; + + /* Save the context in global variables to support the double weak mechanism. */ + s_i2cHandle[instance] = handle; + + /* Save master interrupt handler. */ + s_i2cMasterIsr = I2C_MasterTransferHandleIRQ; + + /* Enable NVIC interrupt. */ + EnableIRQ(s_i2cIrqs[instance]); +} + +status_t I2C_MasterTransferNonBlocking(I2C_Type *base, i2c_master_handle_t *handle, i2c_master_transfer_t *xfer) +{ + assert(handle); + assert(xfer); + + status_t result = kStatus_Success; + + /* Check if the I2C bus is idle - if not return busy status. */ + if (handle->state != kIdleState) + { + result = kStatus_I2C_Busy; + } + else + { + /* Start up the master transfer state machine. */ + result = I2C_InitTransferStateMachine(base, handle, xfer); + + if (result == kStatus_Success) + { + /* Enable the I2C interrupts. */ + I2C_EnableInterrupts(base, kI2C_GlobalInterruptEnable); + } + } + + return result; +} + +status_t I2C_MasterTransferAbort(I2C_Type *base, i2c_master_handle_t *handle) +{ + assert(handle); + + volatile uint8_t dummy = 0; +#if I2C_WAIT_TIMEOUT + uint32_t waitTimes = I2C_WAIT_TIMEOUT; +#endif + + /* Add this to avoid build warning. */ + dummy++; + + /* Disable interrupt. */ + I2C_DisableInterrupts(base, kI2C_GlobalInterruptEnable); + + /* Reset the state to idle. */ + handle->state = kIdleState; + + /* If the bus is already in use, but not by us */ + if (!(base->C1 & I2C_C1_MST_MASK)) + { + return kStatus_I2C_Busy; + } + + /* Send STOP signal. */ + if (handle->transfer.direction == kI2C_Read) + { + base->C1 |= I2C_C1_TXAK_MASK; + +#if I2C_WAIT_TIMEOUT + /* Wait until data transfer complete. */ + while ((!(base->S & kI2C_IntPendingFlag)) && (--waitTimes)) + { + } + if (waitTimes == 0) + { + return kStatus_I2C_Timeout; + } +#else + /* Wait until data transfer complete. */ + while (!(base->S & kI2C_IntPendingFlag)) + { + } +#endif + base->S = kI2C_IntPendingFlag; + + base->C1 &= ~(I2C_C1_MST_MASK | I2C_C1_TX_MASK | I2C_C1_TXAK_MASK); + dummy = base->D; + } + else + { +#if I2C_WAIT_TIMEOUT + /* Wait until data transfer complete. */ + while ((!(base->S & kI2C_IntPendingFlag)) && (--waitTimes)) + { + } + if (waitTimes == 0) + { + return kStatus_I2C_Timeout; + } +#else + /* Wait until data transfer complete. */ + while (!(base->S & kI2C_IntPendingFlag)) + { + } +#endif + base->S = kI2C_IntPendingFlag; + base->C1 &= ~(I2C_C1_MST_MASK | I2C_C1_TX_MASK | I2C_C1_TXAK_MASK); + } + + return kStatus_Success; +} + +status_t I2C_MasterTransferGetCount(I2C_Type *base, i2c_master_handle_t *handle, size_t *count) +{ + assert(handle); + + if (!count) + { + return kStatus_InvalidArgument; + } + + *count = handle->transferSize - handle->transfer.dataSize; + + return kStatus_Success; +} + +void I2C_MasterTransferHandleIRQ(I2C_Type *base, void *i2cHandle) +{ + assert(i2cHandle); + + i2c_master_handle_t *handle = (i2c_master_handle_t *)i2cHandle; + status_t result = kStatus_Success; + bool isDone; + + /* Clear the interrupt flag. */ + base->S = kI2C_IntPendingFlag; + + /* Check transfer complete flag. */ + result = I2C_MasterTransferRunStateMachine(base, handle, &isDone); + + if (isDone || result) + { + /* Send stop command if transfer done or received Nak. */ + if ((!(handle->transfer.flags & kI2C_TransferNoStopFlag)) || (result == kStatus_I2C_Nak) || + (result == kStatus_I2C_Addr_Nak)) + { + /* Ensure stop command is a need. */ + if ((base->C1 & I2C_C1_MST_MASK)) + { + if (I2C_MasterStop(base) != kStatus_Success) + { + result = kStatus_I2C_Timeout; + } + } + } + + /* Restore handle to idle state. */ + handle->state = kIdleState; + + /* Disable interrupt. */ + I2C_DisableInterrupts(base, kI2C_GlobalInterruptEnable); + + /* Call the callback function after the function has completed. */ + if (handle->completionCallback) + { + handle->completionCallback(base, handle, result, handle->userData); + } + } +} + +void I2C_SlaveInit(I2C_Type *base, const i2c_slave_config_t *slaveConfig, uint32_t srcClock_Hz) +{ + assert(slaveConfig); + + uint8_t tmpReg; + +#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) + CLOCK_EnableClock(s_i2cClocks[I2C_GetInstance(base)]); +#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */ + + /* Reset the module. */ + base->A1 = 0; + base->F = 0; + base->C1 = 0; + base->S = 0xFFU; + base->C2 = 0; +#if defined(FSL_FEATURE_I2C_HAS_START_STOP_DETECT) && FSL_FEATURE_I2C_HAS_START_STOP_DETECT + base->FLT = 0x50U; +#elif defined(FSL_FEATURE_I2C_HAS_STOP_DETECT) && FSL_FEATURE_I2C_HAS_STOP_DETECT + base->FLT = 0x40U; +#endif + base->RA = 0; + + /* Configure addressing mode. */ + switch (slaveConfig->addressingMode) + { + case kI2C_Address7bit: + base->A1 = ((uint32_t)(slaveConfig->slaveAddress)) << 1U; + break; + + case kI2C_RangeMatch: + assert(slaveConfig->slaveAddress < slaveConfig->upperAddress); + base->A1 = ((uint32_t)(slaveConfig->slaveAddress)) << 1U; + base->RA = ((uint32_t)(slaveConfig->upperAddress)) << 1U; + base->C2 |= I2C_C2_RMEN_MASK; + break; + + default: + break; + } + + /* Configure low power wake up feature. */ + tmpReg = base->C1; + tmpReg &= ~I2C_C1_WUEN_MASK; + base->C1 = tmpReg | I2C_C1_WUEN(slaveConfig->enableWakeUp) | I2C_C1_IICEN(slaveConfig->enableSlave); + + /* Configure general call & baud rate control. */ + tmpReg = base->C2; + tmpReg &= ~(I2C_C2_SBRC_MASK | I2C_C2_GCAEN_MASK); + tmpReg |= I2C_C2_SBRC(slaveConfig->enableBaudRateCtl) | I2C_C2_GCAEN(slaveConfig->enableGeneralCall); + base->C2 = tmpReg; + +/* Enable/Disable double buffering. */ +#if defined(FSL_FEATURE_I2C_HAS_DOUBLE_BUFFER_ENABLE) && FSL_FEATURE_I2C_HAS_DOUBLE_BUFFER_ENABLE + tmpReg = base->S2 & (~I2C_S2_DFEN_MASK); + base->S2 = tmpReg | I2C_S2_DFEN(slaveConfig->enableDoubleBuffering); +#endif + + /* Set hold time. */ + I2C_SetHoldTime(base, slaveConfig->sclStopHoldTime_ns, srcClock_Hz); +} + +void I2C_SlaveDeinit(I2C_Type *base) +{ + /* Disable I2C module. */ + I2C_Enable(base, false); + +#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) + /* Disable I2C clock. */ + CLOCK_DisableClock(s_i2cClocks[I2C_GetInstance(base)]); +#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */ +} + +void I2C_SlaveGetDefaultConfig(i2c_slave_config_t *slaveConfig) +{ + assert(slaveConfig); + + /* By default slave is addressed with 7-bit address. */ + slaveConfig->addressingMode = kI2C_Address7bit; + + /* General call mode is disabled by default. */ + slaveConfig->enableGeneralCall = false; + + /* Slave address match waking up MCU from low power mode is disabled. */ + slaveConfig->enableWakeUp = false; + + /* Independent slave mode baud rate at maximum frequency is disabled. */ + slaveConfig->enableBaudRateCtl = false; + +/* Default enable double buffering. */ +#if defined(FSL_FEATURE_I2C_HAS_DOUBLE_BUFFER_ENABLE) && FSL_FEATURE_I2C_HAS_DOUBLE_BUFFER_ENABLE + slaveConfig->enableDoubleBuffering = true; +#endif + + /* Set default SCL stop hold time to 4us which is minimum requirement in I2C spec. */ + slaveConfig->sclStopHoldTime_ns = 4000; + + /* Enable the I2C peripheral. */ + slaveConfig->enableSlave = true; +} + +status_t I2C_SlaveWriteBlocking(I2C_Type *base, const uint8_t *txBuff, size_t txSize) +{ + status_t result = kStatus_Success; + volatile uint8_t dummy = 0; + + /* Add this to avoid build warning. */ + dummy++; + +#if defined(FSL_FEATURE_I2C_HAS_START_STOP_DETECT) && FSL_FEATURE_I2C_HAS_START_STOP_DETECT + /* Check start flag. */ + while (!(base->FLT & I2C_FLT_STARTF_MASK)) + { + } + /* Clear STARTF flag. */ + base->FLT |= I2C_FLT_STARTF_MASK; + /* Clear the IICIF flag. */ + base->S = kI2C_IntPendingFlag; +#endif /* FSL_FEATURE_I2C_HAS_START_STOP_DETECT */ + +#if I2C_WAIT_TIMEOUT + uint32_t waitTimes = I2C_WAIT_TIMEOUT; + /* Wait until data transfer complete. */ + while ((!(base->S & kI2C_AddressMatchFlag)) && (--waitTimes)) + { + } + if (waitTimes == 0) + { + return kStatus_I2C_Timeout; + } +#else + /* Wait for address match flag. */ + while (!(base->S & kI2C_AddressMatchFlag)) + { + } +#endif + /* Read dummy to release bus. */ + dummy = base->D; + + result = I2C_MasterWriteBlocking(base, txBuff, txSize, kI2C_TransferDefaultFlag); + + /* Switch to receive mode. */ + base->C1 &= ~(I2C_C1_TX_MASK | I2C_C1_TXAK_MASK); + + /* Read dummy to release bus. */ + dummy = base->D; + + return result; +} + +status_t I2C_SlaveReadBlocking(I2C_Type *base, uint8_t *rxBuff, size_t rxSize) +{ + status_t result = kStatus_Success; + volatile uint8_t dummy = 0; + + /* Add this to avoid build warning. */ + dummy++; + +/* Wait until address match. */ +#if defined(FSL_FEATURE_I2C_HAS_START_STOP_DETECT) && FSL_FEATURE_I2C_HAS_START_STOP_DETECT + /* Check start flag. */ + while (!(base->FLT & I2C_FLT_STARTF_MASK)) + { + } + /* Clear STARTF flag. */ + base->FLT |= I2C_FLT_STARTF_MASK; + /* Clear the IICIF flag. */ + base->S = kI2C_IntPendingFlag; +#endif /* FSL_FEATURE_I2C_HAS_START_STOP_DETECT */ + +#if I2C_WAIT_TIMEOUT + uint32_t waitTimes = I2C_WAIT_TIMEOUT; + /* Wait for address match and int pending flag. */ + while ((!(base->S & kI2C_AddressMatchFlag)) && (--waitTimes)) + { + } + if (waitTimes == 0) + { + return kStatus_I2C_Timeout; + } + + waitTimes = I2C_WAIT_TIMEOUT; + while ((!(base->S & kI2C_IntPendingFlag)) && (--waitTimes)) + { + } + if (waitTimes == 0) + { + return kStatus_I2C_Timeout; + } +#else + /* Wait for address match and int pending flag. */ + while (!(base->S & kI2C_AddressMatchFlag)) + { + } + while (!(base->S & kI2C_IntPendingFlag)) + { + } +#endif + + /* Read dummy to release bus. */ + dummy = base->D; + + /* Clear the IICIF flag. */ + base->S = kI2C_IntPendingFlag; + + /* Setup the I2C peripheral to receive data. */ + base->C1 &= ~(I2C_C1_TX_MASK); + + while (rxSize--) + { +#if I2C_WAIT_TIMEOUT + waitTimes = I2C_WAIT_TIMEOUT; + /* Wait until data transfer complete. */ + while ((!(base->S & kI2C_IntPendingFlag)) && (--waitTimes)) + { + } + if (waitTimes == 0) + { + return kStatus_I2C_Timeout; + } +#else + /* Wait until data transfer complete. */ + while (!(base->S & kI2C_IntPendingFlag)) + { + } +#endif + /* Clear the IICIF flag. */ + base->S = kI2C_IntPendingFlag; + + /* Read from the data register. */ + *rxBuff++ = base->D; + } + + return result; +} + +void I2C_SlaveTransferCreateHandle(I2C_Type *base, + i2c_slave_handle_t *handle, + i2c_slave_transfer_callback_t callback, + void *userData) +{ + assert(handle); + + uint32_t instance = I2C_GetInstance(base); + + /* Zero handle. */ + memset(handle, 0, sizeof(*handle)); + + /* Set callback and userData. */ + handle->callback = callback; + handle->userData = userData; + + /* Save the context in global variables to support the double weak mechanism. */ + s_i2cHandle[instance] = handle; + + /* Save slave interrupt handler. */ + s_i2cSlaveIsr = I2C_SlaveTransferHandleIRQ; + + /* Enable NVIC interrupt. */ + EnableIRQ(s_i2cIrqs[instance]); +} + +status_t I2C_SlaveTransferNonBlocking(I2C_Type *base, i2c_slave_handle_t *handle, uint32_t eventMask) +{ + assert(handle); + + /* Check if the I2C bus is idle - if not return busy status. */ + if (handle->isBusy) + { + return kStatus_I2C_Busy; + } + else + { + /* Disable LPI2C IRQ sources while we configure stuff. */ + I2C_DisableInterrupts(base, kIrqFlags); + + /* Clear transfer in handle. */ + memset(&handle->transfer, 0, sizeof(handle->transfer)); + + /* Record that we're busy. */ + handle->isBusy = true; + + /* Set up event mask. tx and rx are always enabled. */ + handle->eventMask = eventMask | kI2C_SlaveTransmitEvent | kI2C_SlaveReceiveEvent | kI2C_SlaveGenaralcallEvent; + + /* Clear all flags. */ + I2C_SlaveClearStatusFlags(base, kClearFlags); + + /* Enable I2C internal IRQ sources. NVIC IRQ was enabled in CreateHandle() */ + I2C_EnableInterrupts(base, kIrqFlags); + } + + return kStatus_Success; +} + +void I2C_SlaveTransferAbort(I2C_Type *base, i2c_slave_handle_t *handle) +{ + assert(handle); + + if (handle->isBusy) + { + /* Disable interrupts. */ + I2C_DisableInterrupts(base, kIrqFlags); + + /* Reset transfer info. */ + memset(&handle->transfer, 0, sizeof(handle->transfer)); + + /* Reset the state to idle. */ + handle->isBusy = false; + } +} + +status_t I2C_SlaveTransferGetCount(I2C_Type *base, i2c_slave_handle_t *handle, size_t *count) +{ + assert(handle); + + if (!count) + { + return kStatus_InvalidArgument; + } + + /* Catch when there is not an active transfer. */ + if (!handle->isBusy) + { + *count = 0; + return kStatus_NoTransferInProgress; + } + + /* For an active transfer, just return the count from the handle. */ + *count = handle->transfer.transferredCount; + + return kStatus_Success; +} + +void I2C_SlaveTransferHandleIRQ(I2C_Type *base, void *i2cHandle) +{ + assert(i2cHandle); + + uint16_t status; + bool doTransmit = false; + i2c_slave_handle_t *handle = (i2c_slave_handle_t *)i2cHandle; + i2c_slave_transfer_t *xfer; + volatile uint8_t dummy = 0; + + /* Add this to avoid build warning. */ + dummy++; + + status = I2C_SlaveGetStatusFlags(base); + xfer = &(handle->transfer); + +#ifdef I2C_HAS_STOP_DETECT + /* Check stop flag. */ + if (status & kI2C_StopDetectFlag) + { + I2C_MasterClearStatusFlags(base, kI2C_StopDetectFlag); + + /* Clear the interrupt flag. */ + base->S = kI2C_IntPendingFlag; + + /* Call slave callback if this is the STOP of the transfer. */ + if (handle->isBusy) + { + xfer->event = kI2C_SlaveCompletionEvent; + xfer->completionStatus = kStatus_Success; + handle->isBusy = false; + + if ((handle->eventMask & xfer->event) && (handle->callback)) + { + handle->callback(base, xfer, handle->userData); + } + } + + if (!(status & kI2C_AddressMatchFlag)) + { + return; + } + } +#endif /* I2C_HAS_STOP_DETECT */ + +#if defined(FSL_FEATURE_I2C_HAS_START_STOP_DETECT) && FSL_FEATURE_I2C_HAS_START_STOP_DETECT + /* Check start flag. */ + if (status & kI2C_StartDetectFlag) + { + I2C_MasterClearStatusFlags(base, kI2C_StartDetectFlag); + + /* Clear the interrupt flag. */ + base->S = kI2C_IntPendingFlag; + + xfer->event = kI2C_SlaveStartEvent; + + if ((handle->eventMask & xfer->event) && (handle->callback)) + { + handle->callback(base, xfer, handle->userData); + } + + if (!(status & kI2C_AddressMatchFlag)) + { + return; + } + } +#endif /* FSL_FEATURE_I2C_HAS_START_STOP_DETECT */ + + /* Clear the interrupt flag. */ + base->S = kI2C_IntPendingFlag; + + /* Check NAK */ + if (status & kI2C_ReceiveNakFlag) + { + /* Set receive mode. */ + base->C1 &= ~(I2C_C1_TX_MASK | I2C_C1_TXAK_MASK); + + /* Read dummy. */ + dummy = base->D; + + if (handle->transfer.dataSize != 0) + { + xfer->event = kI2C_SlaveCompletionEvent; + xfer->completionStatus = kStatus_I2C_Nak; + handle->isBusy = false; + + if ((handle->eventMask & xfer->event) && (handle->callback)) + { + handle->callback(base, xfer, handle->userData); + } + } + else + { +#ifndef I2C_HAS_STOP_DETECT + xfer->event = kI2C_SlaveCompletionEvent; + xfer->completionStatus = kStatus_Success; + handle->isBusy = false; + + if ((handle->eventMask & xfer->event) && (handle->callback)) + { + handle->callback(base, xfer, handle->userData); + } +#endif /* !FSL_FEATURE_I2C_HAS_START_STOP_DETECT or !FSL_FEATURE_I2C_HAS_STOP_DETECT */ + } + } + /* Check address match. */ + else if (status & kI2C_AddressMatchFlag) + { + handle->isBusy = true; + xfer->event = kI2C_SlaveAddressMatchEvent; + + /* Slave transmit, master reading from slave. */ + if (status & kI2C_TransferDirectionFlag) + { + /* Change direction to send data. */ + base->C1 |= I2C_C1_TX_MASK; + + doTransmit = true; + } + else + { + /* Slave receive, master writing to slave. */ + base->C1 &= ~(I2C_C1_TX_MASK | I2C_C1_TXAK_MASK); + + /* Read dummy to release the bus. */ + dummy = base->D; + + if (dummy == 0) + { + xfer->event = kI2C_SlaveGenaralcallEvent; + } + } + + if ((handle->eventMask & xfer->event) && (handle->callback)) + { + handle->callback(base, xfer, handle->userData); + } + } + /* Check transfer complete flag. */ + else if (status & kI2C_TransferCompleteFlag) + { + /* Slave transmit, master reading from slave. */ + if (status & kI2C_TransferDirectionFlag) + { + doTransmit = true; + } + else + { + /* If we're out of data, invoke callback to get more. */ + if ((!xfer->data) || (!xfer->dataSize)) + { + xfer->event = kI2C_SlaveReceiveEvent; + + if (handle->callback) + { + handle->callback(base, xfer, handle->userData); + } + + /* Clear the transferred count now that we have a new buffer. */ + xfer->transferredCount = 0; + } + + /* Slave receive, master writing to slave. */ + uint8_t data = base->D; + + if (handle->transfer.dataSize) + { + /* Receive data. */ + *handle->transfer.data++ = data; + handle->transfer.dataSize--; + xfer->transferredCount++; + if (!handle->transfer.dataSize) + { +#ifndef I2C_HAS_STOP_DETECT + xfer->event = kI2C_SlaveCompletionEvent; + xfer->completionStatus = kStatus_Success; + handle->isBusy = false; + + /* Proceed receive complete event. */ + if ((handle->eventMask & xfer->event) && (handle->callback)) + { + handle->callback(base, xfer, handle->userData); + } +#endif /* !FSL_FEATURE_I2C_HAS_START_STOP_DETECT or !FSL_FEATURE_I2C_HAS_STOP_DETECT */ + } + } + } + } + else + { + /* Read dummy to release bus. */ + dummy = base->D; + } + + /* Send data if there is the need. */ + if (doTransmit) + { + /* If we're out of data, invoke callback to get more. */ + if ((!xfer->data) || (!xfer->dataSize)) + { + xfer->event = kI2C_SlaveTransmitEvent; + + if (handle->callback) + { + handle->callback(base, xfer, handle->userData); + } + + /* Clear the transferred count now that we have a new buffer. */ + xfer->transferredCount = 0; + } + + if (handle->transfer.dataSize) + { + /* Send data. */ + base->D = *handle->transfer.data++; + handle->transfer.dataSize--; + xfer->transferredCount++; + } + else + { + /* Switch to receive mode. */ + base->C1 &= ~(I2C_C1_TX_MASK | I2C_C1_TXAK_MASK); + + /* Read dummy to release bus. */ + dummy = base->D; + +#ifndef I2C_HAS_STOP_DETECT + xfer->event = kI2C_SlaveCompletionEvent; + xfer->completionStatus = kStatus_Success; + handle->isBusy = false; + + /* Proceed txdone event. */ + if ((handle->eventMask & xfer->event) && (handle->callback)) + { + handle->callback(base, xfer, handle->userData); + } +#endif /* !FSL_FEATURE_I2C_HAS_START_STOP_DETECT or !FSL_FEATURE_I2C_HAS_STOP_DETECT */ + } + } +} + +#if defined(I2C0) +void I2C0_DriverIRQHandler(void) +{ + I2C_TransferCommonIRQHandler(I2C0, s_i2cHandle[0]); +} +#endif + +#if defined(I2C1) +void I2C1_DriverIRQHandler(void) +{ + I2C_TransferCommonIRQHandler(I2C1, s_i2cHandle[1]); +} +#endif + +#if defined(I2C2) +void I2C2_DriverIRQHandler(void) +{ + I2C_TransferCommonIRQHandler(I2C2, s_i2cHandle[2]); +} +#endif + +#if defined(I2C3) +void I2C3_DriverIRQHandler(void) +{ + I2C_TransferCommonIRQHandler(I2C3, s_i2cHandle[3]); +} +#endif diff --git a/drivers/fsl_i2c.h b/drivers/fsl_i2c.h new file mode 100644 index 0000000..04e3e5e --- /dev/null +++ b/drivers/fsl_i2c.h @@ -0,0 +1,821 @@ +/* + * The Clear BSD License + * Copyright (c) 2015, 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: + * + * o Redistributions of source code must retain the above copyright notice, this list + * of conditions and the following disclaimer. + * + * o 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. + * + * o 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_I2C_H_ +#define _FSL_I2C_H_ + +#include "fsl_common.h" + +/*! + * @addtogroup i2c_driver + * @{ + */ + +/******************************************************************************* + * Definitions + ******************************************************************************/ + +/*! @name Driver version */ +/*@{*/ +/*! @brief I2C driver version 2.0.5. */ +#define FSL_I2C_DRIVER_VERSION (MAKE_VERSION(2, 0, 5)) +/*@}*/ + +/*! @brief Timeout times for waiting flag. */ +#ifndef I2C_WAIT_TIMEOUT +#define I2C_WAIT_TIMEOUT 0U /* Define to zero means keep waiting until the flag is assert/deassert. */ +#endif + +#if (defined(FSL_FEATURE_I2C_HAS_START_STOP_DETECT) && FSL_FEATURE_I2C_HAS_START_STOP_DETECT || \ + defined(FSL_FEATURE_I2C_HAS_STOP_DETECT) && FSL_FEATURE_I2C_HAS_STOP_DETECT) +#define I2C_HAS_STOP_DETECT +#endif /* FSL_FEATURE_I2C_HAS_START_STOP_DETECT / FSL_FEATURE_I2C_HAS_STOP_DETECT */ + +/*! @brief I2C status return codes. */ +enum _i2c_status +{ + kStatus_I2C_Busy = MAKE_STATUS(kStatusGroup_I2C, 0), /*!< I2C is busy with current transfer. */ + kStatus_I2C_Idle = MAKE_STATUS(kStatusGroup_I2C, 1), /*!< Bus is Idle. */ + kStatus_I2C_Nak = MAKE_STATUS(kStatusGroup_I2C, 2), /*!< NAK received during transfer. */ + kStatus_I2C_ArbitrationLost = MAKE_STATUS(kStatusGroup_I2C, 3), /*!< Arbitration lost during transfer. */ + kStatus_I2C_Timeout = MAKE_STATUS(kStatusGroup_I2C, 4), /*!< Timeout poling status flags. */ + kStatus_I2C_Addr_Nak = MAKE_STATUS(kStatusGroup_I2C, 5), /*!< NAK received during the address probe. */ +}; + +/*! + * @brief I2C peripheral flags + * + * The following status register flags can be cleared: + * - #kI2C_ArbitrationLostFlag + * - #kI2C_IntPendingFlag + * - #kI2C_StartDetectFlag + * - #kI2C_StopDetectFlag + * + * @note These enumerations are meant to be OR'd together to form a bit mask. + * + */ +enum _i2c_flags +{ + kI2C_ReceiveNakFlag = I2C_S_RXAK_MASK, /*!< I2C receive NAK flag. */ + kI2C_IntPendingFlag = I2C_S_IICIF_MASK, /*!< I2C interrupt pending flag. */ + kI2C_TransferDirectionFlag = I2C_S_SRW_MASK, /*!< I2C transfer direction flag. */ + kI2C_RangeAddressMatchFlag = I2C_S_RAM_MASK, /*!< I2C range address match flag. */ + kI2C_ArbitrationLostFlag = I2C_S_ARBL_MASK, /*!< I2C arbitration lost flag. */ + kI2C_BusBusyFlag = I2C_S_BUSY_MASK, /*!< I2C bus busy flag. */ + kI2C_AddressMatchFlag = I2C_S_IAAS_MASK, /*!< I2C address match flag. */ + kI2C_TransferCompleteFlag = I2C_S_TCF_MASK, /*!< I2C transfer complete flag. */ +#ifdef I2C_HAS_STOP_DETECT + kI2C_StopDetectFlag = I2C_FLT_STOPF_MASK << 8, /*!< I2C stop detect flag. */ +#endif /* FSL_FEATURE_I2C_HAS_START_STOP_DETECT / FSL_FEATURE_I2C_HAS_STOP_DETECT */ + +#if defined(FSL_FEATURE_I2C_HAS_START_STOP_DETECT) && FSL_FEATURE_I2C_HAS_START_STOP_DETECT + kI2C_StartDetectFlag = I2C_FLT_STARTF_MASK << 8, /*!< I2C start detect flag. */ +#endif /* FSL_FEATURE_I2C_HAS_START_STOP_DETECT */ +}; + +/*! @brief I2C feature interrupt source. */ +enum _i2c_interrupt_enable +{ + kI2C_GlobalInterruptEnable = I2C_C1_IICIE_MASK, /*!< I2C global interrupt. */ + +#if defined(FSL_FEATURE_I2C_HAS_STOP_DETECT) && FSL_FEATURE_I2C_HAS_STOP_DETECT + kI2C_StopDetectInterruptEnable = I2C_FLT_STOPIE_MASK, /*!< I2C stop detect interrupt. */ +#endif /* FSL_FEATURE_I2C_HAS_STOP_DETECT */ + +#if defined(FSL_FEATURE_I2C_HAS_START_STOP_DETECT) && FSL_FEATURE_I2C_HAS_START_STOP_DETECT + kI2C_StartStopDetectInterruptEnable = I2C_FLT_SSIE_MASK, /*!< I2C start&stop detect interrupt. */ +#endif /* FSL_FEATURE_I2C_HAS_START_STOP_DETECT */ +}; + +/*! @brief The direction of master and slave transfers. */ +typedef enum _i2c_direction +{ + kI2C_Write = 0x0U, /*!< Master transmits to the slave. */ + kI2C_Read = 0x1U, /*!< Master receives from the slave. */ +} i2c_direction_t; + +/*! @brief Addressing mode. */ +typedef enum _i2c_slave_address_mode +{ + kI2C_Address7bit = 0x0U, /*!< 7-bit addressing mode. */ + kI2C_RangeMatch = 0X2U, /*!< Range address match addressing mode. */ +} i2c_slave_address_mode_t; + +/*! @brief I2C transfer control flag. */ +enum _i2c_master_transfer_flags +{ + kI2C_TransferDefaultFlag = 0x0U, /*!< A transfer starts with a start signal, stops with a stop signal. */ + kI2C_TransferNoStartFlag = 0x1U, /*!< A transfer starts without a start signal, only support write only or + write+read with no start flag, do not support read only with no start flag. */ + kI2C_TransferRepeatedStartFlag = 0x2U, /*!< A transfer starts with a repeated start signal. */ + kI2C_TransferNoStopFlag = 0x4U, /*!< A transfer ends without a stop signal. */ +}; + +/*! + * @brief Set of events sent to the callback for nonblocking slave transfers. + * + * These event enumerations are used for two related purposes. First, a bit mask created by OR'ing together + * events is passed to I2C_SlaveTransferNonBlocking() to specify which events to enable. + * Then, when the slave callback is invoked, it is passed the current event through its @a transfer + * parameter. + * + * @note These enumerations are meant to be OR'd together to form a bit mask of events. + */ +typedef enum _i2c_slave_transfer_event +{ + kI2C_SlaveAddressMatchEvent = 0x01U, /*!< Received the slave address after a start or repeated start. */ + kI2C_SlaveTransmitEvent = 0x02U, /*!< A callback is requested to provide data to transmit + (slave-transmitter role). */ + kI2C_SlaveReceiveEvent = 0x04U, /*!< A callback is requested to provide a buffer in which to place received + data (slave-receiver role). */ + kI2C_SlaveTransmitAckEvent = 0x08U, /*!< A callback needs to either transmit an ACK or NACK. */ +#if defined(FSL_FEATURE_I2C_HAS_START_STOP_DETECT) && FSL_FEATURE_I2C_HAS_START_STOP_DETECT + kI2C_SlaveStartEvent = 0x10U, /*!< A start/repeated start was detected. */ +#endif + kI2C_SlaveCompletionEvent = 0x20U, /*!< A stop was detected or finished transfer, completing the transfer. */ + kI2C_SlaveGenaralcallEvent = 0x40U, /*!< Received the general call address after a start or repeated start. */ + + /*! A bit mask of all available events. */ + kI2C_SlaveAllEvents = kI2C_SlaveAddressMatchEvent | kI2C_SlaveTransmitEvent | kI2C_SlaveReceiveEvent | +#if defined(FSL_FEATURE_I2C_HAS_START_STOP_DETECT) && FSL_FEATURE_I2C_HAS_START_STOP_DETECT + kI2C_SlaveStartEvent | +#endif + kI2C_SlaveCompletionEvent | kI2C_SlaveGenaralcallEvent, +} i2c_slave_transfer_event_t; + +/*! @brief I2C master user configuration. */ +typedef struct _i2c_master_config +{ + bool enableMaster; /*!< Enables the I2C peripheral at initialization time. */ +#if defined(FSL_FEATURE_I2C_HAS_STOP_HOLD_OFF) && FSL_FEATURE_I2C_HAS_STOP_HOLD_OFF + bool enableStopHold; /*!< Controls the stop hold enable. */ +#endif +#if defined(FSL_FEATURE_I2C_HAS_DOUBLE_BUFFER_ENABLE) && FSL_FEATURE_I2C_HAS_DOUBLE_BUFFER_ENABLE + bool enableDoubleBuffering; /*!< Controls double buffer enable; notice that + enabling the double buffer disables the clock stretch. */ +#endif + uint32_t baudRate_Bps; /*!< Baud rate configuration of I2C peripheral. */ + uint8_t glitchFilterWidth; /*!< Controls the width of the glitch. */ +} i2c_master_config_t; + +/*! @brief I2C slave user configuration. */ +typedef struct _i2c_slave_config +{ + bool enableSlave; /*!< Enables the I2C peripheral at initialization time. */ + bool enableGeneralCall; /*!< Enables the general call addressing mode. */ + bool enableWakeUp; /*!< Enables/disables waking up MCU from low-power mode. */ +#if defined(FSL_FEATURE_I2C_HAS_DOUBLE_BUFFER_ENABLE) && FSL_FEATURE_I2C_HAS_DOUBLE_BUFFER_ENABLE + bool enableDoubleBuffering; /*!< Controls a double buffer enable; notice that + enabling the double buffer disables the clock stretch. */ +#endif + bool enableBaudRateCtl; /*!< Enables/disables independent slave baud rate on SCL in very fast I2C modes. */ + uint16_t slaveAddress; /*!< A slave address configuration. */ + uint16_t upperAddress; /*!< A maximum boundary slave address used in a range matching mode. */ + i2c_slave_address_mode_t + addressingMode; /*!< An addressing mode configuration of i2c_slave_address_mode_config_t. */ + uint32_t sclStopHoldTime_ns; /*!< the delay from the rising edge of SCL (I2C clock) to the rising edge of SDA (I2C + data) while SCL is high (stop condition), SDA hold time and SCL start hold time + are also configured according to the SCL stop hold time. */ +} i2c_slave_config_t; + +/*! @brief I2C master handle typedef. */ +typedef struct _i2c_master_handle i2c_master_handle_t; + +/*! @brief I2C master transfer callback typedef. */ +typedef void (*i2c_master_transfer_callback_t)(I2C_Type *base, + i2c_master_handle_t *handle, + status_t status, + void *userData); + +/*! @brief I2C slave handle typedef. */ +typedef struct _i2c_slave_handle i2c_slave_handle_t; + +/*! @brief I2C master transfer structure. */ +typedef struct _i2c_master_transfer +{ + uint32_t flags; /*!< A transfer flag which controls the transfer. */ + uint8_t slaveAddress; /*!< 7-bit slave address. */ + i2c_direction_t direction; /*!< A transfer direction, read or write. */ + uint32_t subaddress; /*!< A sub address. Transferred MSB first. */ + uint8_t subaddressSize; /*!< A size of the command buffer. */ + uint8_t *volatile data; /*!< A transfer buffer. */ + volatile size_t dataSize; /*!< A transfer size. */ +} i2c_master_transfer_t; + +/*! @brief I2C master handle structure. */ +struct _i2c_master_handle +{ + i2c_master_transfer_t transfer; /*!< I2C master transfer copy. */ + size_t transferSize; /*!< Total bytes to be transferred. */ + uint8_t state; /*!< A transfer state maintained during transfer. */ + i2c_master_transfer_callback_t completionCallback; /*!< A callback function called when the transfer is finished. */ + void *userData; /*!< A callback parameter passed to the callback function. */ +}; + +/*! @brief I2C slave transfer structure. */ +typedef struct _i2c_slave_transfer +{ + i2c_slave_transfer_event_t event; /*!< A reason that the callback is invoked. */ + uint8_t *volatile data; /*!< A transfer buffer. */ + volatile size_t dataSize; /*!< A transfer size. */ + status_t completionStatus; /*!< Success or error code describing how the transfer completed. Only applies for + #kI2C_SlaveCompletionEvent. */ + size_t transferredCount; /*!< A number of bytes actually transferred since the start or since the last repeated + start. */ +} i2c_slave_transfer_t; + +/*! @brief I2C slave transfer callback typedef. */ +typedef void (*i2c_slave_transfer_callback_t)(I2C_Type *base, i2c_slave_transfer_t *xfer, void *userData); + +/*! @brief I2C slave handle structure. */ +struct _i2c_slave_handle +{ + volatile bool isBusy; /*!< Indicates whether a transfer is busy. */ + i2c_slave_transfer_t transfer; /*!< I2C slave transfer copy. */ + uint32_t eventMask; /*!< A mask of enabled events. */ + i2c_slave_transfer_callback_t callback; /*!< A callback function called at the transfer event. */ + void *userData; /*!< A callback parameter passed to the callback. */ +}; + +/******************************************************************************* + * Variables + ******************************************************************************/ +/*! @brief Pointers to i2c bases for each instance. */ +extern I2C_Type *const s_i2cBases[]; + +/******************************************************************************* + * API + ******************************************************************************/ + +#if defined(__cplusplus) +extern "C" { +#endif /*_cplusplus. */ + +/*! + * @name Initialization and deinitialization + * @{ + */ + +/*! + * @brief Initializes the I2C peripheral. Call this API to ungate the I2C clock + * and configure the I2C with master configuration. + * + * @note This API should be called at the beginning of the application. + * Otherwise, any operation to the I2C module can cause a hard fault + * because the clock is not enabled. The configuration structure can be custom filled + * or it can be set with default values by using the I2C_MasterGetDefaultConfig(). + * After calling this API, the master is ready to transfer. + * This is an example. + * @code + * i2c_master_config_t config = { + * .enableMaster = true, + * .enableStopHold = false, + * .highDrive = false, + * .baudRate_Bps = 100000, + * .glitchFilterWidth = 0 + * }; + * I2C_MasterInit(I2C0, &config, 12000000U); + * @endcode + * + * @param base I2C base pointer + * @param masterConfig A pointer to the master configuration structure + * @param srcClock_Hz I2C peripheral clock frequency in Hz + */ +void I2C_MasterInit(I2C_Type *base, const i2c_master_config_t *masterConfig, uint32_t srcClock_Hz); + +/*! + * @brief Initializes the I2C peripheral. Call this API to ungate the I2C clock + * and initialize the I2C with the slave configuration. + * + * @note This API should be called at the beginning of the application. + * Otherwise, any operation to the I2C module can cause a hard fault + * because the clock is not enabled. The configuration structure can partly be set + * with default values by I2C_SlaveGetDefaultConfig() or it can be custom filled by the user. + * This is an example. + * @code + * i2c_slave_config_t config = { + * .enableSlave = true, + * .enableGeneralCall = false, + * .addressingMode = kI2C_Address7bit, + * .slaveAddress = 0x1DU, + * .enableWakeUp = false, + * .enablehighDrive = false, + * .enableBaudRateCtl = false, + * .sclStopHoldTime_ns = 4000 + * }; + * I2C_SlaveInit(I2C0, &config, 12000000U); + * @endcode + * + * @param base I2C base pointer + * @param slaveConfig A pointer to the slave configuration structure + * @param srcClock_Hz I2C peripheral clock frequency in Hz + */ +void I2C_SlaveInit(I2C_Type *base, const i2c_slave_config_t *slaveConfig, uint32_t srcClock_Hz); + +/*! + * @brief De-initializes the I2C master peripheral. Call this API to gate the I2C clock. + * The I2C master module can't work unless the I2C_MasterInit is called. + * @param base I2C base pointer + */ +void I2C_MasterDeinit(I2C_Type *base); + +/*! + * @brief De-initializes the I2C slave peripheral. Calling this API gates the I2C clock. + * The I2C slave module can't work unless the I2C_SlaveInit is called to enable the clock. + * @param base I2C base pointer + */ +void I2C_SlaveDeinit(I2C_Type *base); + +/*! + * @brief Get instance number for I2C module. + * + * @param base I2C peripheral base address. + */ +uint32_t I2C_GetInstance(I2C_Type *base); + +/*! + * @brief Sets the I2C master configuration structure to default values. + * + * The purpose of this API is to get the configuration structure initialized for use in the I2C_MasterConfigure(). + * Use the initialized structure unchanged in the I2C_MasterConfigure() or modify + * the structure before calling the I2C_MasterConfigure(). + * This is an example. + * @code + * i2c_master_config_t config; + * I2C_MasterGetDefaultConfig(&config); + * @endcode + * @param masterConfig A pointer to the master configuration structure. +*/ +void I2C_MasterGetDefaultConfig(i2c_master_config_t *masterConfig); + +/*! + * @brief Sets the I2C slave configuration structure to default values. + * + * The purpose of this API is to get the configuration structure initialized for use in the I2C_SlaveConfigure(). + * Modify fields of the structure before calling the I2C_SlaveConfigure(). + * This is an example. + * @code + * i2c_slave_config_t config; + * I2C_SlaveGetDefaultConfig(&config); + * @endcode + * @param slaveConfig A pointer to the slave configuration structure. + */ +void I2C_SlaveGetDefaultConfig(i2c_slave_config_t *slaveConfig); + +/*! + * @brief Enables or disabless the I2C peripheral operation. + * + * @param base I2C base pointer + * @param enable Pass true to enable and false to disable the module. + */ +static inline void I2C_Enable(I2C_Type *base, bool enable) +{ + if (enable) + { + base->C1 |= I2C_C1_IICEN_MASK; + } + else + { + base->C1 &= ~I2C_C1_IICEN_MASK; + } +} + +/* @} */ + +/*! + * @name Status + * @{ + */ + +/*! + * @brief Gets the I2C status flags. + * + * @param base I2C base pointer + * @return status flag, use status flag to AND #_i2c_flags to get the related status. + */ +uint32_t I2C_MasterGetStatusFlags(I2C_Type *base); + +/*! + * @brief Gets the I2C status flags. + * + * @param base I2C base pointer + * @return status flag, use status flag to AND #_i2c_flags to get the related status. + */ +static inline uint32_t I2C_SlaveGetStatusFlags(I2C_Type *base) +{ + return I2C_MasterGetStatusFlags(base); +} + +/*! + * @brief Clears the I2C status flag state. + * + * The following status register flags can be cleared kI2C_ArbitrationLostFlag and kI2C_IntPendingFlag. + * + * @param base I2C base pointer + * @param statusMask The status flag mask, defined in type i2c_status_flag_t. + * The parameter can be any combination of the following values: + * @arg kI2C_StartDetectFlag (if available) + * @arg kI2C_StopDetectFlag (if available) + * @arg kI2C_ArbitrationLostFlag + * @arg kI2C_IntPendingFlagFlag + */ +static inline void I2C_MasterClearStatusFlags(I2C_Type *base, uint32_t statusMask) +{ +/* Must clear the STARTF / STOPF bits prior to clearing IICIF */ +#if defined(FSL_FEATURE_I2C_HAS_START_STOP_DETECT) && FSL_FEATURE_I2C_HAS_START_STOP_DETECT + if (statusMask & kI2C_StartDetectFlag) + { + /* Shift the odd-ball flags back into place. */ + base->FLT |= (uint8_t)(statusMask >> 8U); + } +#endif + +#ifdef I2C_HAS_STOP_DETECT + if (statusMask & kI2C_StopDetectFlag) + { + /* Shift the odd-ball flags back into place. */ + base->FLT |= (uint8_t)(statusMask >> 8U); + } +#endif + + base->S = (uint8_t)statusMask; +} + +/*! + * @brief Clears the I2C status flag state. + * + * The following status register flags can be cleared kI2C_ArbitrationLostFlag and kI2C_IntPendingFlag + * + * @param base I2C base pointer + * @param statusMask The status flag mask, defined in type i2c_status_flag_t. + * The parameter can be any combination of the following values: + * @arg kI2C_StartDetectFlag (if available) + * @arg kI2C_StopDetectFlag (if available) + * @arg kI2C_ArbitrationLostFlag + * @arg kI2C_IntPendingFlagFlag + */ +static inline void I2C_SlaveClearStatusFlags(I2C_Type *base, uint32_t statusMask) +{ + I2C_MasterClearStatusFlags(base, statusMask); +} + +/* @} */ + +/*! + * @name Interrupts + * @{ + */ + +/*! + * @brief Enables I2C interrupt requests. + * + * @param base I2C base pointer + * @param mask interrupt source + * The parameter can be combination of the following source if defined: + * @arg kI2C_GlobalInterruptEnable + * @arg kI2C_StopDetectInterruptEnable/kI2C_StartDetectInterruptEnable + * @arg kI2C_SdaTimeoutInterruptEnable + */ +void I2C_EnableInterrupts(I2C_Type *base, uint32_t mask); + +/*! + * @brief Disables I2C interrupt requests. + * + * @param base I2C base pointer + * @param mask interrupt source + * The parameter can be combination of the following source if defined: + * @arg kI2C_GlobalInterruptEnable + * @arg kI2C_StopDetectInterruptEnable/kI2C_StartDetectInterruptEnable + * @arg kI2C_SdaTimeoutInterruptEnable + */ +void I2C_DisableInterrupts(I2C_Type *base, uint32_t mask); + +/*! + * @name DMA Control + * @{ + */ +#if defined(FSL_FEATURE_I2C_HAS_DMA_SUPPORT) && FSL_FEATURE_I2C_HAS_DMA_SUPPORT +/*! + * @brief Enables/disables the I2C DMA interrupt. + * + * @param base I2C base pointer + * @param enable true to enable, false to disable +*/ +static inline void I2C_EnableDMA(I2C_Type *base, bool enable) +{ + if (enable) + { + base->C1 |= I2C_C1_DMAEN_MASK; + } + else + { + base->C1 &= ~I2C_C1_DMAEN_MASK; + } +} + +#endif /* FSL_FEATURE_I2C_HAS_DMA_SUPPORT */ + +/*! + * @brief Gets the I2C tx/rx data register address. This API is used to provide a transfer address + * for I2C DMA transfer configuration. + * + * @param base I2C base pointer + * @return data register address + */ +static inline uint32_t I2C_GetDataRegAddr(I2C_Type *base) +{ + return (uint32_t)(&(base->D)); +} + +/* @} */ +/*! + * @name Bus Operations + * @{ + */ + +/*! + * @brief Sets the I2C master transfer baud rate. + * + * @param base I2C base pointer + * @param baudRate_Bps the baud rate value in bps + * @param srcClock_Hz Source clock + */ +void I2C_MasterSetBaudRate(I2C_Type *base, uint32_t baudRate_Bps, uint32_t srcClock_Hz); + +/*! + * @brief Sends a START on the I2C bus. + * + * This function is used to initiate a new master mode transfer by sending the START signal. + * The slave address is sent following the I2C START signal. + * + * @param base I2C peripheral base pointer + * @param address 7-bit slave device address. + * @param direction Master transfer directions(transmit/receive). + * @retval kStatus_Success Successfully send the start signal. + * @retval kStatus_I2C_Busy Current bus is busy. + */ +status_t I2C_MasterStart(I2C_Type *base, uint8_t address, i2c_direction_t direction); + +/*! + * @brief Sends a STOP signal on the I2C bus. + * + * @retval kStatus_Success Successfully send the stop signal. + * @retval kStatus_I2C_Timeout Send stop signal failed, timeout. + */ +status_t I2C_MasterStop(I2C_Type *base); + +/*! + * @brief Sends a REPEATED START on the I2C bus. + * + * @param base I2C peripheral base pointer + * @param address 7-bit slave device address. + * @param direction Master transfer directions(transmit/receive). + * @retval kStatus_Success Successfully send the start signal. + * @retval kStatus_I2C_Busy Current bus is busy but not occupied by current I2C master. + */ +status_t I2C_MasterRepeatedStart(I2C_Type *base, uint8_t address, i2c_direction_t direction); + +/*! + * @brief Performs a polling send transaction on the I2C bus. + * + * @param base The I2C peripheral base pointer. + * @param txBuff The pointer to the data to be transferred. + * @param txSize The length in bytes of the data to be transferred. + * @param flags Transfer control flag to decide whether need to send a stop, use kI2C_TransferDefaultFlag +* to issue a stop and kI2C_TransferNoStop to not send a stop. + * @retval kStatus_Success Successfully complete the data transmission. + * @retval kStatus_I2C_ArbitrationLost Transfer error, arbitration lost. + * @retval kStataus_I2C_Nak Transfer error, receive NAK during transfer. + */ +status_t I2C_MasterWriteBlocking(I2C_Type *base, const uint8_t *txBuff, size_t txSize, uint32_t flags); + +/*! + * @brief Performs a polling receive transaction on the I2C bus. + * + * @note The I2C_MasterReadBlocking function stops the bus before reading the final byte. + * Without stopping the bus prior for the final read, the bus issues another read, resulting + * in garbage data being read into the data register. + * + * @param base I2C peripheral base pointer. + * @param rxBuff The pointer to the data to store the received data. + * @param rxSize The length in bytes of the data to be received. + * @param flags Transfer control flag to decide whether need to send a stop, use kI2C_TransferDefaultFlag +* to issue a stop and kI2C_TransferNoStop to not send a stop. + * @retval kStatus_Success Successfully complete the data transmission. + * @retval kStatus_I2C_Timeout Send stop signal failed, timeout. + */ +status_t I2C_MasterReadBlocking(I2C_Type *base, uint8_t *rxBuff, size_t rxSize, uint32_t flags); + +/*! + * @brief Performs a polling send transaction on the I2C bus. + * + * @param base The I2C peripheral base pointer. + * @param txBuff The pointer to the data to be transferred. + * @param txSize The length in bytes of the data to be transferred. + * @retval kStatus_Success Successfully complete the data transmission. + * @retval kStatus_I2C_ArbitrationLost Transfer error, arbitration lost. + * @retval kStataus_I2C_Nak Transfer error, receive NAK during transfer. + */ +status_t I2C_SlaveWriteBlocking(I2C_Type *base, const uint8_t *txBuff, size_t txSize); + +/*! + * @brief Performs a polling receive transaction on the I2C bus. + * + * @param base I2C peripheral base pointer. + * @param rxBuff The pointer to the data to store the received data. + * @param rxSize The length in bytes of the data to be received. + * @retval kStatus_Success Successfully complete data receive. + * @retval kStatus_I2C_Timeout Wait status flag timeout. + */ +status_t I2C_SlaveReadBlocking(I2C_Type *base, uint8_t *rxBuff, size_t rxSize); + +/*! + * @brief Performs a master polling transfer on the I2C bus. + * + * @note The API does not return until the transfer succeeds or fails due + * to arbitration lost or receiving a NAK. + * + * @param base I2C peripheral base address. + * @param xfer Pointer to the transfer structure. + * @retval kStatus_Success Successfully complete the data transmission. + * @retval kStatus_I2C_Busy Previous transmission still not finished. + * @retval kStatus_I2C_Timeout Transfer error, wait signal timeout. + * @retval kStatus_I2C_ArbitrationLost Transfer error, arbitration lost. + * @retval kStataus_I2C_Nak Transfer error, receive NAK during transfer. + */ +status_t I2C_MasterTransferBlocking(I2C_Type *base, i2c_master_transfer_t *xfer); + +/* @} */ + +/*! + * @name Transactional + * @{ + */ + +/*! + * @brief Initializes the I2C handle which is used in transactional functions. + * + * @param base I2C base pointer. + * @param handle pointer to i2c_master_handle_t structure to store the transfer state. + * @param callback pointer to user callback function. + * @param userData user parameter passed to the callback function. + */ +void I2C_MasterTransferCreateHandle(I2C_Type *base, + i2c_master_handle_t *handle, + i2c_master_transfer_callback_t callback, + void *userData); + +/*! + * @brief Performs a master interrupt non-blocking transfer on the I2C bus. + * + * @note Calling the API returns immediately after transfer initiates. The user needs + * to call I2C_MasterGetTransferCount to poll the transfer status to check whether + * the transfer is finished. If the return status is not kStatus_I2C_Busy, the transfer + * is finished. + * + * @param base I2C base pointer. + * @param handle pointer to i2c_master_handle_t structure which stores the transfer state. + * @param xfer pointer to i2c_master_transfer_t structure. + * @retval kStatus_Success Successfully start the data transmission. + * @retval kStatus_I2C_Busy Previous transmission still not finished. + * @retval kStatus_I2C_Timeout Transfer error, wait signal timeout. + */ +status_t I2C_MasterTransferNonBlocking(I2C_Type *base, i2c_master_handle_t *handle, i2c_master_transfer_t *xfer); + +/*! + * @brief Gets the master transfer status during a interrupt non-blocking transfer. + * + * @param base I2C base pointer. + * @param handle pointer to i2c_master_handle_t structure which stores the transfer state. + * @param count Number of bytes transferred so far by the non-blocking transaction. + * @retval kStatus_InvalidArgument count is Invalid. + * @retval kStatus_Success Successfully return the count. + */ +status_t I2C_MasterTransferGetCount(I2C_Type *base, i2c_master_handle_t *handle, size_t *count); + +/*! + * @brief Aborts an interrupt non-blocking transfer early. + * + * @note This API can be called at any time when an interrupt non-blocking transfer initiates + * to abort the transfer early. + * + * @param base I2C base pointer. + * @param handle pointer to i2c_master_handle_t structure which stores the transfer state + * @retval kStatus_I2C_Timeout Timeout during polling flag. + * @retval kStatus_Success Successfully abort the transfer. + */ +status_t I2C_MasterTransferAbort(I2C_Type *base, i2c_master_handle_t *handle); + +/*! + * @brief Master interrupt handler. + * + * @param base I2C base pointer. + * @param i2cHandle pointer to i2c_master_handle_t structure. + */ +void I2C_MasterTransferHandleIRQ(I2C_Type *base, void *i2cHandle); + +/*! + * @brief Initializes the I2C handle which is used in transactional functions. + * + * @param base I2C base pointer. + * @param handle pointer to i2c_slave_handle_t structure to store the transfer state. + * @param callback pointer to user callback function. + * @param userData user parameter passed to the callback function. + */ +void I2C_SlaveTransferCreateHandle(I2C_Type *base, + i2c_slave_handle_t *handle, + i2c_slave_transfer_callback_t callback, + void *userData); + +/*! + * @brief Starts accepting slave transfers. + * + * Call this API after calling the I2C_SlaveInit() and I2C_SlaveTransferCreateHandle() to start processing + * transactions driven by an I2C master. The slave monitors the I2C bus and passes events to the + * callback that was passed into the call to I2C_SlaveTransferCreateHandle(). The callback is always invoked + * from the interrupt context. + * + * The set of events received by the callback is customizable. To do so, set the @a eventMask parameter to + * the OR'd combination of #i2c_slave_transfer_event_t enumerators for the events you wish to receive. + * The #kI2C_SlaveTransmitEvent and #kLPI2C_SlaveReceiveEvent events are always enabled and do not need + * to be included in the mask. Alternatively, pass 0 to get a default set of only the transmit and + * receive events that are always enabled. In addition, the #kI2C_SlaveAllEvents constant is provided as + * a convenient way to enable all events. + * + * @param base The I2C peripheral base address. + * @param handle Pointer to #i2c_slave_handle_t structure which stores the transfer state. + * @param eventMask Bit mask formed by OR'ing together #i2c_slave_transfer_event_t enumerators to specify + * which events to send to the callback. Other accepted values are 0 to get a default set of + * only the transmit and receive events, and #kI2C_SlaveAllEvents to enable all events. + * + * @retval #kStatus_Success Slave transfers were successfully started. + * @retval #kStatus_I2C_Busy Slave transfers have already been started on this handle. + */ +status_t I2C_SlaveTransferNonBlocking(I2C_Type *base, i2c_slave_handle_t *handle, uint32_t eventMask); + +/*! + * @brief Aborts the slave transfer. + * + * @note This API can be called at any time to stop slave for handling the bus events. + * + * @param base I2C base pointer. + * @param handle pointer to i2c_slave_handle_t structure which stores the transfer state. + */ +void I2C_SlaveTransferAbort(I2C_Type *base, i2c_slave_handle_t *handle); + +/*! + * @brief Gets the slave transfer remaining bytes during a interrupt non-blocking transfer. + * + * @param base I2C base pointer. + * @param handle pointer to i2c_slave_handle_t structure. + * @param count Number of bytes transferred so far by the non-blocking transaction. + * @retval kStatus_InvalidArgument count is Invalid. + * @retval kStatus_Success Successfully return the count. + */ +status_t I2C_SlaveTransferGetCount(I2C_Type *base, i2c_slave_handle_t *handle, size_t *count); + +/*! + * @brief Slave interrupt handler. + * + * @param base I2C base pointer. + * @param i2cHandle pointer to i2c_slave_handle_t structure which stores the transfer state + */ +void I2C_SlaveTransferHandleIRQ(I2C_Type *base, void *i2cHandle); + +/* @} */ +#if defined(__cplusplus) +} +#endif /*_cplusplus. */ +/*@}*/ + +#endif /* _FSL_I2C_H_*/ diff --git a/drivers/fsl_i2c_edma.c b/drivers/fsl_i2c_edma.c new file mode 100644 index 0000000..6671149 --- /dev/null +++ b/drivers/fsl_i2c_edma.c @@ -0,0 +1,570 @@ +/* + * The Clear BSD License + * Copyright (c) 2015, 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: + * + * o Redistributions of source code must retain the above copyright notice, this list + * of conditions and the following disclaimer. + * + * o 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. + * + * o 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. + */ + +#include "fsl_i2c_edma.h" + +/******************************************************************************* + * Definitions + ******************************************************************************/ + +/* Component ID definition, used by tools. */ +#ifndef FSL_COMPONENT_ID +#define FSL_COMPONENT_ID "platform.drivers.i2c_edma" +#endif + + +/*base, false); + + /* Send stop if kI2C_TransferNoStop flag is not asserted. */ + if (!(i2cPrivateHandle->handle->transfer.flags & kI2C_TransferNoStopFlag)) + { + if (i2cPrivateHandle->handle->transfer.direction == kI2C_Read) + { + /* Change to send NAK at the last byte. */ + i2cPrivateHandle->base->C1 |= I2C_C1_TXAK_MASK; + + /* Wait the last data to be received. */ + while (!(i2cPrivateHandle->base->S & kI2C_TransferCompleteFlag)) + { + } + + /* Send stop signal. */ + result = I2C_MasterStop(i2cPrivateHandle->base); + + /* Read the last data byte. */ + *(i2cPrivateHandle->handle->transfer.data + i2cPrivateHandle->handle->transfer.dataSize - 1) = + i2cPrivateHandle->base->D; + } + else + { + /* Wait the last data to be sent. */ + while (!(i2cPrivateHandle->base->S & kI2C_TransferCompleteFlag)) + { + } + + /* Send stop signal. */ + result = I2C_MasterStop(i2cPrivateHandle->base); + } + } + else + { + if (i2cPrivateHandle->handle->transfer.direction == kI2C_Read) + { + /* Change to send NAK at the last byte. */ + i2cPrivateHandle->base->C1 |= I2C_C1_TXAK_MASK; + + /* Wait the last data to be received. */ + while (!(i2cPrivateHandle->base->S & kI2C_TransferCompleteFlag)) + { + } + + /* Change direction to send. */ + i2cPrivateHandle->base->C1 |= I2C_C1_TX_MASK; + + /* Read the last data byte. */ + *(i2cPrivateHandle->handle->transfer.data + i2cPrivateHandle->handle->transfer.dataSize - 1) = + i2cPrivateHandle->base->D; + } + } + + i2cPrivateHandle->handle->state = kIdleState; + + if (i2cPrivateHandle->handle->completionCallback) + { + i2cPrivateHandle->handle->completionCallback(i2cPrivateHandle->base, i2cPrivateHandle->handle, result, + i2cPrivateHandle->handle->userData); + } +} + +static status_t I2C_CheckAndClearError(I2C_Type *base, uint32_t status) +{ + status_t result = kStatus_Success; + + /* Check arbitration lost. */ + if (status & kI2C_ArbitrationLostFlag) + { + /* Clear arbitration lost flag. */ + base->S = kI2C_ArbitrationLostFlag; + result = kStatus_I2C_ArbitrationLost; + } + /* Check NAK */ + else if (status & kI2C_ReceiveNakFlag) + { + result = kStatus_I2C_Nak; + } + else + { + } + + return result; +} + +static status_t I2C_InitTransferStateMachineEDMA(I2C_Type *base, + i2c_master_edma_handle_t *handle, + i2c_master_transfer_t *xfer) +{ + assert(handle); + assert(xfer); + + status_t result = kStatus_Success; + + if (handle->state != kIdleState) + { + return kStatus_I2C_Busy; + } + else + { + i2c_direction_t direction = xfer->direction; + + /* Init the handle member. */ + handle->transfer = *xfer; + + /* Save total transfer size. */ + handle->transferSize = xfer->dataSize; + + handle->state = kTransferDataState; + + /* Clear all status before transfer. */ + I2C_MasterClearStatusFlags(base, kClearFlags); + + /* Change to send write address when it's a read operation with command. */ + if ((xfer->subaddressSize > 0) && (xfer->direction == kI2C_Read)) + { + direction = kI2C_Write; + } + + /* If repeated start is requested, send repeated start. */ + if (handle->transfer.flags & kI2C_TransferRepeatedStartFlag) + { + result = I2C_MasterRepeatedStart(base, handle->transfer.slaveAddress, direction); + } + else /* For normal transfer, send start. */ + { + result = I2C_MasterStart(base, handle->transfer.slaveAddress, direction); + } + + if (result) + { + return result; + } + + while (!(base->S & kI2C_IntPendingFlag)) + { + } + + /* Check if there's transfer error. */ + result = I2C_CheckAndClearError(base, base->S); + + /* Return if error. */ + if (result) + { + if (result == kStatus_I2C_Nak) + { + result = kStatus_I2C_Addr_Nak; + + if (I2C_MasterStop(base) != kStatus_Success) + { + result = kStatus_I2C_Timeout; + } + + if (handle->completionCallback) + { + (handle->completionCallback)(base, handle, result, handle->userData); + } + } + + return result; + } + + /* Send subaddress. */ + if (handle->transfer.subaddressSize) + { + do + { + /* Clear interrupt pending flag. */ + base->S = kI2C_IntPendingFlag; + + handle->transfer.subaddressSize--; + base->D = ((handle->transfer.subaddress) >> (8 * handle->transfer.subaddressSize)); + + /* Wait until data transfer complete. */ + while (!(base->S & kI2C_IntPendingFlag)) + { + } + + /* Check if there's transfer error. */ + result = I2C_CheckAndClearError(base, base->S); + + if (result) + { + return result; + } + + } while (handle->transfer.subaddressSize > 0); + + if (handle->transfer.direction == kI2C_Read) + { + /* Clear pending flag. */ + base->S = kI2C_IntPendingFlag; + + /* Send repeated start and slave address. */ + result = I2C_MasterRepeatedStart(base, handle->transfer.slaveAddress, kI2C_Read); + + if (result) + { + return result; + } + + /* Wait until data transfer complete. */ + while (!(base->S & kI2C_IntPendingFlag)) + { + } + + /* Check if there's transfer error. */ + result = I2C_CheckAndClearError(base, base->S); + + if (result) + { + return result; + } + } + } + + /* Clear pending flag. */ + base->S = kI2C_IntPendingFlag; + } + + return result; +} + +static void I2C_MasterTransferEDMAConfig(I2C_Type *base, i2c_master_edma_handle_t *handle) +{ + edma_transfer_config_t transfer_config; + + if (handle->transfer.direction == kI2C_Read) + { + transfer_config.srcAddr = (uint32_t)I2C_GetDataRegAddr(base); + transfer_config.destAddr = (uint32_t)(handle->transfer.data); + transfer_config.majorLoopCounts = (handle->transfer.dataSize - 1); + transfer_config.srcTransferSize = kEDMA_TransferSize1Bytes; + transfer_config.srcOffset = 0; + transfer_config.destTransferSize = kEDMA_TransferSize1Bytes; + transfer_config.destOffset = 1; + transfer_config.minorLoopBytes = 1; + } + else + { + transfer_config.srcAddr = (uint32_t)(handle->transfer.data + 1); + transfer_config.destAddr = (uint32_t)I2C_GetDataRegAddr(base); + transfer_config.majorLoopCounts = (handle->transfer.dataSize - 1); + transfer_config.srcTransferSize = kEDMA_TransferSize1Bytes; + transfer_config.srcOffset = 1; + transfer_config.destTransferSize = kEDMA_TransferSize1Bytes; + transfer_config.destOffset = 0; + transfer_config.minorLoopBytes = 1; + } + + /* Store the initially configured eDMA minor byte transfer count into the I2C handle */ + handle->nbytes = transfer_config.minorLoopBytes; + + EDMA_SubmitTransfer(handle->dmaHandle, &transfer_config); + EDMA_StartTransfer(handle->dmaHandle); +} + +void I2C_MasterCreateEDMAHandle(I2C_Type *base, + i2c_master_edma_handle_t *handle, + i2c_master_edma_transfer_callback_t callback, + void *userData, + edma_handle_t *edmaHandle) +{ + assert(handle); + assert(edmaHandle); + + uint32_t instance = I2C_GetInstance(base); + + /* Zero handle. */ + memset(handle, 0, sizeof(*handle)); + + /* Set the user callback and userData. */ + handle->completionCallback = callback; + handle->userData = userData; + + /* Set the base for the handle. */ + base = base; + + /* Set the handle for EDMA. */ + handle->dmaHandle = edmaHandle; + + s_edmaPrivateHandle[instance].base = base; + s_edmaPrivateHandle[instance].handle = handle; + + EDMA_SetCallback(edmaHandle, (edma_callback)I2C_MasterTransferCallbackEDMA, &s_edmaPrivateHandle[instance]); +} + +status_t I2C_MasterTransferEDMA(I2C_Type *base, i2c_master_edma_handle_t *handle, i2c_master_transfer_t *xfer) +{ + assert(handle); + assert(xfer); + + status_t result; + uint8_t tmpReg; + volatile uint8_t dummy = 0; + + /* Add this to avoid build warning. */ + dummy++; + + /* Disable dma xfer. */ + I2C_EnableDMA(base, false); + + /* Send address and command buffer(if there is), until senddata phase or receive data phase. */ + result = I2C_InitTransferStateMachineEDMA(base, handle, xfer); + + if (result) + { + /* Send stop if received Nak. */ + if (result == kStatus_I2C_Nak) + { + if (I2C_MasterStop(base) != kStatus_Success) + { + result = kStatus_I2C_Timeout; + } + } + + /* Reset the state to idle state. */ + handle->state = kIdleState; + + return result; + } + + /* Configure dma transfer. */ + /* For i2c send, need to send 1 byte first to trigger the dma, for i2c read, + need to send stop before reading the last byte, so the dma transfer size should + be (xSize - 1). */ + if (handle->transfer.dataSize > 1) + { + I2C_MasterTransferEDMAConfig(base, handle); + if (handle->transfer.direction == kI2C_Read) + { + /* Change direction for receive. */ + base->C1 &= ~(I2C_C1_TX_MASK | I2C_C1_TXAK_MASK); + + /* Read dummy to release the bus. */ + dummy = base->D; + + /* Enabe dma transfer. */ + I2C_EnableDMA(base, true); + } + else + { + /* Enabe dma transfer. */ + I2C_EnableDMA(base, true); + + /* Send the first data. */ + base->D = *handle->transfer.data; + } + } + else /* If transfer size is 1, use polling method. */ + { + if (handle->transfer.direction == kI2C_Read) + { + tmpReg = base->C1; + + /* Change direction to Rx. */ + tmpReg &= ~I2C_C1_TX_MASK; + + /* Configure send NAK */ + tmpReg |= I2C_C1_TXAK_MASK; + + base->C1 = tmpReg; + + /* Read dummy to release the bus. */ + dummy = base->D; + } + else + { + base->D = *handle->transfer.data; + } + + /* Wait until data transfer complete. */ + while (!(base->S & kI2C_IntPendingFlag)) + { + } + + /* Clear pending flag. */ + base->S = kI2C_IntPendingFlag; + + /* Send stop if kI2C_TransferNoStop flag is not asserted. */ + if (!(handle->transfer.flags & kI2C_TransferNoStopFlag)) + { + result = I2C_MasterStop(base); + } + else + { + /* Change direction to send. */ + base->C1 |= I2C_C1_TX_MASK; + } + + /* Read the last byte of data. */ + if (handle->transfer.direction == kI2C_Read) + { + *handle->transfer.data = base->D; + } + + /* Reset the state to idle. */ + handle->state = kIdleState; + } + + return result; +} + +status_t I2C_MasterTransferGetCountEDMA(I2C_Type *base, i2c_master_edma_handle_t *handle, size_t *count) +{ + assert(handle->dmaHandle); + + if (!count) + { + return kStatus_InvalidArgument; + } + + if (kIdleState != handle->state) + { + *count = (handle->transferSize - + (uint32_t)handle->nbytes * + EDMA_GetRemainingMajorLoopCount(handle->dmaHandle->base, handle->dmaHandle->channel)); + } + else + { + *count = handle->transferSize; + } + + return kStatus_Success; +} + +void I2C_MasterTransferAbortEDMA(I2C_Type *base, i2c_master_edma_handle_t *handle) +{ + EDMA_AbortTransfer(handle->dmaHandle); + + /* Disable dma transfer. */ + I2C_EnableDMA(base, false); + + /* Reset the state to idle. */ + handle->state = kIdleState; +} diff --git a/drivers/fsl_i2c_edma.h b/drivers/fsl_i2c_edma.h new file mode 100644 index 0000000..d1c5620 --- /dev/null +++ b/drivers/fsl_i2c_edma.h @@ -0,0 +1,141 @@ +/* + * The Clear BSD License + * Copyright (c) 2015, 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: + * + * o Redistributions of source code must retain the above copyright notice, this list + * of conditions and the following disclaimer. + * + * o 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. + * + * o 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_I2C_DMA_H_ +#define _FSL_I2C_DMA_H_ + +#include "fsl_i2c.h" +#include "fsl_edma.h" + +/*! + * @addtogroup i2c_edma_driver + * @{ + */ + +/******************************************************************************* + * Definitions + ******************************************************************************/ + +/*! @name Driver version */ +/*@{*/ +/*! @brief I2C EDMA driver version 2.0.5. */ +#define FSL_I2C_EDMA_DRIVER_VERSION (MAKE_VERSION(2, 0, 5)) +/*@}*/ + +/*! @brief I2C master eDMA handle typedef. */ +typedef struct _i2c_master_edma_handle i2c_master_edma_handle_t; + +/*! @brief I2C master eDMA transfer callback typedef. */ +typedef void (*i2c_master_edma_transfer_callback_t)(I2C_Type *base, + i2c_master_edma_handle_t *handle, + status_t status, + void *userData); + +/*! @brief I2C master eDMA transfer structure. */ +struct _i2c_master_edma_handle +{ + i2c_master_transfer_t transfer; /*!< I2C master transfer structure. */ + size_t transferSize; /*!< Total bytes to be transferred. */ + uint8_t nbytes; /*!< eDMA minor byte transfer count initially configured. */ + uint8_t state; /*!< I2C master transfer status. */ + edma_handle_t *dmaHandle; /*!< The eDMA handler used. */ + i2c_master_edma_transfer_callback_t + completionCallback; /*!< A callback function called after the eDMA transfer is finished. */ + void *userData; /*!< A callback parameter passed to the callback function. */ +}; + +/******************************************************************************* + * API + ******************************************************************************/ + +#if defined(__cplusplus) +extern "C" { +#endif /*_cplusplus. */ + +/*! + * @name I2C Block eDMA Transfer Operation + * @{ + */ + +/*! + * @brief Initializes the I2C handle which is used in transcational functions. + * + * @param base I2C peripheral base address. + * @param handle A pointer to the i2c_master_edma_handle_t structure. + * @param callback A pointer to the user callback function. + * @param userData A user parameter passed to the callback function. + * @param edmaHandle eDMA handle pointer. + */ +void I2C_MasterCreateEDMAHandle(I2C_Type *base, + i2c_master_edma_handle_t *handle, + i2c_master_edma_transfer_callback_t callback, + void *userData, + edma_handle_t *edmaHandle); + +/*! + * @brief Performs a master eDMA non-blocking transfer on the I2C bus. + * + * @param base I2C peripheral base address. + * @param handle A pointer to the i2c_master_edma_handle_t structure. + * @param xfer A pointer to the transfer structure of i2c_master_transfer_t. + * @retval kStatus_Success Sucessfully completed the data transmission. + * @retval kStatus_I2C_Busy A previous transmission is still not finished. + * @retval kStatus_I2C_Timeout Transfer error, waits for a signal timeout. + * @retval kStatus_I2C_ArbitrationLost Transfer error, arbitration lost. + * @retval kStataus_I2C_Nak Transfer error, receive NAK during transfer. + */ +status_t I2C_MasterTransferEDMA(I2C_Type *base, i2c_master_edma_handle_t *handle, i2c_master_transfer_t *xfer); + +/*! + * @brief Gets a master transfer status during the eDMA non-blocking transfer. + * + * @param base I2C peripheral base address. + * @param handle A pointer to the i2c_master_edma_handle_t structure. + * @param count A number of bytes transferred by the non-blocking transaction. + */ +status_t I2C_MasterTransferGetCountEDMA(I2C_Type *base, i2c_master_edma_handle_t *handle, size_t *count); + +/*! + * @brief Aborts a master eDMA non-blocking transfer early. + * + * @param base I2C peripheral base address. + * @param handle A pointer to the i2c_master_edma_handle_t structure. + */ +void I2C_MasterTransferAbortEDMA(I2C_Type *base, i2c_master_edma_handle_t *handle); + +/* @} */ +#if defined(__cplusplus) +} +#endif /*_cplusplus. */ +/*@}*/ +#endif /*_FSL_I2C_DMA_H_*/ diff --git a/drivers/fsl_pit.c b/drivers/fsl_pit.c new file mode 100644 index 0000000..e6ff9c8 --- /dev/null +++ b/drivers/fsl_pit.c @@ -0,0 +1,138 @@ +/* + * The Clear BSD License + * Copyright (c) 2015, 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: + * + * o Redistributions of source code must retain the above copyright notice, this list + * of conditions and the following disclaimer. + * + * o 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. + * + * o 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. + */ + +#include "fsl_pit.h" + +/* Component ID definition, used by tools. */ +#ifndef FSL_COMPONENT_ID +#define FSL_COMPONENT_ID "platform.drivers.pit" +#endif + + +/******************************************************************************* + * Prototypes + ******************************************************************************/ +/*! + * @brief Gets the instance from the base address to be used to gate or ungate the module clock + * + * @param base PIT peripheral base address + * + * @return The PIT instance + */ +static uint32_t PIT_GetInstance(PIT_Type *base); + +/******************************************************************************* + * Variables + ******************************************************************************/ +/*! @brief Pointers to PIT bases for each instance. */ +static PIT_Type *const s_pitBases[] = PIT_BASE_PTRS; + +#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) +/*! @brief Pointers to PIT clocks for each instance. */ +static const clock_ip_name_t s_pitClocks[] = PIT_CLOCKS; +#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */ + +/******************************************************************************* + * Code + ******************************************************************************/ +static uint32_t PIT_GetInstance(PIT_Type *base) +{ + uint32_t instance; + + /* Find the instance index from base address mappings. */ + for (instance = 0; instance < ARRAY_SIZE(s_pitBases); instance++) + { + if (s_pitBases[instance] == base) + { + break; + } + } + + assert(instance < ARRAY_SIZE(s_pitBases)); + + return instance; +} + +void PIT_Init(PIT_Type *base, const pit_config_t *config) +{ + assert(config); + +#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) + /* Ungate the PIT clock*/ + CLOCK_EnableClock(s_pitClocks[PIT_GetInstance(base)]); +#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */ + +#if defined(FSL_FEATURE_PIT_HAS_MDIS) && FSL_FEATURE_PIT_HAS_MDIS + /* Enable PIT timers */ + base->MCR &= ~PIT_MCR_MDIS_MASK; +#endif + /* Config timer operation when in debug mode */ + if (config->enableRunInDebug) + { + base->MCR &= ~PIT_MCR_FRZ_MASK; + } + else + { + base->MCR |= PIT_MCR_FRZ_MASK; + } +} + +void PIT_Deinit(PIT_Type *base) +{ +#if defined(FSL_FEATURE_PIT_HAS_MDIS) && FSL_FEATURE_PIT_HAS_MDIS + /* Disable PIT timers */ + base->MCR |= PIT_MCR_MDIS_MASK; +#endif + +#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) + /* Gate the PIT clock*/ + CLOCK_DisableClock(s_pitClocks[PIT_GetInstance(base)]); +#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */ +} + +#if defined(FSL_FEATURE_PIT_HAS_LIFETIME_TIMER) && FSL_FEATURE_PIT_HAS_LIFETIME_TIMER + +uint64_t PIT_GetLifetimeTimerCount(PIT_Type *base) +{ + uint32_t valueH = 0U; + uint32_t valueL = 0U; + + /* LTMR64H should be read before LTMR64L */ + valueH = base->LTMR64H; + valueL = base->LTMR64L; + + return (((uint64_t)valueH << 32U) + (uint64_t)(valueL)); +} + +#endif /* FSL_FEATURE_PIT_HAS_LIFETIME_TIMER */ diff --git a/drivers/fsl_pit.h b/drivers/fsl_pit.h new file mode 100644 index 0000000..55abdd5 --- /dev/null +++ b/drivers/fsl_pit.h @@ -0,0 +1,358 @@ +/* + * The Clear BSD License + * Copyright (c) 2015, 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: + * + * o Redistributions of source code must retain the above copyright notice, this list + * of conditions and the following disclaimer. + * + * o 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. + * + * o 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_PIT_H_ +#define _FSL_PIT_H_ + +#include "fsl_common.h" + +/*! + * @addtogroup pit + * @{ + */ + + +/******************************************************************************* + * Definitions + ******************************************************************************/ + +/*! @name Driver version */ +/*@{*/ +#define FSL_PIT_DRIVER_VERSION (MAKE_VERSION(2, 0, 0)) /*!< Version 2.0.0 */ +/*@}*/ + +/*! + * @brief List of PIT channels + * @note Actual number of available channels is SoC dependent + */ +typedef enum _pit_chnl +{ + kPIT_Chnl_0 = 0U, /*!< PIT channel number 0*/ + kPIT_Chnl_1, /*!< PIT channel number 1 */ + kPIT_Chnl_2, /*!< PIT channel number 2 */ + kPIT_Chnl_3, /*!< PIT channel number 3 */ +} pit_chnl_t; + +/*! @brief List of PIT interrupts */ +typedef enum _pit_interrupt_enable +{ + kPIT_TimerInterruptEnable = PIT_TCTRL_TIE_MASK, /*!< Timer interrupt enable*/ +} pit_interrupt_enable_t; + +/*! @brief List of PIT status flags */ +typedef enum _pit_status_flags +{ + kPIT_TimerFlag = PIT_TFLG_TIF_MASK, /*!< Timer flag */ +} pit_status_flags_t; + +/*! + * @brief PIT configuration structure + * + * This structure holds the configuration settings for the PIT peripheral. To initialize this + * structure to reasonable defaults, call the PIT_GetDefaultConfig() function and pass a + * pointer to your config structure instance. + * + * The configuration structure can be made constant so it resides in flash. + */ +typedef struct _pit_config +{ + bool enableRunInDebug; /*!< true: Timers run in debug mode; false: Timers stop in debug mode */ +} pit_config_t; + +/******************************************************************************* + * API + ******************************************************************************/ + +#if defined(__cplusplus) +extern "C" { +#endif + +/*! + * @name Initialization and deinitialization + * @{ + */ + +/*! + * @brief Ungates the PIT clock, enables the PIT module, and configures the peripheral for basic operations. + * + * @note This API should be called at the beginning of the application using the PIT driver. + * + * @param base PIT peripheral base address + * @param config Pointer to the user's PIT config structure + */ +void PIT_Init(PIT_Type *base, const pit_config_t *config); + +/*! + * @brief Gates the PIT clock and disables the PIT module. + * + * @param base PIT peripheral base address + */ +void PIT_Deinit(PIT_Type *base); + +/*! + * @brief Fills in the PIT configuration structure with the default settings. + * + * The default values are as follows. + * @code + * config->enableRunInDebug = false; + * @endcode + * @param config Pointer to the onfiguration structure. + */ +static inline void PIT_GetDefaultConfig(pit_config_t *config) +{ + assert(config); + + /* Timers are stopped in Debug mode */ + config->enableRunInDebug = false; +} + +#if defined(FSL_FEATURE_PIT_HAS_CHAIN_MODE) && FSL_FEATURE_PIT_HAS_CHAIN_MODE + +/*! + * @brief Enables or disables chaining a timer with the previous timer. + * + * When a timer has a chain mode enabled, it only counts after the previous + * timer has expired. If the timer n-1 has counted down to 0, counter n + * decrements the value by one. Each timer is 32-bits, which allows the developers + * to chain timers together and form a longer timer (64-bits and larger). The first timer + * (timer 0) can't be chained to any other timer. + * + * @param base PIT peripheral base address + * @param channel Timer channel number which is chained with the previous timer + * @param enable Enable or disable chain. + * true: Current timer is chained with the previous timer. + * false: Timer doesn't chain with other timers. + */ +static inline void PIT_SetTimerChainMode(PIT_Type *base, pit_chnl_t channel, bool enable) +{ + if (enable) + { + base->CHANNEL[channel].TCTRL |= PIT_TCTRL_CHN_MASK; + } + else + { + base->CHANNEL[channel].TCTRL &= ~PIT_TCTRL_CHN_MASK; + } +} + +#endif /* FSL_FEATURE_PIT_HAS_CHAIN_MODE */ + +/*! @}*/ + +/*! + * @name Interrupt Interface + * @{ + */ + +/*! + * @brief Enables the selected PIT interrupts. + * + * @param base PIT peripheral base address + * @param channel Timer channel number + * @param mask The interrupts to enable. This is a logical OR of members of the + * enumeration ::pit_interrupt_enable_t + */ +static inline void PIT_EnableInterrupts(PIT_Type *base, pit_chnl_t channel, uint32_t mask) +{ + base->CHANNEL[channel].TCTRL |= mask; +} + +/*! + * @brief Disables the selected PIT interrupts. + * + * @param base PIT peripheral base address + * @param channel Timer channel number + * @param mask The interrupts to disable. This is a logical OR of members of the + * enumeration ::pit_interrupt_enable_t + */ +static inline void PIT_DisableInterrupts(PIT_Type *base, pit_chnl_t channel, uint32_t mask) +{ + base->CHANNEL[channel].TCTRL &= ~mask; +} + +/*! + * @brief Gets the enabled PIT interrupts. + * + * @param base PIT peripheral base address + * @param channel Timer channel number + * + * @return The enabled interrupts. This is the logical OR of members of the + * enumeration ::pit_interrupt_enable_t + */ +static inline uint32_t PIT_GetEnabledInterrupts(PIT_Type *base, pit_chnl_t channel) +{ + return (base->CHANNEL[channel].TCTRL & PIT_TCTRL_TIE_MASK); +} + +/*! @}*/ + +/*! + * @name Status Interface + * @{ + */ + +/*! + * @brief Gets the PIT status flags. + * + * @param base PIT peripheral base address + * @param channel Timer channel number + * + * @return The status flags. This is the logical OR of members of the + * enumeration ::pit_status_flags_t + */ +static inline uint32_t PIT_GetStatusFlags(PIT_Type *base, pit_chnl_t channel) +{ + return (base->CHANNEL[channel].TFLG & PIT_TFLG_TIF_MASK); +} + +/*! + * @brief Clears the PIT status flags. + * + * @param base PIT peripheral base address + * @param channel Timer channel number + * @param mask The status flags to clear. This is a logical OR of members of the + * enumeration ::pit_status_flags_t + */ +static inline void PIT_ClearStatusFlags(PIT_Type *base, pit_chnl_t channel, uint32_t mask) +{ + base->CHANNEL[channel].TFLG = mask; +} + +/*! @}*/ + +/*! + * @name Read and Write the timer period + * @{ + */ + +/*! + * @brief Sets the timer period in units of count. + * + * Timers begin counting from the value set by this function until it reaches 0, + * then it generates an interrupt and load this register value again. + * Writing a new value to this register does not restart the timer. Instead, the value + * is loaded after the timer expires. + * + * @note Users can call the utility macros provided in fsl_common.h to convert to ticks. + * + * @param base PIT peripheral base address + * @param channel Timer channel number + * @param count Timer period in units of ticks + */ +static inline void PIT_SetTimerPeriod(PIT_Type *base, pit_chnl_t channel, uint32_t count) +{ + base->CHANNEL[channel].LDVAL = count; +} + +/*! + * @brief Reads the current timer counting value. + * + * This function returns the real-time timer counting value, in a range from 0 to a + * timer period. + * + * @note Users can call the utility macros provided in fsl_common.h to convert ticks to usec or msec. + * + * @param base PIT peripheral base address + * @param channel Timer channel number + * + * @return Current timer counting value in ticks + */ +static inline uint32_t PIT_GetCurrentTimerCount(PIT_Type *base, pit_chnl_t channel) +{ + return base->CHANNEL[channel].CVAL; +} + +/*! @}*/ + +/*! + * @name Timer Start and Stop + * @{ + */ + +/*! + * @brief Starts the timer counting. + * + * After calling this function, timers load period value, count down to 0 and + * then load the respective start value again. Each time a timer reaches 0, + * it generates a trigger pulse and sets the timeout interrupt flag. + * + * @param base PIT peripheral base address + * @param channel Timer channel number. + */ +static inline void PIT_StartTimer(PIT_Type *base, pit_chnl_t channel) +{ + base->CHANNEL[channel].TCTRL |= PIT_TCTRL_TEN_MASK; +} + +/*! + * @brief Stops the timer counting. + * + * This function stops every timer counting. Timers reload their periods + * respectively after the next time they call the PIT_DRV_StartTimer. + * + * @param base PIT peripheral base address + * @param channel Timer channel number. + */ +static inline void PIT_StopTimer(PIT_Type *base, pit_chnl_t channel) +{ + base->CHANNEL[channel].TCTRL &= ~PIT_TCTRL_TEN_MASK; +} + +/*! @}*/ + +#if defined(FSL_FEATURE_PIT_HAS_LIFETIME_TIMER) && FSL_FEATURE_PIT_HAS_LIFETIME_TIMER + +/*! + * @brief Reads the current lifetime counter value. + * + * The lifetime timer is a 64-bit timer which chains timer 0 and timer 1 together. + * Timer 0 and 1 are chained by calling the PIT_SetTimerChainMode before using this timer. + * The period of lifetime timer is equal to the "period of timer 0 * period of timer 1". + * For the 64-bit value, the higher 32-bit has the value of timer 1, and the lower 32-bit + * has the value of timer 0. + * + * @param base PIT peripheral base address + * + * @return Current lifetime timer value + */ +uint64_t PIT_GetLifetimeTimerCount(PIT_Type *base); + +#endif /* FSL_FEATURE_PIT_HAS_LIFETIME_TIMER */ + +#if defined(__cplusplus) +} +#endif + +/*! @}*/ + +#endif /* _FSL_PIT_H_ */ diff --git a/drivers/fsl_port.h b/drivers/fsl_port.h new file mode 100644 index 0000000..655e524 --- /dev/null +++ b/drivers/fsl_port.h @@ -0,0 +1,497 @@ +/* + * The Clear BSD License + * Copyright (c) 2015, 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: + * + * o Redistributions of source code must retain the above copyright notice, this list + * of conditions and the following disclaimer. + * + * o 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. + * + * o 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_PORT_H_ +#define _FSL_PORT_H_ + +#include "fsl_common.h" + +/*! + * @addtogroup port + * @{ + */ + +/******************************************************************************* + * Definitions + ******************************************************************************/ + +/* Component ID definition, used by tools. */ +#ifndef FSL_COMPONENT_ID +#define FSL_COMPONENT_ID "platform.drivers.port" +#endif + + +/*! @name Driver version */ +/*@{*/ +/*! Version 2.0.2. */ +#define FSL_PORT_DRIVER_VERSION (MAKE_VERSION(2, 0, 2)) +/*@}*/ + +#if defined(FSL_FEATURE_PORT_HAS_PULL_ENABLE) && FSL_FEATURE_PORT_HAS_PULL_ENABLE +/*! @brief Internal resistor pull feature selection */ +enum _port_pull +{ + kPORT_PullDisable = 0U, /*!< Internal pull-up/down resistor is disabled. */ + kPORT_PullDown = 2U, /*!< Internal pull-down resistor is enabled. */ + kPORT_PullUp = 3U, /*!< Internal pull-up resistor is enabled. */ +}; +#endif /* FSL_FEATURE_PORT_HAS_PULL_ENABLE */ + +#if defined(FSL_FEATURE_PORT_HAS_SLEW_RATE) && FSL_FEATURE_PORT_HAS_SLEW_RATE +/*! @brief Slew rate selection */ +enum _port_slew_rate +{ + kPORT_FastSlewRate = 0U, /*!< Fast slew rate is configured. */ + kPORT_SlowSlewRate = 1U, /*!< Slow slew rate is configured. */ +}; +#endif /* FSL_FEATURE_PORT_HAS_SLEW_RATE */ + +#if defined(FSL_FEATURE_PORT_HAS_OPEN_DRAIN) && FSL_FEATURE_PORT_HAS_OPEN_DRAIN +/*! @brief Open Drain feature enable/disable */ +enum _port_open_drain_enable +{ + kPORT_OpenDrainDisable = 0U, /*!< Open drain output is disabled. */ + kPORT_OpenDrainEnable = 1U, /*!< Open drain output is enabled. */ +}; +#endif /* FSL_FEATURE_PORT_HAS_OPEN_DRAIN */ + +#if defined(FSL_FEATURE_PORT_HAS_PASSIVE_FILTER) && FSL_FEATURE_PORT_HAS_PASSIVE_FILTER +/*! @brief Passive filter feature enable/disable */ +enum _port_passive_filter_enable +{ + kPORT_PassiveFilterDisable = 0U, /*!< Passive input filter is disabled. */ + kPORT_PassiveFilterEnable = 1U, /*!< Passive input filter is enabled. */ +}; +#endif + +#if defined(FSL_FEATURE_PORT_HAS_DRIVE_STRENGTH) && FSL_FEATURE_PORT_HAS_DRIVE_STRENGTH +/*! @brief Configures the drive strength. */ +enum _port_drive_strength +{ + kPORT_LowDriveStrength = 0U, /*!< Low-drive strength is configured. */ + kPORT_HighDriveStrength = 1U, /*!< High-drive strength is configured. */ +}; +#endif /* FSL_FEATURE_PORT_HAS_DRIVE_STRENGTH */ + +#if defined(FSL_FEATURE_PORT_HAS_PIN_CONTROL_LOCK) && FSL_FEATURE_PORT_HAS_PIN_CONTROL_LOCK +/*! @brief Unlock/lock the pin control register field[15:0] */ +enum _port_lock_register +{ + kPORT_UnlockRegister = 0U, /*!< Pin Control Register fields [15:0] are not locked. */ + kPORT_LockRegister = 1U, /*!< Pin Control Register fields [15:0] are locked. */ +}; +#endif /* FSL_FEATURE_PORT_HAS_PIN_CONTROL_LOCK */ + +#if defined(FSL_FEATURE_PORT_PCR_MUX_WIDTH) && FSL_FEATURE_PORT_PCR_MUX_WIDTH +/*! @brief Pin mux selection */ +typedef enum _port_mux +{ + kPORT_PinDisabledOrAnalog = 0U, /*!< Corresponding pin is disabled, but is used as an analog pin. */ + kPORT_MuxAsGpio = 1U, /*!< Corresponding pin is configured as GPIO. */ + kPORT_MuxAlt2 = 2U, /*!< Chip-specific */ + kPORT_MuxAlt3 = 3U, /*!< Chip-specific */ + kPORT_MuxAlt4 = 4U, /*!< Chip-specific */ + kPORT_MuxAlt5 = 5U, /*!< Chip-specific */ + kPORT_MuxAlt6 = 6U, /*!< Chip-specific */ + kPORT_MuxAlt7 = 7U, /*!< Chip-specific */ + kPORT_MuxAlt8 = 8U, /*!< Chip-specific */ + kPORT_MuxAlt9 = 9U, /*!< Chip-specific */ + kPORT_MuxAlt10 = 10U, /*!< Chip-specific */ + kPORT_MuxAlt11 = 11U, /*!< Chip-specific */ + kPORT_MuxAlt12 = 12U, /*!< Chip-specific */ + kPORT_MuxAlt13 = 13U, /*!< Chip-specific */ + kPORT_MuxAlt14 = 14U, /*!< Chip-specific */ + kPORT_MuxAlt15 = 15U, /*!< Chip-specific */ +} port_mux_t; +#endif /* FSL_FEATURE_PORT_PCR_MUX_WIDTH */ + +/*! @brief Configures the interrupt generation condition. */ +typedef enum _port_interrupt +{ + kPORT_InterruptOrDMADisabled = 0x0U, /*!< Interrupt/DMA request is disabled. */ +#if defined(FSL_FEATURE_PORT_HAS_DMA_REQUEST) && FSL_FEATURE_PORT_HAS_DMA_REQUEST + kPORT_DMARisingEdge = 0x1U, /*!< DMA request on rising edge. */ + kPORT_DMAFallingEdge = 0x2U, /*!< DMA request on falling edge. */ + kPORT_DMAEitherEdge = 0x3U, /*!< DMA request on either edge. */ +#endif +#if defined(FSL_FEATURE_PORT_HAS_IRQC_FLAG) && FSL_FEATURE_PORT_HAS_IRQC_FLAG + kPORT_FlagRisingEdge = 0x05U, /*!< Flag sets on rising edge. */ + kPORT_FlagFallingEdge = 0x06U, /*!< Flag sets on falling edge. */ + kPORT_FlagEitherEdge = 0x07U, /*!< Flag sets on either edge. */ +#endif + kPORT_InterruptLogicZero = 0x8U, /*!< Interrupt when logic zero. */ + kPORT_InterruptRisingEdge = 0x9U, /*!< Interrupt on rising edge. */ + kPORT_InterruptFallingEdge = 0xAU, /*!< Interrupt on falling edge. */ + kPORT_InterruptEitherEdge = 0xBU, /*!< Interrupt on either edge. */ + kPORT_InterruptLogicOne = 0xCU, /*!< Interrupt when logic one. */ +#if defined(FSL_FEATURE_PORT_HAS_IRQC_TRIGGER) && FSL_FEATURE_PORT_HAS_IRQC_TRIGGER + kPORT_ActiveHighTriggerOutputEnable = 0xDU, /*!< Enable active high-trigger output. */ + kPORT_ActiveLowTriggerOutputEnable = 0xEU, /*!< Enable active low-trigger output. */ +#endif +} port_interrupt_t; + +#if defined(FSL_FEATURE_PORT_HAS_DIGITAL_FILTER) && FSL_FEATURE_PORT_HAS_DIGITAL_FILTER +/*! @brief Digital filter clock source selection */ +typedef enum _port_digital_filter_clock_source +{ + kPORT_BusClock = 0U, /*!< Digital filters are clocked by the bus clock. */ + kPORT_LpoClock = 1U, /*!< Digital filters are clocked by the 1 kHz LPO clock. */ +} port_digital_filter_clock_source_t; + +/*! @brief PORT digital filter feature configuration definition */ +typedef struct _port_digital_filter_config +{ + uint32_t digitalFilterWidth; /*!< Set digital filter width */ + port_digital_filter_clock_source_t clockSource; /*!< Set digital filter clockSource */ +} port_digital_filter_config_t; +#endif /* FSL_FEATURE_PORT_HAS_DIGITAL_FILTER */ + +#if defined(FSL_FEATURE_PORT_PCR_MUX_WIDTH) && FSL_FEATURE_PORT_PCR_MUX_WIDTH +/*! @brief PORT pin configuration structure */ +typedef struct _port_pin_config +{ +#if defined(FSL_FEATURE_PORT_HAS_PULL_ENABLE) && FSL_FEATURE_PORT_HAS_PULL_ENABLE + uint16_t pullSelect : 2; /*!< No-pull/pull-down/pull-up select */ +#else + uint16_t : 2; +#endif /* FSL_FEATURE_PORT_HAS_PULL_ENABLE */ + +#if defined(FSL_FEATURE_PORT_HAS_SLEW_RATE) && FSL_FEATURE_PORT_HAS_SLEW_RATE + uint16_t slewRate : 1; /*!< Fast/slow slew rate Configure */ +#else + uint16_t : 1; +#endif /* FSL_FEATURE_PORT_HAS_SLEW_RATE */ + + uint16_t : 1; + +#if defined(FSL_FEATURE_PORT_HAS_PASSIVE_FILTER) && FSL_FEATURE_PORT_HAS_PASSIVE_FILTER + uint16_t passiveFilterEnable : 1; /*!< Passive filter enable/disable */ +#else + uint16_t : 1; +#endif /* FSL_FEATURE_PORT_HAS_PASSIVE_FILTER */ + +#if defined(FSL_FEATURE_PORT_HAS_OPEN_DRAIN) && FSL_FEATURE_PORT_HAS_OPEN_DRAIN + uint16_t openDrainEnable : 1; /*!< Open drain enable/disable */ +#else + uint16_t : 1; +#endif /* FSL_FEATURE_PORT_HAS_OPEN_DRAIN */ + +#if defined(FSL_FEATURE_PORT_HAS_DRIVE_STRENGTH) && FSL_FEATURE_PORT_HAS_DRIVE_STRENGTH + uint16_t driveStrength : 1; /*!< Fast/slow drive strength configure */ +#else + uint16_t : 1; +#endif + + uint16_t : 1; + +#if defined(FSL_FEATURE_PORT_PCR_MUX_WIDTH) && (FSL_FEATURE_PORT_PCR_MUX_WIDTH == 3) + uint16_t mux : 3; /*!< Pin mux Configure */ + uint16_t : 4; +#elif defined(FSL_FEATURE_PORT_PCR_MUX_WIDTH) && (FSL_FEATURE_PORT_PCR_MUX_WIDTH == 4) + uint16_t mux : 4; /*!< Pin mux Configure */ + uint16_t : 3; +#else + uint16_t : 7, +#endif + +#if defined(FSL_FEATURE_PORT_HAS_PIN_CONTROL_LOCK) && FSL_FEATURE_PORT_HAS_PIN_CONTROL_LOCK + uint16_t lockRegister : 1; /*!< Lock/unlock the PCR field[15:0] */ +#else + uint16_t : 1; +#endif /* FSL_FEATURE_PORT_HAS_PIN_CONTROL_LOCK */ +} port_pin_config_t; +#endif /* FSL_FEATURE_PORT_PCR_MUX_WIDTH */ + +/******************************************************************************* +* API +******************************************************************************/ + +#if defined(__cplusplus) +extern "C" { +#endif + +#if defined(FSL_FEATURE_PORT_PCR_MUX_WIDTH) && FSL_FEATURE_PORT_PCR_MUX_WIDTH +/*! @name Configuration */ +/*@{*/ + +/*! + * @brief Sets the port PCR register. + * + * This is an example to define an input pin or output pin PCR configuration. + * @code + * // Define a digital input pin PCR configuration + * port_pin_config_t config = { + * kPORT_PullUp, + * kPORT_FastSlewRate, + * kPORT_PassiveFilterDisable, + * kPORT_OpenDrainDisable, + * kPORT_LowDriveStrength, + * kPORT_MuxAsGpio, + * kPORT_UnLockRegister, + * }; + * @endcode + * + * @param base PORT peripheral base pointer. + * @param pin PORT pin number. + * @param config PORT PCR register configuration structure. + */ +static inline void PORT_SetPinConfig(PORT_Type *base, uint32_t pin, const port_pin_config_t *config) +{ + assert(config); + uint32_t addr = (uint32_t)&base->PCR[pin]; + *(volatile uint16_t *)(addr) = *((const uint16_t *)config); +} + +/*! + * @brief Sets the port PCR register for multiple pins. + * + * This is an example to define input pins or output pins PCR configuration. + * @code + * // Define a digital input pin PCR configuration + * port_pin_config_t config = { + * kPORT_PullUp , + * kPORT_PullEnable, + * kPORT_FastSlewRate, + * kPORT_PassiveFilterDisable, + * kPORT_OpenDrainDisable, + * kPORT_LowDriveStrength, + * kPORT_MuxAsGpio, + * kPORT_UnlockRegister, + * }; + * @endcode + * + * @param base PORT peripheral base pointer. + * @param mask PORT pin number macro. + * @param config PORT PCR register configuration structure. + */ +static inline void PORT_SetMultiplePinsConfig(PORT_Type *base, uint32_t mask, const port_pin_config_t *config) +{ + assert(config); + + uint16_t pcrl = *((const uint16_t *)config); + + if (mask & 0xffffU) + { + base->GPCLR = ((mask & 0xffffU) << 16) | pcrl; + } + if (mask >> 16) + { + base->GPCHR = (mask & 0xffff0000U) | pcrl; + } +} + +#if defined(FSL_FEATURE_PORT_HAS_MULTIPLE_IRQ_CONFIG) && FSL_FEATURE_PORT_HAS_MULTIPLE_IRQ_CONFIG +/*! + * @brief Sets the port interrupt configuration in PCR register for multiple pins. + * + * @param base PORT peripheral base pointer. + * @param mask PORT pin number macro. + * @param config PORT pin interrupt configuration. + * - #kPORT_InterruptOrDMADisabled: Interrupt/DMA request disabled. + * - #kPORT_DMARisingEdge : DMA request on rising edge(if the DMA requests exit). + * - #kPORT_DMAFallingEdge: DMA request on falling edge(if the DMA requests exit). + * - #kPORT_DMAEitherEdge : DMA request on either edge(if the DMA requests exit). + * - #kPORT_FlagRisingEdge : Flag sets on rising edge(if the Flag states exit). + * - #kPORT_FlagFallingEdge : Flag sets on falling edge(if the Flag states exit). + * - #kPORT_FlagEitherEdge : Flag sets on either edge(if the Flag states exit). + * - #kPORT_InterruptLogicZero : Interrupt when logic zero. + * - #kPORT_InterruptRisingEdge : Interrupt on rising edge. + * - #kPORT_InterruptFallingEdge: Interrupt on falling edge. + * - #kPORT_InterruptEitherEdge : Interrupt on either edge. + * - #kPORT_InterruptLogicOne : Interrupt when logic one. + * - #kPORT_ActiveHighTriggerOutputEnable : Enable active high-trigger output (if the trigger states exit). + * - #kPORT_ActiveLowTriggerOutputEnable : Enable active low-trigger output (if the trigger states exit).. + */ +static inline void PORT_SetMultipleInterruptPinsConfig(PORT_Type *base, uint32_t mask, port_interrupt_t config) +{ + assert(config); + + if (mask & 0xffffU) + { + base->GICLR = (config << 16) | (mask & 0xffffU); + } + mask = mask >> 16; + if (mask) + { + base->GICHR = (config << 16) | (mask & 0xffffU); + } +} +#endif + +/*! + * @brief Configures the pin muxing. + * + * @param base PORT peripheral base pointer. + * @param pin PORT pin number. + * @param mux pin muxing slot selection. + * - #kPORT_PinDisabledOrAnalog: Pin disabled or work in analog function. + * - #kPORT_MuxAsGpio : Set as GPIO. + * - #kPORT_MuxAlt2 : chip-specific. + * - #kPORT_MuxAlt3 : chip-specific. + * - #kPORT_MuxAlt4 : chip-specific. + * - #kPORT_MuxAlt5 : chip-specific. + * - #kPORT_MuxAlt6 : chip-specific. + * - #kPORT_MuxAlt7 : chip-specific. + * @Note : This function is NOT recommended to use together with the PORT_SetPinsConfig, because + * the PORT_SetPinsConfig need to configure the pin mux anyway (Otherwise the pin mux is + * reset to zero : kPORT_PinDisabledOrAnalog). + * This function is recommended to use to reset the pin mux + * + */ +static inline void PORT_SetPinMux(PORT_Type *base, uint32_t pin, port_mux_t mux) +{ + base->PCR[pin] = (base->PCR[pin] & ~PORT_PCR_MUX_MASK) | PORT_PCR_MUX(mux); +} +#endif /* FSL_FEATURE_PORT_PCR_MUX_WIDTH */ + +#if defined(FSL_FEATURE_PORT_HAS_DIGITAL_FILTER) && FSL_FEATURE_PORT_HAS_DIGITAL_FILTER + +/*! + * @brief Enables the digital filter in one port, each bit of the 32-bit register represents one pin. + * + * @param base PORT peripheral base pointer. + * @param mask PORT pin number macro. + */ +static inline void PORT_EnablePinsDigitalFilter(PORT_Type *base, uint32_t mask, bool enable) +{ + if (enable == true) + { + base->DFER |= mask; + } + else + { + base->DFER &= ~mask; + } +} + +/*! + * @brief Sets the digital filter in one port, each bit of the 32-bit register represents one pin. + * + * @param base PORT peripheral base pointer. + * @param config PORT digital filter configuration structure. + */ +static inline void PORT_SetDigitalFilterConfig(PORT_Type *base, const port_digital_filter_config_t *config) +{ + assert(config); + + base->DFCR = PORT_DFCR_CS(config->clockSource); + base->DFWR = PORT_DFWR_FILT(config->digitalFilterWidth); +} + +#endif /* FSL_FEATURE_PORT_HAS_DIGITAL_FILTER */ + +/*@}*/ + +/*! @name Interrupt */ +/*@{*/ + +/*! + * @brief Configures the port pin interrupt/DMA request. + * + * @param base PORT peripheral base pointer. + * @param pin PORT pin number. + * @param config PORT pin interrupt configuration. + * - #kPORT_InterruptOrDMADisabled: Interrupt/DMA request disabled. + * - #kPORT_DMARisingEdge : DMA request on rising edge(if the DMA requests exit). + * - #kPORT_DMAFallingEdge: DMA request on falling edge(if the DMA requests exit). + * - #kPORT_DMAEitherEdge : DMA request on either edge(if the DMA requests exit). + * - #kPORT_FlagRisingEdge : Flag sets on rising edge(if the Flag states exit). + * - #kPORT_FlagFallingEdge : Flag sets on falling edge(if the Flag states exit). + * - #kPORT_FlagEitherEdge : Flag sets on either edge(if the Flag states exit). + * - #kPORT_InterruptLogicZero : Interrupt when logic zero. + * - #kPORT_InterruptRisingEdge : Interrupt on rising edge. + * - #kPORT_InterruptFallingEdge: Interrupt on falling edge. + * - #kPORT_InterruptEitherEdge : Interrupt on either edge. + * - #kPORT_InterruptLogicOne : Interrupt when logic one. + * - #kPORT_ActiveHighTriggerOutputEnable : Enable active high-trigger output (if the trigger states exit). + * - #kPORT_ActiveLowTriggerOutputEnable : Enable active low-trigger output (if the trigger states exit). + */ +static inline void PORT_SetPinInterruptConfig(PORT_Type *base, uint32_t pin, port_interrupt_t config) +{ + base->PCR[pin] = (base->PCR[pin] & ~PORT_PCR_IRQC_MASK) | PORT_PCR_IRQC(config); +} + +#if defined(FSL_FEATURE_PORT_HAS_DRIVE_STRENGTH) && FSL_FEATURE_PORT_HAS_DRIVE_STRENGTH +/*! + * @brief Configures the port pin drive strength. + * + * @param base PORT peripheral base pointer. + * @param pin PORT pin number. + * @param config PORT pin drive strength + * - #kPORT_LowDriveStrength = 0U - Low-drive strength is configured. + * - #kPORT_HighDriveStrength = 1U - High-drive strength is configured. + */ +static inline void PORT_SetPinDriveStrength(PORT_Type* base, uint32_t pin, uint8_t strength) +{ + base->PCR[pin] = (base->PCR[pin] & ~PORT_PCR_DSE_MASK) | PORT_PCR_DSE(strength); +} +#endif + +/*! + * @brief Reads the whole port status flag. + * + * If a pin is configured to generate the DMA request, the corresponding flag + * is cleared automatically at the completion of the requested DMA transfer. + * Otherwise, the flag remains set until a logic one is written to that flag. + * If configured for a level sensitive interrupt that remains asserted, the flag + * is set again immediately. + * + * @param base PORT peripheral base pointer. + * @return Current port interrupt status flags, for example, 0x00010001 means the + * pin 0 and 16 have the interrupt. + */ +static inline uint32_t PORT_GetPinsInterruptFlags(PORT_Type *base) +{ + return base->ISFR; +} + +/*! + * @brief Clears the multiple pin interrupt status flag. + * + * @param base PORT peripheral base pointer. + * @param mask PORT pin number macro. + */ +static inline void PORT_ClearPinsInterruptFlags(PORT_Type *base, uint32_t mask) +{ + base->ISFR = mask; +} + +/*@}*/ + +#if defined(__cplusplus) +} +#endif + +/*! @}*/ + +#endif /* _FSL_PORT_H_ */ diff --git a/drivers/fsl_uart.c b/drivers/fsl_uart.c new file mode 100644 index 0000000..c7a9f80 --- /dev/null +++ b/drivers/fsl_uart.c @@ -0,0 +1,1356 @@ +/* + * The Clear BSD License + * Copyright (c) 2015-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: + * + * o Redistributions of source code must retain the above copyright notice, this list + * of conditions and the following disclaimer. + * + * o 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. + * + * o 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. + */ + +#include "fsl_uart.h" + +/******************************************************************************* + * Definitions + ******************************************************************************/ + +/* Component ID definition, used by tools. */ +#ifndef FSL_COMPONENT_ID +#define FSL_COMPONENT_ID "platform.drivers.uart" +#endif + +/* UART transfer state. */ +enum _uart_tansfer_states +{ + kUART_TxIdle, /* TX idle. */ + kUART_TxBusy, /* TX busy. */ + kUART_RxIdle, /* RX idle. */ + kUART_RxBusy, /* RX busy. */ + kUART_RxFramingError, /* Rx framing error */ + kUART_RxParityError /* Rx parity error */ +}; + +/* Typedef for interrupt handler. */ +typedef void (*uart_isr_t)(UART_Type *base, uart_handle_t *handle); + +/******************************************************************************* + * Prototypes + ******************************************************************************/ +/*! + * @brief Check whether the RX ring buffer is full. + * + * @param handle UART handle pointer. + * @retval true RX ring buffer is full. + * @retval false RX ring buffer is not full. + */ +static bool UART_TransferIsRxRingBufferFull(uart_handle_t *handle); + +/*! + * @brief Read RX register using non-blocking method. + * + * This function reads data from the TX register directly, upper layer must make + * sure the RX register is full or TX FIFO has data before calling this function. + * + * @param base UART peripheral base address. + * @param data Start addresss of the buffer to store the received data. + * @param length Size of the buffer. + */ +static void UART_ReadNonBlocking(UART_Type *base, uint8_t *data, size_t length); + +/*! + * @brief Write to TX register using non-blocking method. + * + * This function writes data to the TX register directly, upper layer must make + * sure the TX register is empty or TX FIFO has empty room before calling this function. + * + * @note This function does not check whether all the data has been sent out to bus, + * so before disable TX, check kUART_TransmissionCompleteFlag to ensure the TX is + * finished. + * + * @param base UART peripheral base address. + * @param data Start addresss of the data to write. + * @param length Size of the buffer to be sent. + */ +static void UART_WriteNonBlocking(UART_Type *base, const uint8_t *data, size_t length); + +/******************************************************************************* + * Variables + ******************************************************************************/ +/* Array of UART handle. */ +#if (defined(UART5)) +#define UART_HANDLE_ARRAY_SIZE 6 +#else /* UART5 */ +#if (defined(UART4)) +#define UART_HANDLE_ARRAY_SIZE 5 +#else /* UART4 */ +#if (defined(UART3)) +#define UART_HANDLE_ARRAY_SIZE 4 +#else /* UART3 */ +#if (defined(UART2)) +#define UART_HANDLE_ARRAY_SIZE 3 +#else /* UART2 */ +#if (defined(UART1)) +#define UART_HANDLE_ARRAY_SIZE 2 +#else /* UART1 */ +#if (defined(UART0)) +#define UART_HANDLE_ARRAY_SIZE 1 +#else /* UART0 */ +#error No UART instance. +#endif /* UART 0 */ +#endif /* UART 1 */ +#endif /* UART 2 */ +#endif /* UART 3 */ +#endif /* UART 4 */ +#endif /* UART 5 */ +static uart_handle_t *s_uartHandle[UART_HANDLE_ARRAY_SIZE]; +/* Array of UART peripheral base address. */ +static UART_Type *const s_uartBases[] = UART_BASE_PTRS; + +/* Array of UART IRQ number. */ +static const IRQn_Type s_uartIRQ[] = UART_RX_TX_IRQS; +#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) +/* Array of UART clock name. */ +static const clock_ip_name_t s_uartClock[] = UART_CLOCKS; +#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */ + +/* UART ISR for transactional APIs. */ +static uart_isr_t s_uartIsr; + +/******************************************************************************* + * Code + ******************************************************************************/ + +uint32_t UART_GetInstance(UART_Type *base) +{ + uint32_t instance; + uint32_t uartArrayCount = (sizeof(s_uartBases) / sizeof(s_uartBases[0])); + + /* Find the instance index from base address mappings. */ + for (instance = 0; instance < uartArrayCount; instance++) + { + if (s_uartBases[instance] == base) + { + break; + } + } + + assert(instance < uartArrayCount); + + return instance; +} + +size_t UART_TransferGetRxRingBufferLength(uart_handle_t *handle) +{ + assert(handle); + + size_t size; + + if (handle->rxRingBufferTail > handle->rxRingBufferHead) + { + size = (size_t)(handle->rxRingBufferHead + handle->rxRingBufferSize - handle->rxRingBufferTail); + } + else + { + size = (size_t)(handle->rxRingBufferHead - handle->rxRingBufferTail); + } + + return size; +} + +static bool UART_TransferIsRxRingBufferFull(uart_handle_t *handle) +{ + assert(handle); + + bool full; + + if (UART_TransferGetRxRingBufferLength(handle) == (handle->rxRingBufferSize - 1U)) + { + full = true; + } + else + { + full = false; + } + + return full; +} + +status_t UART_Init(UART_Type *base, const uart_config_t *config, uint32_t srcClock_Hz) +{ + assert(config); + assert(config->baudRate_Bps); +#if defined(FSL_FEATURE_UART_HAS_FIFO) && FSL_FEATURE_UART_HAS_FIFO + assert(FSL_FEATURE_UART_FIFO_SIZEn(base) >= config->txFifoWatermark); + assert(FSL_FEATURE_UART_FIFO_SIZEn(base) >= config->rxFifoWatermark); +#endif + + uint16_t sbr = 0; + uint8_t temp = 0; + uint32_t baudDiff = 0; + + /* Calculate the baud rate modulo divisor, sbr*/ + sbr = srcClock_Hz / (config->baudRate_Bps * 16); + /* set sbrTemp to 1 if the sourceClockInHz can not satisfy the desired baud rate */ + if (sbr == 0) + { + sbr = 1; + } +#if defined(FSL_FEATURE_UART_HAS_BAUD_RATE_FINE_ADJUST_SUPPORT) && FSL_FEATURE_UART_HAS_BAUD_RATE_FINE_ADJUST_SUPPORT + /* Determine if a fractional divider is needed to fine tune closer to the + * desired baud, each value of brfa is in 1/32 increments, + * hence the multiply-by-32. */ + uint32_t tempBaud = 0; + + uint16_t brfa = (2 * srcClock_Hz / (config->baudRate_Bps)) - 32 * sbr; + + /* Calculate the baud rate based on the temporary SBR values and BRFA */ + tempBaud = (srcClock_Hz * 2 / ((sbr * 32 + brfa))); + baudDiff = + (tempBaud > config->baudRate_Bps) ? (tempBaud - config->baudRate_Bps) : (config->baudRate_Bps - tempBaud); + +#else + /* Calculate the baud rate based on the temporary SBR values */ + baudDiff = (srcClock_Hz / (sbr * 16)) - config->baudRate_Bps; + + /* Select the better value between sbr and (sbr + 1) */ + if (baudDiff > (config->baudRate_Bps - (srcClock_Hz / (16 * (sbr + 1))))) + { + baudDiff = config->baudRate_Bps - (srcClock_Hz / (16 * (sbr + 1))); + sbr++; + } +#endif + + /* next, check to see if actual baud rate is within 3% of desired baud rate + * based on the calculate SBR value */ + if (baudDiff > ((config->baudRate_Bps / 100) * 3)) + { + /* Unacceptable baud rate difference of more than 3%*/ + return kStatus_UART_BaudrateNotSupport; + } + +#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) + /* Enable uart clock */ + CLOCK_EnableClock(s_uartClock[UART_GetInstance(base)]); +#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */ + + /* Disable UART TX RX before setting. */ + base->C2 &= ~(UART_C2_TE_MASK | UART_C2_RE_MASK); + + /* Write the sbr value to the BDH and BDL registers*/ + base->BDH = (base->BDH & ~UART_BDH_SBR_MASK) | (uint8_t)(sbr >> 8); + base->BDL = (uint8_t)sbr; + +#if defined(FSL_FEATURE_UART_HAS_BAUD_RATE_FINE_ADJUST_SUPPORT) && FSL_FEATURE_UART_HAS_BAUD_RATE_FINE_ADJUST_SUPPORT + /* Write the brfa value to the register*/ + base->C4 = (base->C4 & ~UART_C4_BRFA_MASK) | (brfa & UART_C4_BRFA_MASK); +#endif + + /* Set bit count/parity mode/idle type. */ + temp = base->C1 & ~(UART_C1_PE_MASK | UART_C1_PT_MASK | UART_C1_M_MASK | UART_C1_ILT_MASK); + + temp |= UART_C1_ILT(config->idleType); + + if (kUART_ParityDisabled != config->parityMode) + { + temp |= (UART_C1_M_MASK | (uint8_t)config->parityMode); + } + + base->C1 = temp; + +#if defined(FSL_FEATURE_UART_HAS_STOP_BIT_CONFIG_SUPPORT) && FSL_FEATURE_UART_HAS_STOP_BIT_CONFIG_SUPPORT + /* Set stop bit per char */ + base->BDH = (base->BDH & ~UART_BDH_SBNS_MASK) | UART_BDH_SBNS((uint8_t)config->stopBitCount); +#endif + +#if defined(FSL_FEATURE_UART_HAS_FIFO) && FSL_FEATURE_UART_HAS_FIFO + /* Set tx/rx FIFO watermark + Note: + Take care of the RX FIFO, RX interrupt request only assert when received bytes + equal or more than RX water mark, there is potential issue if RX water + mark larger than 1. + For example, if RX FIFO water mark is 2, upper layer needs 5 bytes and + 5 bytes are received. the last byte will be saved in FIFO but not trigger + RX interrupt because the water mark is 2. + */ + base->TWFIFO = config->txFifoWatermark; + base->RWFIFO = config->rxFifoWatermark; + + /* Enable tx/rx FIFO */ + base->PFIFO |= (UART_PFIFO_TXFE_MASK | UART_PFIFO_RXFE_MASK); + + /* Flush FIFO */ + base->CFIFO |= (UART_CFIFO_TXFLUSH_MASK | UART_CFIFO_RXFLUSH_MASK); +#endif +#if defined(FSL_FEATURE_UART_HAS_MODEM_SUPPORT) && FSL_FEATURE_UART_HAS_MODEM_SUPPORT + if (config->enableRxRTS) + { + /* Enable receiver RTS(request-to-send) function. */ + base->MODEM |= UART_MODEM_RXRTSE_MASK; + } + if (config->enableTxCTS) + { + /* Enable transmiter CTS(clear-to-send) function. */ + base->MODEM |= UART_MODEM_TXCTSE_MASK; + } +#endif + + /* Enable TX/RX base on configure structure. */ + temp = base->C2; + + if (config->enableTx) + { + temp |= UART_C2_TE_MASK; + } + + if (config->enableRx) + { + temp |= UART_C2_RE_MASK; + } + + base->C2 = temp; + + return kStatus_Success; +} + +void UART_Deinit(UART_Type *base) +{ +#if defined(FSL_FEATURE_UART_HAS_FIFO) && FSL_FEATURE_UART_HAS_FIFO + /* Wait tx FIFO send out*/ + while (0 != base->TCFIFO) + { + } +#endif + /* Wait last char shoft out */ + while (0 == (base->S1 & UART_S1_TC_MASK)) + { + } + + /* Disable the module. */ + base->C2 = 0; + +#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) + /* Disable uart clock */ + CLOCK_DisableClock(s_uartClock[UART_GetInstance(base)]); +#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */ +} + +void UART_GetDefaultConfig(uart_config_t *config) +{ + assert(config); + + config->baudRate_Bps = 115200U; + config->parityMode = kUART_ParityDisabled; +#if defined(FSL_FEATURE_UART_HAS_STOP_BIT_CONFIG_SUPPORT) && FSL_FEATURE_UART_HAS_STOP_BIT_CONFIG_SUPPORT + config->stopBitCount = kUART_OneStopBit; +#endif +#if defined(FSL_FEATURE_UART_HAS_FIFO) && FSL_FEATURE_UART_HAS_FIFO + config->txFifoWatermark = 0; + config->rxFifoWatermark = 1; +#endif +#if defined(FSL_FEATURE_UART_HAS_MODEM_SUPPORT) && FSL_FEATURE_UART_HAS_MODEM_SUPPORT + config->enableRxRTS = false; + config->enableTxCTS = false; +#endif + config->idleType = kUART_IdleTypeStartBit; + config->enableTx = false; + config->enableRx = false; +} + +status_t UART_SetBaudRate(UART_Type *base, uint32_t baudRate_Bps, uint32_t srcClock_Hz) +{ + assert(baudRate_Bps); + + uint16_t sbr = 0; + uint32_t baudDiff = 0; + uint8_t oldCtrl; + + /* Calculate the baud rate modulo divisor, sbr*/ + sbr = srcClock_Hz / (baudRate_Bps * 16); + /* set sbrTemp to 1 if the sourceClockInHz can not satisfy the desired baud rate */ + if (sbr == 0) + { + sbr = 1; + } +#if defined(FSL_FEATURE_UART_HAS_BAUD_RATE_FINE_ADJUST_SUPPORT) && FSL_FEATURE_UART_HAS_BAUD_RATE_FINE_ADJUST_SUPPORT + /* Determine if a fractional divider is needed to fine tune closer to the + * desired baud, each value of brfa is in 1/32 increments, + * hence the multiply-by-32. */ + uint32_t tempBaud = 0; + + uint16_t brfa = (2 * srcClock_Hz / (baudRate_Bps)) - 32 * sbr; + + /* Calculate the baud rate based on the temporary SBR values and BRFA */ + tempBaud = (srcClock_Hz * 2 / ((sbr * 32 + brfa))); + baudDiff = (tempBaud > baudRate_Bps) ? (tempBaud - baudRate_Bps) : (baudRate_Bps - tempBaud); +#else + /* Calculate the baud rate based on the temporary SBR values */ + baudDiff = (srcClock_Hz / (sbr * 16)) - baudRate_Bps; + + /* Select the better value between sbr and (sbr + 1) */ + if (baudDiff > (baudRate_Bps - (srcClock_Hz / (16 * (sbr + 1))))) + { + baudDiff = baudRate_Bps - (srcClock_Hz / (16 * (sbr + 1))); + sbr++; + } +#endif + + /* next, check to see if actual baud rate is within 3% of desired baud rate + * based on the calculate SBR value */ + if (baudDiff < ((baudRate_Bps / 100) * 3)) + { + /* Store C2 before disable Tx and Rx */ + oldCtrl = base->C2; + + /* Disable UART TX RX before setting. */ + base->C2 &= ~(UART_C2_TE_MASK | UART_C2_RE_MASK); + + /* Write the sbr value to the BDH and BDL registers*/ + base->BDH = (base->BDH & ~UART_BDH_SBR_MASK) | (uint8_t)(sbr >> 8); + base->BDL = (uint8_t)sbr; + +#if defined(FSL_FEATURE_UART_HAS_BAUD_RATE_FINE_ADJUST_SUPPORT) && FSL_FEATURE_UART_HAS_BAUD_RATE_FINE_ADJUST_SUPPORT + /* Write the brfa value to the register*/ + base->C4 = (base->C4 & ~UART_C4_BRFA_MASK) | (brfa & UART_C4_BRFA_MASK); +#endif + /* Restore C2. */ + base->C2 = oldCtrl; + + return kStatus_Success; + } + else + { + /* Unacceptable baud rate difference of more than 3%*/ + return kStatus_UART_BaudrateNotSupport; + } +} + +void UART_EnableInterrupts(UART_Type *base, uint32_t mask) +{ + mask &= kUART_AllInterruptsEnable; + + /* The interrupt mask is combined by control bits from several register: ((CFIFO<<24) | (C3<<16) | (C2<<8) |(BDH)) + */ + base->BDH |= mask; + base->C2 |= (mask >> 8); + base->C3 |= (mask >> 16); + +#if defined(FSL_FEATURE_UART_HAS_FIFO) && FSL_FEATURE_UART_HAS_FIFO + base->CFIFO |= (mask >> 24); +#endif +} + +void UART_DisableInterrupts(UART_Type *base, uint32_t mask) +{ + mask &= kUART_AllInterruptsEnable; + + /* The interrupt mask is combined by control bits from several register: ((CFIFO<<24) | (C3<<16) | (C2<<8) |(BDH)) + */ + base->BDH &= ~mask; + base->C2 &= ~(mask >> 8); + base->C3 &= ~(mask >> 16); + +#if defined(FSL_FEATURE_UART_HAS_FIFO) && FSL_FEATURE_UART_HAS_FIFO + base->CFIFO &= ~(mask >> 24); +#endif +} + +uint32_t UART_GetEnabledInterrupts(UART_Type *base) +{ + uint32_t temp; + + temp = base->BDH | ((uint32_t)(base->C2) << 8) | ((uint32_t)(base->C3) << 16); + +#if defined(FSL_FEATURE_UART_HAS_FIFO) && FSL_FEATURE_UART_HAS_FIFO + temp |= ((uint32_t)(base->CFIFO) << 24); +#endif + + return temp & kUART_AllInterruptsEnable; +} + +uint32_t UART_GetStatusFlags(UART_Type *base) +{ + uint32_t status_flag; + + status_flag = base->S1 | ((uint32_t)(base->S2) << 8); + +#if defined(FSL_FEATURE_UART_HAS_EXTENDED_DATA_REGISTER_FLAGS) && FSL_FEATURE_UART_HAS_EXTENDED_DATA_REGISTER_FLAGS + status_flag |= ((uint32_t)(base->ED) << 16); +#endif + +#if defined(FSL_FEATURE_UART_HAS_FIFO) && FSL_FEATURE_UART_HAS_FIFO + status_flag |= ((uint32_t)(base->SFIFO) << 24); +#endif + + return status_flag; +} + +status_t UART_ClearStatusFlags(UART_Type *base, uint32_t mask) +{ + uint8_t reg = base->S2; + status_t status; + +#if defined(FSL_FEATURE_UART_HAS_LIN_BREAK_DETECT) && FSL_FEATURE_UART_HAS_LIN_BREAK_DETECT + reg &= ~(UART_S2_RXEDGIF_MASK | UART_S2_LBKDIF_MASK); +#else + reg &= ~UART_S2_RXEDGIF_MASK; +#endif + + base->S2 = reg | (uint8_t)(mask >> 8); + +#if defined(FSL_FEATURE_UART_HAS_FIFO) && FSL_FEATURE_UART_HAS_FIFO + base->SFIFO = (uint8_t)(mask >> 24); +#endif + + if (mask & (kUART_IdleLineFlag | kUART_NoiseErrorFlag | kUART_FramingErrorFlag | kUART_ParityErrorFlag)) + { + /* Read base->D to clear the flags. */ + (void)base->S1; + (void)base->D; + } + + if (mask & kUART_RxOverrunFlag) + { + /* Read base->D to clear the flags and Flush all data in FIFO. */ + (void)base->S1; + (void)base->D; +#if defined(FSL_FEATURE_UART_HAS_FIFO) && FSL_FEATURE_UART_HAS_FIFO + /* Flush FIFO date, otherwise FIFO pointer will be in unknown state. */ + base->CFIFO |= UART_CFIFO_RXFLUSH_MASK; +#endif + } + + /* If some flags still pending. */ + if (mask & UART_GetStatusFlags(base)) + { + /* Some flags can only clear or set by the hardware itself, these flags are: kUART_TxDataRegEmptyFlag, + kUART_TransmissionCompleteFlag, kUART_RxDataRegFullFlag, kUART_RxActiveFlag, kUART_NoiseErrorInRxDataRegFlag, + kUART_ParityErrorInRxDataRegFlag, kUART_TxFifoEmptyFlag, kUART_RxFifoEmptyFlag. */ + status = kStatus_UART_FlagCannotClearManually; + } + else + { + status = kStatus_Success; + } + + return status; +} + +void UART_WriteBlocking(UART_Type *base, const uint8_t *data, size_t length) +{ + /* This API can only ensure that the data is written into the data buffer but can't + ensure all data in the data buffer are sent into the transmit shift buffer. */ + while (length--) + { + while (!(base->S1 & UART_S1_TDRE_MASK)) + { + } + base->D = *(data++); + } +} + +static void UART_WriteNonBlocking(UART_Type *base, const uint8_t *data, size_t length) +{ + assert(data); + + size_t i; + + /* The Non Blocking write data API assume user have ensured there is enough space in + peripheral to write. */ + for (i = 0; i < length; i++) + { + base->D = data[i]; + } +} + +status_t UART_ReadBlocking(UART_Type *base, uint8_t *data, size_t length) +{ + assert(data); + + uint32_t statusFlag; + + while (length--) + { +#if defined(FSL_FEATURE_UART_HAS_FIFO) && FSL_FEATURE_UART_HAS_FIFO + while (!base->RCFIFO) +#else + while (!(base->S1 & UART_S1_RDRF_MASK)) +#endif + { + statusFlag = UART_GetStatusFlags(base); + + if (statusFlag & kUART_RxOverrunFlag) + { + return kStatus_UART_RxHardwareOverrun; + } + + if (statusFlag & kUART_NoiseErrorFlag) + { + return kStatus_UART_NoiseError; + } + + if (statusFlag & kUART_FramingErrorFlag) + { + return kStatus_UART_FramingError; + } + + if (statusFlag & kUART_ParityErrorFlag) + { + return kStatus_UART_ParityError; + } + } + *(data++) = base->D; + } + + return kStatus_Success; +} + +static void UART_ReadNonBlocking(UART_Type *base, uint8_t *data, size_t length) +{ + assert(data); + + size_t i; + + /* The Non Blocking read data API assume user have ensured there is enough space in + peripheral to write. */ + for (i = 0; i < length; i++) + { + data[i] = base->D; + } +} + +void UART_TransferCreateHandle(UART_Type *base, + uart_handle_t *handle, + uart_transfer_callback_t callback, + void *userData) +{ + assert(handle); + + uint32_t instance; + + /* Zero the handle. */ + memset(handle, 0, sizeof(*handle)); + + /* Set the TX/RX state. */ + handle->rxState = kUART_RxIdle; + handle->txState = kUART_TxIdle; + + /* Set the callback and user data. */ + handle->callback = callback; + handle->userData = userData; + + /* Get instance from peripheral base address. */ + instance = UART_GetInstance(base); + + /* Save the handle in global variables to support the double weak mechanism. */ + s_uartHandle[instance] = handle; + + s_uartIsr = UART_TransferHandleIRQ; + /* Enable interrupt in NVIC. */ + EnableIRQ(s_uartIRQ[instance]); +} + +void UART_TransferStartRingBuffer(UART_Type *base, uart_handle_t *handle, uint8_t *ringBuffer, size_t ringBufferSize) +{ + assert(handle); + assert(ringBuffer); + + /* Setup the ringbuffer address */ + handle->rxRingBuffer = ringBuffer; + handle->rxRingBufferSize = ringBufferSize; + handle->rxRingBufferHead = 0U; + handle->rxRingBufferTail = 0U; + + /* Enable the interrupt to accept the data when user need the ring buffer. */ + UART_EnableInterrupts( + base, kUART_RxDataRegFullInterruptEnable | kUART_RxOverrunInterruptEnable | kUART_FramingErrorInterruptEnable); + /* Enable parity error interrupt when parity mode is enable*/ + if (UART_C1_PE_MASK & base->C1) + { + UART_EnableInterrupts(base, kUART_ParityErrorInterruptEnable); + } +} + +void UART_TransferStopRingBuffer(UART_Type *base, uart_handle_t *handle) +{ + assert(handle); + + if (handle->rxState == kUART_RxIdle) + { + UART_DisableInterrupts(base, kUART_RxDataRegFullInterruptEnable | kUART_RxOverrunInterruptEnable | + kUART_FramingErrorInterruptEnable); + /* Disable parity error interrupt when parity mode is enable*/ + if (UART_C1_PE_MASK & base->C1) + { + UART_DisableInterrupts(base, kUART_ParityErrorInterruptEnable); + } + } + + handle->rxRingBuffer = NULL; + handle->rxRingBufferSize = 0U; + handle->rxRingBufferHead = 0U; + handle->rxRingBufferTail = 0U; +} + +status_t UART_TransferSendNonBlocking(UART_Type *base, uart_handle_t *handle, uart_transfer_t *xfer) +{ + assert(handle); + assert(xfer); + assert(xfer->dataSize); + assert(xfer->data); + + status_t status; + + /* Return error if current TX busy. */ + if (kUART_TxBusy == handle->txState) + { + status = kStatus_UART_TxBusy; + } + else + { + handle->txData = xfer->data; + handle->txDataSize = xfer->dataSize; + handle->txDataSizeAll = xfer->dataSize; + handle->txState = kUART_TxBusy; + + /* Enable transmiter interrupt. */ + UART_EnableInterrupts(base, kUART_TxDataRegEmptyInterruptEnable); + + status = kStatus_Success; + } + + return status; +} + +void UART_TransferAbortSend(UART_Type *base, uart_handle_t *handle) +{ + assert(handle); + + UART_DisableInterrupts(base, kUART_TxDataRegEmptyInterruptEnable | kUART_TransmissionCompleteInterruptEnable); + + handle->txDataSize = 0; + handle->txState = kUART_TxIdle; +} + +status_t UART_TransferGetSendCount(UART_Type *base, uart_handle_t *handle, uint32_t *count) +{ + assert(handle); + assert(count); + + if (kUART_TxIdle == handle->txState) + { + return kStatus_NoTransferInProgress; + } + + *count = handle->txDataSizeAll - handle->txDataSize; + + return kStatus_Success; +} + +status_t UART_TransferReceiveNonBlocking(UART_Type *base, + uart_handle_t *handle, + uart_transfer_t *xfer, + size_t *receivedBytes) +{ + assert(handle); + assert(xfer); + assert(xfer->data); + assert(xfer->dataSize); + + uint32_t i; + status_t status; + /* How many bytes to copy from ring buffer to user memory. */ + size_t bytesToCopy = 0U; + /* How many bytes to receive. */ + size_t bytesToReceive; + /* How many bytes currently have received. */ + size_t bytesCurrentReceived; + + /* How to get data: + 1. If RX ring buffer is not enabled, then save xfer->data and xfer->dataSize + to uart handle, enable interrupt to store received data to xfer->data. When + all data received, trigger callback. + 2. If RX ring buffer is enabled and not empty, get data from ring buffer first. + If there are enough data in ring buffer, copy them to xfer->data and return. + If there are not enough data in ring buffer, copy all of them to xfer->data, + save the xfer->data remained empty space to uart handle, receive data + to this empty space and trigger callback when finished. */ + + if (kUART_RxBusy == handle->rxState) + { + status = kStatus_UART_RxBusy; + } + else + { + bytesToReceive = xfer->dataSize; + bytesCurrentReceived = 0U; + + /* If RX ring buffer is used. */ + if (handle->rxRingBuffer) + { + /* Disable UART RX IRQ, protect ring buffer. */ + UART_DisableInterrupts(base, kUART_RxDataRegFullInterruptEnable); + + /* How many bytes in RX ring buffer currently. */ + bytesToCopy = UART_TransferGetRxRingBufferLength(handle); + + if (bytesToCopy) + { + bytesToCopy = MIN(bytesToReceive, bytesToCopy); + + bytesToReceive -= bytesToCopy; + + /* Copy data from ring buffer to user memory. */ + for (i = 0U; i < bytesToCopy; i++) + { + xfer->data[bytesCurrentReceived++] = handle->rxRingBuffer[handle->rxRingBufferTail]; + + /* Wrap to 0. Not use modulo (%) because it might be large and slow. */ + if (handle->rxRingBufferTail + 1U == handle->rxRingBufferSize) + { + handle->rxRingBufferTail = 0U; + } + else + { + handle->rxRingBufferTail++; + } + } + } + + /* If ring buffer does not have enough data, still need to read more data. */ + if (bytesToReceive) + { + /* No data in ring buffer, save the request to UART handle. */ + handle->rxData = xfer->data + bytesCurrentReceived; + handle->rxDataSize = bytesToReceive; + handle->rxDataSizeAll = bytesToReceive; + handle->rxState = kUART_RxBusy; + } + + /* Enable UART RX IRQ if previously enabled. */ + UART_EnableInterrupts(base, kUART_RxDataRegFullInterruptEnable); + + /* Call user callback since all data are received. */ + if (0 == bytesToReceive) + { + if (handle->callback) + { + handle->callback(base, handle, kStatus_UART_RxIdle, handle->userData); + } + } + } + /* Ring buffer not used. */ + else + { + handle->rxData = xfer->data + bytesCurrentReceived; + handle->rxDataSize = bytesToReceive; + handle->rxDataSizeAll = bytesToReceive; + handle->rxState = kUART_RxBusy; + + /* Enable RX/Rx overrun/framing error/idle line interrupt. */ + UART_EnableInterrupts(base, kUART_RxDataRegFullInterruptEnable | kUART_RxOverrunInterruptEnable | + kUART_FramingErrorInterruptEnable | kUART_IdleLineInterruptEnable); + /* Enable parity error interrupt when parity mode is enable*/ + if (UART_C1_PE_MASK & base->C1) + { + UART_EnableInterrupts(base, kUART_ParityErrorInterruptEnable); + } + } + + /* Return the how many bytes have read. */ + if (receivedBytes) + { + *receivedBytes = bytesCurrentReceived; + } + + status = kStatus_Success; + } + + return status; +} + +void UART_TransferAbortReceive(UART_Type *base, uart_handle_t *handle) +{ + assert(handle); + + /* Only abort the receive to handle->rxData, the RX ring buffer is still working. */ + if (!handle->rxRingBuffer) + { + /* Disable RX interrupt. */ + UART_DisableInterrupts(base, kUART_RxDataRegFullInterruptEnable | kUART_RxOverrunInterruptEnable | + kUART_FramingErrorInterruptEnable | kUART_IdleLineInterruptEnable); + /* Disable parity error interrupt when parity mode is enable*/ + if (UART_C1_PE_MASK & base->C1) + { + UART_DisableInterrupts(base, kUART_ParityErrorInterruptEnable); + } + } + + handle->rxDataSize = 0U; + handle->rxState = kUART_RxIdle; +} + +status_t UART_TransferGetReceiveCount(UART_Type *base, uart_handle_t *handle, uint32_t *count) +{ + assert(handle); + assert(count); + + if (kUART_RxIdle == handle->rxState) + { + return kStatus_NoTransferInProgress; + } + + if (!count) + { + return kStatus_InvalidArgument; + } + + *count = handle->rxDataSizeAll - handle->rxDataSize; + + return kStatus_Success; +} + +void UART_TransferHandleIRQ(UART_Type *base, uart_handle_t *handle) +{ + assert(handle); + + uint8_t count; + uint8_t tempCount; + + /* If RX framing error */ + if (UART_S1_FE_MASK & base->S1) + { + /* Read base->D to clear framing error flag, otherwise the RX does not work. */ + while (base->S1 & UART_S1_RDRF_MASK) + { + (void)base->D; + } +#if defined(FSL_FEATURE_UART_HAS_FIFO) && FSL_FEATURE_UART_HAS_FIFO + /* Flush FIFO date, otherwise FIFO pointer will be in unknown state. */ + base->CFIFO |= UART_CFIFO_RXFLUSH_MASK; +#endif + + handle->rxState = kUART_RxFramingError; + handle->rxDataSize = 0U; + /* Trigger callback. */ + if (handle->callback) + { + handle->callback(base, handle, kStatus_UART_FramingError, handle->userData); + } + } + + /* If RX parity error */ + if (UART_S1_PF_MASK & base->S1) + { + /* Read base->D to clear parity error flag, otherwise the RX does not work. */ + while (base->S1 & UART_S1_RDRF_MASK) + { + (void)base->D; + } +#if defined(FSL_FEATURE_UART_HAS_FIFO) && FSL_FEATURE_UART_HAS_FIFO + /* Flush FIFO date, otherwise FIFO pointer will be in unknown state. */ + base->CFIFO |= UART_CFIFO_RXFLUSH_MASK; +#endif + + handle->rxState = kUART_RxParityError; + handle->rxDataSize = 0U; + /* Trigger callback. */ + if (handle->callback) + { + handle->callback(base, handle, kStatus_UART_ParityError, handle->userData); + } + } + + /* If RX overrun. */ + if (UART_S1_OR_MASK & base->S1) + { + /* Read base->D to clear overrun flag, otherwise the RX does not work. */ + while (base->S1 & UART_S1_RDRF_MASK) + { + (void)base->D; + } +#if defined(FSL_FEATURE_UART_HAS_FIFO) && FSL_FEATURE_UART_HAS_FIFO + /* Flush FIFO date, otherwise FIFO pointer will be in unknown state. */ + base->CFIFO |= UART_CFIFO_RXFLUSH_MASK; +#endif + /* Trigger callback. */ + if (handle->callback) + { + handle->callback(base, handle, kStatus_UART_RxHardwareOverrun, handle->userData); + } + } + + /* If IDLE line was detected. */ + if ((UART_S1_IDLE_MASK & base->S1) && (UART_C2_ILIE_MASK & base->C2)) + { +#if defined(FSL_FEATURE_UART_HAS_FIFO) && FSL_FEATURE_UART_HAS_FIFO + /* If still some data in the FIFO, read out these data to user data buffer. */ + count = base->RCFIFO; + /* If handle->rxDataSize is not 0, first save data to handle->rxData. */ + while ((count) && (handle->rxDataSize)) + { + tempCount = MIN(handle->rxDataSize, count); + + /* Using non block API to read the data from the registers. */ + UART_ReadNonBlocking(base, handle->rxData, tempCount); + handle->rxData += tempCount; + handle->rxDataSize -= tempCount; + count -= tempCount; + + /* If all the data required for upper layer is ready, trigger callback. */ + if (!handle->rxDataSize) + { + handle->rxState = kUART_RxIdle; + + /* Disable RX interrupt/overrun interrupt/fram error/idle line detected interrupt */ + UART_DisableInterrupts(base, kUART_RxDataRegFullInterruptEnable | kUART_RxOverrunInterruptEnable | + kUART_FramingErrorInterruptEnable); + + /* Disable parity error interrupt when parity mode is enable*/ + if (UART_C1_PE_MASK & base->C1) + { + UART_DisableInterrupts(base, kUART_ParityErrorInterruptEnable); + } + + if (handle->callback) + { + handle->callback(base, handle, kStatus_UART_RxIdle, handle->userData); + } + } + } +#endif + /* To clear IDLE, read UART status S1 with IDLE set and then read D.*/ + while (UART_S1_IDLE_MASK & base->S1) + { + (void)base->D; + } +#if defined(FSL_FEATURE_UART_HAS_FIFO) && FSL_FEATURE_UART_HAS_FIFO + /* Flush FIFO date, otherwise FIFO pointer will be in unknown state. */ + base->CFIFO |= UART_CFIFO_RXFLUSH_MASK; +#endif + /* If rxDataSize is 0, disable idle line interrupt.*/ + if (!(handle->rxDataSize)) + { + UART_DisableInterrupts(base, kUART_IdleLineInterruptEnable); + } + /* If callback is not NULL and rxDataSize is not 0. */ + if ((handle->callback) && (handle->rxDataSize)) + { + handle->callback(base, handle, kStatus_UART_IdleLineDetected, handle->userData); + } + } + /* Receive data register full */ + if ((UART_S1_RDRF_MASK & base->S1) && (UART_C2_RIE_MASK & base->C2)) + { +/* Get the size that can be stored into buffer for this interrupt. */ +#if defined(FSL_FEATURE_UART_HAS_FIFO) && FSL_FEATURE_UART_HAS_FIFO + count = base->RCFIFO; +#else + count = 1; +#endif + + /* If handle->rxDataSize is not 0, first save data to handle->rxData. */ + while ((count) && (handle->rxDataSize)) + { +#if defined(FSL_FEATURE_UART_HAS_FIFO) && FSL_FEATURE_UART_HAS_FIFO + tempCount = MIN(handle->rxDataSize, count); +#else + tempCount = 1; +#endif + + /* Using non block API to read the data from the registers. */ + UART_ReadNonBlocking(base, handle->rxData, tempCount); + handle->rxData += tempCount; + handle->rxDataSize -= tempCount; + count -= tempCount; + + /* If all the data required for upper layer is ready, trigger callback. */ + if (!handle->rxDataSize) + { + handle->rxState = kUART_RxIdle; + + if (handle->callback) + { + handle->callback(base, handle, kStatus_UART_RxIdle, handle->userData); + } + } + } + + /* If use RX ring buffer, receive data to ring buffer. */ + if (handle->rxRingBuffer) + { + while (count--) + { + /* If RX ring buffer is full, trigger callback to notify over run. */ + if (UART_TransferIsRxRingBufferFull(handle)) + { + if (handle->callback) + { + handle->callback(base, handle, kStatus_UART_RxRingBufferOverrun, handle->userData); + } + } + + /* If ring buffer is still full after callback function, the oldest data is overrided. */ + if (UART_TransferIsRxRingBufferFull(handle)) + { + /* Increase handle->rxRingBufferTail to make room for new data. */ + if (handle->rxRingBufferTail + 1U == handle->rxRingBufferSize) + { + handle->rxRingBufferTail = 0U; + } + else + { + handle->rxRingBufferTail++; + } + } + + /* Read data. */ + handle->rxRingBuffer[handle->rxRingBufferHead] = base->D; + + /* Increase handle->rxRingBufferHead. */ + if (handle->rxRingBufferHead + 1U == handle->rxRingBufferSize) + { + handle->rxRingBufferHead = 0U; + } + else + { + handle->rxRingBufferHead++; + } + } + } + + else if (!handle->rxDataSize) + { + /* Disable RX interrupt/overrun interrupt/fram error/idle line detected interrupt */ + UART_DisableInterrupts(base, kUART_RxDataRegFullInterruptEnable | kUART_RxOverrunInterruptEnable | + kUART_FramingErrorInterruptEnable); + + /* Disable parity error interrupt when parity mode is enable*/ + if (UART_C1_PE_MASK & base->C1) + { + UART_DisableInterrupts(base, kUART_ParityErrorInterruptEnable); + } + } + else + { + } + } + + /* If framing error or parity error happened, stop the RX interrupt when ues no ring buffer */ + if (((handle->rxState == kUART_RxFramingError) || (handle->rxState == kUART_RxParityError)) && + (!handle->rxRingBuffer)) + { + UART_DisableInterrupts(base, kUART_RxDataRegFullInterruptEnable | kUART_RxOverrunInterruptEnable | + kUART_FramingErrorInterruptEnable | kUART_IdleLineInterruptEnable); + + /* Disable parity error interrupt when parity mode is enable*/ + if (UART_C1_PE_MASK & base->C1) + { + UART_DisableInterrupts(base, kUART_ParityErrorInterruptEnable); + } + } + + /* Send data register empty and the interrupt is enabled. */ + if ((base->S1 & UART_S1_TDRE_MASK) && (base->C2 & UART_C2_TIE_MASK)) + { +/* Get the bytes that available at this moment. */ +#if defined(FSL_FEATURE_UART_HAS_FIFO) && FSL_FEATURE_UART_HAS_FIFO + count = FSL_FEATURE_UART_FIFO_SIZEn(base) - base->TCFIFO; +#else + count = 1; +#endif + + while ((count) && (handle->txDataSize)) + { +#if defined(FSL_FEATURE_UART_HAS_FIFO) && FSL_FEATURE_UART_HAS_FIFO + tempCount = MIN(handle->txDataSize, count); +#else + tempCount = 1; +#endif + + /* Using non block API to write the data to the registers. */ + UART_WriteNonBlocking(base, handle->txData, tempCount); + handle->txData += tempCount; + handle->txDataSize -= tempCount; + count -= tempCount; + + /* If all the data are written to data register, TX finished. */ + if (!handle->txDataSize) + { + handle->txState = kUART_TxIdle; + + /* Disable TX register empty interrupt. */ + base->C2 = (base->C2 & ~UART_C2_TIE_MASK); + + /* Trigger callback. */ + if (handle->callback) + { + handle->callback(base, handle, kStatus_UART_TxIdle, handle->userData); + } + } + } + } +} + +void UART_TransferHandleErrorIRQ(UART_Type *base, uart_handle_t *handle) +{ + /* To be implemented by User. */ +} + +#if defined(UART0) +#if ((!(defined(FSL_FEATURE_SOC_LPSCI_COUNT))) || \ + ((defined(FSL_FEATURE_SOC_LPSCI_COUNT)) && (FSL_FEATURE_SOC_LPSCI_COUNT == 0))) +void UART0_DriverIRQHandler(void) +{ + s_uartIsr(UART0, s_uartHandle[0]); +/* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void UART0_RX_TX_DriverIRQHandler(void) +{ + UART0_DriverIRQHandler(); +/* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} +#endif +#endif + +#if defined(UART1) +void UART1_DriverIRQHandler(void) +{ + s_uartIsr(UART1, s_uartHandle[1]); +/* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void UART1_RX_TX_DriverIRQHandler(void) +{ + UART1_DriverIRQHandler(); +/* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} +#endif + +#if defined(UART2) +void UART2_DriverIRQHandler(void) +{ + s_uartIsr(UART2, s_uartHandle[2]); +/* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void UART2_RX_TX_DriverIRQHandler(void) +{ + UART2_DriverIRQHandler(); +/* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} +#endif + +#if defined(UART3) +void UART3_DriverIRQHandler(void) +{ + s_uartIsr(UART3, s_uartHandle[3]); +/* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void UART3_RX_TX_DriverIRQHandler(void) +{ + UART3_DriverIRQHandler(); +/* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} +#endif + +#if defined(UART4) +void UART4_DriverIRQHandler(void) +{ + s_uartIsr(UART4, s_uartHandle[4]); +/* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void UART4_RX_TX_DriverIRQHandler(void) +{ + UART4_DriverIRQHandler(); +/* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} +#endif + +#if defined(UART5) +void UART5_DriverIRQHandler(void) +{ + s_uartIsr(UART5, s_uartHandle[5]); +/* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} + +void UART5_RX_TX_DriverIRQHandler(void) +{ + UART5_DriverIRQHandler(); +/* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + exception return operation might vector to incorrect interrupt */ +#if defined __CORTEX_M && (__CORTEX_M == 4U) + __DSB(); +#endif +} +#endif diff --git a/drivers/fsl_uart.h b/drivers/fsl_uart.h new file mode 100644 index 0000000..3abffbd --- /dev/null +++ b/drivers/fsl_uart.h @@ -0,0 +1,808 @@ +/* + * The Clear BSD License + * Copyright (c) 2015-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: + * + * o Redistributions of source code must retain the above copyright notice, this list + * of conditions and the following disclaimer. + * + * o 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. + * + * o 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_UART_H_ +#define _FSL_UART_H_ + +#include "fsl_common.h" + +/*! + * @addtogroup uart_driver + * @{ + */ + +/******************************************************************************* + * Definitions + ******************************************************************************/ + +/*! @name Driver version */ +/*@{*/ +/*! @brief UART driver version 2.1.5. */ +#define FSL_UART_DRIVER_VERSION (MAKE_VERSION(2, 1, 5)) +/*@}*/ + +/*! @brief Error codes for the UART driver. */ +enum _uart_status +{ + kStatus_UART_TxBusy = MAKE_STATUS(kStatusGroup_UART, 0), /*!< Transmitter is busy. */ + kStatus_UART_RxBusy = MAKE_STATUS(kStatusGroup_UART, 1), /*!< Receiver is busy. */ + kStatus_UART_TxIdle = MAKE_STATUS(kStatusGroup_UART, 2), /*!< UART transmitter is idle. */ + kStatus_UART_RxIdle = MAKE_STATUS(kStatusGroup_UART, 3), /*!< UART receiver is idle. */ + kStatus_UART_TxWatermarkTooLarge = MAKE_STATUS(kStatusGroup_UART, 4), /*!< TX FIFO watermark too large */ + kStatus_UART_RxWatermarkTooLarge = MAKE_STATUS(kStatusGroup_UART, 5), /*!< RX FIFO watermark too large */ + kStatus_UART_FlagCannotClearManually = + MAKE_STATUS(kStatusGroup_UART, 6), /*!< UART flag can't be manually cleared. */ + kStatus_UART_Error = MAKE_STATUS(kStatusGroup_UART, 7), /*!< Error happens on UART. */ + kStatus_UART_RxRingBufferOverrun = MAKE_STATUS(kStatusGroup_UART, 8), /*!< UART RX software ring buffer overrun. */ + kStatus_UART_RxHardwareOverrun = MAKE_STATUS(kStatusGroup_UART, 9), /*!< UART RX receiver overrun. */ + kStatus_UART_NoiseError = MAKE_STATUS(kStatusGroup_UART, 10), /*!< UART noise error. */ + kStatus_UART_FramingError = MAKE_STATUS(kStatusGroup_UART, 11), /*!< UART framing error. */ + kStatus_UART_ParityError = MAKE_STATUS(kStatusGroup_UART, 12), /*!< UART parity error. */ + kStatus_UART_BaudrateNotSupport = + MAKE_STATUS(kStatusGroup_UART, 13), /*!< Baudrate is not support in current clock source */ + kStatus_UART_IdleLineDetected = MAKE_STATUS(kStatusGroup_UART, 14), /*!< UART IDLE line detected. */ +}; + +/*! @brief UART parity mode. */ +typedef enum _uart_parity_mode +{ + kUART_ParityDisabled = 0x0U, /*!< Parity disabled */ + kUART_ParityEven = 0x2U, /*!< Parity enabled, type even, bit setting: PE|PT = 10 */ + kUART_ParityOdd = 0x3U, /*!< Parity enabled, type odd, bit setting: PE|PT = 11 */ +} uart_parity_mode_t; + +/*! @brief UART stop bit count. */ +typedef enum _uart_stop_bit_count +{ + kUART_OneStopBit = 0U, /*!< One stop bit */ + kUART_TwoStopBit = 1U, /*!< Two stop bits */ +} uart_stop_bit_count_t; + +/*! @brief UART idle type select. */ +typedef enum _uart_idle_type_select +{ + kUART_IdleTypeStartBit = 0U, /*!< Start counting after a valid start bit. */ + kUART_IdleTypeStopBit = 1U, /*!< Start conuting after a stop bit. */ +} uart_idle_type_select_t; + +/*! + * @brief UART interrupt configuration structure, default settings all disabled. + * + * This structure contains the settings for all of the UART interrupt configurations. + */ +enum _uart_interrupt_enable +{ +#if defined(FSL_FEATURE_UART_HAS_LIN_BREAK_DETECT) && FSL_FEATURE_UART_HAS_LIN_BREAK_DETECT + kUART_LinBreakInterruptEnable = (UART_BDH_LBKDIE_MASK), /*!< LIN break detect interrupt. */ +#endif + kUART_RxActiveEdgeInterruptEnable = (UART_BDH_RXEDGIE_MASK), /*!< RX active edge interrupt. */ + kUART_TxDataRegEmptyInterruptEnable = (UART_C2_TIE_MASK << 8), /*!< Transmit data register empty interrupt. */ + kUART_TransmissionCompleteInterruptEnable = (UART_C2_TCIE_MASK << 8), /*!< Transmission complete interrupt. */ + kUART_RxDataRegFullInterruptEnable = (UART_C2_RIE_MASK << 8), /*!< Receiver data register full interrupt. */ + kUART_IdleLineInterruptEnable = (UART_C2_ILIE_MASK << 8), /*!< Idle line interrupt. */ + kUART_RxOverrunInterruptEnable = (UART_C3_ORIE_MASK << 16), /*!< Receiver overrun interrupt. */ + kUART_NoiseErrorInterruptEnable = (UART_C3_NEIE_MASK << 16), /*!< Noise error flag interrupt. */ + kUART_FramingErrorInterruptEnable = (UART_C3_FEIE_MASK << 16), /*!< Framing error flag interrupt. */ + kUART_ParityErrorInterruptEnable = (UART_C3_PEIE_MASK << 16), /*!< Parity error flag interrupt. */ +#if defined(FSL_FEATURE_UART_HAS_FIFO) && FSL_FEATURE_UART_HAS_FIFO + kUART_RxFifoOverflowInterruptEnable = (UART_CFIFO_RXOFE_MASK << 24), /*!< RX FIFO overflow interrupt. */ + kUART_TxFifoOverflowInterruptEnable = (UART_CFIFO_TXOFE_MASK << 24), /*!< TX FIFO overflow interrupt. */ + kUART_RxFifoUnderflowInterruptEnable = (UART_CFIFO_RXUFE_MASK << 24), /*!< RX FIFO underflow interrupt. */ +#endif + kUART_AllInterruptsEnable = +#if defined(FSL_FEATURE_UART_HAS_LIN_BREAK_DETECT) && FSL_FEATURE_UART_HAS_LIN_BREAK_DETECT + kUART_LinBreakInterruptEnable | +#endif + kUART_RxActiveEdgeInterruptEnable | kUART_TxDataRegEmptyInterruptEnable | + kUART_TransmissionCompleteInterruptEnable | kUART_RxDataRegFullInterruptEnable | kUART_IdleLineInterruptEnable | + kUART_RxOverrunInterruptEnable | kUART_NoiseErrorInterruptEnable | kUART_FramingErrorInterruptEnable | + kUART_ParityErrorInterruptEnable +#if defined(FSL_FEATURE_UART_HAS_FIFO) && FSL_FEATURE_UART_HAS_FIFO + | + kUART_RxFifoOverflowInterruptEnable | kUART_TxFifoOverflowInterruptEnable | kUART_RxFifoUnderflowInterruptEnable +#endif + , +}; + +/*! + * @brief UART status flags. + * + * This provides constants for the UART status flags for use in the UART functions. + */ +enum _uart_flags +{ + kUART_TxDataRegEmptyFlag = (UART_S1_TDRE_MASK), /*!< TX data register empty flag. */ + kUART_TransmissionCompleteFlag = (UART_S1_TC_MASK), /*!< Transmission complete flag. */ + kUART_RxDataRegFullFlag = (UART_S1_RDRF_MASK), /*!< RX data register full flag. */ + kUART_IdleLineFlag = (UART_S1_IDLE_MASK), /*!< Idle line detect flag. */ + kUART_RxOverrunFlag = (UART_S1_OR_MASK), /*!< RX overrun flag. */ + kUART_NoiseErrorFlag = (UART_S1_NF_MASK), /*!< RX takes 3 samples of each received bit. + If any of these samples differ, noise flag sets */ + kUART_FramingErrorFlag = (UART_S1_FE_MASK), /*!< Frame error flag, sets if logic 0 was detected + where stop bit expected */ + kUART_ParityErrorFlag = (UART_S1_PF_MASK), /*!< If parity enabled, sets upon parity error detection */ +#if defined(FSL_FEATURE_UART_HAS_LIN_BREAK_DETECT) && FSL_FEATURE_UART_HAS_LIN_BREAK_DETECT + kUART_LinBreakFlag = + (UART_S2_LBKDIF_MASK + << 8), /*!< LIN break detect interrupt flag, sets when LIN break char detected and LIN circuit enabled */ +#endif + kUART_RxActiveEdgeFlag = + (UART_S2_RXEDGIF_MASK << 8), /*!< RX pin active edge interrupt flag,sets when active edge detected */ + kUART_RxActiveFlag = + (UART_S2_RAF_MASK << 8), /*!< Receiver Active Flag (RAF), sets at beginning of valid start bit */ +#if defined(FSL_FEATURE_UART_HAS_EXTENDED_DATA_REGISTER_FLAGS) && FSL_FEATURE_UART_HAS_EXTENDED_DATA_REGISTER_FLAGS + kUART_NoiseErrorInRxDataRegFlag = (UART_ED_NOISY_MASK << 16), /*!< Noisy bit, sets if noise detected. */ + kUART_ParityErrorInRxDataRegFlag = (UART_ED_PARITYE_MASK << 16), /*!< Paritye bit, sets if parity error detected. */ +#endif +#if defined(FSL_FEATURE_UART_HAS_FIFO) && FSL_FEATURE_UART_HAS_FIFO + kUART_TxFifoEmptyFlag = (UART_SFIFO_TXEMPT_MASK << 24), /*!< TXEMPT bit, sets if TX buffer is empty */ + kUART_RxFifoEmptyFlag = (UART_SFIFO_RXEMPT_MASK << 24), /*!< RXEMPT bit, sets if RX buffer is empty */ + kUART_TxFifoOverflowFlag = (UART_SFIFO_TXOF_MASK << 24), /*!< TXOF bit, sets if TX buffer overflow occurred */ + kUART_RxFifoOverflowFlag = (UART_SFIFO_RXOF_MASK << 24), /*!< RXOF bit, sets if receive buffer overflow */ + kUART_RxFifoUnderflowFlag = (UART_SFIFO_RXUF_MASK << 24), /*!< RXUF bit, sets if receive buffer underflow */ +#endif +}; + +/*! @brief UART configuration structure. */ +typedef struct _uart_config +{ + uint32_t baudRate_Bps; /*!< UART baud rate */ + uart_parity_mode_t parityMode; /*!< Parity mode, disabled (default), even, odd */ +#if defined(FSL_FEATURE_UART_HAS_STOP_BIT_CONFIG_SUPPORT) && FSL_FEATURE_UART_HAS_STOP_BIT_CONFIG_SUPPORT + uart_stop_bit_count_t stopBitCount; /*!< Number of stop bits, 1 stop bit (default) or 2 stop bits */ +#endif +#if defined(FSL_FEATURE_UART_HAS_FIFO) && FSL_FEATURE_UART_HAS_FIFO + uint8_t txFifoWatermark; /*!< TX FIFO watermark */ + uint8_t rxFifoWatermark; /*!< RX FIFO watermark */ +#endif +#if defined(FSL_FEATURE_UART_HAS_MODEM_SUPPORT) && FSL_FEATURE_UART_HAS_MODEM_SUPPORT + bool enableRxRTS; /*!< RX RTS enable */ + bool enableTxCTS; /*!< TX CTS enable */ +#endif + uart_idle_type_select_t idleType; /*!< IDLE type select. */ + bool enableTx; /*!< Enable TX */ + bool enableRx; /*!< Enable RX */ +} uart_config_t; + +/*! @brief UART transfer structure. */ +typedef struct _uart_transfer +{ + uint8_t *data; /*!< The buffer of data to be transfer.*/ + size_t dataSize; /*!< The byte count to be transfer. */ +} uart_transfer_t; + +/* Forward declaration of the handle typedef. */ +typedef struct _uart_handle uart_handle_t; + +/*! @brief UART transfer callback function. */ +typedef void (*uart_transfer_callback_t)(UART_Type *base, uart_handle_t *handle, status_t status, void *userData); + +/*! @brief UART handle structure. */ +struct _uart_handle +{ + uint8_t *volatile txData; /*!< Address of remaining data to send. */ + volatile size_t txDataSize; /*!< Size of the remaining data to send. */ + size_t txDataSizeAll; /*!< Size of the data to send out. */ + uint8_t *volatile rxData; /*!< Address of remaining data to receive. */ + volatile size_t rxDataSize; /*!< Size of the remaining data to receive. */ + size_t rxDataSizeAll; /*!< Size of the data to receive. */ + + uint8_t *rxRingBuffer; /*!< Start address of the receiver ring buffer. */ + size_t rxRingBufferSize; /*!< Size of the ring buffer. */ + volatile uint16_t rxRingBufferHead; /*!< Index for the driver to store received data into ring buffer. */ + volatile uint16_t rxRingBufferTail; /*!< Index for the user to get data from the ring buffer. */ + + uart_transfer_callback_t callback; /*!< Callback function. */ + void *userData; /*!< UART callback function parameter.*/ + + volatile uint8_t txState; /*!< TX transfer state. */ + volatile uint8_t rxState; /*!< RX transfer state */ +}; + +/******************************************************************************* + * API + ******************************************************************************/ + +#if defined(__cplusplus) +extern "C" { +#endif /* _cplusplus */ + +/*! + * @brief Get the UART instance from peripheral base address. + * + * @param base UART peripheral base address. + * @return UART instance. + */ +uint32_t UART_GetInstance(UART_Type *base); + +/*! + * @name Initialization and deinitialization + * @{ + */ + +/*! + * @brief Initializes a UART instance with a user configuration structure and peripheral clock. + * + * This function configures the UART module with the user-defined settings. The user can configure the configuration + * structure and also get the default configuration by using the UART_GetDefaultConfig() function. + * The example below shows how to use this API to configure UART. + * @code + * uart_config_t uartConfig; + * uartConfig.baudRate_Bps = 115200U; + * uartConfig.parityMode = kUART_ParityDisabled; + * uartConfig.stopBitCount = kUART_OneStopBit; + * uartConfig.txFifoWatermark = 0; + * uartConfig.rxFifoWatermark = 1; + * UART_Init(UART1, &uartConfig, 20000000U); + * @endcode + * + * @param base UART peripheral base address. + * @param config Pointer to the user-defined configuration structure. + * @param srcClock_Hz UART clock source frequency in HZ. + * @retval kStatus_UART_BaudrateNotSupport Baudrate is not support in current clock source. + * @retval kStatus_Success Status UART initialize succeed + */ +status_t UART_Init(UART_Type *base, const uart_config_t *config, uint32_t srcClock_Hz); + +/*! + * @brief Deinitializes a UART instance. + * + * This function waits for TX complete, disables TX and RX, and disables the UART clock. + * + * @param base UART peripheral base address. + */ +void UART_Deinit(UART_Type *base); + +/*! + * @brief Gets the default configuration structure. + * + * This function initializes the UART configuration structure to a default value. The default + * values are as follows. + * uartConfig->baudRate_Bps = 115200U; + * uartConfig->bitCountPerChar = kUART_8BitsPerChar; + * uartConfig->parityMode = kUART_ParityDisabled; + * uartConfig->stopBitCount = kUART_OneStopBit; + * uartConfig->txFifoWatermark = 0; + * uartConfig->rxFifoWatermark = 1; + * uartConfig->idleType = kUART_IdleTypeStartBit; + * uartConfig->enableTx = false; + * uartConfig->enableRx = false; + * + * @param config Pointer to configuration structure. + */ +void UART_GetDefaultConfig(uart_config_t *config); + +/*! + * @brief Sets the UART instance baud rate. + * + * This function configures the UART module baud rate. This function is used to update + * the UART module baud rate after the UART module is initialized by the UART_Init. + * @code + * UART_SetBaudRate(UART1, 115200U, 20000000U); + * @endcode + * + * @param base UART peripheral base address. + * @param baudRate_Bps UART baudrate to be set. + * @param srcClock_Hz UART clock source freqency in Hz. + * @retval kStatus_UART_BaudrateNotSupport Baudrate is not support in the current clock source. + * @retval kStatus_Success Set baudrate succeeded. + */ +status_t UART_SetBaudRate(UART_Type *base, uint32_t baudRate_Bps, uint32_t srcClock_Hz); + +/* @} */ + +/*! + * @name Status + * @{ + */ + +/*! + * @brief Gets UART status flags. + * + * This function gets all UART status flags. The flags are returned as the logical + * OR value of the enumerators @ref _uart_flags. To check a specific status, + * compare the return value with enumerators in @ref _uart_flags. + * For example, to check whether the TX is empty, do the following. + * @code + * if (kUART_TxDataRegEmptyFlag & UART_GetStatusFlags(UART1)) + * { + * ... + * } + * @endcode + * + * @param base UART peripheral base address. + * @return UART status flags which are ORed by the enumerators in the _uart_flags. + */ +uint32_t UART_GetStatusFlags(UART_Type *base); + +/*! + * @brief Clears status flags with the provided mask. + * + * This function clears UART status flags with a provided mask. An automatically cleared flag + * can't be cleared by this function. + * These flags can only be cleared or set by hardware. + * kUART_TxDataRegEmptyFlag, kUART_TransmissionCompleteFlag, kUART_RxDataRegFullFlag, + * kUART_RxActiveFlag, kUART_NoiseErrorInRxDataRegFlag, kUART_ParityErrorInRxDataRegFlag, + * kUART_TxFifoEmptyFlag,kUART_RxFifoEmptyFlag + * Note that this API should be called when the Tx/Rx is idle. Otherwise it has no effect. + * + * @param base UART peripheral base address. + * @param mask The status flags to be cleared; it is logical OR value of @ref _uart_flags. + * @retval kStatus_UART_FlagCannotClearManually The flag can't be cleared by this function but + * it is cleared automatically by hardware. + * @retval kStatus_Success Status in the mask is cleared. + */ +status_t UART_ClearStatusFlags(UART_Type *base, uint32_t mask); + +/* @} */ + +/*! + * @name Interrupts + * @{ + */ + +/*! + * @brief Enables UART interrupts according to the provided mask. + * + * This function enables the UART interrupts according to the provided mask. The mask + * is a logical OR of enumeration members. See @ref _uart_interrupt_enable. + * For example, to enable TX empty interrupt and RX full interrupt, do the following. + * @code + * UART_EnableInterrupts(UART1,kUART_TxDataRegEmptyInterruptEnable | kUART_RxDataRegFullInterruptEnable); + * @endcode + * + * @param base UART peripheral base address. + * @param mask The interrupts to enable. Logical OR of @ref _uart_interrupt_enable. + */ +void UART_EnableInterrupts(UART_Type *base, uint32_t mask); + +/*! + * @brief Disables the UART interrupts according to the provided mask. + * + * This function disables the UART interrupts according to the provided mask. The mask + * is a logical OR of enumeration members. See @ref _uart_interrupt_enable. + * For example, to disable TX empty interrupt and RX full interrupt do the following. + * @code + * UART_DisableInterrupts(UART1,kUART_TxDataRegEmptyInterruptEnable | kUART_RxDataRegFullInterruptEnable); + * @endcode + * + * @param base UART peripheral base address. + * @param mask The interrupts to disable. Logical OR of @ref _uart_interrupt_enable. + */ +void UART_DisableInterrupts(UART_Type *base, uint32_t mask); + +/*! + * @brief Gets the enabled UART interrupts. + * + * This function gets the enabled UART interrupts. The enabled interrupts are returned + * as the logical OR value of the enumerators @ref _uart_interrupt_enable. To check + * a specific interrupts enable status, compare the return value with enumerators + * in @ref _uart_interrupt_enable. + * For example, to check whether TX empty interrupt is enabled, do the following. + * @code + * uint32_t enabledInterrupts = UART_GetEnabledInterrupts(UART1); + * + * if (kUART_TxDataRegEmptyInterruptEnable & enabledInterrupts) + * { + * ... + * } + * @endcode + * + * @param base UART peripheral base address. + * @return UART interrupt flags which are logical OR of the enumerators in @ref _uart_interrupt_enable. + */ +uint32_t UART_GetEnabledInterrupts(UART_Type *base); + +/* @} */ + +#if defined(FSL_FEATURE_UART_HAS_DMA_SELECT) && FSL_FEATURE_UART_HAS_DMA_SELECT +/*! + * @name DMA Control + * @{ + */ + +/*! + * @brief Gets the UART data register address. + * + * This function returns the UART data register address, which is mainly used by DMA/eDMA. + * + * @param base UART peripheral base address. + * @return UART data register addresses which are used both by the transmitter and the receiver. + */ +static inline uint32_t UART_GetDataRegisterAddress(UART_Type *base) +{ + return (uint32_t) & (base->D); +} + +/*! + * @brief Enables or disables the UART transmitter DMA request. + * + * This function enables or disables the transmit data register empty flag, S1[TDRE], to generate the DMA requests. + * + * @param base UART peripheral base address. + * @param enable True to enable, false to disable. + */ +static inline void UART_EnableTxDMA(UART_Type *base, bool enable) +{ + if (enable) + { +#if (defined(FSL_FEATURE_UART_IS_SCI) && FSL_FEATURE_UART_IS_SCI) + base->C4 |= UART_C4_TDMAS_MASK; +#else + base->C5 |= UART_C5_TDMAS_MASK; +#endif + base->C2 |= UART_C2_TIE_MASK; + } + else + { +#if (defined(FSL_FEATURE_UART_IS_SCI) && FSL_FEATURE_UART_IS_SCI) + base->C4 &= ~UART_C4_TDMAS_MASK; +#else + base->C5 &= ~UART_C5_TDMAS_MASK; +#endif + base->C2 &= ~UART_C2_TIE_MASK; + } +} + +/*! + * @brief Enables or disables the UART receiver DMA. + * + * This function enables or disables the receiver data register full flag, S1[RDRF], to generate DMA requests. + * + * @param base UART peripheral base address. + * @param enable True to enable, false to disable. + */ +static inline void UART_EnableRxDMA(UART_Type *base, bool enable) +{ + if (enable) + { +#if (defined(FSL_FEATURE_UART_IS_SCI) && FSL_FEATURE_UART_IS_SCI) + base->C4 |= UART_C4_RDMAS_MASK; +#else + base->C5 |= UART_C5_RDMAS_MASK; +#endif + base->C2 |= UART_C2_RIE_MASK; + } + else + { +#if (defined(FSL_FEATURE_UART_IS_SCI) && FSL_FEATURE_UART_IS_SCI) + base->C4 &= ~UART_C4_RDMAS_MASK; +#else + base->C5 &= ~UART_C5_RDMAS_MASK; +#endif + base->C2 &= ~UART_C2_RIE_MASK; + } +} + +/* @} */ +#endif /* FSL_FEATURE_UART_HAS_DMA_SELECT */ + +/*! + * @name Bus Operations + * @{ + */ + +/*! + * @brief Enables or disables the UART transmitter. + * + * This function enables or disables the UART transmitter. + * + * @param base UART peripheral base address. + * @param enable True to enable, false to disable. + */ +static inline void UART_EnableTx(UART_Type *base, bool enable) +{ + if (enable) + { + base->C2 |= UART_C2_TE_MASK; + } + else + { + base->C2 &= ~UART_C2_TE_MASK; + } +} + +/*! + * @brief Enables or disables the UART receiver. + * + * This function enables or disables the UART receiver. + * + * @param base UART peripheral base address. + * @param enable True to enable, false to disable. + */ +static inline void UART_EnableRx(UART_Type *base, bool enable) +{ + if (enable) + { + base->C2 |= UART_C2_RE_MASK; + } + else + { + base->C2 &= ~UART_C2_RE_MASK; + } +} + +/*! + * @brief Writes to the TX register. + * + * This function writes data to the TX register directly. The upper layer must ensure + * that the TX register is empty or TX FIFO has empty room before calling this function. + * + * @param base UART peripheral base address. + * @param data The byte to write. + */ +static inline void UART_WriteByte(UART_Type *base, uint8_t data) +{ + base->D = data; +} + +/*! + * @brief Reads the RX register directly. + * + * This function reads data from the RX register directly. The upper layer must + * ensure that the RX register is full or that the TX FIFO has data before calling this function. + * + * @param base UART peripheral base address. + * @return The byte read from UART data register. + */ +static inline uint8_t UART_ReadByte(UART_Type *base) +{ + return base->D; +} + +/*! + * @brief Writes to the TX register using a blocking method. + * + * This function polls the TX register, waits for the TX register to be empty or for the TX FIFO + * to have room and writes data to the TX buffer. + * + * @note This function does not check whether all data is sent out to the bus. + * Before disabling the TX, check kUART_TransmissionCompleteFlag to ensure that the TX is + * finished. + * + * @param base UART peripheral base address. + * @param data Start address of the data to write. + * @param length Size of the data to write. + */ +void UART_WriteBlocking(UART_Type *base, const uint8_t *data, size_t length); + +/*! + * @brief Read RX data register using a blocking method. + * + * This function polls the RX register, waits for the RX register to be full or for RX FIFO to + * have data, and reads data from the TX register. + * + * @param base UART peripheral base address. + * @param data Start address of the buffer to store the received data. + * @param length Size of the buffer. + * @retval kStatus_UART_RxHardwareOverrun Receiver overrun occurred while receiving data. + * @retval kStatus_UART_NoiseError A noise error occurred while receiving data. + * @retval kStatus_UART_FramingError A framing error occurred while receiving data. + * @retval kStatus_UART_ParityError A parity error occurred while receiving data. + * @retval kStatus_Success Successfully received all data. + */ +status_t UART_ReadBlocking(UART_Type *base, uint8_t *data, size_t length); + +/* @} */ + +/*! + * @name Transactional + * @{ + */ + +/*! + * @brief Initializes the UART handle. + * + * This function initializes the UART handle which can be used for other UART + * transactional APIs. Usually, for a specified UART instance, + * call this API once to get the initialized handle. + * + * @param base UART peripheral base address. + * @param handle UART handle pointer. + * @param callback The callback function. + * @param userData The parameter of the callback function. + */ +void UART_TransferCreateHandle(UART_Type *base, + uart_handle_t *handle, + uart_transfer_callback_t callback, + void *userData); + +/*! + * @brief Sets up the RX ring buffer. + * + * This function sets up the RX ring buffer to a specific UART handle. + * + * When the RX ring buffer is used, data received are stored into the ring buffer even when the + * user doesn't call the UART_TransferReceiveNonBlocking() API. If data is already received + * in the ring buffer, the user can get the received data from the ring buffer directly. + * + * @note When using the RX ring buffer, one byte is reserved for internal use. In other + * words, if @p ringBufferSize is 32, only 31 bytes are used for saving data. + * + * @param base UART peripheral base address. + * @param handle UART handle pointer. + * @param ringBuffer Start address of the ring buffer for background receiving. Pass NULL to disable the ring buffer. + * @param ringBufferSize Size of the ring buffer. + */ +void UART_TransferStartRingBuffer(UART_Type *base, uart_handle_t *handle, uint8_t *ringBuffer, size_t ringBufferSize); + +/*! + * @brief Aborts the background transfer and uninstalls the ring buffer. + * + * This function aborts the background transfer and uninstalls the ring buffer. + * + * @param base UART peripheral base address. + * @param handle UART handle pointer. + */ +void UART_TransferStopRingBuffer(UART_Type *base, uart_handle_t *handle); + +/*! + * @brief Get the length of received data in RX ring buffer. + * + * @param handle UART handle pointer. + * @return Length of received data in RX ring buffer. + */ +size_t UART_TransferGetRxRingBufferLength(uart_handle_t *handle); + +/*! + * @brief Transmits a buffer of data using the interrupt method. + * + * This function sends data using an interrupt method. This is a non-blocking function, which + * returns directly without waiting for all data to be written to the TX register. When + * all data is written to the TX register in the ISR, the UART driver calls the callback + * function and passes the @ref kStatus_UART_TxIdle as status parameter. + * + * @note The kStatus_UART_TxIdle is passed to the upper layer when all data is written + * to the TX register. However, it does not ensure that all data is sent out. Before disabling the TX, + * check the kUART_TransmissionCompleteFlag to ensure that the TX is finished. + * + * @param base UART peripheral base address. + * @param handle UART handle pointer. + * @param xfer UART transfer structure. See #uart_transfer_t. + * @retval kStatus_Success Successfully start the data transmission. + * @retval kStatus_UART_TxBusy Previous transmission still not finished; data not all written to TX register yet. + * @retval kStatus_InvalidArgument Invalid argument. + */ +status_t UART_TransferSendNonBlocking(UART_Type *base, uart_handle_t *handle, uart_transfer_t *xfer); + +/*! + * @brief Aborts the interrupt-driven data transmit. + * + * This function aborts the interrupt-driven data sending. The user can get the remainBytes to find out + * how many bytes are not sent out. + * + * @param base UART peripheral base address. + * @param handle UART handle pointer. + */ +void UART_TransferAbortSend(UART_Type *base, uart_handle_t *handle); + +/*! + * @brief Gets the number of bytes written to the UART TX register. + * + * This function gets the number of bytes written to the UART TX + * register by using the interrupt method. + * + * @param base UART peripheral base address. + * @param handle UART handle pointer. + * @param count Send bytes count. + * @retval kStatus_NoTransferInProgress No send in progress. + * @retval kStatus_InvalidArgument The parameter is invalid. + * @retval kStatus_Success Get successfully through the parameter \p count; + */ +status_t UART_TransferGetSendCount(UART_Type *base, uart_handle_t *handle, uint32_t *count); + +/*! + * @brief Receives a buffer of data using an interrupt method. + * + * This function receives data using an interrupt method. This is a non-blocking function, which + * returns without waiting for all data to be received. + * If the RX ring buffer is used and not empty, the data in the ring buffer is copied and + * the parameter @p receivedBytes shows how many bytes are copied from the ring buffer. + * After copying, if the data in the ring buffer is not enough to read, the receive + * request is saved by the UART driver. When the new data arrives, the receive request + * is serviced first. When all data is received, the UART driver notifies the upper layer + * through a callback function and passes the status parameter @ref kStatus_UART_RxIdle. + * For example, the upper layer needs 10 bytes but there are only 5 bytes in the ring buffer. + * The 5 bytes are copied to the xfer->data and this function returns with the + * parameter @p receivedBytes set to 5. For the left 5 bytes, newly arrived data is + * saved from the xfer->data[5]. When 5 bytes are received, the UART driver notifies the upper layer. + * If the RX ring buffer is not enabled, this function enables the RX and RX interrupt + * to receive data to the xfer->data. When all data is received, the upper layer is notified. + * + * @param base UART peripheral base address. + * @param handle UART handle pointer. + * @param xfer UART transfer structure, see #uart_transfer_t. + * @param receivedBytes Bytes received from the ring buffer directly. + * @retval kStatus_Success Successfully queue the transfer into transmit queue. + * @retval kStatus_UART_RxBusy Previous receive request is not finished. + * @retval kStatus_InvalidArgument Invalid argument. + */ +status_t UART_TransferReceiveNonBlocking(UART_Type *base, + uart_handle_t *handle, + uart_transfer_t *xfer, + size_t *receivedBytes); + +/*! + * @brief Aborts the interrupt-driven data receiving. + * + * This function aborts the interrupt-driven data receiving. The user can get the remainBytes to know + * how many bytes are not received yet. + * + * @param base UART peripheral base address. + * @param handle UART handle pointer. + */ +void UART_TransferAbortReceive(UART_Type *base, uart_handle_t *handle); + +/*! + * @brief Gets the number of bytes that have been received. + * + * This function gets the number of bytes that have been received. + * + * @param base UART peripheral base address. + * @param handle UART handle pointer. + * @param count Receive bytes count. + * @retval kStatus_NoTransferInProgress No receive in progress. + * @retval kStatus_InvalidArgument Parameter is invalid. + * @retval kStatus_Success Get successfully through the parameter \p count; + */ +status_t UART_TransferGetReceiveCount(UART_Type *base, uart_handle_t *handle, uint32_t *count); + +/*! + * @brief UART IRQ handle function. + * + * This function handles the UART transmit and receive IRQ request. + * + * @param base UART peripheral base address. + * @param handle UART handle pointer. + */ +void UART_TransferHandleIRQ(UART_Type *base, uart_handle_t *handle); + +/*! + * @brief UART Error IRQ handle function. + * + * This function handles the UART error IRQ request. + * + * @param base UART peripheral base address. + * @param handle UART handle pointer. + */ +void UART_TransferHandleErrorIRQ(UART_Type *base, uart_handle_t *handle); + +/* @} */ + +#if defined(__cplusplus) +} +#endif + +/*! @}*/ + +#endif /* _FSL_UART_H_ */ diff --git a/source/cmds.c b/source/cmds.c new file mode 100644 index 0000000..f0f9124 --- /dev/null +++ b/source/cmds.c @@ -0,0 +1,48 @@ +/* + * cmds.c + * + * Copyright (C) 2018, 2019 Mind Chasers Inc. + * + * 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. + * + * function: convenience structs for sending commands to FPGA internal controller + * + */ + + + + +#include "cmds.h" + + +struct gen0_config i_init = {.cmd = 'i', .term = '\r'}; + +struct gen0_config pcs_s = {.cmd = 'p', .term = '\r'}; +struct gen0_config link_s = {.cmd = 'l', .term = '\r'}; + +struct gen1_config m0 = {.cmd = 'm', .b0 = 0x0, .term = '\r'}; +struct gen1_config m1 = {.cmd = 'm', .b0 = 0x1, .term = '\r'}; + +struct gen0_config test_tx_pkt = {.cmd = 't', .term = '\r'}; + +struct x_config x_reset = {.cmd = 'x', .ch0 = 0x3, .ch1 = 0x3, .ch2 = 0x3, .ch3 = 0x3, .term = '\r'}; +struct x_config x_init0 = {.cmd = 'x', .ch0 = 0x1, .ch1 = 0x1, .ch2 = 0x1, .ch3 = 0x1, .term = '\r'}; +struct x_config x_init1 = {.cmd = 'x', .ch0 = 0x0, .ch1 = 0x0, .ch2 = 0x0, .ch3 = 0x0, .term = '\r'}; + +struct u_config u_reset = {.cmd = 'u', .dcu0 = 0x7, .dcu1 = 0x7, .term = '\r'}; +struct u_config u_init = {.cmd = 'u', .dcu0 = 0x0, .dcu1 = 0x0, .term = '\r'}; + +struct c_config c_reset = {.cmd = 'c', .ch0 = 0x7, .ch1 = 0x7, .ch2 = 0x7, .ch3 = 0x7, .term = '\r'}; +struct c_config c_init0 = {.cmd = 'c', .ch0 = 0x5, .ch1 = 0x5, .ch2 = 0x5, .ch3 = 0x5, .term = '\r'}; +struct c_config c_init1 = {.cmd = 'c', .ch0 = 0x0, .ch1 = 0x0, .ch2 = 0x0, .ch3 = 0x0, .term = '\r'}; +struct c_config c_init_pcsr = {.cmd = 'c', .ch0 = 0x0, .ch1 = 0x0, .ch2 = 0x1, .ch3 = 0x1, .term = '\r'}; diff --git a/source/cmds.h b/source/cmds.h new file mode 100644 index 0000000..f03f8e4 --- /dev/null +++ b/source/cmds.h @@ -0,0 +1,100 @@ +/* + * cmds.h + * + * Copyright (C) 2018, 2019 Mind Chasers Inc. + * + * 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 CMDS_H_ +#define CMDS_H_ + +#include "stdint.h" + +// PCS Bit Map +#define RX_CDR_LOL_0 0x01 +#define RX_CDR_LOL_1 0x02 +#define RX_CDR_LOL_2 0x04 +#define PLL_LOL_0 0x08 +#define PLL_LOL_1 0x10 + +// Link Status Bit Map +#define PORT_UP_0 0x1 +#define PORT_UP_1 0x2 + +// SCI Address Definitions + +#define SCI_SEL_CH0 0x00 +#define SCI_SEL_CH1 0x40 +#define SCI_SEL_AUX 0xC0 + +struct x_config { + char cmd; + uint8_t ch3; + uint8_t ch2; + uint8_t ch1; + uint8_t ch0; + char term; +}; + +struct c_config { + char cmd; + uint8_t ch3; + uint8_t ch2; + uint8_t ch1; + uint8_t ch0; + char term; +}; + +struct u_config { + char cmd; + uint8_t dcu1; + uint8_t dcu0; + char term; +}; + +struct gen0_config { + char cmd; + char term; +}; + +struct gen1_config { + char cmd; + uint8_t b0; + char term; +}; + +extern struct gen0_config i_init; +extern struct gen0_config pcs_s; +extern struct gen0_config link_s; + +extern struct gen1_config m0; +extern struct gen1_config m1; + +extern struct gen0_config test_tx_pkt; + +extern struct x_config x_reset; +extern struct x_config x_init0; +extern struct x_config x_init1; + +extern struct u_config u_reset; +extern struct u_config u_init; + +extern struct c_config c_reset; +extern struct c_config c_init0; +extern struct c_config c_init1; +extern struct c_config c_init_pcsr; + +#endif /* CMDS_H_ */ diff --git a/source/ecp5_driver.c b/source/ecp5_driver.c new file mode 100644 index 0000000..99373cd --- /dev/null +++ b/source/ecp5_driver.c @@ -0,0 +1,123 @@ +/* + * cmds.c + * + * Copyright (C) 2018, 2019 Mind Chasers Inc. + * + * 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. + * + * function: Initialize ECP PCS block + * + */ + +#include +#include +#include "board.h" +#include "fsl_debug_console.h" +#include "fsl_i2c.h" +#include "ecp5_driver.h" +#include "cmds.h" +#include "utils.h" +#include "main.h" + + +/* set PCS/SERDES block to reset */ +void ecp5_pcs_reset(i2c_master_transfer_t* pXfer) { + // reset our sgmii_cont modules, but leave the PHYs out of reset + i2c_write(pXfer, I2C_ECP5_ADDR, (uint8_t*) &x_init0, sizeof(x_init0)); + + // assert all channel resets + i2c_write(pXfer, I2C_ECP5_ADDR, (uint8_t*) &c_reset, sizeof(c_reset)); + + // assert all DCU resets + i2c_write(pXfer, I2C_ECP5_ADDR, (uint8_t*) &u_reset, sizeof(u_reset)); +} + + +int ecp5_pcs_init(i2c_master_transfer_t* pXfer, uint8_t* pBuff) { + uint8_t errors = 0; + + + // clear the I2C buffer of anything in the read FIFO + i2c_read(pXfer, I2C_ECP5_ADDR, (uint8_t*) pBuff, 8); + + /* + * Check RX and TX status for health + * If PLL isn't locked, then we need a reset. + */ + PRINTF("Check PCS Status (p) \r\n"); + i2c_write(pXfer,I2C_ECP5_ADDR, (uint8_t*) &pcs_s, sizeof(pcs_s)); + i2c_read(pXfer, I2C_ECP5_ADDR, (uint8_t*) pBuff, 8); + dump_data((uint8_t*) pBuff, 8, true); + errors = ascii_to_bin(pBuff[2]) << 4 | ascii_to_bin(pBuff[3]); + + if (errors == 0 ) { + return 0; + } + + PRINTF("Channel 1, DCU1 Init (u00) \r\n"); + i2c_write(pXfer, I2C_ECP5_ADDR, (uint8_t*) &u_init, sizeof(u_init)); + i2c_read(pXfer, I2C_ECP5_ADDR, (uint8_t*) pBuff, 8); + dump_data((uint8_t*) pBuff, 8, true); + + PRINTF("Remove SERDES Channel Resets (c555) :\r\n"); + i2c_write(pXfer, I2C_ECP5_ADDR, (uint8_t*) &c_init0, sizeof(c_init0)); + i2c_read(pXfer, I2C_ECP5_ADDR, (uint8_t*) pBuff, 8); + dump_data((uint8_t*) pBuff, 8, true); + + for (int i=0; i<20; i++) { + PRINTF("Check PCS Status (p) \r\n"); + i2c_write(pXfer, I2C_ECP5_ADDR, (uint8_t*) &pcs_s, sizeof(pcs_s)); + i2c_read(pXfer, I2C_ECP5_ADDR, (uint8_t*) pBuff, 8); + dump_data((uint8_t*) pBuff, 8, true); + + if ( pBuff[3] & PLL_LOL_0 ) { + PRINTF("Keep Testing Until PLL Lock\r\n"); + if (i==19) { + // give up + ecp5_pcs_reset(pXfer); + return -1; + } + } + else { + break; + } + } + + + PRINTF("Remove PCS Channel Resets (c000) :\r\n"); + i2c_write(pXfer, I2C_ECP5_ADDR, (uint8_t*) &c_init1, sizeof(c_init1)); + i2c_read(pXfer, I2C_ECP5_ADDR, (uint8_t*) pBuff, 8); + dump_data((uint8_t*) pBuff, 8, true); + + PRINTF("Remove SGMII Controller Resets (x000) :\r\n"); + i2c_write(pXfer, I2C_ECP5_ADDR, (uint8_t*) &x_init1, sizeof(x_init1)); + i2c_read(pXfer, I2C_ECP5_ADDR, (uint8_t*) pBuff, 8); + dump_data((uint8_t*) pBuff, 8, true); + + PRINTF("Check PCS Status (p) \r\n"); + i2c_write(pXfer, I2C_ECP5_ADDR, (uint8_t*) &pcs_s, sizeof(pcs_s)); + i2c_read(pXfer, I2C_ECP5_ADDR, (uint8_t*) pBuff, 8); + dump_data((uint8_t*) pBuff, 8, true); + errors = ascii_to_bin(pBuff[2]) << 4 | ascii_to_bin(pBuff[3]); + + if ( errors == 0) { + return 0; + } + else { + // configure resets back to default, so we can try again + ecp5_pcs_reset(pXfer); + return -1; + } + + return 0; +} diff --git a/source/ecp5_driver.h b/source/ecp5_driver.h new file mode 100644 index 0000000..887ebe3 --- /dev/null +++ b/source/ecp5_driver.h @@ -0,0 +1,34 @@ +/* + * ecp5_driver.h + * + * Copyright (C) 2018, 2019 Mind Chasers Inc. + * + * 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 ECP5_DRIVER_H_ +#define ECP5_DRIVER_H_ + +#define PCS_RX_ERROR_0 0x1 +#define PCS_RX_ERROR_1 0x2 +#define PCS_RX_ERROR_2 0x4 +#define PCS_RX_ERROR_3 0x8 + +#define PCS_TX_PLL_LOL_0 0x10 +#define PCS_TX_PLL_LOL_1 0x20 + + +int ecp5_pcs_init(i2c_master_transfer_t*, uint8_t*); + +#endif /* ECP5_DRIVER_H_ */ diff --git a/source/flexbus.h b/source/flexbus.h new file mode 100644 index 0000000..0f89564 --- /dev/null +++ b/source/flexbus.h @@ -0,0 +1,48 @@ +/* + * flexbus.h + * + * Copyright (C) 2018, 2019 Mind Chasers Inc. + * + * 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 FLEXBUS_H_ +#define FLEXBUS_H_ + + +// CREGS Bit Definitions +#define MEM_SEL_DCU 0x0 +#define MEM_SEL_DPR 0x1 +#define RESET_HFIFO_PTRS 0x4 + + +// Flex Bus Memory Map +#define MRAM_START_ADDRESS 0x60000000U +#define CREG_MEM_SEL MRAM_START_ADDRESS +#define CREG_IACK MRAM_START_ADDRESS+1 + +// Flex Bus Base Offsets for DCU +#define DCU_SCI_CH0 MRAM_START_ADDRESS+0x000 +#define DCU_SCI_CH1 MRAM_START_ADDRESS+0x040 +#define DCU_DUAL1 MRAM_START_ADDRESS+0x080 +#define DCU_SCI_CH2 MRAM_START_ADDRESS+0x100 +#define DCU_SCI_SPARE MRAM_START_ADDRESS+0x140 +#define DCU_DUAL0 MRAM_START_ADDRESS+0x180 + +// Flex Bus Base Offsets for DPRAM +#define DPRAM_RX MRAM_START_ADDRESS+0x000 +#define DPRAM_TX MRAM_START_ADDRESS+0x040 +#define DPRAM_META MRAM_START_ADDRESS+0x080 + +#endif /* FLEXBUS_H_ */ diff --git a/source/main.c b/source/main.c new file mode 100644 index 0000000..51b5daa --- /dev/null +++ b/source/main.c @@ -0,0 +1,272 @@ +/* + * main.c + * + * Copyright (C) 2018, 2019 Mind Chasers Inc. + * + * 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. + * + */ + +#include +#include "board.h" +#include "peripherals.h" +#include "pin_mux.h" +#include "clock_config.h" +#include "MK02F12810.h" +#include "fsl_debug_console.h" +#include "fsl_gpio.h" +#include "fsl_i2c.h" +#include "fsl_dspi.h" +#include "pin_mux.h" +#include "fsl_pit.h" + +#include "pmic.h" +#include "utils.h" +#include "cmds.h" +#include "spi.h" +#include "pwr_driver.h" +#include "phy_driver.h" +#include "ecp5_driver.h" + +#include "main.h" + + +/******************************************************************************* + * Global Variables + ******************************************************************************/ +bool power = true; +volatile int pit_cnt = 40; +bool interactive = true; +uint8_t cnt_scl_clk = 0; +uint8_t cnt_bit = 0; +uint8_t buf[100]; +i2c_master_config_t i2c_masterConfig; +i2c_master_transfer_t i2c_masterXfer; + +/* + * Todo: Make sure the operations are atomic inside and outside the ISR + */ +void PIT0_IRQHandler(void) { + /* Clear interrupt flag.*/ + PIT_ClearStatusFlags(PIT, kPIT_Chnl_0, kPIT_TimerFlag); + pit_cnt--; + if (pit_cnt == 0) { + pit_cnt = 40; + } +} + +/*! + * @brief PHY Interrupt. Handle PTD5 (fpga_int) + * + */ +void PORTD_IRQHandler(void) { + uint8_t data; + volatile uint32_t temp; + + i2c_write(&i2c_masterXfer, I2C_ECP5_ADDR, (uint8_t*) &c_init_pcsr, sizeof(c_init_pcsr)); + i2c_write(&i2c_masterXfer, I2C_ECP5_ADDR, (uint8_t*) &c_init1, sizeof(c_init1)); + + temp = GPIO_PinRead(GPIOD, 0x5); + + // clear int src bits + data=0; + write_spi(SPI_DEV_AD_INT_SEL, 1, &data, 1); + + /* Clear external interrupt flag. */ + GPIO_PortClearInterruptFlags(GPIOD, 0x1<<5); + + temp = GPIO_PortGetInterruptFlags(GPIOD); + +} + + +/* + * @brief Application entry point. + */ +int main(void) { + int size; + uint32_t sourceClock; + volatile static int i = 0; + volatile uint32_t temp; + pit_config_t pitConfig; // Periodic Interrupt Timer + + + gpio_pin_config_t pb7; // (10) PTE24 + gpio_pin_config_t pb6; // (11) PTE25 + + gpio_pin_config_t pmic_dcdc_e; // (17) PTA18 + gpio_pin_config_t pmic_ldo_e; // (18) PTA19 + + gpio_pin_config_t fcfg_pgmn; // (20) PTB0 + gpio_pin_config_t fcfg_done; // (21) PTB1 + + gpio_pin_config_t fpga_gpio; // (22) PTC1 + gpio_pin_config_t fpga_resetn; // (29) PTD4 + gpio_pin_config_t fpga_int; // (30) PTD5 + + dspi_master_config_t spi_masterConfig; + + + /* Init board hardware. */ + BOARD_InitBootPins(); + BOARD_InitBootClocks(); + BOARD_InitBootPeripherals(); + BOARD_InitDebugConsole(); + + /* Init GPIO */ + pmic_ldo_e.pinDirection = kGPIO_DigitalOutput; + pmic_ldo_e.outputLogic = 0; + GPIO_PinInit(GPIOA, 19, &pmic_ldo_e); + + // Negate FPGA_RESETN + GPIO_WritePinOutput(BOARD_INITPINS_FPGA_RESETN_GPIO, BOARD_INITPINS_FPGA_RESETN_PIN, 1); + + /* + * Initialize PIT module + * pitConfig.enableRunInDebug = false; + * Calls CLOCK_EnableCLock to enable PIT clock (gate control) in SIM_SCGC6 + * Configures PIT MCR register to enable clock for PIT timer and disable run during debug + */ + PIT_GetDefaultConfig(&pitConfig); + PIT_Init(PIT, &pitConfig); + + /* Set timer period for channel 0, + * calls CLOCK_GetFreq() + * sets PIT_LDVAL0 + */ + PIT_SetTimerPeriod(PIT, kPIT_Chnl_0, USEC_TO_COUNT(100U, CLOCK_GetFreq(kCLOCK_BusClk))); + + + /* Enable timer interrupts for channel 0 , + * set PIT_TCTRL0 = 2 (Timer Interrupt Enable ) + */ + PIT_EnableInterrupts(PIT, kPIT_Chnl_0, kPIT_TimerInterruptEnable); + + /* Start PIT channel 0 */ + PIT_StartTimer(PIT, kPIT_Chnl_0); + + + printf("Initialize I2C0.\n"); + I2C_MasterGetDefaultConfig(&i2c_masterConfig); + i2c_masterConfig.baudRate_Bps = I2C_BAUDRATE; + + sourceClock = CLOCK_GetFreq(I2C_MASTER_CLK_SRC); + + I2C_MasterInit(I2C_MASTER_BASEADDR, &i2c_masterConfig, sourceClock); + + memset(&i2c_masterXfer, 0, sizeof(i2c_masterXfer)); + + // set up defaults applicable to all transfers + i2c_masterXfer.subaddress = 0; + i2c_masterXfer.subaddressSize = 0; + i2c_masterXfer.flags = kI2C_TransferDefaultFlag; + + if (power) { + printf("Initialize Power\n\r"); + power_init(&i2c_masterXfer, buf); + } + + // wait for the FPGA to be ready + // TODO: add a robust handshake that also interrogates the FPGA image + while (i2c_read(&i2c_masterXfer, I2C_ECP5_ADDR, buf, 8) < 0) { + PRINTF("."); + } + + spi_init(spi_masterConfig); + + + + + PRINTF("\r\n Darsena! \r\n"); + i=0; + while (phy_init(&i2c_masterXfer, buf) < 0) { + i++; + } + + i=0; + while (ecp5_pcs_init(&i2c_masterXfer, buf) < 0) { + i++; + + } + + /* + buf[0]=192; + buf[1]=168; + buf[2]=3; + buf[3]=1; + + for (i = 0; i< 100; i++) { + PRINTF("\r\n test_spi() \r\n"); + write_spi(SPI_DEV_AD_DPRAM_RX, 0, buf, 4); + read_spi(SPI_DEV_AD_DPRAM_RX, 0, buf, 4); + + write_spi(SPI_DEV_AD_DPRAM_TX, 0, buf, 4); + read_spi(SPI_DEV_AD_DPRAM_TX, 0, buf, 4); + + write_spi(SPI_DEV_AD_PKT_FILTER_01, 0, buf, 4); + + read_spi(SPI_DEV_AD_SCI_SEL_CH_0, 0, buf, 4); + } + */ + temp = GPIO_PortGetInterruptFlags(GPIOD); + EnableIRQ(PIT0_IRQn); + EnableIRQ(PORTD_IRQn); + + while(interactive) { + + PRINTF("\r\n I2C Command Line. Hit enter to continue \r\n"); + DbgConsole_Flush(); + + do { + size = get_cmd(buf, 10); + PRINTF("\r\n received %d bytes \r\n", size); + + if (size != 0) { + if (buf[0] == 'T') { + phy_compliance_test(&i2c_masterXfer, buf[1]); + } + else { + i2c_write(&i2c_masterXfer, I2C_ECP5_ADDR, buf, size); + i2c_read(&i2c_masterXfer, I2C_ECP5_ADDR, buf, 8); + dump_data((uint8_t*) buf, 4, true ); + } + } + + + + } while(size != 0); + + } + + + /* Force the counter to be placed into memory. */ + + while(1) { + PRINTF("."); + i++; + } + return 0 ; +} + +/* + p_reg = (uint32_t*) 0x40037104; + temp_reg = *p_reg; + temp_reg = PIT_GetStatusFlags(PIT, kPIT_Chnl_0); + if (temp_reg != 0) { + // *pTFLG = 1; + temp_reg = __get_PRIMASK(); + temp_reg = __get_IPSR(); + temp_reg = NVIC_GetActive(PIT0_IRQn); + temp_reg = NVIC_GetEnableIRQ(PIT0_IRQn); + } + */ diff --git a/source/main.h b/source/main.h new file mode 100644 index 0000000..978e42c --- /dev/null +++ b/source/main.h @@ -0,0 +1,42 @@ +/* + * main.h + * + * Copyright (C) 2018, 2019 Mind Chasers Inc. + * + * 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 SOURCES_MAIN_H_ +#define SOURCES_MAIN_H_ + +#include + +/* board level I2C defines */ +#define I2C_MASTER_BASEADDR I2C0 +#define I2C_MASTER_CLK_SRC I2C0_CLK_SRC +#define I2C_DATA_MAX_LENGTH 257U +/* 200KHz */ +#define I2C_BAUDRATE 200000U + +#define I2C_ECP5_ADDR (uint8_t) 0x10U +#define I2C_PMIC_ADDR (uint8_t) 0x48U + +void PIT0_IRQHandler(void) __attribute__ ((isr)); +void PORTD_IRQHandler(void) __attribute__ ((isr)); + +status_t i2c_write(i2c_master_transfer_t* pxfer, uint8_t, uint8_t * pdata, size_t size); +status_t i2c_read(i2c_master_transfer_t* pxfer, uint8_t, uint8_t * pdata, size_t size); + +#endif /* SOURCES_MAIN_H_ */ diff --git a/source/phy_driver.c b/source/phy_driver.c new file mode 100644 index 0000000..fa0522f --- /dev/null +++ b/source/phy_driver.c @@ -0,0 +1,234 @@ +/* + * phy_driver.c + * + * Copyright (C) 2018, 2019 Mind Chasers Inc. + * + * 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. + * + */ + +#include +#include +#include "phy_driver.h" +#include "board.h" +#include "fsl_debug_console.h" +#include "fsl_i2c.h" +#include "ecp5_driver.h" +#include "cmds.h" +#include "utils.h" +#include "main.h" + + +/* + * Test 0 resets the PHY + */ + +void phy_compliance_test(i2c_master_transfer_t* pXfer, uint8_t test) { + + PRINTF("PHY TEST %d\n\r", test); + if (test == 0) { + write_mdio(pXfer, 0x1F, 0x8000); // reset PHY + } + else if (test == 1) { + write_mdio(pXfer, 0x1F, 0x8000); // reset PHY + write_mdio(pXfer, 0x00, 0x0140); // 1000 Base-T mode + write_mdio(pXfer, 0x10, 0x5008); // forced MDI mode + write_mdio(pXfer, 0x09, 0x3B00); // Test Mode 1 + write_mdio(pXfer, 0x25, 0x0480); // Output test mode to all channels + write_mdio(pXfer, 0x1D5, 0xF508); + } + else if (test == 2) { + write_mdio(pXfer, 0x1F, 0x8000); // reset PHY + write_mdio(pXfer, 0x00, 0x0140); // 1000 Base-T mode + write_mdio(pXfer, 0x10, 0x5008); // forced MDI mode + write_mdio(pXfer, 0x09, 0x5B00); // Test Mode 2 + write_mdio(pXfer, 0x25, 0x0480); // Output test mode to all channels + } + else if (test == 3) { + write_mdio(pXfer, 0x1F, 0x8000); // reset PHY + write_mdio(pXfer, 0x00, 0x0140); // 1000 Base-T mode + write_mdio(pXfer, 0x10, 0x5008); // forced MDI mode + write_mdio(pXfer, 0x09, 0x7B00); // Test Mode 3 + write_mdio(pXfer, 0x25, 0x0480); // Output test mode to all channels + } + else if (test == 4) { + write_mdio(pXfer, 0x1F, 0x8000); // reset PHY + write_mdio(pXfer, 0x00, 0x0140); // 1000 Base-T mode + write_mdio(pXfer, 0x10, 0x5008); // forced MDI mode + write_mdio(pXfer, 0x09, 0x9B00); // Test Mode 3 + write_mdio(pXfer, 0x25, 0x0400); // Channel A + } + else { + PRINTF("not supported\n\r"); + } + +} + + +/* + * Write using Extended Addressing + */ +void write_mdio(i2c_master_transfer_t* pXfer, uint16_t addr, uint16_t data) { + /* set the write address first with a read */ + read_mdio(pXfer, addr); + + uint8_t buf[16]; + buf[0]='z'; + buf[1] = (data & 0xf000) >> 12; + buf[2] = (data & 0x0f00) >> 8; + buf[3] = (data & 0x00f0) >> 4; + buf[4] = data & 0x000f; + buf[5]=0xd; + + i2c_write(pXfer, I2C_ECP5_ADDR, buf, 6); + i2c_read(pXfer,I2C_ECP5_ADDR, buf, 6); +} +/* + * Read using Extended Addressing. + */ +uint16_t read_mdio(i2c_master_transfer_t* pXfer, uint16_t addr) { + uint16_t temp; + uint8_t buf[16]; + + buf[0]='y'; + buf[1] = (addr & 0xf000) >> 12; + buf[2] = (addr & 0x0f00) >> 8; + buf[3] = (addr & 0x00f0) >> 4; + buf[4] = addr & 0x000f; + buf[5]=0xd; + + i2c_write(pXfer, I2C_ECP5_ADDR, buf, 6); + i2c_read(pXfer,I2C_ECP5_ADDR, buf, 6); + + temp = (buf[0] & 0xf) << 12 | (buf[1] & 0xf) << 8 | (buf[2] & 0xf) << 4 | (buf[3] & 0xf); + return temp; +} + +int invert_sgmii_polarity(i2c_master_transfer_t* pXfer, uint8_t phy) { + uint8_t buf[16]; + + // set the right PHY mux_sel + buf[0]='m'; + buf[1]=phy; + i2c_write(pXfer, I2C_ECP5_ADDR, buf, 2); + i2c_read(pXfer,I2C_ECP5_ADDR, buf, 6); + + // Extended Write of 0x01D5 + + // Read 0xD + buf[0]='r'; + buf[1]=0x0; + buf[2]=0xd; + i2c_write(pXfer, I2C_ECP5_ADDR, buf, 3); + i2c_read(pXfer,I2C_ECP5_ADDR, buf, 6); + + // Write 0x001f to 0xD + buf[0]='w'; + buf[1]=0x0; + buf[2]=0x0; + buf[3]=0x1; + buf[4]=0xf; + i2c_write(pXfer, I2C_ECP5_ADDR, buf, 5); + i2c_read(pXfer,I2C_ECP5_ADDR, buf, 6); + + // Read 0xE to set address + buf[0]='r'; + buf[1]=0x0; + buf[2]=0xe; + i2c_write(pXfer, I2C_ECP5_ADDR, buf, 3); + i2c_read(pXfer,I2C_ECP5_ADDR, buf, 6); + + // Write the extended address 0x01D0 to 0xe + buf[0]='w'; + buf[1]=0x0; + buf[2]=0x1; + buf[3]=0xD; + buf[4]=0x5; + i2c_write(pXfer, I2C_ECP5_ADDR, buf, 5); + i2c_read(pXfer,I2C_ECP5_ADDR, buf, 6); + + // Read 0xD to set address + buf[0]='r'; + buf[1]=0x0; + buf[2]=0xd; + i2c_write(pXfer, I2C_ECP5_ADDR, buf, 3); + i2c_read(pXfer,I2C_ECP5_ADDR, buf, 6); + + // Write 0x401f to 0xD + buf[0]='w'; + buf[1]=0x4; + buf[2]=0x0; + buf[3]=0x1; + buf[4]=0xf; + i2c_write(pXfer, I2C_ECP5_ADDR, buf, 5); + i2c_read(pXfer,I2C_ECP5_ADDR, buf, 6); + + // Read 0xE to set address + buf[0]='r'; + buf[1]=0x0; + buf[2]=0xe; + i2c_write(pXfer, I2C_ECP5_ADDR, buf, 3); + i2c_read(pXfer,I2C_ECP5_ADDR, buf, 6); + + // Write inversion bits to 0xE + buf[0]='w'; + buf[1]=0x0; + buf[2]=0x0; + buf[3]=0x0; + buf[4]=0x3; + i2c_write(pXfer, I2C_ECP5_ADDR, buf, 5); + i2c_read(pXfer,I2C_ECP5_ADDR, buf, 6); + + // Perform a soft reset: bit 15 at 0x1f (CTRL Reg) + + // Read 0x1F to set address + buf[0]='r'; + buf[1]=0x1; + buf[2]=0xf; + i2c_write(pXfer, I2C_ECP5_ADDR, buf, 3); + i2c_read(pXfer,I2C_ECP5_ADDR, buf, 6); + + // Write bit 14 (0x8000) (SW reset, not including registers) + buf[0]='w'; + buf[1]=0x4; + buf[2]=0x0; + buf[3]=0x0; + buf[4]=0x0; + i2c_write(pXfer, I2C_ECP5_ADDR, buf, 5); + i2c_read(pXfer,I2C_ECP5_ADDR, buf, 6); + + return(0); + +} + + + +/* The assumption is that the PHY is brought up before the FPGA / Switch */ +//TODO: Should read the other values, so we don't change them / affect other parts of the register */ +int phy_init(i2c_master_transfer_t* pXfer, uint8_t* pBuff) { + + PRINTF("Take PHYs out of reset (x111) \r\n"); + i2c_write(pXfer, I2C_ECP5_ADDR, (uint8_t*) &x_init0, sizeof(x_init0)); + i2c_read(pXfer, I2C_ECP5_ADDR, (uint8_t*) pBuff, 8); + dump_data((uint8_t*) pBuff, 8, true); + + /* + invert_sgmii_polarity(0); + invert_sgmii_polarity(1); + */ + + return(0); + +} + + diff --git a/source/phy_driver.h b/source/phy_driver.h new file mode 100644 index 0000000..df6d5bc --- /dev/null +++ b/source/phy_driver.h @@ -0,0 +1,33 @@ +/* + * phy_driver.h + * + * Copyright (C) 2018, 2019 Mind Chasers Inc. + * + * 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 PHY_DRIVER_H_ +#define PHY_DRIVER_H_ + +#include +#include "fsl_i2c.h" + +void phy_compliance_test(i2c_master_transfer_t*, uint8_t); + +void write_mdio(i2c_master_transfer_t*, uint16_t, uint16_t ); +uint16_t read_mdio(i2c_master_transfer_t* , uint16_t ); + +int phy_init(i2c_master_transfer_t*, uint8_t*); + +#endif /* PHY_DRIVER_H_ */ diff --git a/source/pmic.h b/source/pmic.h new file mode 100644 index 0000000..06ac9fb --- /dev/null +++ b/source/pmic.h @@ -0,0 +1,49 @@ +/* + * pmic.h + * + * Copyright (C) 2018, 2019 Mind Chasers Inc. + * + * 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 SOURCES_PMIC_H_ +#define SOURCES_PMIC_H_ + +#define PMIC_VERSION 0 +#define PMIC_PGOODZ 1 +#define PMIC_MASK 2 +#define PMIC_REG_CTRL 3 +#define PMIC_CON_CTRL 4 +#define PMIC_CON_CTRL2 5 +#define PMIC_DEFCORE 6 +#define PMIC_DEFSLEW 7 +#define PMIC_LDO_CTRL 8 + +// PMIC_PGOODZ +#define PGOODZ_LDO1 2 + +// PMIC_REG_CTRL +#define LDO1_ENABLE 0x02 +#define LDO2_ENABLE 0x04 +#define VDDC3_ENABLE 0x08 +#define VDDC2_ENABLE 0x10 +#define VDDC1_ENABLE 0x20 + +// PMIC_LDO_CTRL +// LDO2 = 2.5V, LD01 = 1.1V +#define LDO1_1_1V 1 +#define LDO2_2_5V 4 + +#endif /* SOURCES_PMIC_H_ */ diff --git a/source/pwr_driver.c b/source/pwr_driver.c new file mode 100644 index 0000000..37abbd4 --- /dev/null +++ b/source/pwr_driver.c @@ -0,0 +1,113 @@ +/* + * pwr_driver.c + * + * Copyright (C) 2018, 2019 Mind Chasers Inc. + * + * 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. + * + */ + +#include "board.h" +#include "pmic.h" +#include "fsl_debug_console.h" +#include "fsl_common.h" +#include "fsl_i2c.h" +#include "fsl_gpio.h" +#include "main.h" + +int power_init(i2c_master_transfer_t* pXfer, uint8_t* pBuff) { + + bool repeat = false; + uint8_t addr,data; + uint8_t buf[2]; // write address followed by data +_loop: + + PRINTF("Power Init\r\n"); + + // Read version + addr=PMIC_VERSION; + i2c_write(pXfer, I2C_PMIC_ADDR, &addr, 1); + i2c_read(pXfer, I2C_PMIC_ADDR, (uint8_t*) pBuff, 1); + //PRINTF("Version: 0x%2x\r\n", *pBuff); + + // Read PGOODZ + addr=PMIC_PGOODZ; + i2c_write(pXfer, I2C_PMIC_ADDR, &addr, 1); + i2c_read(pXfer, I2C_PMIC_ADDR, (uint8_t*) pBuff, 1); + //PRINTF("PGOODZ: 0x%2x\r\n", *pBuff); + + // Read MASK + addr=PMIC_MASK; + i2c_write(pXfer, I2C_PMIC_ADDR, &addr, 1); + i2c_read(pXfer, I2C_PMIC_ADDR, (uint8_t*) pBuff, 1); + //PRINTF("MASK: 0x%2x\r\n", *pBuff); + + // Read REG_CTRL + addr=PMIC_REG_CTRL; + i2c_write(pXfer, I2C_PMIC_ADDR, &addr, 1); + i2c_read(pXfer, I2C_PMIC_ADDR, (uint8_t*) pBuff, 1); + //PRINTF("REG_CTRL: 0x%2x\r\n", *pBuff); + + // Read CON_CTRL + addr=PMIC_CON_CTRL; + i2c_write(pXfer, I2C_PMIC_ADDR, &addr, 1); + i2c_read(pXfer, I2C_PMIC_ADDR, (uint8_t*) pBuff, 1); + // PRINTF("CON_CTRL: 0x%2x\r\n", *pBuff); + + // Read CON_CTRL2 + addr=PMIC_CON_CTRL2; + i2c_write(pXfer, I2C_PMIC_ADDR, &addr, 1); + i2c_read(pXfer, I2C_PMIC_ADDR, (uint8_t*) pBuff, 1); + //PRINTF("CON_CTRL2: 0x%2x\r\n", *pBuff); + + // Read DEFCORE + // We want 1.1V: 0xc + addr=PMIC_DEFCORE; + i2c_write(pXfer, I2C_PMIC_ADDR, &addr, 1); + i2c_read(pXfer, I2C_PMIC_ADDR, (uint8_t*) pBuff, 1); + //PRINTF("DEFSLEW: 0x%2x\r\n", *pBuff); + + // Read DEFSLEW + addr=PMIC_DEFSLEW; + i2c_write(pXfer, I2C_PMIC_ADDR, &addr, 1); + i2c_read(pXfer, I2C_PMIC_ADDR, (uint8_t*) pBuff, 1); + //PRINTF("DEFSLEW: 0x%2x\r\n", *pBuff); + + // Read LDO_CTRL + addr=PMIC_LDO_CTRL; + i2c_write(pXfer, I2C_PMIC_ADDR, &addr, 1); + i2c_read(pXfer, I2C_PMIC_ADDR, (uint8_t*) pBuff, 1); + //PRINTF("LDO_CTRL: 0x%2x\r\n", *pBuff); + + // Write LDO_CTRL + addr=PMIC_LDO_CTRL; + data=LDO2_2_5V<<4|LDO1_1_1V; + buf[0]=addr; + buf[1]=data; + i2c_write(pXfer, I2C_PMIC_ADDR, buf, 2); + i2c_read(pXfer, I2C_PMIC_ADDR, (uint8_t*) pBuff, 1); + //PRINTF("LDO_CTRL: 0x%2x\r\n", *pBuff); + + GPIO_WritePinOutput(GPIOA, 19, 1); + + // Read PGOODZ + addr=PMIC_PGOODZ; + i2c_write(pXfer, I2C_PMIC_ADDR, &addr, 1); + i2c_read(pXfer, I2C_PMIC_ADDR, (uint8_t*) pBuff, 1); + //PRINTF("PGOODZ: 0x%2x\r\n", *pBuff); + + + if (repeat) goto _loop; + + return 0; +} diff --git a/source/pwr_driver.h b/source/pwr_driver.h new file mode 100644 index 0000000..4a63956 --- /dev/null +++ b/source/pwr_driver.h @@ -0,0 +1,26 @@ +/* + * pwr_driver.h + * + * Copyright (C) 2018, 2019 Mind Chasers Inc. + * + * 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 SOURCES_PWR_DRIVER_H_ +#define SOURCES_PWR_DRIVER_H_ + +int power_init(i2c_master_transfer_t*, uint8_t*); + + +#endif /* SOURCES_PWR_DRIVER_H_ */ diff --git a/source/semihost_hardfault.c b/source/semihost_hardfault.c new file mode 100644 index 0000000..dc8d3ae --- /dev/null +++ b/source/semihost_hardfault.c @@ -0,0 +1,109 @@ +// **************************************************************************** +// semihost_hardfault.c +// - Provides hard fault handler to allow semihosting code not +// to hang application when debugger not connected. +// +// **************************************************************************** +// Copyright(C) NXP Semiconductors, 2017-2018 +// All rights reserved. +// +// Software that is described herein is for illustrative purposes only +// which provides customers with programming information regarding the +// NXP Cortex-M based MCUs. This software is supplied "AS IS" without any +// warranties of any kind, and NXP Semiconductors and its licensor disclaim any +// and all warranties, express or implied, including all implied warranties of +// merchantability, fitness for a particular purpose and non-infringement of +// intellectual property rights. NXP Semiconductors assumes no responsibility +// or liability for the use of the software, conveys no license or rights under +// any patent, copyright, mask work right, or any other intellectual property +// rights in or to any products. NXP Semiconductors reserves the right to make +// changes in the software without notification. NXP Semiconductors also makes +// no representation or warranty that such application will be suitable for the +// specified use without further testing or modification. +// +// Permission to use, copy, modify, and distribute this software and its +// documentation is hereby granted, under NXP Semiconductors' and its +// licensor's relevant copyrights in the software, without fee, provided that it +// is used in conjunction with NXP Semiconductors microcontrollers. This +// copyright, permission, and disclaimer notice must appear in all copies of +// this code. +// **************************************************************************** +// +// ===== DESCRIPTION ===== +// +// One of the issues with applications that make use of semihosting operations +// (such as printf calls) is that the code will not execute correctly when the +// debugger is not connected. Generally this will show up with the application +// appearing to just hang. This may include the application running from reset +// or powering up the board (with the application already in FLASH), and also +// as the application failing to continue to execute after a debug session is +// terminated. +// +// The problem here is that the "bottom layer" of the semihosted variants of +// the C library, semihosting is implemented by a "BKPT 0xAB" instruction. +// When the debug tools are not connected, this instruction triggers a hard +// fault - and the default hard fault handler within an application will +// typically just contains an infinite loop - causing the application to +// appear to have hang when no debugger is connected. +// +// The below code provides an example hard fault handler which instead looks +// to see what the instruction that caused the hard fault was - and if it +// was a "BKPT 0xAB", then it instead returns back to the user application. +// +// In most cases this will allow applications containing semihosting +// operations to execute (to some degree) when the debugger is not connected. +// +// == NOTE == +// +// Correct execution of the application containing semihosted operations +// which are vectored onto this hard fault handler cannot be guaranteed. This +// is because the handler may not return data or return codes that the higher +// level C library code or application code expects. This hard fault handler +// is meant as a development aid, and it is not recommended to leave +// semihosted code in a production build of your application! +// +// **************************************************************************** + +// Allow handler to be removed by setting a define (via command line) +#if !defined (__SEMIHOST_HARDFAULT_DISABLE) + +__attribute__((naked)) +void HardFault_Handler(void){ + __asm( ".syntax unified\n" + // Check which stack is in use + "MOVS R0, #4 \n" + "MOV R1, LR \n" + "TST R0, R1 \n" + "BEQ _MSP \n" + "MRS R0, PSP \n" + "B _process \n" + "_MSP: \n" + "MRS R0, MSP \n" + // Load the instruction that triggered hard fault + "_process: \n" + "LDR R1,[R0,#24] \n" + "LDRH R2,[r1] \n" + // Semihosting instruction is "BKPT 0xAB" (0xBEAB) + "LDR R3,=0xBEAB \n" + "CMP R2,R3 \n" + "BEQ _semihost_return \n" + // Wasn't semihosting instruction so enter infinite loop + "B . \n" + // Was semihosting instruction, so adjust location to + // return to by 1 instruction (2 bytes), then exit function + "_semihost_return: \n" + "ADDS R1,#2 \n" + "STR R1,[R0,#24] \n" + // Set a return value from semihosting operation. + // 32 is slightly arbitrary, but appears to allow most + // C Library IO functions sitting on top of semihosting to + // continue to operate to some degree + "MOVS R1,#32 \n" + "STR R1,[ R0,#0 ] \n" // R0 is at location 0 on stack + // Return from hard fault handler to application + "BX LR \n" + ".syntax divided\n") ; +} + +#endif + diff --git a/source/spi.c b/source/spi.c new file mode 100644 index 0000000..aa36877 --- /dev/null +++ b/source/spi.c @@ -0,0 +1,159 @@ +/* + * spi.c + * + * Copyright (C) 2018, 2019 Mind Chasers Inc. + * + * 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. + * + */ + + +#include "fsl_debug_console.h" +#include "fsl_dspi.h" +#include "stdint.h" +#include "spi.h" + +int spi_init(dspi_master_config_t spi_masterConfig) { + uint32_t srcClock_Hz; + spi_masterConfig.whichCtar = kDSPI_Ctar0; + spi_masterConfig.ctarConfig.baudRate = DSPI_TRANSFER_BAUDRATE; + spi_masterConfig.ctarConfig.bitsPerFrame = 9U; + spi_masterConfig.ctarConfig.cpol = kDSPI_ClockPolarityActiveHigh; + spi_masterConfig.ctarConfig.cpha = kDSPI_ClockPhaseFirstEdge; + spi_masterConfig.ctarConfig.direction = kDSPI_MsbFirst; + spi_masterConfig.ctarConfig.pcsToSckDelayInNanoSec = 1000000000U / DSPI_TRANSFER_BAUDRATE; + spi_masterConfig.ctarConfig.lastSckToPcsDelayInNanoSec = 1000000000U / DSPI_TRANSFER_BAUDRATE; + spi_masterConfig.ctarConfig.betweenTransferDelayInNanoSec = 1000000000U / DSPI_TRANSFER_BAUDRATE; + + spi_masterConfig.whichPcs = kDSPI_Pcs0; + spi_masterConfig.pcsActiveHighOrLow = kDSPI_PcsActiveHigh; + + spi_masterConfig.enableContinuousSCK = false; + spi_masterConfig.enableRxFifoOverWrite = false; + spi_masterConfig.enableModifiedTimingFormat = false; + spi_masterConfig.samplePoint = kDSPI_SckToSin0Clock; + + srcClock_Hz = DSPI_MASTER_CLK_FREQ; + DSPI_MasterInit(DSPI_MASTER_BASEADDR, &spi_masterConfig, srcClock_Hz); + + return(0); +} + +int write_spi(uint8_t dev_ad, uint8_t addr, uint8_t* pBuff, uint8_t sz) { + uint16_t transfer_cnt = (sz+2)*2; + uint16_t masterRxData[256] = {0U}; + uint16_t masterTxData[256] = {0U}; + dspi_transfer_t masterXfer; + + // SPI_RWN = 0 for write, so no operation is required + masterTxData[0] = (dev_ad<<1); + masterTxData[1] = addr; // addr + + for (int i = 2; i < sz+2; i++ ) { + masterTxData[i] = *pBuff++; + } + + /* Start master transfer, send data to slave */ + masterXfer.txData = (uint8_t*) masterTxData; + masterXfer.rxData = (uint8_t*) masterRxData; + masterXfer.dataSize = transfer_cnt; + masterXfer.configFlags = kDSPI_MasterCtar0 | kDSPI_MasterPcs0 | kDSPI_MasterPcsContinuous; + DSPI_MasterTransferBlocking(DSPI_MASTER_BASEADDR, &masterXfer); + + return(0); + +} + +int read_spi(uint8_t dev_ad, uint8_t addr, uint8_t* pBuff, uint8_t sz) { + uint16_t transfer_cnt = (sz+2)*2; + uint16_t masterRxData[256] = {0U}; + uint16_t masterTxData[256] = {0U}; + dspi_transfer_t masterXfer; + + masterTxData[0] = (dev_ad<<1) | SPI_READ; + masterTxData[1] = addr; + + /* Start master transfer, send data to slave */ + masterXfer.txData = (uint8_t*) masterTxData; + masterXfer.rxData = (uint8_t*) masterRxData; + masterXfer.dataSize = transfer_cnt; + masterXfer.configFlags = kDSPI_MasterCtar0 | kDSPI_MasterPcs0 | kDSPI_MasterPcsContinuous; + DSPI_MasterTransferBlocking(DSPI_MASTER_BASEADDR, &masterXfer); + + return(0); + +} + + +int test_spi(uint8_t rwn, uint8_t dev_ad) { + + volatile static int i = 0; + uint16_t transfer_cnt = 10; + uint16_t masterRxData[256] = {0U}; + uint16_t masterTxData[256] = {0U}; + dspi_transfer_t masterXfer; + + if (!rwn) { + // write TX buffer + /* Set up the transfer data */ + masterTxData[0] = (dev_ad<<1) | rwn; // dev_ad|RWN + masterTxData[1] = 0x01; // addr + masterTxData[2] = 0x77; // data + masterTxData[3] = 0x33; // data + masterTxData[4] = 0xaa; // data + } + else { + // read TX buffer + masterTxData[0] = (dev_ad<<1) | rwn; // dev_ad|RWN + masterTxData[1] = 0x01; // addr + masterTxData[2] = 0x00; // data + masterTxData[3] = 0x00; // data + masterTxData[4] = 0x00; // data + } + + /* Print out transmit buffer */ + PRINTF("\r\n Master transmit:\r\n"); + for (i = 0U; i < transfer_cnt; i++) + { + /* Print 16 numbers in a line */ + if ((i & 0x0FU) == 0U) + { + PRINTF("\r\n"); + } + PRINTF(" %02X", masterTxData[i]); + } + PRINTF("\r\n"); + + /* Start master transfer, send data to slave */ + masterXfer.txData = (uint8_t*) masterTxData; + masterXfer.rxData = (uint8_t*) masterRxData; + masterXfer.dataSize = transfer_cnt; + masterXfer.configFlags = kDSPI_MasterCtar0 | kDSPI_MasterPcs0 | kDSPI_MasterPcsContinuous; + DSPI_MasterTransferBlocking(DSPI_MASTER_BASEADDR, &masterXfer); + + /* Print out receive buffer */ + PRINTF("\r\n Master transmit:\r\n"); + for (i = 0U; i < transfer_cnt; i++) + { + /* Print 16 numbers in a line */ + if ((i & 0x0FU) == 0U) + { + PRINTF("\r\n"); + } + PRINTF(" %02X", masterRxData[i]); + } + PRINTF("\r\n"); + + return(0); + +} diff --git a/source/spi.h b/source/spi.h new file mode 100644 index 0000000..100a73c --- /dev/null +++ b/source/spi.h @@ -0,0 +1,71 @@ +/* + * spi.h + * + * Copyright (C) 2018, 2019 Mind Chasers Inc. + * + * 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 SPI_H_ +#define SPI_H_ + +/******************************************************************************* +* SPI Definitions +******************************************************************************/ +#define DSPI_MASTER_BASEADDR SPI0 +#define DSPI_MASTER_CLK_SRC DSPI0_CLK_SRC +#define DSPI_MASTER_CLK_FREQ CLOCK_GetFreq(DSPI0_CLK_SRC) +#define DSPI_TRANSFER_BAUDRATE 1000000U /*! Transfer baudrate - 1M */ + +/* Memory Address Map + * 9-bit words are transferred + * DEV_AD, RWN + * MEM_AD + */ + +#define SPI_READ 1 +#define SPI_WRITE 0 + +#define SPI_DEV_AD_SCI_SEL_CH_0 0x00 +#define SPI_DEV_AD_SCI_SEL_CH_1 0x01 +#define SPI_DEV_AD_DUAL_0 0x02 +#define SPI_DEV_AD_SCI_SEL_CH_2 0x04 +#define SPI_DEV_AD_SCI_SEL_CH_3 0x05 +#define SPI_DEV_AD_DUAL_1 0x06 +#define SPI_DEV_AD_DPRAM_RX 0x08 +#define SPI_DEV_AD_DPRAM_TX 0x0c +#define SPI_DEV_AD_DPRAM_PTRS 0x10 +#define SPI_DEV_AD_INT_SEL 0X11 +#define SPI_DEV_AD_PARAM_0 0x20 +#define SPI_DEV_AD_PARAM_1 0x24 +#define SPI_DEV_AD_PARAM_2 0x28 +#define SPI_DEV_AD_PARAM_2 0x2C +#define SPI_DEV_AD_PKT_FILTER_01 0X41 +#define SPI_DEV_AD_PKT_FILTER_02 0X42 +#define SPI_DEV_AD_PKT_FILTER_03 0X43 +#define SPI_DEV_AD_PKT_FILTER_10 0X48 +#define SPI_DEV_AD_PKT_FILTER_12 0X4a +#define SPI_DEV_AD_PKT_FILTER_13 0X4b +#define SPI_DEV_AD_PKT_FILTER_20 0x50 +#define SPI_DEV_AD_PKT_FILTER_21 0X51 +#define SPI_DEV_AD_PKT_FILTER_23 0X53 + + + +int spi_init(dspi_master_config_t); +int test_spi(uint8_t, uint8_t); +int write_spi(uint8_t, uint8_t, uint8_t*, uint8_t); +int read_spi(uint8_t, uint8_t, uint8_t*, uint8_t); + +#endif /* SPI_H_ */ diff --git a/source/utils.c b/source/utils.c new file mode 100644 index 0000000..5cfce86 --- /dev/null +++ b/source/utils.c @@ -0,0 +1,156 @@ +/* + * utils.c + * + * Copyright (C) 2018, 2019 Mind Chasers Inc. + * + * 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. + * + */ + +/* Standard C Included Files */ +#include +#include +#include +#include + +/* SDK Included Files */ +#include "board.h" +#include "fsl_debug_console.h" +#include "fsl_i2c.h" + +#include "main.h" + +/* + * Stop dumping the data when we msbit is set + */ +void dump_data(uint8_t * pdata, size_t size, bool i2c_data ) { + + for (uint32_t i = 0U; i < size; i++) { + if (!i2c_data && (i % 8 == 0)) { + printf("\r\n"); + } + + // printf("0x%2x ", *pdata++); + PUTCHAR( *pdata++ & 0x7f ); + + if (i2c_data && (*pdata & 0x80) ) { + // printf("0x%2x ", *pdata); + PUTCHAR( *pdata & 0x7f ); + break; + } + + } + + PRINTF("\r\n"); +} + +uint8_t get_cmd(uint8_t * pdata, size_t size) { + int i=0; + char buf; + + if (size <= 1) + return 0; + + buf = (char) GETCHAR(); + PUTCHAR(buf); + + if (buf == 13 ) { + PUTCHAR(10); // LF + return 0; + } + + *pdata = buf; // capture the cmd + + for(i=1; i= 48 && buf <= 57) { + buf = buf-48; + } + + // Convert A through F ASCII to int base 16 (hex) + else if (buf >= 65 && buf <= 70) { + buf = buf-55; + } + + // Convert a through f ASCII to int base 16 (hex) + else if (buf >= 97 && buf <= 102) { + buf = buf-87; + } + + else if (buf == 13) { + pdata[i] = buf; + break; + } + else { + PUTCHAR(10); // LF + return 0; // error + } + + pdata[i] = buf; + + } + + PUTCHAR(10); + return i+1; + +} + +/* convert ASCII hex characters to integers */ +uint8_t ascii_to_bin(uint8_t data) { + uint8_t temp = 0; + if (data > 0x39) { + temp = data - 0x57; // a should map to 10 and so on + } + else { + temp = data - 0x30; + } + return temp; +} + +status_t i2c_write(i2c_master_transfer_t* pxfer, uint8_t devaddr, uint8_t * pdata, + size_t size) { + status_t result = kStatus_Success; + pxfer->slaveAddress = devaddr; + pxfer->direction = kI2C_Write; + pxfer->data = pdata; + pxfer->dataSize = size; + return( I2C_MasterTransferBlocking(I2C_MASTER_BASEADDR, pxfer)); + if (result!=kStatus_Success) { + // printf("\r\n I2C Transfer Error \r\n"); + return -1; + } + else { + return 0; + } +} + +status_t i2c_read(i2c_master_transfer_t* pxfer, uint8_t devaddr, uint8_t * pdata, + size_t size) { + status_t result = kStatus_Success; + pxfer->slaveAddress = devaddr; + pxfer->direction = kI2C_Read; + pxfer->data = pdata; + pxfer->dataSize = size; + result = I2C_MasterTransferBlocking(I2C_MASTER_BASEADDR, pxfer); + if (result!=kStatus_Success) { + // printf("\r\n I2C Transfer Error \r\n"); + return -1; + } + else { + return 0; + } + +} diff --git a/source/utils.h b/source/utils.h new file mode 100644 index 0000000..626042e --- /dev/null +++ b/source/utils.h @@ -0,0 +1,27 @@ +/* + * utils.h + * + * Copyright (C) 2018, 2019 Mind Chasers Inc. + * + * 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 UTILS_H_ +#define UTILS_H_ + +void dump_data(uint8_t *, size_t, bool ); +uint8_t get_cmd(uint8_t *, size_t); +uint8_t ascii_to_bin(uint8_t); + +#endif /* UTILS_H_ */ diff --git a/startup/startup_mk02f12810.c b/startup/startup_mk02f12810.c new file mode 100644 index 0000000..51a0987 --- /dev/null +++ b/startup/startup_mk02f12810.c @@ -0,0 +1,823 @@ +//***************************************************************************** +// MK02F12810 startup code for use with MCUXpresso IDE +// +// Version : 051217 +//***************************************************************************** +// +// The Clear BSD License +// 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. +//***************************************************************************** + +#if defined (DEBUG) +#pragma GCC push_options +#pragma GCC optimize ("Og") +#endif // (DEBUG) + +#if defined (__cplusplus) +#ifdef __REDLIB__ +#error Redlib does not support C++ +#else +//***************************************************************************** +// +// The entry point for the C++ library startup +// +//***************************************************************************** +extern "C" { + extern void __libc_init_array(void); +} +#endif +#endif + +#define WEAK __attribute__ ((weak)) +#define WEAK_AV __attribute__ ((weak, section(".after_vectors"))) +#define ALIAS(f) __attribute__ ((weak, alias (#f))) + +//***************************************************************************** +#if defined (__cplusplus) +extern "C" { +#endif + +//***************************************************************************** +// Flash Configuration block : 16-byte flash configuration field that stores +// default protection settings (loaded on reset) and security information that +// allows the MCU to restrict access to the Flash Memory module. +// Placed at address 0x400 by the linker script. +//***************************************************************************** +__attribute__ ((used,section(".FlashConfig"))) const struct { + unsigned int word1; + unsigned int word2; + unsigned int word3; + unsigned int word4; +} Flash_Config = {0xFFFFFFFF, 0xFFFFFFFF, 0xFFFFFFFF, 0xFFFFFBFE}; +//***************************************************************************** +// Declaration of external SystemInit function +//***************************************************************************** +#if defined (__USE_CMSIS) +extern void SystemInit(void); +#endif // (__USE_CMSIS) + +//***************************************************************************** +// Forward declaration of the core exception handlers. +// When the application defines a handler (with the same name), this will +// automatically take precedence over these weak definitions +//***************************************************************************** + void ResetISR(void); +WEAK void NMI_Handler(void); +WEAK void HardFault_Handler(void); +WEAK void MemManage_Handler(void); +WEAK void BusFault_Handler(void); +WEAK void UsageFault_Handler(void); +WEAK void SVC_Handler(void); +WEAK void DebugMon_Handler(void); +WEAK void PendSV_Handler(void); +WEAK void SysTick_Handler(void); +WEAK void IntDefaultHandler(void); + +//***************************************************************************** +// Forward declaration of the application IRQ handlers. When the application +// defines a handler (with the same name), this will automatically take +// precedence over weak definitions below +//***************************************************************************** +WEAK void DMA0_IRQHandler(void); +WEAK void DMA1_IRQHandler(void); +WEAK void DMA2_IRQHandler(void); +WEAK void DMA3_IRQHandler(void); +WEAK void Reserved20_IRQHandler(void); +WEAK void Reserved21_IRQHandler(void); +WEAK void Reserved22_IRQHandler(void); +WEAK void Reserved23_IRQHandler(void); +WEAK void Reserved24_IRQHandler(void); +WEAK void Reserved25_IRQHandler(void); +WEAK void Reserved26_IRQHandler(void); +WEAK void Reserved27_IRQHandler(void); +WEAK void Reserved28_IRQHandler(void); +WEAK void Reserved29_IRQHandler(void); +WEAK void Reserved30_IRQHandler(void); +WEAK void Reserved31_IRQHandler(void); +WEAK void DMA_Error_IRQHandler(void); +WEAK void MCM_IRQHandler(void); +WEAK void FTF_IRQHandler(void); +WEAK void Read_Collision_IRQHandler(void); +WEAK void LVD_LVW_IRQHandler(void); +WEAK void LLWU_IRQHandler(void); +WEAK void WDOG_EWM_IRQHandler(void); +WEAK void Reserved39_IRQHandler(void); +WEAK void I2C0_IRQHandler(void); +WEAK void Reserved41_IRQHandler(void); +WEAK void SPI0_IRQHandler(void); +WEAK void Reserved43_IRQHandler(void); +WEAK void Reserved44_IRQHandler(void); +WEAK void Reserved45_IRQHandler(void); +WEAK void Reserved46_IRQHandler(void); +WEAK void UART0_RX_TX_IRQHandler(void); +WEAK void UART0_ERR_IRQHandler(void); +WEAK void UART1_RX_TX_IRQHandler(void); +WEAK void UART1_ERR_IRQHandler(void); +WEAK void Reserved51_IRQHandler(void); +WEAK void Reserved52_IRQHandler(void); +WEAK void Reserved53_IRQHandler(void); +WEAK void Reserved54_IRQHandler(void); +WEAK void ADC0_IRQHandler(void); +WEAK void CMP0_IRQHandler(void); +WEAK void CMP1_IRQHandler(void); +WEAK void FTM0_IRQHandler(void); +WEAK void FTM1_IRQHandler(void); +WEAK void FTM2_IRQHandler(void); +WEAK void Reserved61_IRQHandler(void); +WEAK void Reserved62_IRQHandler(void); +WEAK void Reserved63_IRQHandler(void); +WEAK void PIT0_IRQHandler(void); +WEAK void PIT1_IRQHandler(void); +WEAK void PIT2_IRQHandler(void); +WEAK void PIT3_IRQHandler(void); +WEAK void PDB0_IRQHandler(void); +WEAK void Reserved69_IRQHandler(void); +WEAK void Reserved70_IRQHandler(void); +WEAK void Reserved71_IRQHandler(void); +WEAK void DAC0_IRQHandler(void); +WEAK void MCG_IRQHandler(void); +WEAK void LPTMR0_IRQHandler(void); +WEAK void PORTA_IRQHandler(void); +WEAK void PORTB_IRQHandler(void); +WEAK void PORTC_IRQHandler(void); +WEAK void PORTD_IRQHandler(void); +WEAK void PORTE_IRQHandler(void); +WEAK void SWI_IRQHandler(void); + +//***************************************************************************** +// Forward declaration of the driver IRQ handlers. These are aliased +// to the IntDefaultHandler, which is a 'forever' loop. When the driver +// defines a handler (with the same name), this will automatically take +// precedence over these weak definitions +//***************************************************************************** +void DMA0_DriverIRQHandler(void) ALIAS(IntDefaultHandler); +void DMA1_DriverIRQHandler(void) ALIAS(IntDefaultHandler); +void DMA2_DriverIRQHandler(void) ALIAS(IntDefaultHandler); +void DMA3_DriverIRQHandler(void) ALIAS(IntDefaultHandler); +void Reserved20_DriverIRQHandler(void) ALIAS(IntDefaultHandler); +void Reserved21_DriverIRQHandler(void) ALIAS(IntDefaultHandler); +void Reserved22_DriverIRQHandler(void) ALIAS(IntDefaultHandler); +void Reserved23_DriverIRQHandler(void) ALIAS(IntDefaultHandler); +void Reserved24_DriverIRQHandler(void) ALIAS(IntDefaultHandler); +void Reserved25_DriverIRQHandler(void) ALIAS(IntDefaultHandler); +void Reserved26_DriverIRQHandler(void) ALIAS(IntDefaultHandler); +void Reserved27_DriverIRQHandler(void) ALIAS(IntDefaultHandler); +void Reserved28_DriverIRQHandler(void) ALIAS(IntDefaultHandler); +void Reserved29_DriverIRQHandler(void) ALIAS(IntDefaultHandler); +void Reserved30_DriverIRQHandler(void) ALIAS(IntDefaultHandler); +void Reserved31_DriverIRQHandler(void) ALIAS(IntDefaultHandler); +void DMA_Error_DriverIRQHandler(void) ALIAS(IntDefaultHandler); +void MCM_DriverIRQHandler(void) ALIAS(IntDefaultHandler); +void FTF_DriverIRQHandler(void) ALIAS(IntDefaultHandler); +void Read_Collision_DriverIRQHandler(void) ALIAS(IntDefaultHandler); +void LVD_LVW_DriverIRQHandler(void) ALIAS(IntDefaultHandler); +void LLWU_DriverIRQHandler(void) ALIAS(IntDefaultHandler); +void WDOG_EWM_DriverIRQHandler(void) ALIAS(IntDefaultHandler); +void Reserved39_DriverIRQHandler(void) ALIAS(IntDefaultHandler); +void I2C0_DriverIRQHandler(void) ALIAS(IntDefaultHandler); +void Reserved41_DriverIRQHandler(void) ALIAS(IntDefaultHandler); +void SPI0_DriverIRQHandler(void) ALIAS(IntDefaultHandler); +void Reserved43_DriverIRQHandler(void) ALIAS(IntDefaultHandler); +void Reserved44_DriverIRQHandler(void) ALIAS(IntDefaultHandler); +void Reserved45_DriverIRQHandler(void) ALIAS(IntDefaultHandler); +void Reserved46_DriverIRQHandler(void) ALIAS(IntDefaultHandler); +void UART0_RX_TX_DriverIRQHandler(void) ALIAS(IntDefaultHandler); +void UART0_ERR_DriverIRQHandler(void) ALIAS(IntDefaultHandler); +void UART1_RX_TX_DriverIRQHandler(void) ALIAS(IntDefaultHandler); +void UART1_ERR_DriverIRQHandler(void) ALIAS(IntDefaultHandler); +void Reserved51_DriverIRQHandler(void) ALIAS(IntDefaultHandler); +void Reserved52_DriverIRQHandler(void) ALIAS(IntDefaultHandler); +void Reserved53_DriverIRQHandler(void) ALIAS(IntDefaultHandler); +void Reserved54_DriverIRQHandler(void) ALIAS(IntDefaultHandler); +void ADC0_DriverIRQHandler(void) ALIAS(IntDefaultHandler); +void CMP0_DriverIRQHandler(void) ALIAS(IntDefaultHandler); +void CMP1_DriverIRQHandler(void) ALIAS(IntDefaultHandler); +void FTM0_DriverIRQHandler(void) ALIAS(IntDefaultHandler); +void FTM1_DriverIRQHandler(void) ALIAS(IntDefaultHandler); +void FTM2_DriverIRQHandler(void) ALIAS(IntDefaultHandler); +void Reserved61_DriverIRQHandler(void) ALIAS(IntDefaultHandler); +void Reserved62_DriverIRQHandler(void) ALIAS(IntDefaultHandler); +void Reserved63_DriverIRQHandler(void) ALIAS(IntDefaultHandler); +void PIT0_DriverIRQHandler(void) ALIAS(IntDefaultHandler); +void PIT1_DriverIRQHandler(void) ALIAS(IntDefaultHandler); +void PIT2_DriverIRQHandler(void) ALIAS(IntDefaultHandler); +void PIT3_DriverIRQHandler(void) ALIAS(IntDefaultHandler); +void PDB0_DriverIRQHandler(void) ALIAS(IntDefaultHandler); +void Reserved69_DriverIRQHandler(void) ALIAS(IntDefaultHandler); +void Reserved70_DriverIRQHandler(void) ALIAS(IntDefaultHandler); +void Reserved71_DriverIRQHandler(void) ALIAS(IntDefaultHandler); +void DAC0_DriverIRQHandler(void) ALIAS(IntDefaultHandler); +void MCG_DriverIRQHandler(void) ALIAS(IntDefaultHandler); +void LPTMR0_DriverIRQHandler(void) ALIAS(IntDefaultHandler); +void PORTA_DriverIRQHandler(void) ALIAS(IntDefaultHandler); +void PORTB_DriverIRQHandler(void) ALIAS(IntDefaultHandler); +void PORTC_DriverIRQHandler(void) ALIAS(IntDefaultHandler); +void PORTD_DriverIRQHandler(void) ALIAS(IntDefaultHandler); +void PORTE_DriverIRQHandler(void) ALIAS(IntDefaultHandler); +void SWI_DriverIRQHandler(void) ALIAS(IntDefaultHandler); + +//***************************************************************************** +// The entry point for the application. +// __main() is the entry point for Redlib based applications +// main() is the entry point for Newlib based applications +//***************************************************************************** +#if defined (__REDLIB__) +extern void __main(void); +#endif +extern int main(void); + +//***************************************************************************** +// External declaration for the pointer to the stack top from the Linker Script +//***************************************************************************** +extern void _vStackTop(void); +//***************************************************************************** +#if defined (__cplusplus) +} // extern "C" +#endif +//***************************************************************************** +// The vector table. +// This relies on the linker script to place at correct location in memory. +//***************************************************************************** +extern void (* const g_pfnVectors[])(void); +extern void * __Vectors __attribute__ ((alias ("g_pfnVectors"))); + +__attribute__ ((used, section(".isr_vector"))) +void (* const g_pfnVectors[])(void) = { + // Core Level - CM4 + &_vStackTop, // The initial stack pointer + ResetISR, // The reset handler + NMI_Handler, // The NMI handler + HardFault_Handler, // The hard fault handler + MemManage_Handler, // The MPU fault handler + BusFault_Handler, // The bus fault handler + UsageFault_Handler, // The usage fault handler + 0, // Reserved + 0, // Reserved + 0, // Reserved + 0, // Reserved + SVC_Handler, // SVCall handler + DebugMon_Handler, // Debug monitor handler + 0, // Reserved + PendSV_Handler, // The PendSV handler + SysTick_Handler, // The SysTick handler + + // Chip Level - MK02F12810 + DMA0_IRQHandler, // 16: DMA Channel 0 Transfer Complete + DMA1_IRQHandler, // 17: DMA Channel 1 Transfer Complete + DMA2_IRQHandler, // 18: DMA Channel 2 Transfer Complete + DMA3_IRQHandler, // 19: DMA Channel 3 Transfer Complete + Reserved20_IRQHandler, // 20: Reserved interrupt + Reserved21_IRQHandler, // 21: Reserved interrupt + Reserved22_IRQHandler, // 22: Reserved interrupt + Reserved23_IRQHandler, // 23: Reserved interrupt + Reserved24_IRQHandler, // 24: Reserved interrupt + Reserved25_IRQHandler, // 25: Reserved interrupt + Reserved26_IRQHandler, // 26: Reserved interrupt + Reserved27_IRQHandler, // 27: Reserved interrupt + Reserved28_IRQHandler, // 28: Reserved interrupt + Reserved29_IRQHandler, // 29: Reserved interrupt + Reserved30_IRQHandler, // 30: Reserved interrupt + Reserved31_IRQHandler, // 31: Reserved interrupt + DMA_Error_IRQHandler, // 32: DMA Error Interrupt + MCM_IRQHandler, // 33: Normal Interrupt + FTF_IRQHandler, // 34: FTFA Command complete interrupt + Read_Collision_IRQHandler, // 35: Read Collision Interrupt + LVD_LVW_IRQHandler, // 36: Low Voltage Detect, Low Voltage Warning + LLWU_IRQHandler, // 37: Low Leakage Wakeup Unit + WDOG_EWM_IRQHandler, // 38: WDOG Interrupt + Reserved39_IRQHandler, // 39: Reserved interrupt + I2C0_IRQHandler, // 40: I2C0 interrupt + Reserved41_IRQHandler, // 41: Reserved interrupt + SPI0_IRQHandler, // 42: SPI0 Interrupt + Reserved43_IRQHandler, // 43: Reserved interrupt + Reserved44_IRQHandler, // 44: Reserved interrupt + Reserved45_IRQHandler, // 45: Reserved interrupt + Reserved46_IRQHandler, // 46: Reserved interrupt + UART0_RX_TX_IRQHandler, // 47: UART0 Receive/Transmit interrupt + UART0_ERR_IRQHandler, // 48: UART0 Error interrupt + UART1_RX_TX_IRQHandler, // 49: UART1 Receive/Transmit interrupt + UART1_ERR_IRQHandler, // 50: UART1 Error interrupt + Reserved51_IRQHandler, // 51: Reserved interrupt + Reserved52_IRQHandler, // 52: Reserved interrupt + Reserved53_IRQHandler, // 53: Reserved interrupt + Reserved54_IRQHandler, // 54: Reserved interrupt + ADC0_IRQHandler, // 55: ADC0 interrupt + CMP0_IRQHandler, // 56: CMP0 interrupt + CMP1_IRQHandler, // 57: CMP1 interrupt + FTM0_IRQHandler, // 58: FTM0 fault, overflow and channels interrupt + FTM1_IRQHandler, // 59: FTM1 fault, overflow and channels interrupt + FTM2_IRQHandler, // 60: FTM2 fault, overflow and channels interrupt + Reserved61_IRQHandler, // 61: Reserved interrupt + Reserved62_IRQHandler, // 62: Reserved interrupt + Reserved63_IRQHandler, // 63: Reserved interrupt + PIT0_IRQHandler, // 64: PIT timer channel 0 interrupt + PIT1_IRQHandler, // 65: PIT timer channel 1 interrupt + PIT2_IRQHandler, // 66: PIT timer channel 2 interrupt + PIT3_IRQHandler, // 67: PIT timer channel 3 interrupt + PDB0_IRQHandler, // 68: PDB0 Interrupt + Reserved69_IRQHandler, // 69: Reserved interrupt + Reserved70_IRQHandler, // 70: Reserved interrupt + Reserved71_IRQHandler, // 71: Reserved interrupt + DAC0_IRQHandler, // 72: DAC0 interrupt + MCG_IRQHandler, // 73: MCG Interrupt + LPTMR0_IRQHandler, // 74: LPTimer interrupt + PORTA_IRQHandler, // 75: Port A interrupt + PORTB_IRQHandler, // 76: Port B interrupt + PORTC_IRQHandler, // 77: Port C interrupt + PORTD_IRQHandler, // 78: Port D interrupt + PORTE_IRQHandler, // 79: Port E interrupt + SWI_IRQHandler, // 80: Software interrupt +}; /* End of g_pfnVectors */ + +//***************************************************************************** +// Functions to carry out the initialization of RW and BSS data sections. These +// are written as separate functions rather than being inlined within the +// ResetISR() function in order to cope with MCUs with multiple banks of +// memory. +//***************************************************************************** +__attribute__ ((section(".after_vectors.init_data"))) +void data_init(unsigned int romstart, unsigned int start, unsigned int len) { + unsigned int *pulDest = (unsigned int*) start; + unsigned int *pulSrc = (unsigned int*) romstart; + unsigned int loop; + for (loop = 0; loop < len; loop = loop + 4) + *pulDest++ = *pulSrc++; +} + +__attribute__ ((section(".after_vectors.init_bss"))) +void bss_init(unsigned int start, unsigned int len) { + unsigned int *pulDest = (unsigned int*) start; + unsigned int loop; + for (loop = 0; loop < len; loop = loop + 4) + *pulDest++ = 0; +} + +//***************************************************************************** +// The following symbols are constructs generated by the linker, indicating +// the location of various points in the "Global Section Table". This table is +// created by the linker via the Code Red managed linker script mechanism. It +// contains the load address, execution address and length of each RW data +// section and the execution and length of each BSS (zero initialized) section. +//***************************************************************************** +extern unsigned int __data_section_table; +extern unsigned int __data_section_table_end; +extern unsigned int __bss_section_table; +extern unsigned int __bss_section_table_end; + +//***************************************************************************** +// Reset entry point for your code. +// Sets up a simple runtime environment and initializes the C/C++ +// library. +//***************************************************************************** +__attribute__ ((section(".after_vectors.reset"))) +void ResetISR(void) { + + // Disable interrupts + __asm volatile ("cpsid i"); + +#if defined (__USE_CMSIS) +// If __USE_CMSIS defined, then call CMSIS SystemInit code + SystemInit(); + +#else + // Disable Watchdog + // Write 0xC520 to watchdog unlock register + *((volatile unsigned short *)0x4005200E) = 0xC520; + // Followed by 0xD928 to complete the unlock + *((volatile unsigned short *)0x4005200E) = 0xD928; + // Now disable watchdog via STCTRLH register + *((volatile unsigned short *)0x40052000) = 0x01D2u; +#endif // (__USE_CMSIS) + + // + // Copy the data sections from flash to SRAM. + // + unsigned int LoadAddr, ExeAddr, SectionLen; + unsigned int *SectionTableAddr; + + // Load base address of Global Section Table + SectionTableAddr = &__data_section_table; + + // Copy the data sections from flash to SRAM. + while (SectionTableAddr < &__data_section_table_end) { + LoadAddr = *SectionTableAddr++; + ExeAddr = *SectionTableAddr++; + SectionLen = *SectionTableAddr++; + data_init(LoadAddr, ExeAddr, SectionLen); + } + + // At this point, SectionTableAddr = &__bss_section_table; + // Zero fill the bss segment + while (SectionTableAddr < &__bss_section_table_end) { + ExeAddr = *SectionTableAddr++; + SectionLen = *SectionTableAddr++; + bss_init(ExeAddr, SectionLen); + } + +#if !defined (__USE_CMSIS) +// Assume that if __USE_CMSIS defined, then CMSIS SystemInit code +// will enable the FPU +#if defined (__VFP_FP__) && !defined (__SOFTFP__) + // + // Code to enable the Cortex-M4 FPU only included + // if appropriate build options have been selected. + // Code taken from Section 7.1, Cortex-M4 TRM (DDI0439C) + // + // Read CPACR (located at address 0xE000ED88) + // Set bits 20-23 to enable CP10 and CP11 coprocessors + // Write back the modified value to the CPACR + asm volatile ("LDR.W R0, =0xE000ED88\n\t" + "LDR R1, [R0]\n\t" + "ORR R1, R1, #(0xF << 20)\n\t" + "STR R1, [R0]"); +#endif // (__VFP_FP__) && !(__SOFTFP__) +#endif // (__USE_CMSIS) + +#if !defined (__USE_CMSIS) +// Assume that if __USE_CMSIS defined, then CMSIS SystemInit code +// will setup the VTOR register + + // Check to see if we are running the code from a non-zero + // address (eg RAM, external flash), in which case we need + // to modify the VTOR register to tell the CPU that the + // vector table is located at a non-0x0 address. + unsigned int * pSCB_VTOR = (unsigned int *) 0xE000ED08; + if ((unsigned int *)g_pfnVectors!=(unsigned int *) 0x00000000) { + *pSCB_VTOR = (unsigned int)g_pfnVectors; + } +#endif // (__USE_CMSIS) + +#if defined (__cplusplus) + // + // Call C++ library initialisation + // + __libc_init_array(); +#endif + + // Reenable interrupts + __asm volatile ("cpsie i"); + +#if defined (__REDLIB__) + // Call the Redlib library, which in turn calls main() + __main(); +#else + main(); +#endif + + // + // main() shouldn't return, but if it does, we'll just enter an infinite loop + // + while (1) { + ; + } +} + +//***************************************************************************** +// Default core exception handlers. Override the ones here by defining your own +// handler routines in your application code. +//***************************************************************************** +WEAK_AV void NMI_Handler(void) +{ while(1) {} +} + +WEAK_AV void HardFault_Handler(void) +{ while(1) {} +} + +WEAK_AV void MemManage_Handler(void) +{ while(1) {} +} + +WEAK_AV void BusFault_Handler(void) +{ while(1) {} +} + +WEAK_AV void UsageFault_Handler(void) +{ while(1) {} +} + +WEAK_AV void SVC_Handler(void) +{ while(1) {} +} + +WEAK_AV void DebugMon_Handler(void) +{ while(1) {} +} + +WEAK_AV void PendSV_Handler(void) +{ while(1) {} +} + +WEAK_AV void SysTick_Handler(void) +{ while(1) {} +} + +//***************************************************************************** +// Processor ends up here if an unexpected interrupt occurs or a specific +// handler is not present in the application code. +//***************************************************************************** +WEAK_AV void IntDefaultHandler(void) +{ while(1) {} +} + +//***************************************************************************** +// Default application exception handlers. Override the ones here by defining +// your own handler routines in your application code. These routines call +// driver exception handlers or IntDefaultHandler() if no driver exception +// handler is included. +//***************************************************************************** +WEAK void DMA0_IRQHandler(void) +{ DMA0_DriverIRQHandler(); +} + +WEAK void DMA1_IRQHandler(void) +{ DMA1_DriverIRQHandler(); +} + +WEAK void DMA2_IRQHandler(void) +{ DMA2_DriverIRQHandler(); +} + +WEAK void DMA3_IRQHandler(void) +{ DMA3_DriverIRQHandler(); +} + +WEAK void Reserved20_IRQHandler(void) +{ Reserved20_DriverIRQHandler(); +} + +WEAK void Reserved21_IRQHandler(void) +{ Reserved21_DriverIRQHandler(); +} + +WEAK void Reserved22_IRQHandler(void) +{ Reserved22_DriverIRQHandler(); +} + +WEAK void Reserved23_IRQHandler(void) +{ Reserved23_DriverIRQHandler(); +} + +WEAK void Reserved24_IRQHandler(void) +{ Reserved24_DriverIRQHandler(); +} + +WEAK void Reserved25_IRQHandler(void) +{ Reserved25_DriverIRQHandler(); +} + +WEAK void Reserved26_IRQHandler(void) +{ Reserved26_DriverIRQHandler(); +} + +WEAK void Reserved27_IRQHandler(void) +{ Reserved27_DriverIRQHandler(); +} + +WEAK void Reserved28_IRQHandler(void) +{ Reserved28_DriverIRQHandler(); +} + +WEAK void Reserved29_IRQHandler(void) +{ Reserved29_DriverIRQHandler(); +} + +WEAK void Reserved30_IRQHandler(void) +{ Reserved30_DriverIRQHandler(); +} + +WEAK void Reserved31_IRQHandler(void) +{ Reserved31_DriverIRQHandler(); +} + +WEAK void DMA_Error_IRQHandler(void) +{ DMA_Error_DriverIRQHandler(); +} + +WEAK void MCM_IRQHandler(void) +{ MCM_DriverIRQHandler(); +} + +WEAK void FTF_IRQHandler(void) +{ FTF_DriverIRQHandler(); +} + +WEAK void Read_Collision_IRQHandler(void) +{ Read_Collision_DriverIRQHandler(); +} + +WEAK void LVD_LVW_IRQHandler(void) +{ LVD_LVW_DriverIRQHandler(); +} + +WEAK void LLWU_IRQHandler(void) +{ LLWU_DriverIRQHandler(); +} + +WEAK void WDOG_EWM_IRQHandler(void) +{ WDOG_EWM_DriverIRQHandler(); +} + +WEAK void Reserved39_IRQHandler(void) +{ Reserved39_DriverIRQHandler(); +} + +WEAK void I2C0_IRQHandler(void) +{ I2C0_DriverIRQHandler(); +} + +WEAK void Reserved41_IRQHandler(void) +{ Reserved41_DriverIRQHandler(); +} + +WEAK void SPI0_IRQHandler(void) +{ SPI0_DriverIRQHandler(); +} + +WEAK void Reserved43_IRQHandler(void) +{ Reserved43_DriverIRQHandler(); +} + +WEAK void Reserved44_IRQHandler(void) +{ Reserved44_DriverIRQHandler(); +} + +WEAK void Reserved45_IRQHandler(void) +{ Reserved45_DriverIRQHandler(); +} + +WEAK void Reserved46_IRQHandler(void) +{ Reserved46_DriverIRQHandler(); +} + +WEAK void UART0_RX_TX_IRQHandler(void) +{ UART0_RX_TX_DriverIRQHandler(); +} + +WEAK void UART0_ERR_IRQHandler(void) +{ UART0_ERR_DriverIRQHandler(); +} + +WEAK void UART1_RX_TX_IRQHandler(void) +{ UART1_RX_TX_DriverIRQHandler(); +} + +WEAK void UART1_ERR_IRQHandler(void) +{ UART1_ERR_DriverIRQHandler(); +} + +WEAK void Reserved51_IRQHandler(void) +{ Reserved51_DriverIRQHandler(); +} + +WEAK void Reserved52_IRQHandler(void) +{ Reserved52_DriverIRQHandler(); +} + +WEAK void Reserved53_IRQHandler(void) +{ Reserved53_DriverIRQHandler(); +} + +WEAK void Reserved54_IRQHandler(void) +{ Reserved54_DriverIRQHandler(); +} + +WEAK void ADC0_IRQHandler(void) +{ ADC0_DriverIRQHandler(); +} + +WEAK void CMP0_IRQHandler(void) +{ CMP0_DriverIRQHandler(); +} + +WEAK void CMP1_IRQHandler(void) +{ CMP1_DriverIRQHandler(); +} + +WEAK void FTM0_IRQHandler(void) +{ FTM0_DriverIRQHandler(); +} + +WEAK void FTM1_IRQHandler(void) +{ FTM1_DriverIRQHandler(); +} + +WEAK void FTM2_IRQHandler(void) +{ FTM2_DriverIRQHandler(); +} + +WEAK void Reserved61_IRQHandler(void) +{ Reserved61_DriverIRQHandler(); +} + +WEAK void Reserved62_IRQHandler(void) +{ Reserved62_DriverIRQHandler(); +} + +WEAK void Reserved63_IRQHandler(void) +{ Reserved63_DriverIRQHandler(); +} + +WEAK void PIT0_IRQHandler(void) +{ PIT0_DriverIRQHandler(); +} + +WEAK void PIT1_IRQHandler(void) +{ PIT1_DriverIRQHandler(); +} + +WEAK void PIT2_IRQHandler(void) +{ PIT2_DriverIRQHandler(); +} + +WEAK void PIT3_IRQHandler(void) +{ PIT3_DriverIRQHandler(); +} + +WEAK void PDB0_IRQHandler(void) +{ PDB0_DriverIRQHandler(); +} + +WEAK void Reserved69_IRQHandler(void) +{ Reserved69_DriverIRQHandler(); +} + +WEAK void Reserved70_IRQHandler(void) +{ Reserved70_DriverIRQHandler(); +} + +WEAK void Reserved71_IRQHandler(void) +{ Reserved71_DriverIRQHandler(); +} + +WEAK void DAC0_IRQHandler(void) +{ DAC0_DriverIRQHandler(); +} + +WEAK void MCG_IRQHandler(void) +{ MCG_DriverIRQHandler(); +} + +WEAK void LPTMR0_IRQHandler(void) +{ LPTMR0_DriverIRQHandler(); +} + +WEAK void PORTA_IRQHandler(void) +{ PORTA_DriverIRQHandler(); +} + +WEAK void PORTB_IRQHandler(void) +{ PORTB_DriverIRQHandler(); +} + +WEAK void PORTC_IRQHandler(void) +{ PORTC_DriverIRQHandler(); +} + +WEAK void PORTD_IRQHandler(void) +{ PORTD_DriverIRQHandler(); +} + +WEAK void PORTE_IRQHandler(void) +{ PORTE_DriverIRQHandler(); +} + +WEAK void SWI_IRQHandler(void) +{ SWI_DriverIRQHandler(); +} + +//***************************************************************************** + +#if defined (DEBUG) +#pragma GCC pop_options +#endif // (DEBUG) diff --git a/utilities/fsl_debug_console.c b/utilities/fsl_debug_console.c new file mode 100644 index 0000000..30c762f --- /dev/null +++ b/utilities/fsl_debug_console.c @@ -0,0 +1,366 @@ +/* + * This is a modified version of the file printf.c, which was distributed + * by Motorola as part of the M5407C3BOOT.zip package used to initialize + * the M5407C3 evaluation board. + * + * Copyright: + * 1999-2000 MOTOROLA, INC. All Rights Reserved. + * You are hereby granted a copyright license to use, modify, and + * distribute the SOFTWARE so long as this entire notice is + * retained without alteration in any modified and/or redistributed + * versions, and that such modified versions are clearly identified + * as such. No licenses are granted by implication, estoppel or + * otherwise under any patents or trademarks of Motorola, Inc. This + * software is provided on an "AS IS" basis and without warranty. + * + * To the maximum extent permitted by applicable law, MOTOROLA + * DISCLAIMS ALL WARRANTIES WHETHER EXPRESS OR IMPLIED, INCLUDING + * IMPLIED WARRANTIES OF MERCHANTABILITY OR FITNESS FOR A PARTICULAR + * PURPOSE AND ANY WARRANTY AGAINST INFRINGEMENT WITH REGARD TO THE + * SOFTWARE (INCLUDING ANY MODIFIED VERSIONS THEREOF) AND ANY + * ACCOMPANYING WRITTEN MATERIALS. + * + * To the maximum extent permitted by applicable law, IN NO EVENT + * SHALL MOTOROLA BE LIABLE FOR ANY DAMAGES WHATSOEVER (INCLUDING + * WITHOUT LIMITATION, DAMAGES FOR LOSS OF BUSINESS PROFITS, BUSINESS + * INTERRUPTION, LOSS OF BUSINESS INFORMATION, OR OTHER PECUNIARY + * LOSS) ARISING OF THE USE OR INABILITY TO USE THE SOFTWARE. + * + * Motorola assumes no responsibility for the maintenance and support + * of this software + + * Copyright (c) 2015, Freescale Semiconductor, Inc. + * Copyright 2016-2017 NXP + * + * Redistribution and use in source and binary forms, with or without modification, + * are permitted provided that the following conditions are met: + * + * o Redistributions of source code must retain the above copyright notice, this list + * of conditions and the following disclaimer. + * + * o 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. + * + * o 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. + * + * 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. + */ + +#include +#include +#if defined(__CC_ARM) +#include +#endif + +#include "fsl_debug_console.h" +#include "fsl_debug_console_conf.h" +#include "fsl_log.h" +#include "fsl_str.h" + +/******************************************************************************* + * Definitions + ******************************************************************************/ + +/******************************************************************************* + * Variables + ******************************************************************************/ + +/******************************************************************************* + * Prototypes + ******************************************************************************/ +/*! + * @brief This is a printf call back function which is used to relocate the log to buffer + * or print the log immediately when the local buffer is full. + * + * @param[in] buf Buffer to store log. + * @param[in] indicator Buffer index. + * @param[in] val Target character to store. + * @param[in] len length of the character + * + */ +#if SDK_DEBUGCONSOLE +static void DbgConsole_RelocateLog(char *buf, int32_t *indicator, char val, int len); +#endif +/******************************************************************************* + * Code + ******************************************************************************/ + +/*************Code for DbgConsole Init, Deinit, Printf, Scanf *******************************/ + +/* See fsl_debug_console.h for documentation of this function. */ +status_t DbgConsole_Init(uint32_t baseAddr, uint32_t baudRate, uint8_t device, uint32_t clkSrcFreq) +{ + assert(device != DEBUG_CONSOLE_DEVICE_TYPE_NONE); + + return LOG_Init(baseAddr, device, baudRate, clkSrcFreq); +} + +/* See fsl_debug_console.h for documentation of this function. */ +status_t DbgConsole_Deinit(void) +{ + /* LOG deinit */ + LOG_Deinit(); + + return kStatus_Success; +} + +status_t DbgConsole_Flush(void) +{ + /* wait log and io idle */ + return LOG_WaitIdle(); +} + +#if SDK_DEBUGCONSOLE +/* See fsl_debug_console.h for documentation of this function. */ +int DbgConsole_Printf(const char *fmt_s, ...) +{ + va_list ap; + int logLength = 0U, result = 0U; + char printBuf[DEBUG_CONSOLE_PRINTF_MAX_LOG_LEN] = {0U}; + + va_start(ap, fmt_s); + /* format print log first */ + logLength = StrFormatPrintf(fmt_s, ap, printBuf, DbgConsole_RelocateLog); + /* print log */ + result = LOG_Push((uint8_t *)printBuf, logLength); + + va_end(ap); + + return result; +} + +/* See fsl_debug_console.h for documentation of this function. */ +int DbgConsole_Putchar(int ch) +{ + /* print char */ + return LOG_Push((uint8_t *)&ch, 1U); +} + +/* See fsl_debug_console.h for documentation of this function. */ +int DbgConsole_Scanf(char *fmt_ptr, ...) +{ + va_list ap; + int result; + char scanfBuf[DEBUG_CONSOLE_SCANF_MAX_LOG_LEN + 1U] = {0U}; + + /* scanf log */ + LOG_ReadLine((uint8_t *)scanfBuf, DEBUG_CONSOLE_SCANF_MAX_LOG_LEN); + /* get va_list */ + va_start(ap, fmt_ptr); + /* format scanf log */ + result = StrFormatScanf(scanfBuf, fmt_ptr, ap); + + va_end(ap); + + return result; +} + +#ifdef DEBUG_CONSOLE_TRANSFER_NON_BLOCKING +status_t DbgConsole_TryGetchar(char *ch) +{ + if (NULL != ch) + { + return LOG_TryReadCharacter((uint8_t *)ch); + } + + return kStatus_Fail; +} +#endif + +/* See fsl_debug_console.h for documentation of this function. */ +int DbgConsole_Getchar(void) +{ + uint8_t ch; + + /* Get char */ + LOG_ReadCharacter(&ch); + + return ch; +} + +static void DbgConsole_RelocateLog(char *buf, int32_t *indicator, char val, int len) +{ + int i = 0; + + for (i = 0; i < len; i++) + { + if ((*indicator + 1) >= DEBUG_CONSOLE_PRINTF_MAX_LOG_LEN) + { + LOG_Push((uint8_t *)buf, *indicator); + *indicator = 0U; + } + + buf[*indicator] = val; + (*indicator)++; + } +} + +#endif /* SDK_DEBUGCONSOLE */ + +/*************Code to support toolchain's printf, scanf *******************************/ +/* These function __write and __read is used to support IAR toolchain to printf and scanf*/ +#if (defined(__ICCARM__)) +#if defined(SDK_DEBUGCONSOLE_UART) +#pragma weak __write +size_t __write(int handle, const unsigned char *buffer, size_t size) +{ + if (buffer == 0) + { + /* + * This means that we should flush internal buffers. Since we don't we just return. + * (Remember, "handle" == -1 means that all handles should be flushed.) + */ + return 0; + } + + /* This function only writes to "standard out" and "standard err" for all other file handles it returns failure. */ + if ((handle != 1) && (handle != 2)) + { + return ((size_t)-1); + } + + /* Send data. */ + LOG_Push((uint8_t *)buffer, 1U); + + return size; +} + +#pragma weak __read +size_t __read(int handle, unsigned char *buffer, size_t size) +{ + /* This function only reads from "standard in", for all other file handles it returns failure. */ + if (handle != 0) + { + return ((size_t)-1); + } + + /* Receive data.*/ + LOG_ReadLine(buffer, size); + + return size; +} +#endif /* SDK_DEBUGCONSOLE_UART */ + +/* support LPC Xpresso with RedLib */ +#elif(defined(__REDLIB__)) + +#if (!SDK_DEBUGCONSOLE) && (defined(SDK_DEBUGCONSOLE_UART)) +int __attribute__((weak)) __sys_write(int handle, char *buffer, int size) +{ + if (buffer == 0) + { + /* return -1 if error. */ + return -1; + } + + /* This function only writes to "standard out" and "standard err" for all other file handles it returns failure. */ + if ((handle != 1) && (handle != 2)) + { + return -1; + } + + /* Send data. */ + LOG_Push((uint8_t *)buffer, size); + + return 0; +} + +int __attribute__((weak)) __sys_readc(void) +{ + char tmp; + + /* Receive data. */ + LOG_ReadCharacter((uint8_t *)&tmp); + + return tmp; +} +#endif + +/* These function __write and __read is used to support ARM_GCC, KDS, Atollic toolchains to printf and scanf*/ +#elif(defined(__GNUC__)) + +#if ((defined(__GNUC__) && (!defined(__MCUXPRESSO)) && (defined(SDK_DEBUGCONSOLE_UART))) || \ + (defined(__MCUXPRESSO) && (!SDK_DEBUGCONSOLE) && (defined(SDK_DEBUGCONSOLE_UART)))) + +int __attribute__((weak)) _write(int handle, char *buffer, int size) +{ + if (buffer == 0) + { + /* return -1 if error. */ + return -1; + } + + /* This function only writes to "standard out" and "standard err" for all other file handles it returns failure. */ + if ((handle != 1) && (handle != 2)) + { + return -1; + } + + /* Send data. */ + LOG_Push((uint8_t *)buffer, size); + + return size; +} + +int __attribute__((weak)) _read(int handle, char *buffer, int size) +{ + /* This function only reads from "standard in", for all other file handles it returns failure. */ + if (handle != 0) + { + return -1; + } + + /* Receive data. */ + return LOG_ReadLine((uint8_t *)buffer, size); +} +#endif + +/* These function fputc and fgetc is used to support KEIL toolchain to printf and scanf*/ +#elif defined(__CC_ARM) +#if defined(SDK_DEBUGCONSOLE_UART) +struct __FILE +{ + int handle; + /* + * Whatever you require here. If the only file you are using is standard output using printf() for debugging, + * no file handling is required. + */ +}; + +/* FILE is typedef in stdio.h. */ +#pragma weak __stdout +#pragma weak __stdin +FILE __stdout; +FILE __stdin; + +#pragma weak fputc +int fputc(int ch, FILE *f) +{ + /* Send data. */ + return LOG_Push((uint8_t *)(&ch), 1); +} + +#pragma weak fgetc +int fgetc(FILE *f) +{ + char ch; + + /* Receive data. */ + LOG_ReadCharacter((uint8_t *)&ch); + + return ch; +} +#endif /* SDK_DEBUGCONSOLE_UART */ +#endif /* __ICCARM__ */ diff --git a/utilities/fsl_debug_console.h b/utilities/fsl_debug_console.h new file mode 100644 index 0000000..14dd3a0 --- /dev/null +++ b/utilities/fsl_debug_console.h @@ -0,0 +1,207 @@ +/* + * The Clear BSD License + * Copyright (c) 2013 - 2015, 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: + * + * o Redistributions of source code must retain the above copyright notice, this list + * of conditions and the following disclaimer. + * + * o 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. + * + * o 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. + * + * Debug console shall provide input and output functions to scan and print formatted data. + * o Support a format specifier for PRINTF follows this prototype "%[flags][width][.precision][length]specifier" + * - [flags] :'-', '+', '#', ' ', '0' + * - [width]: number (0,1...) + * - [.precision]: number (0,1...) + * - [length]: do not support + * - [specifier]: 'd', 'i', 'f', 'F', 'x', 'X', 'o', 'p', 'u', 'c', 's', 'n' + * o Support a format specifier for SCANF follows this prototype " %[*][width][length]specifier" + * - [*]: is supported. + * - [width]: number (0,1...) + * - [length]: 'h', 'hh', 'l','ll','L'. ignore ('j','z','t') + * - [specifier]: 'd', 'i', 'u', 'f', 'F', 'e', 'E', 'g', 'G', 'a', 'A', 'o', 'c', 's' + */ + +#ifndef _FSL_DEBUGCONSOLE_H_ +#define _FSL_DEBUGCONSOLE_H_ + +#include "fsl_common.h" +/*! + * @addtogroup debugconsole + * @{ + */ + +/******************************************************************************* + * Definitions + ******************************************************************************/ + +/*! @brief Definition to select sdk or toolchain printf, scanf. */ +#ifndef SDK_DEBUGCONSOLE +#define SDK_DEBUGCONSOLE 1U +#endif + +/*! @brief Definition to select redirect toolchain printf, scanf to uart or not. */ +#ifndef SDK_DEBUGCONSOLE_UART +/* mcux will handle this macro, not define it here */ +#if (!defined(__MCUXPRESSO)) +#define SDK_DEBUGCONSOLE_UART +#endif +#endif + +#if defined(SDK_DEBUGCONSOLE) && !(SDK_DEBUGCONSOLE) +#include +#endif + +#if SDK_DEBUGCONSOLE /* Select printf, scanf, putchar, getchar of SDK version. */ +#define PRINTF DbgConsole_Printf +#define SCANF DbgConsole_Scanf +#define PUTCHAR DbgConsole_Putchar +#define GETCHAR DbgConsole_Getchar +#else /* Select printf, scanf, putchar, getchar of toolchain. */ +#define PRINTF printf +#define SCANF scanf +#define PUTCHAR putchar +#define GETCHAR getchar +#endif /* SDK_DEBUGCONSOLE */ + +/******************************************************************************* + * Prototypes + ******************************************************************************/ + +#if defined(__cplusplus) +extern "C" { +#endif /* __cplusplus */ + +/*! @name Initialization*/ +/* @{ */ + +/*! + * @brief Initializes the peripheral used for debug messages. + * + * Call this function to enable debug log messages to be output via the specified peripheral, + * frequency of peripheral source clock, and base address at the specified baud rate. + * After this function has returned, stdout and stdin are connected to the selected peripheral. + * + * @param baseAddr Indicates the address of the peripheral used to send debug messages. + * @param baudRate The desired baud rate in bits per second. + * @param device Low level device type for the debug console, can be one of the following. + * @arg DEBUG_CONSOLE_DEVICE_TYPE_UART, + * @arg DEBUG_CONSOLE_DEVICE_TYPE_LPUART, + * @arg DEBUG_CONSOLE_DEVICE_TYPE_LPSCI, + * @arg DEBUG_CONSOLE_DEVICE_TYPE_USBCDC. + * @param clkSrcFreq Frequency of peripheral source clock. + * + * @return Indicates whether initialization was successful or not. + * @retval kStatus_Success Execution successfully + * @retval kStatus_Fail Execution failure + * @retval kStatus_InvalidArgument Invalid argument existed + */ +status_t DbgConsole_Init(uint32_t baseAddr, uint32_t baudRate, uint8_t device, uint32_t clkSrcFreq); + +/*! + * @brief De-initializes the peripheral used for debug messages. + * + * Call this function to disable debug log messages to be output via the specified peripheral + * base address and at the specified baud rate. + * + * @return Indicates whether de-initialization was successful or not. + */ +status_t DbgConsole_Deinit(void); + +#if SDK_DEBUGCONSOLE +/*! + * @brief Writes formatted output to the standard output stream. + * + * Call this function to write a formatted output to the standard output stream. + * + * @param fmt_s Format control string. + * @return Returns the number of characters printed or a negative value if an error occurs. + */ +int DbgConsole_Printf(const char *fmt_s, ...); + +/*! + * @brief Writes a character to stdout. + * + * Call this function to write a character to stdout. + * + * @param ch Character to be written. + * @return Returns the character written. + */ +int DbgConsole_Putchar(int ch); + +/*! + * @brief Reads formatted data from the standard input stream. + * + * Call this function to read formatted data from the standard input stream. + * + * @param fmt_ptr Format control string. + * @return Returns the number of fields successfully converted and assigned. + */ +int DbgConsole_Scanf(char *fmt_ptr, ...); + +/*! + * @brief Reads a character from standard input. + * + * Call this function to read a character from standard input. + * + * @return Returns the character read. + */ +int DbgConsole_Getchar(void); + +/*! + * @brief Debug console flush log. + * + * Call this function to wait the buffer empty and io idle before. + * If interrupt transfer is using, make sure the global IRQ is enable before call this function + * This function should be called when + * 1, before enter power down mode + * 2, log is required to print to terminal immediately + * @return Indicates whether wait idle was successful or not. + */ +status_t DbgConsole_Flush(void); + +#ifdef DEBUG_CONSOLE_TRANSFER_NON_BLOCKING +/*! + * @brief Debug console try to get char + * This function provide a api which will not block current task, if character is + * avaliable return it , otherwise return fail. + * @param ch the address of char to receive + * @return Indicates get char was successful or not. + */ +status_t DbgConsole_TryGetchar(char *ch); +#endif + +#endif /* SDK_DEBUGCONSOLE */ + +/*! @} */ + +#if defined(__cplusplus) +} +#endif /* __cplusplus */ + +/*! @} */ + +#endif /* _FSL_DEBUGCONSOLE_H_ */ diff --git a/utilities/fsl_debug_console_conf.h b/utilities/fsl_debug_console_conf.h new file mode 100644 index 0000000..7dfad42 --- /dev/null +++ b/utilities/fsl_debug_console_conf.h @@ -0,0 +1,160 @@ +/* + * The Clear BSD License + * Copyright 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: + * + * o Redistributions of source code must retain the above copyright notice, this list + * of conditions and the following disclaimer. + * + * o 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. + * + * o 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_DEBUG_CONSOLE_CONF_H_ +#define _FSL_DEBUG_CONSOLE_CONF_H_ + +/****************Debug console configuration********************/ + +/*! @brief If Non-blocking mode is needed, please define it at project setting, +* otherwise blocking mode is the default transfer mode. +* Warning: If you want to use non-blocking transfer,please make sure the corresponding +* IO interrupt is enable, otherwise there is no output. +* And non-blocking is combine with buffer, no matter bare-metal or rtos. +*/ +#ifdef DEBUG_CONSOLE_TRANSFER_NON_BLOCKING +/*! @brief define the transmit buffer length which is used to store the multi task log, buffer is enabled automatically +* when +* non-blocking transfer is using, +* This value will affect the RAM's ultilization, should be set per paltform's capability and software requirement. +* If it is configured too small, log maybe missed , because the log will not be +* buffered if the buffer is full, and the print will return immediately with -1. +* And this value should be multiple of 4 to meet memory alignment. +* +*/ +#ifndef DEBUG_CONSOLE_TRANSMIT_BUFFER_LEN +#define DEBUG_CONSOLE_TRANSMIT_BUFFER_LEN (512U) +#endif /* DEBUG_CONSOLE_TRANSMIT_BUFFER_LEN */ + +/*! @brief define the receive buffer length which is used to store the user input, buffer is enabled automatically when +* non-blocking transfer is using, +* This value will affect the RAM's ultilization, should be set per paltform's capability and software requirement. +* If it is configured too small, log maybe missed, because buffer will be overwrited if buffer is too small. +* And this value should be multiple of 4 to meet memory alignment. +* +*/ +#ifndef DEBUG_CONSOLE_RECEIVE_BUFFER_LEN +#define DEBUG_CONSOLE_RECEIVE_BUFFER_LEN (512U) +#endif /* DEBUG_CONSOLE_RECEIVE_BUFFER_LEN */ + +#else +#define DEBUG_CONSOLE_TRANSFER_BLOCKING +#endif /* DEBUG_CONSOLE_TRANSFER_NON_BLOCKING */ + +/*!@ brief define the MAX log length debug console support , that is when you call printf("log", x);, the log +* length can not bigger than this value. +* This macro decide the local log buffer length, the buffer locate at stack, the stack maybe overflow if +* the buffer is too big and current task stack size not big enough. +*/ +#ifndef DEBUG_CONSOLE_PRINTF_MAX_LOG_LEN +#define DEBUG_CONSOLE_PRINTF_MAX_LOG_LEN (128U) +#endif /* DEBUG_CONSOLE_PRINTF_MAX_LOG_LEN */ + +/*!@ brief define the buffer support buffer scanf log length, that is when you call scanf("log", &x);, the log +* length can not bigger than this value. +* As same as the DEBUG_CONSOLE_BUFFER_PRINTF_MAX_LOG_LEN. +*/ +#ifndef DEBUG_CONSOLE_SCANF_MAX_LOG_LEN +#define DEBUG_CONSOLE_SCANF_MAX_LOG_LEN (20U) +#endif /* DEBUG_CONSOLE_SCANF_MAX_LOG_LEN */ + +/*! @brief Debug console synchronization +* User should not change these macro for synchronization mode, but add the +* corresponding synchronization mechanism per different software environment. +* Such as, if another RTOS is used, +* add: +* #define DEBUG_CONSOLE_SYNCHRONIZATION_XXXX 3 +* in this configuration file and implement the synchronization in fsl.log.c. +*/ +/*! @brief synchronization for baremetal software */ +#define DEBUG_CONSOLE_SYNCHRONIZATION_BM 0 +/*! @brief synchronization for freertos software */ +#define DEBUG_CONSOLE_SYNCHRONIZATION_FREERTOS 1 + +/*! @brief RTOS synchronization mechanism disable +* If not defined, default is enable, to avoid multitask log print mess. +* If other RTOS is used, you can implement the RTOS's specific synchronization mechanism in fsl.log.c +* If synchronization is disabled, log maybe messed on terminal. +*/ +#ifndef DEBUG_CONSOLE_DISABLE_RTOS_SYNCHRONIZATION +#ifdef DEBUG_CONSOLE_TRANSFER_NON_BLOCKING +#ifdef FSL_RTOS_FREE_RTOS +#define DEBUG_CONSOLE_SYNCHRONIZATION_MODE DEBUG_CONSOLE_SYNCHRONIZATION_FREERTOS +#else +#define DEBUG_CONSOLE_SYNCHRONIZATION_MODE DEBUG_CONSOLE_SYNCHRONIZATION_BM +#endif /* FSL_RTOS_FREE_RTOS */ +#else +#define DEBUG_CONSOLE_SYNCHRONIZATION_MODE DEBUG_CONSOLE_SYNCHRONIZATION_BM +#endif /* DEBUG_CONSOLE_TRANSFER_NON_BLOCKING */ +#endif /* DEBUG_CONSOLE_DISABLE_RTOS_SYNCHRONIZATION */ + +/*! @brief echo function support +* If you want to use the echo function,please define DEBUG_CONSOLE_ENABLE_ECHO +* at your project setting. +*/ +#ifndef DEBUG_CONSOLE_ENABLE_ECHO +#define DEBUG_CONSOLE_ENABLE_ECHO_FUNCTION 0 +#else +#define DEBUG_CONSOLE_ENABLE_ECHO_FUNCTION 1 +#endif /* DEBUG_CONSOLE_ENABLE_ECHO */ + +/*********************************************************************/ + +/***************Debug console other configuration*********************/ +/*! @brief Definition to printf the float number. */ +#ifndef PRINTF_FLOAT_ENABLE +#define PRINTF_FLOAT_ENABLE 0U +#endif /* PRINTF_FLOAT_ENABLE */ + +/*! @brief Definition to scanf the float number. */ +#ifndef SCANF_FLOAT_ENABLE +#define SCANF_FLOAT_ENABLE 0U +#endif /* SCANF_FLOAT_ENABLE */ + +/*! @brief Definition to support advanced format specifier for printf. */ +#ifndef PRINTF_ADVANCED_ENABLE +#define PRINTF_ADVANCED_ENABLE 0U +#endif /* PRINTF_ADVANCED_ENABLE */ + +/*! @brief Definition to support advanced format specifier for scanf. */ +#ifndef SCANF_ADVANCED_ENABLE +#define SCANF_ADVANCED_ENABLE 0U +#endif /* SCANF_ADVANCED_ENABLE */ + +/*! @brief Definition to select virtual com(USB CDC) as the debug console. */ +#ifndef BOARD_USE_VIRTUALCOM +#define BOARD_USE_VIRTUALCOM 0U +#endif +/*******************************************************************/ + +#endif /* _FSL_DEBUG_CONSOLE_CONF_H_ */ diff --git a/utilities/fsl_io.c b/utilities/fsl_io.c new file mode 100644 index 0000000..4345641 --- /dev/null +++ b/utilities/fsl_io.c @@ -0,0 +1,815 @@ +/* + * The Clear BSD License + * Copyright 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: + * + * o Redistributions of source code must retain the above copyright notice, this list + * of conditions and the following disclaimer. + * + * o 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. + * + * o Neither the name of Freescale Semiconductor, Inc. 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 EPRESS 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, EEMPLARY, 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. + * + */ +#include "fsl_io.h" +#include "fsl_debug_console_conf.h" + +/******************************************************************************* + * Definitions + ******************************************************************************/ +/* check avaliable device */ +#if (defined(FSL_FEATURE_SOC_UART_COUNT) && (FSL_FEATURE_SOC_UART_COUNT != 0)) +#define DEBUG_CONSOLE_IO_UART +#endif + +#if (defined(FSL_FEATURE_SOC_IUART_COUNT) && (FSL_FEATURE_SOC_IUART_COUNT != 0)) +#define DEBUG_CONSOLE_IO_IUART +#endif + +#if (defined(FSL_FEATURE_SOC_LPUART_COUNT) && (FSL_FEATURE_SOC_LPUART_COUNT != 0)) +#define DEBUG_CONSOLE_IO_LPUART +#endif + +#if (defined(FSL_FEATURE_SOC_LPSCI_COUNT) && (FSL_FEATURE_SOC_LPSCI_COUNT != 0)) +#define DEBUG_CONSOLE_IO_LPSCI +#endif + +#if ((defined(FSL_FEATURE_SOC_USB_COUNT) && (FSL_FEATURE_SOC_USB_COUNT != 0)) && \ + (defined(BOARD_USE_VIRTUALCOM) && (BOARD_USE_VIRTUALCOM != 0))) +#define DEBUG_CONSOLE_IO_USBCDC +#endif + +#if (defined(FSL_FEATURE_SOC_FLEXCOMM_COUNT) && (FSL_FEATURE_SOC_FLEXCOMM_COUNT != 0)) +#define DEBUG_CONSOLE_IO_FLEXCOMM +#endif + +#if (defined(FSL_FEATURE_SOC_VFIFO_COUNT) && (FSL_FEATURE_SOC_VFIFO_COUNT != 0)) +#define DEBUG_CONSOLE_IO_VUSART +#endif + +/* If none of above io is supported, enable the swo for debug console, or swo can be enabled by define + * DEBUG_CONSOLE_IO_SWO directly */ +#if (!defined(DEBUG_CONSOLE_IO_SWO) && !defined(DEBUG_CONSOLE_IO_UART) && !defined(DEBUG_CONSOLE_IO_IUART) && \ +!defined(DEBUG_CONSOLE_IO_LPUART) && \ + !defined(DEBUG_CONSOLE_IO_LPSCI) && !defined(DEBUG_CONSOLE_IO_USBCDC) && \ +!defined(DEBUG_CONSOLE_IO_FLEXCOMM) && \ + !defined(DEBUG_CONSOLE_IO_VUSART)) +#define DEBUG_CONSOLE_IO_SWO +#endif + +/* configuration for debug console device */ +/* If new device is required as the low level device for debug console, + * Add the #elif branch and add the preprocessor macro to judge whether + * this kind of device exist in this SOC. */ +#if (defined DEBUG_CONSOLE_IO_UART) || (defined DEBUG_CONSOLE_IO_IUART) +#include "fsl_uart.h" +#ifdef DEBUG_CONSOLE_TRANSFER_NON_BLOCKING +static uart_handle_t s_ioUartHandler; +#endif /* DEBUG_CONSOLE_TRANSFER_NON_BLOCKING */ +#endif /* defined DEBUG_CONSOLE_IO_UART) || (defined DEBUG_CONSOLE_IO_IUART */ + +#if defined DEBUG_CONSOLE_IO_LPUART +#include "fsl_lpuart.h" +#ifdef DEBUG_CONSOLE_TRANSFER_NON_BLOCKING +static lpuart_handle_t s_ioLpuartHandler; +#endif /* DEBUG_CONSOLE_TRANSFER_NON_BLOCKING */ +#endif /* DEBUG_CONSOLE_IO_LPUART */ + +#if defined DEBUG_CONSOLE_IO_LPSCI +#include "fsl_lpsci.h" +#ifdef DEBUG_CONSOLE_TRANSFER_NON_BLOCKING +static lpsci_handle_t s_ioLpsciHandler; +#endif /* DEBUG_CONSOLE_TRANSFER_NON_BLOCKING */ +#endif /* DEBUG_CONSOLE_IO_LPSCI */ + +#if defined DEBUG_CONSOLE_IO_USBCDC +#include "usb_device_config.h" +#include "usb.h" +#include "usb_device_cdc_acm.h" +#include "usb_device_ch9.h" +#include "virtual_com.h" +#endif /* DEBUG_CONSOLE_IO_USBCDC */ + +#if (defined DEBUG_CONSOLE_IO_FLEXCOMM) || (defined DEBUG_CONSOLE_IO_VUSART) +#include "fsl_usart.h" +#ifdef DEBUG_CONSOLE_TRANSFER_NON_BLOCKING +static usart_handle_t s_ioUsartHandler; +#endif /* DEBUG_CONSOLE_TRANSFER_NON_BLOCKING */ +#endif /* defined DEBUG_CONSOLE_IO_FLEXCOMM) || (defined DEBUG_CONSOLE_IO_VUSART */ + +#if defined DEBUG_CONSOLE_IO_SWO +#include "fsl_swo.h" +#endif + +/******************************************************************************* + * Variables + ******************************************************************************/ + +/*! @brief Debug console IO state information. */ +static io_state_t s_debugConsoleIO = { + .ioBase = NULL, + .ioType = DEBUG_CONSOLE_DEVICE_TYPE_NONE, +#ifdef DEBUG_CONSOLE_TRANSFER_NON_BLOCKING + .callBack = NULL, +#endif /* DEBUG_CONSOLE_TRANSFER_NON_BLOCKING */ +}; + +/******************************************************************************* + * Code + ******************************************************************************/ + +#ifdef DEBUG_CONSOLE_TRANSFER_NON_BLOCKING + +#if (defined DEBUG_CONSOLE_IO_UART) || (defined DEBUG_CONSOLE_IO_IUART) +static void UART_Callback(UART_Type *base, uart_handle_t *handle, status_t status, void *userData) +{ + bool tx = false, rx = false; + size_t size = 0U; + + if (status == kStatus_UART_RxIdle) + { + rx = true; + size = handle->txDataSizeAll; + } + + if (status == kStatus_UART_TxIdle) + { + tx = true; + size = handle->txDataSizeAll; + } + + /* inform the buffer layer that transfer is complete */ + if (s_debugConsoleIO.callBack != NULL) + { + /* call buffer callback function */ + s_debugConsoleIO.callBack(&size, rx, tx); + } +} +#endif /* defined DEBUG_CONSOLE_IO_UART) || (defined DEBUG_CONSOLE_IO_IUART */ + +#if defined DEBUG_CONSOLE_IO_LPSCI +static void LPSCI_Callback(UART0_Type *base, lpsci_handle_t *handle, status_t status, void *userData) +{ + bool tx = false, rx = false; + size_t size = 0U; + + if (status == kStatus_LPSCI_RxIdle) + { + rx = true; + size = handle->txDataSizeAll; + } + + if (status == kStatus_LPSCI_TxIdle) + { + tx = true; + size = handle->txDataSizeAll; + } + + /* inform the buffer layer that transfer is complete */ + if (s_debugConsoleIO.callBack != NULL) + { + /* call buffer callback function */ + s_debugConsoleIO.callBack(&size, rx, tx); + } +} +#endif /* DEBUG_CONSOLE_IO_LPSCI */ + +#if defined DEBUG_CONSOLE_IO_LPUART +static void LPUART_Callback(LPUART_Type *base, lpuart_handle_t *handle, status_t status, void *userData) +{ + bool tx = false, rx = false; + size_t size = 0U; + + if (status == kStatus_LPUART_RxIdle) + { + rx = true; + size = handle->txDataSizeAll; + } + + if (status == kStatus_LPUART_TxIdle) + { + tx = true; + size = handle->txDataSizeAll; + } + + /* inform the buffer layer that transfer is complete */ + if (s_debugConsoleIO.callBack != NULL) + { + /* call buffer callback function */ + s_debugConsoleIO.callBack(&size, rx, tx); + } +} +#endif /* DEBUG_CONSOLE_IO_LPUART */ + +#if (defined DEBUG_CONSOLE_IO_FLEXCOMM) || (defined DEBUG_CONSOLE_IO_VUSART) +static void USART_Callback(USART_Type *base, usart_handle_t *handle, status_t status, void *userData) +{ + bool tx = false, rx = false; + size_t size = 0U; + + if (status == kStatus_USART_RxIdle) + { + rx = true; + size = handle->txDataSizeAll; + } + + if (status == kStatus_USART_TxIdle) + { + tx = true; + size = handle->txDataSizeAll; + } + + /* inform the buffer layer that transfer is complete */ + if (s_debugConsoleIO.callBack != NULL) + { + /* call buffer callback function */ + s_debugConsoleIO.callBack(&size, rx, tx); + } +} +#endif /* defined DEBUG_CONSOLE_IO_FLEXCOMM) || (defined DEBUG_CONSOLE_IO_VUSART */ +#endif /* DEBUG_CONSOLE_TRANSFER_NON_BLOCKING */ + +void IO_Init(io_state_t *io, uint32_t baudRate, uint32_t clkSrcFreq, uint8_t *ringBuffer) +{ + assert(NULL != io); + + /* record device type/base */ + s_debugConsoleIO.ioType = io->ioType; + s_debugConsoleIO.ioBase = (void *)(io->ioBase); + + switch (s_debugConsoleIO.ioType) + { +#if (defined DEBUG_CONSOLE_IO_UART) || (defined DEBUG_CONSOLE_IO_IUART) + case DEBUG_CONSOLE_DEVICE_TYPE_UART: + case DEBUG_CONSOLE_DEVICE_TYPE_IUART: + { + uart_config_t uart_config; + UART_GetDefaultConfig(&uart_config); + uart_config.baudRate_Bps = baudRate; + /* Enable clock and initial UART module follow user configure structure. */ + UART_Init((UART_Type *)s_debugConsoleIO.ioBase, &uart_config, clkSrcFreq); + UART_EnableTx(s_debugConsoleIO.ioBase, true); + UART_EnableRx(s_debugConsoleIO.ioBase, true); +#ifdef DEBUG_CONSOLE_TRANSFER_NON_BLOCKING + s_debugConsoleIO.callBack = io->callBack; + /* create handler for interrupt transfer */ + UART_TransferCreateHandle(s_debugConsoleIO.ioBase, &s_ioUartHandler, UART_Callback, NULL); + /* start ring buffer */ + UART_TransferStartRingBuffer(s_debugConsoleIO.ioBase, &s_ioUartHandler, ringBuffer, + DEBUG_CONSOLE_RECEIVE_BUFFER_LEN); +#endif + } + break; +#endif + +#if defined DEBUG_CONSOLE_IO_LPUART + case DEBUG_CONSOLE_DEVICE_TYPE_LPUART: + { + lpuart_config_t lpuart_config; + LPUART_GetDefaultConfig(&lpuart_config); + lpuart_config.baudRate_Bps = baudRate; + /* Enable clock and initial UART module follow user configure structure. */ + LPUART_Init((LPUART_Type *)s_debugConsoleIO.ioBase, &lpuart_config, clkSrcFreq); + LPUART_EnableTx(s_debugConsoleIO.ioBase, true); + LPUART_EnableRx(s_debugConsoleIO.ioBase, true); +#ifdef DEBUG_CONSOLE_TRANSFER_NON_BLOCKING + s_debugConsoleIO.callBack = io->callBack; + /* create handler for interrupt transfer */ + LPUART_TransferCreateHandle(s_debugConsoleIO.ioBase, &s_ioLpuartHandler, LPUART_Callback, NULL); + /* start ring buffer */ + LPUART_TransferStartRingBuffer(s_debugConsoleIO.ioBase, &s_ioLpuartHandler, ringBuffer, + DEBUG_CONSOLE_RECEIVE_BUFFER_LEN); +#endif + } + break; +#endif +#if defined DEBUG_CONSOLE_IO_LPSCI + case DEBUG_CONSOLE_DEVICE_TYPE_LPSCI: + { + lpsci_config_t lpsci_config; + LPSCI_GetDefaultConfig(&lpsci_config); + lpsci_config.baudRate_Bps = baudRate; + /* Enable clock and initial UART module follow user configure structure. */ + LPSCI_Init((UART0_Type *)s_debugConsoleIO.ioBase, &lpsci_config, clkSrcFreq); + LPSCI_EnableTx(s_debugConsoleIO.ioBase, true); + LPSCI_EnableRx(s_debugConsoleIO.ioBase, true); +#ifdef DEBUG_CONSOLE_TRANSFER_NON_BLOCKING + s_debugConsoleIO.callBack = io->callBack; + /* create handler for interrupt transfer */ + LPSCI_TransferCreateHandle(s_debugConsoleIO.ioBase, &s_ioLpsciHandler, LPSCI_Callback, NULL); + /* start ring buffer */ + LPSCI_TransferStartRingBuffer(s_debugConsoleIO.ioBase, &s_ioLpsciHandler, ringBuffer, + DEBUG_CONSOLE_RECEIVE_BUFFER_LEN); +#endif + } + break; +#endif +#if defined DEBUG_CONSOLE_IO_USBCDC + case DEBUG_CONSOLE_DEVICE_TYPE_USBCDC: + { + s_debugConsoleIO.ioBase = USB_VcomInit(); + } + break; +#endif +#if defined DEBUG_CONSOLE_IO_FLEXCOMM + case DEBUG_CONSOLE_DEVICE_TYPE_FLEXCOMM: + { + usart_config_t usart_config; + USART_GetDefaultConfig(&usart_config); + usart_config.baudRate_Bps = baudRate; + /* Enable clock and initial UART module follow user configure structure. */ + USART_Init((USART_Type *)s_debugConsoleIO.ioBase, &usart_config, clkSrcFreq); +#ifdef DEBUG_CONSOLE_TRANSFER_NON_BLOCKING + s_debugConsoleIO.callBack = io->callBack; + /* create handler for interrupt transfer */ + USART_TransferCreateHandle(s_debugConsoleIO.ioBase, &s_ioUsartHandler, USART_Callback, NULL); + /* start ring buffer */ + USART_TransferStartRingBuffer(s_debugConsoleIO.ioBase, &s_ioUsartHandler, ringBuffer, + DEBUG_CONSOLE_RECEIVE_BUFFER_LEN); +#endif + } + break; +#endif +#if defined DEBUG_CONSOLE_IO_VUSART + case DEBUG_CONSOLE_DEVICE_TYPE_VUSART: + { + usart_config_t usart_config; + USART_GetDefaultConfig(&usart_config); + usart_config.baudRate_Bps = baudRate; + usart_config.enableRx = true; + usart_config.enableTx = true; + /* Enable rx fifo for user's continously input */ + usart_config.fifoConfig.enableRxFifo = true; + usart_config.fifoConfig.rxFifoSize = 8; + /* Enable clock and initial UART module follow user configure structure. */ + USART_Init((USART_Type *)s_debugConsoleIO.ioBase, &usart_config, clkSrcFreq); +#ifdef DEBUG_CONSOLE_TRANSFER_NON_BLOCKING + s_debugConsoleIO.callBack = io->callBack; + /* create handler for interrupt transfer */ + USART_TransferCreateHandle(s_debugConsoleIO.ioBase, &s_ioUsartHandler, USART_Callback, NULL); + /* start ring buffer */ + USART_TransferStartRingBuffer(s_debugConsoleIO.ioBase, &s_ioUsartHandler, ringBuffer, + DEBUG_CONSOLE_RECEIVE_BUFFER_LEN); +#endif + } + break; +#endif + +#if defined DEBUG_CONSOLE_IO_SWO + case DEBUG_CONSOLE_DEVICE_TYPE_SWO: + SWO_Init((uint32_t)s_debugConsoleIO.ioBase, baudRate, clkSrcFreq); + break; +#endif + default: + break; + } +} + +status_t IO_Deinit(void) +{ + if (s_debugConsoleIO.ioType == DEBUG_CONSOLE_DEVICE_TYPE_NONE) + { + return kStatus_Success; + } + + switch (s_debugConsoleIO.ioType) + { +#if (defined DEBUG_CONSOLE_IO_UART) || (defined DEBUG_CONSOLE_IO_IUART) + case DEBUG_CONSOLE_DEVICE_TYPE_UART: + case DEBUG_CONSOLE_DEVICE_TYPE_IUART: +#ifdef DEBUG_CONSOLE_TRANSFER_NON_BLOCKING + /* stop ring buffer */ + UART_TransferStopRingBuffer(s_debugConsoleIO.ioBase, &s_ioUartHandler); +#endif + /* Disable UART module. */ + UART_Deinit((UART_Type *)s_debugConsoleIO.ioBase); + + break; +#endif +#if defined DEBUG_CONSOLE_IO_LPSCI + case DEBUG_CONSOLE_DEVICE_TYPE_LPSCI: +#ifdef DEBUG_CONSOLE_TRANSFER_NON_BLOCKING + /* stop ring buffer */ + LPSCI_TransferStopRingBuffer(s_debugConsoleIO.ioBase, &s_ioLpsciHandler); +#endif + /* Disable LPSCI module. */ + LPSCI_Deinit((UART0_Type *)s_debugConsoleIO.ioBase); + + break; +#endif +#if defined DEBUG_CONSOLE_IO_LPUART + case DEBUG_CONSOLE_DEVICE_TYPE_LPUART: +#ifdef DEBUG_CONSOLE_TRANSFER_NON_BLOCKING + /* stop ring buffer */ + LPUART_TransferStopRingBuffer(s_debugConsoleIO.ioBase, &s_ioLpuartHandler); +#endif + /* Disable LPUART module. */ + LPUART_Deinit((LPUART_Type *)s_debugConsoleIO.ioBase); + + break; +#endif +#if defined DEBUG_CONSOLE_IO_USBCDC + case DEBUG_CONSOLE_DEVICE_TYPE_USBCDC: + /* Disable USBCDC module. */ + USB_VcomDeinit(s_debugConsoleIO.ioBase); + break; +#endif +#if (defined DEBUG_CONSOLE_IO_FLEXCOMM) || (defined DEBUG_CONSOLE_IO_VUSART) + case DEBUG_CONSOLE_DEVICE_TYPE_FLEXCOMM: + case DEBUG_CONSOLE_DEVICE_TYPE_VUSART: +#ifdef DEBUG_CONSOLE_TRANSFER_NON_BLOCKING + /* stop ring buffer */ + USART_TransferStopRingBuffer(s_debugConsoleIO.ioBase, &s_ioUsartHandler); +#endif + /* deinit IO */ + USART_Deinit((USART_Type *)s_debugConsoleIO.ioBase); + + break; +#endif + +#if defined DEBUG_CONSOLE_IO_SWO + + case DEBUG_CONSOLE_DEVICE_TYPE_SWO: + SWO_Deinit((uint32_t)s_debugConsoleIO.ioBase); + break; +#endif + default: + s_debugConsoleIO.ioType = DEBUG_CONSOLE_DEVICE_TYPE_NONE; + break; + } + + s_debugConsoleIO.ioType = DEBUG_CONSOLE_DEVICE_TYPE_NONE; + + return kStatus_Success; +} + +status_t IO_WaitIdle(void) +{ + switch (s_debugConsoleIO.ioType) + { +#if (defined DEBUG_CONSOLE_IO_UART) + case DEBUG_CONSOLE_DEVICE_TYPE_UART: + /* wait transfer complete flag */ + while (!(UART_GetStatusFlags(s_debugConsoleIO.ioBase) & kUART_TransmissionCompleteFlag)) + { + } + + break; +#endif + +#if (defined DEBUG_CONSOLE_IO_IUART) + case DEBUG_CONSOLE_DEVICE_TYPE_IUART: + /* wait transfer complete flag */ + while (!(UART_GetStatusFlag(s_debugConsoleIO.ioBase, kUART_TxCompleteFlag))) + { + } + + break; +#endif + +#if defined DEBUG_CONSOLE_IO_LPSCI + case DEBUG_CONSOLE_DEVICE_TYPE_LPSCI: + /* wait transfer complete flag */ + while (!(LPSCI_GetStatusFlags(s_debugConsoleIO.ioBase) & kLPSCI_TransmissionCompleteFlag)) + { + } + + break; +#endif + +#if defined DEBUG_CONSOLE_IO_LPUART + case DEBUG_CONSOLE_DEVICE_TYPE_LPUART: + /* wait transfer complete flag */ + while (!(LPUART_GetStatusFlags(s_debugConsoleIO.ioBase) & kLPUART_TransmissionCompleteFlag)) + { + } + break; +#endif + +#if (defined DEBUG_CONSOLE_IO_FLEXCOMM) || (defined DEBUG_CONSOLE_IO_VUSART) + case DEBUG_CONSOLE_DEVICE_TYPE_FLEXCOMM: + case DEBUG_CONSOLE_DEVICE_TYPE_VUSART: + /* wait transfer complete flag */ + while (!(USART_GetStatusFlags(s_debugConsoleIO.ioBase) & kUSART_TxFifoEmptyFlag)) + { + } + break; +#endif + default: + break; + } + + return kStatus_Success; +} + +#ifdef DEBUG_CONSOLE_TRANSFER_NON_BLOCKING + +status_t IO_Transfer(uint8_t *ch, size_t size, bool tx) +{ + status_t status = kStatus_Fail; + + switch (s_debugConsoleIO.ioType) + { +#if (defined DEBUG_CONSOLE_IO_UART) || (defined DEBUG_CONSOLE_IO_IUART) + case DEBUG_CONSOLE_DEVICE_TYPE_UART: + case DEBUG_CONSOLE_DEVICE_TYPE_IUART: + { + uart_transfer_t transfer = {0U}; + transfer.data = ch; + transfer.dataSize = size; + /* transfer data */ + if (tx) + { + status = UART_TransferSendNonBlocking(s_debugConsoleIO.ioBase, &s_ioUartHandler, &transfer); + } + else + { + status = UART_TransferReceiveNonBlocking(s_debugConsoleIO.ioBase, &s_ioUartHandler, &transfer, NULL); + } + } + break; +#endif +#if defined DEBUG_CONSOLE_IO_LPSCI + case DEBUG_CONSOLE_DEVICE_TYPE_LPSCI: + { + lpsci_transfer_t transfer = {0U}; + transfer.data = ch; + transfer.dataSize = size; + /* transfer data */ + if (tx) + { + status = LPSCI_TransferSendNonBlocking(s_debugConsoleIO.ioBase, &s_ioLpsciHandler, &transfer); + } + else + { + status = LPSCI_TransferReceiveNonBlocking(s_debugConsoleIO.ioBase, &s_ioLpsciHandler, &transfer, NULL); + } + } + break; +#endif + +#if defined DEBUG_CONSOLE_IO_LPUART + case DEBUG_CONSOLE_DEVICE_TYPE_LPUART: + { + lpuart_transfer_t transfer = {0U}; + transfer.data = ch; + transfer.dataSize = size; + /* transfer data */ + if (tx) + { + status = LPUART_TransferSendNonBlocking(s_debugConsoleIO.ioBase, &s_ioLpuartHandler, &transfer); + } + else + { + status = + LPUART_TransferReceiveNonBlocking(s_debugConsoleIO.ioBase, &s_ioLpuartHandler, &transfer, NULL); + } + } + break; +#endif + +#if defined DEBUG_CONSOLE_IO_USBCDC + case DEBUG_CONSOLE_DEVICE_TYPE_USBCDC: + { + if (tx) + { + USB_VcomWriteBlocking(s_debugConsoleIO.ioBase, ch, size); + } + else + { + USB_VcomReadBlocking(s_debugConsoleIO.ioBase, ch, size); + } + } + break; +#endif + +#if (defined DEBUG_CONSOLE_IO_FLEXCOMM) || (defined DEBUG_CONSOLE_IO_VUSART) + case DEBUG_CONSOLE_DEVICE_TYPE_FLEXCOMM: + case DEBUG_CONSOLE_DEVICE_TYPE_VUSART: + { + usart_transfer_t transfer = {0U}; + transfer.data = ch; + transfer.dataSize = size; + /* transfer data */ + if (tx) + { + status = USART_TransferSendNonBlocking(s_debugConsoleIO.ioBase, &s_ioUsartHandler, &transfer); + } + else + { + status = USART_TransferReceiveNonBlocking(s_debugConsoleIO.ioBase, &s_ioUsartHandler, &transfer, NULL); + } + } + break; +#endif + +#if defined DEBUG_CONSOLE_IO_SWO + case DEBUG_CONSOLE_DEVICE_TYPE_SWO: + status = SWO_SendBlocking((uint32_t)s_debugConsoleIO.ioBase, ch, size); + break; +#endif + default: + break; + } + + return status; +} + +status_t IO_TryReceiveCharacter(uint8_t *ch) +{ + status_t status = kStatus_Fail; + uint32_t size = 1U; + + switch (s_debugConsoleIO.ioType) + { +#if (defined DEBUG_CONSOLE_IO_UART) || (defined DEBUG_CONSOLE_IO_IUART) + case DEBUG_CONSOLE_DEVICE_TYPE_UART: + case DEBUG_CONSOLE_DEVICE_TYPE_IUART: + { + uart_transfer_t transfer = {0U}; + transfer.data = ch; + transfer.dataSize = size; + if (UART_TransferGetRxRingBufferLength(&s_ioUartHandler) >= size) + { + /* transfer data */ + status = UART_TransferReceiveNonBlocking(s_debugConsoleIO.ioBase, &s_ioUartHandler, &transfer, NULL); + } + } + break; +#endif +#if defined DEBUG_CONSOLE_IO_LPSCI + case DEBUG_CONSOLE_DEVICE_TYPE_LPSCI: + { + lpsci_transfer_t transfer = {0U}; + transfer.data = ch; + transfer.dataSize = size; + if (LPSCI_TransferGetRxRingBufferLength(&s_ioLpsciHandler) >= size) + { + /* transfer data */ + status = LPSCI_TransferReceiveNonBlocking(s_debugConsoleIO.ioBase, &s_ioLpsciHandler, &transfer, NULL); + } + } + break; +#endif + +#if defined DEBUG_CONSOLE_IO_LPUART + case DEBUG_CONSOLE_DEVICE_TYPE_LPUART: + { + lpuart_transfer_t transfer = {0U}; + transfer.data = ch; + transfer.dataSize = size; + if (LPUART_TransferGetRxRingBufferLength(s_debugConsoleIO.ioBase, &s_ioLpuartHandler) >= size) + { + /* transfer data */ + status = + LPUART_TransferReceiveNonBlocking(s_debugConsoleIO.ioBase, &s_ioLpuartHandler, &transfer, NULL); + } + } + break; +#endif + +#if defined DEBUG_CONSOLE_IO_USBCDC + case DEBUG_CONSOLE_DEVICE_TYPE_USBCDC: + break; +#endif + +#if (defined DEBUG_CONSOLE_IO_FLEXCOMM) || (defined DEBUG_CONSOLE_IO_VUSART) + case DEBUG_CONSOLE_DEVICE_TYPE_FLEXCOMM: + case DEBUG_CONSOLE_DEVICE_TYPE_VUSART: + { + usart_transfer_t transfer = {0U}; + transfer.data = ch; + transfer.dataSize = size; + if (USART_TransferGetRxRingBufferLength(&s_ioUsartHandler) >= size) + { + /* transfer data */ + status = USART_TransferReceiveNonBlocking(s_debugConsoleIO.ioBase, &s_ioUsartHandler, &transfer, NULL); + } + } + break; +#endif + default: + break; + } + + return status; +} + +#else + +status_t IO_Transfer(uint8_t *ch, size_t size, bool tx) +{ + status_t status = kStatus_Success; + switch (s_debugConsoleIO.ioType) + { +#if (defined DEBUG_CONSOLE_IO_UART) || (defined DEBUG_CONSOLE_IO_IUART) + case DEBUG_CONSOLE_DEVICE_TYPE_UART: + case DEBUG_CONSOLE_DEVICE_TYPE_IUART: + { + if (tx) + { + UART_WriteBlocking(s_debugConsoleIO.ioBase, ch, size); + } + else + { + status = UART_ReadBlocking(s_debugConsoleIO.ioBase, ch, size); + } + } + break; +#endif +#if defined DEBUG_CONSOLE_IO_LPSCI + case DEBUG_CONSOLE_DEVICE_TYPE_LPSCI: + { + if (tx) + { + LPSCI_WriteBlocking(s_debugConsoleIO.ioBase, ch, size); + } + else + { + status = LPSCI_ReadBlocking(s_debugConsoleIO.ioBase, ch, size); + } + } + break; +#endif + +#if defined DEBUG_CONSOLE_IO_LPUART + case DEBUG_CONSOLE_DEVICE_TYPE_LPUART: + { + if (tx) + { + LPUART_WriteBlocking(s_debugConsoleIO.ioBase, ch, size); + } + else + { + status = LPUART_ReadBlocking(s_debugConsoleIO.ioBase, ch, size); + } + } + break; +#endif + +#if defined DEBUG_CONSOLE_IO_USBCDC + case DEBUG_CONSOLE_DEVICE_TYPE_USBCDC: + { + if (tx) + { + USB_VcomWriteBlocking(s_debugConsoleIO.ioBase, ch, size); + } + else + { + status = USB_VcomReadBlocking(s_debugConsoleIO.ioBase, ch, size); + } + } + break; +#endif + +#if (defined DEBUG_CONSOLE_IO_FLEXCOMM) || (defined DEBUG_CONSOLE_IO_VUSART) + case DEBUG_CONSOLE_DEVICE_TYPE_FLEXCOMM: + case DEBUG_CONSOLE_DEVICE_TYPE_VUSART: + { + if (tx) + { + USART_WriteBlocking(s_debugConsoleIO.ioBase, ch, size); + } + else + { + status = USART_ReadBlocking(s_debugConsoleIO.ioBase, ch, size); + } + } + break; +#endif + +#if defined DEBUG_CONSOLE_IO_SWO + case DEBUG_CONSOLE_DEVICE_TYPE_SWO: + status = SWO_SendBlocking((uint32_t)s_debugConsoleIO.ioBase, ch, size); + break; +#endif + default: + status = kStatus_Fail; + break; + } + + return status; +} + +#endif /* DEBUG_CONSOLE_TRANSFER_NON_BLOCKING */ diff --git a/utilities/fsl_io.h b/utilities/fsl_io.h new file mode 100644 index 0000000..396f66c --- /dev/null +++ b/utilities/fsl_io.h @@ -0,0 +1,140 @@ +/* + * The Clear BSD License + * Copyright 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: + * + * o Redistributions of source code must retain the above copyright notice, this list + * of conditions and the following disclaimer. + * + * o 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. + * + * o Neither the name of Freescale Semiconductor, Inc. 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_IO_H +#define _FSL_IO_H + +#include "fsl_common.h" + +/*! + * @addtogroup debugconsole + * @{ + */ + +/******************************************************************************* + * Definitions + ******************************************************************************/ +/*! @brief define a notify callback for IO +* @param size , transfer data size. +* @param rx, indicate a rx transfer is success. +* @param tx, indicate a tx transfer is success. +*/ +typedef void (*notify)(size_t *size, bool rx, bool tx); + +/*! @brief State structure storing io. */ +typedef struct io_State +{ + void *ioBase; /*!< Base of the IP register. */ + uint8_t ioType; /*!< device type */ +#ifdef DEBUG_CONSOLE_TRANSFER_NON_BLOCKING + notify callBack; /*!< define the callback function for buffer */ +#endif + +} io_state_t; + +/******************************************************************************* + * Prototypes + ******************************************************************************/ +#if defined(__cplusplus) +extern "C" { +#endif /* __cplusplus */ + +/*! + * @brief io init function. + * + * Call this function to init IO. + * + * @param io configuration pointer + * @param baudRate baud rate + * @param clkSrcFreq clock freq + * @param ringbuffer used to receive character + */ +void IO_Init(io_state_t *io, uint32_t baudRate, uint32_t clkSrcFreq, uint8_t *ringBuffer); + +/*! + * @brief Deinit IO. + * + * Call this function to Deinit IO. + * + * @return deinit status + */ +status_t IO_Deinit(void); + +/*! + * @brief io transfer function. + * + * Call this function to transfer log. + * Print log: + * @code + * IO_Transfer(ch, size, true); + * @endcode + * Scanf log: + * @code + * IO_Transfer(ch, size, false); + * @endcode + * + * @param ch transfer buffer pointer + * @param size transfer size + * @param tx indicate the transfer is TX or RX + */ +status_t IO_Transfer(uint8_t *ch, size_t size, bool tx); + +/*! + * @brief io wait idle. + * + * Call this function to wait the io idle + * + * @return Indicates whether wait idle was successful or not. + */ +status_t IO_WaitIdle(void); + +#ifdef DEBUG_CONSOLE_TRANSFER_NON_BLOCKING +/*! + * @brief io try to receive one character. + * + * Call this function try to receive character + * @param ch the address of char to receive + * @return Indicates try getchar was successful or not. + */ +status_t IO_TryReceiveCharacter(uint8_t *ch); +#endif + +#if defined(__cplusplus) +} +#endif /* __cplusplus */ + +/*! @} */ + +#endif /* _FSL_IO_H */ diff --git a/utilities/fsl_log.c b/utilities/fsl_log.c new file mode 100644 index 0000000..e36832d --- /dev/null +++ b/utilities/fsl_log.c @@ -0,0 +1,587 @@ +/* + * The Clear BSD License + * Copyright 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: + * + * o Redistributions of source code must retain the above copyright notice, this list + * of conditions and the following disclaimer. + * + * o 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. + * + * o Neither the name of Freescale Semiconductor, Inc. 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 EPRESS 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, EEMPLARY, 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. + * + */ +#include "fsl_log.h" +#include "fsl_debug_console_conf.h" +#include "fsl_io.h" +#ifdef FSL_RTOS_FREE_RTOS +#include "FreeRTOS.h" +#include "task.h" +#include "semphr.h" +#endif +/******************************************************************************* + * Definitions + ******************************************************************************/ +#ifndef BACKSPACE +/*! @brief character backspace ASCII value */ +#define BACKSPACE 127 +#endif + +#ifdef DEBUG_CONSOLE_TRANSFER_NON_BLOCKING +/*! @brief increase pop member */ +#define LOG_CHECK_BUFFER_INDEX_OVERFLOW(index) \ + { \ + if (index >= DEBUG_CONSOLE_TRANSMIT_BUFFER_LEN) \ + { \ + index -= DEBUG_CONSOLE_TRANSMIT_BUFFER_LEN; \ + } \ + \ +\ +} + +/*! @brief get current runing environment is ISR or not */ +#ifdef __CA7_REV +#define IS_RUNNING_IN_ISR() SystemGetIRQNestingLevel() +#else +#define IS_RUNNING_IN_ISR() __get_IPSR() +#endif /* __CA7_REV */ + +#else +#define IS_RUNNING_IN_ISR() (0U) +#endif /* DEBUG_CONSOLE_TRANSFER_NON_BLOCKING */ + +/* define for rtos */ +#if (DEBUG_CONSOLE_SYNCHRONIZATION_MODE == DEBUG_CONSOLE_SYNCHRONIZATION_FREERTOS) +/* metex semaphore */ +#define LOG_CREATE_MUTEX_SEMAPHORE(mutex) (mutex = xSemaphoreCreateMutex()) + +#define LOG_GIVE_MUTEX_SEMAPHORE(mutex) \ + \ +{ \ + if (IS_RUNNING_IN_ISR() == 0U) \ + { \ + xSemaphoreGive(mutex); \ + } \ + \ +} + +#define LOG_TAKE_MUTEX_SEMAPHORE_BLOCKING(mutex) \ + \ +{ \ + if (IS_RUNNING_IN_ISR() == 0U) \ + { \ + xSemaphoreTake(mutex, portMAX_DELAY); \ + } \ + \ +} + +#define LOG_TAKE_MUTEX_SEMAPHORE_NONBLOCKING(mutex, result) \ + \ +{ \ + if (IS_RUNNING_IN_ISR() == 0U) \ + { \ + result = xSemaphoreTake(mutex, 0U); \ + } \ + else \ + { \ + result = 1U; \ + } \ + \ +} + +/* Binary semaphore */ +#define LOG_CREATE_BINARY_SEMAPHORE(binary) (binary = xSemaphoreCreateBinary()) +#define LOG_TAKE_BINARY_SEMAPHORE_BLOCKING(binary) (xSemaphoreTake(binary, portMAX_DELAY)) +#define LOG_GIVE_BINARY_SEMAPHORE_FROM_ISR(binary) (xSemaphoreGiveFromISR(binary, NULL)) + +#elif(DEBUG_CONSOLE_SYNCHRONIZATION_MODE == DEBUG_CONSOLE_SYNCHRONIZATION_BM) + +#define LOG_CREATE_MUTEX_SEMAPHORE(mutex) +#define LOG_TAKE_MUTEX_SEMAPHORE_BLOCKING(mutex) +#define LOG_GIVE_MUTEX_SEMAPHORE(mutex) +#define LOG_CREATE_BINARY_SEMAPHORE(binary) +#define LOG_TAKE_MUTEX_SEMAPHORE_NONBLOCKING(mutex, result) (result = 1U) +#ifdef DEBUG_CONSOLE_TRANSFER_NON_BLOCKING +#define LOG_TAKE_BINARY_SEMAPHORE_BLOCKING(binary) \ + \ +{ \ + while (!binary) \ + ; \ + binary = false; \ + \ +\ +} +#define LOG_GIVE_BINARY_SEMAPHORE_FROM_ISR(binary) (binary = true) +#else +#define LOG_TAKE_BINARY_SEMAPHORE_BLOCKING(binary) +#define LOG_GIVE_BINARY_SEMAPHORE_FROM_ISR(binary) +#endif /* DEBUG_CONSOLE_TRANSFER_NON_BLOCKING */ + +/* add other implementation here +*such as : +* #elif(DEBUG_CONSOLE_SYNCHRONIZATION_MODE == DEBUG_CONSOLE_SYNCHRONIZATION_xxx) +*/ + +#else + +#define LOG_CREATE_MUTEX_SEMAPHORE(mutex) +#define LOG_TAKE_MUTEX_SEMAPHORE_BLOCKING(mutex) +#define LOG_TAKE_MUTEX_SEMAPHORE_NONBLOCKING(mutex, result) (result = 1U) +#define LOG_GIVE_MUTEX_SEMAPHORE(mutex) +#define LOG_CREATE_BINARY_SEMAPHORE(binary) +#define LOG_TAKE_BINARY_SEMAPHORE_BLOCKING(binary) +#endif /* DEBUG_CONSOLE_SYNCHRONIZATION_MODE == DEBUG_CONSOLE_SYNCHRONIZATION_FREERTOS */ + +#ifdef DEBUG_CONSOLE_TRANSFER_NON_BLOCKING +/*! @brief Define the buffer +* The total buffer size should be calucate as (BUFFER_SUPPORT_LOG_LENGTH + 1) * BUFFER_SUPPORT_LOG_NUM * 4 +*/ +typedef struct _log_buffer +{ + volatile uint16_t totalIndex; /*!< indicate the total usage of the buffer */ + volatile uint16_t pushIndex; /*!< indicate the next push index */ + volatile uint16_t popIndex; /*!< indicate the pop index */ + uint8_t txBuf[DEBUG_CONSOLE_TRANSMIT_BUFFER_LEN]; /*!< buffer to store printf log */ + + uint8_t rxBuf[DEBUG_CONSOLE_RECEIVE_BUFFER_LEN]; /*!< buffer to store scanf log */ +} log_buffer_t; +#endif /* DEBUG_CONSOLE_TRANSFER_NON_BLOCKING */ + +/******************************************************************************* + * Variables + ******************************************************************************/ +#ifdef DEBUG_CONSOLE_TRANSFER_NON_BLOCKING +/* A global log buffer */ +static log_buffer_t s_log_buffer; +#endif /* DEBUG_CONSOLE_TRANSFER_NON_BLOCKING */ + +/* lock definition */ +#if (DEBUG_CONSOLE_SYNCHRONIZATION_MODE == DEBUG_CONSOLE_SYNCHRONIZATION_FREERTOS) +#ifdef DEBUG_CONSOLE_TRANSFER_NON_BLOCKING +static SemaphoreHandle_t s_logPushSemaphore = NULL; +static SemaphoreHandle_t s_logReadSemaphore = NULL; +#endif /* DEBUG_CONSOLE_TRANSFER_NON_BLOCKING */ +static SemaphoreHandle_t s_logPopSemaphore = NULL; +static SemaphoreHandle_t s_logReadWaitSemaphore = NULL; + +#elif(DEBUG_CONSOLE_SYNCHRONIZATION_MODE == DEBUG_CONSOLE_SYNCHRONIZATION_BM) + +#ifdef DEBUG_CONSOLE_TRANSFER_NON_BLOCKING + +static volatile bool s_logReadWaitSemaphore = false; /* transferred event from ISR for bare-metal + interrupt */ + +#endif /* DEBUG_CONSOLE_TRANSFER_NON_BLOCKING */ + +#else +#endif /* DEBUG_CONSOLE_TRANSFER_NON_BLOCKING */ + +/******************************************************************************* +* Prototypes +******************************************************************************/ +#ifdef DEBUG_CONSOLE_TRANSFER_NON_BLOCKING +/*! + * @brief callback function for IO layer to notify LOG + * + * @param size last transfer data size + * @param receive indicate a RX transfer + * @param transmit indicate a TX transfer + * + */ +static void LOG_Transferred(size_t *size, bool receive, bool transmit); + +/*! + * @brief log push function + * + * @param buf target buffer + * @param size log size + * + */ +static int LOG_BufPush(uint8_t *buf, size_t size); + +/*! + * @brief Get next avaliable log + * + * @param next avaliable size + * @return next avaliable address + */ +static uint8_t *LOG_BufGetNextAvaliableLog(size_t *size); + +/*! + * @brief buf pop + * + * @param size log size popped and next available log size + * @return next avaliable address + */ +static uint8_t *LOG_BufPop(size_t *size); + +#endif /* DEBUG_CONSOLE_TRANSFER_NON_BLOCKING */ + +/*! + * @brief read one character + * + * @param ch character address + * @return indicate the read status + * + */ +static status_t LOG_ReadOneCharacter(uint8_t *ch); + +#if DEBUG_CONSOLE_ENABLE_ECHO_FUNCTION +/*! + * @brief echo one character + * + * @param ch character address + * @param isGetchar flag to distinguish getchar from scanf + * @param index special for scanf to support backspace + * @return indicate the read status + * + */ +static status_t LOG_EchoCharacter(uint8_t *ch, bool isGetChar, int *index); +#endif + +/******************************************************************************* + * Code + ******************************************************************************/ +status_t LOG_Init(uint32_t baseAddr, uint8_t device, uint32_t baudRate, uint32_t clkSrcFreq) +{ + io_state_t io; + /* init io */ + io.ioBase = (void *)baseAddr; + io.ioType = device; + +#ifdef DEBUG_CONSOLE_TRANSFER_NON_BLOCKING + /* memset the global queue */ + memset(&s_log_buffer, 0U, sizeof(s_log_buffer)); + /* init callback for NON-BLOCKING */ + io.callBack = LOG_Transferred; + /* io init function */ + IO_Init(&io, baudRate, clkSrcFreq, s_log_buffer.rxBuf); + /* Debug console buffer push lock create */ + LOG_CREATE_MUTEX_SEMAPHORE(s_logPushSemaphore); + /* Debug console get/scanf mutex lock create */ + LOG_CREATE_MUTEX_SEMAPHORE(s_logReadSemaphore); +#else + IO_Init(&io, baudRate, clkSrcFreq, NULL); +#endif /* DEBUG_CONSOLE_TRANSFER_NON_BLOCKING */ + + /* Debug console lock create */ + LOG_CREATE_MUTEX_SEMAPHORE(s_logPopSemaphore); + LOG_CREATE_BINARY_SEMAPHORE(s_logReadWaitSemaphore); + + return kStatus_Success; +} + +void LOG_Deinit(void) +{ +#ifdef DEBUG_CONSOLE_TRANSFER_NON_BLOCKING + /* memset the global queue */ + memset(&s_log_buffer, 0U, sizeof(s_log_buffer)); +#endif /*DEBUG_CONSOLE_TRANSFER_NON_BLOCKING*/ + /* Deinit IO */ + IO_Deinit(); +} + +status_t LOG_WaitIdle(void) +{ +#ifdef DEBUG_CONSOLE_TRANSFER_NON_BLOCKING + /* wait buffer empty */ + while (!(s_log_buffer.totalIndex == 0U)) + ; +#endif /*DEBUG_CONSOLE_TRANSFER_NON_BLOCKING*/ + /* wait IO idle */ + IO_WaitIdle(); + + return kStatus_Success; +} + +int LOG_Push(uint8_t *buf, size_t size) +{ + assert(buf != NULL); + +#ifdef DEBUG_CONSOLE_TRANSFER_NON_BLOCKING + /* push to buffer */ + LOG_BufPush(buf, size); + buf = LOG_BufGetNextAvaliableLog(&size); +#endif /* DEBUG_CONSOLE_TRANSFER_NON_BLOCKING */ + /* pop log */ + return LOG_Pop(buf, size); +} + +int LOG_Pop(uint8_t *buf, size_t size) +{ + uint8_t getLock = 0U; + + if ((0 != size) && (NULL != buf)) + { + /* take POP lock, should be non-blocking */ + LOG_TAKE_MUTEX_SEMAPHORE_NONBLOCKING(s_logPopSemaphore, getLock); + + if (getLock) + { + /* call IO transfer function */ + if (IO_Transfer(buf, size, true) != kStatus_Success) + { + size = 0U; + } + /* release POP lock */ + LOG_GIVE_MUTEX_SEMAPHORE(s_logPopSemaphore); + } + } + + return size; +} + +int LOG_ReadLine(uint8_t *buf, size_t size) +{ + assert(buf != NULL); + + int i = 0; + + /* take mutex lock function */ + LOG_TAKE_MUTEX_SEMAPHORE_BLOCKING(s_logReadSemaphore); + + for (i = 0; i < size; i++) + { + /* recieve one char every time */ + if (LOG_ReadOneCharacter(&buf[i]) != kStatus_Success) + { + return -1; + } +#if DEBUG_CONSOLE_ENABLE_ECHO_FUNCTION + LOG_EchoCharacter(&buf[i], false, &i); +#endif + /* analysis data */ + if ((buf[i] == '\r') || (buf[i] == '\n')) + { + /* End of Line. */ + if (i == 0) + { + buf[i] = '\0'; + i = -1; + } + else + { + break; + } + } + } + /* get char should not add '\0'*/ + if (i == size) + { + buf[i] = '\0'; + } + else + { + buf[i + 1] = '\0'; + } + + /* release mutex lock function */ + LOG_GIVE_MUTEX_SEMAPHORE(s_logReadSemaphore); + + return i; +} + +int LOG_ReadCharacter(uint8_t *ch) +{ + assert(ch != NULL); + int ret = 0; + + /* take mutex lock function */ + LOG_TAKE_MUTEX_SEMAPHORE_BLOCKING(s_logReadSemaphore); + /* read one character */ + if (LOG_ReadOneCharacter(ch) == kStatus_Success) + { + ret = 1; +#if DEBUG_CONSOLE_ENABLE_ECHO_FUNCTION + LOG_EchoCharacter(ch, true, NULL); +#endif + } + else + { + ret = -1; + } + + /* release mutex lock function */ + LOG_GIVE_MUTEX_SEMAPHORE(s_logReadSemaphore); + + return ret; +} + +static status_t LOG_ReadOneCharacter(uint8_t *ch) +{ + /* recieve one char every time */ + if (IO_Transfer(ch, 1U, false) != kStatus_Success) + { + return kStatus_Fail; + } + + /* wait release from ISR */ + LOG_TAKE_BINARY_SEMAPHORE_BLOCKING(s_logReadWaitSemaphore); + + return kStatus_Success; +} + +#if DEBUG_CONSOLE_ENABLE_ECHO_FUNCTION +static status_t LOG_EchoCharacter(uint8_t *ch, bool isGetChar, int *index) +{ + /* Due to scanf take \n and \r as end of string,should not echo */ + if (((*ch != '\r') && (*ch != '\n')) || (isGetChar)) + { + /* recieve one char every time */ + if (IO_Transfer(ch, 1U, true) != kStatus_Success) + { + return kStatus_Fail; + } + } + + if (!isGetChar) + { + if ((*index > 0) && (*ch == BACKSPACE)) + { + *index -= 2; + } + } + + return kStatus_Success; +} +#endif + +#ifdef DEBUG_CONSOLE_TRANSFER_NON_BLOCKING +static int LOG_BufPush(uint8_t *buf, size_t size) +{ + uint32_t pushIndex = 0U, i = 0U; + bool pushAvaliable = false; + + /* take mutex lock function */ + LOG_TAKE_MUTEX_SEMAPHORE_BLOCKING(s_logPushSemaphore); + if (size <= (DEBUG_CONSOLE_TRANSMIT_BUFFER_LEN - s_log_buffer.totalIndex)) + { + /* get push index */ + pushIndex = s_log_buffer.pushIndex; + s_log_buffer.pushIndex += size; + /* check index overflow */ + LOG_CHECK_BUFFER_INDEX_OVERFLOW(s_log_buffer.pushIndex); + /* update push/total index value */ + s_log_buffer.totalIndex += size; + pushAvaliable = true; + } + /* release mutex lock function */ + LOG_GIVE_MUTEX_SEMAPHORE(s_logPushSemaphore); + + /* check the buffer if have enough space to store the log */ + if (pushAvaliable) + { + for (i = size; i > 0; i--) + { + /* copy log to buffer, the buffer only support a fixed length argument, if the log argument + is longer than the fixed length, the left argument will be losed */ + s_log_buffer.txBuf[pushIndex] = *buf++; + /* increase index */ + pushIndex++; + /* check index overflow */ + LOG_CHECK_BUFFER_INDEX_OVERFLOW(pushIndex); + } + } + else + { + size = 0U; + } + + return size; +} + +static uint8_t *LOG_BufGetNextAvaliableLog(size_t *size) +{ + uint16_t popIndex = s_log_buffer.popIndex; + + /* get avaliable size */ + if (s_log_buffer.totalIndex > (DEBUG_CONSOLE_TRANSMIT_BUFFER_LEN - popIndex)) + { + *size = (DEBUG_CONSOLE_TRANSMIT_BUFFER_LEN - popIndex); + } + else + { + *size = s_log_buffer.totalIndex; + } + + /* return address */ + return (&(s_log_buffer.txBuf[popIndex])); +} + +static uint8_t *LOG_BufPop(size_t *size) +{ + if (s_log_buffer.totalIndex >= *size) + { + /* decrease the log total member */ + s_log_buffer.totalIndex -= *size; + /* there is more log in the queue to be pushed */ + if (s_log_buffer.totalIndex > 0U) + { + /* update the pop index */ + s_log_buffer.popIndex += *size; + /* check index overflow */ + LOG_CHECK_BUFFER_INDEX_OVERFLOW(s_log_buffer.popIndex); + + return LOG_BufGetNextAvaliableLog(size); + } + else + { + /* reset push and pop */ + s_log_buffer.popIndex = 0U; + s_log_buffer.pushIndex = 0U; + *size = 0U; + } + } + + return NULL; +} + +static void LOG_Transferred(size_t *size, bool receive, bool transmit) +{ + uint8_t *addr = NULL; + + if (transmit) + { + addr = LOG_BufPop(size); + /* continue pop log from buffer */ + LOG_Pop(addr, *size); + } + + if (receive) + { + /* release from ISR */ + LOG_GIVE_BINARY_SEMAPHORE_FROM_ISR(s_logReadWaitSemaphore); + } +} +#endif /* DEBUG_CONSOLE_TRANSFER_NON_BLOCKING */ + +#ifdef DEBUG_CONSOLE_TRANSFER_NON_BLOCKING +status_t LOG_TryReadCharacter(uint8_t *ch) +{ + if (NULL != ch) + { + return IO_TryReceiveCharacter(ch); + } + return kStatus_Fail; +} +#endif diff --git a/utilities/fsl_log.h b/utilities/fsl_log.h new file mode 100644 index 0000000..87f4c8a --- /dev/null +++ b/utilities/fsl_log.h @@ -0,0 +1,146 @@ +/* + * The Clear BSD License + * Copyright 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: + * + * o Redistributions of source code must retain the above copyright notice, this list + * of conditions and the following disclaimer. + * + * o 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. + * + * o Neither the name of Freescale Semiconductor, Inc. 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_LOG_H +#define _FSL_LOG_H + +#include "fsl_common.h" + +/*! + * @addtogroup debugconsole + * @{ + */ + +/******************************************************************************* + * Definitions + ******************************************************************************/ + +/************************************************************************************************* + * Prototypes + ************************************************************************************************/ +#if defined(__cplusplus) +extern "C" { +#endif /* __cplusplus */ + +/*! + * @brief Initializes + * + * Call this function to init the buffer + * @param baseAddr, device base address + * @param device, device type + * @param baudRate, device communicate baudrate + * @param clkSrcFreq, device source clock freq + * + * @return Indicates whether initialization was successful or not. + * @retval kStatus_Success Execution successfully + * @retval kStatus_Fail Execution failure + */ +status_t LOG_Init(uint32_t baseAddr, uint8_t device, uint32_t baudRate, uint32_t clkSrcFreq); + +/*! + * @brief De-Initializes + * + * Call this function to deinit the buffer + * + * @return Indicates whether Deinit was successful or not. + */ +void LOG_Deinit(void); + +/*! + * @brief log push interface + * + * Call this function to print log + * @param fmt, buffer pointer + * @param size, avaliable size + * @return indicate the push size + * @retval-1 indicate buffer is full or transfer fail. + * @retval size return the push log size. + */ +int LOG_Push(uint8_t *buf, size_t size); + +/*! + * @brief log read one line function + * + * Call this function to print log + * @param fmt, buffer pointer + * @param size, avaliable size + * @reutrn the number of the recieved character + */ +int LOG_ReadLine(uint8_t *buf, size_t size); + +/*! + * @brief log read one character function + * + * Call this function to GETCHAR + * @param ch receive address + * @reutrn the number of the recieved character + */ +int LOG_ReadCharacter(uint8_t *ch); + +/*! + * @brief wait log and io idle + * + * Call this function to wait log buffer empty and io idle before enter low power mode. + * @return Indicates whether wait idle was successful or not. + */ +status_t LOG_WaitIdle(void); + +#ifdef DEBUG_CONSOLE_TRANSFER_NON_BLOCKING +/*! + * @brief log try read one character + * Call this function to check character avaliable or not, if not return fail, otherwise return it. + * @param ch the address of char to receive + * @return Indicates try getchar was successful or not. + */ +status_t LOG_TryReadCharacter(uint8_t *ch); +#endif + +/*! + * @brief log pop function + * + * Call this function to pop log from buffer. + * @param buf buffer address to pop + * @param size log size to pop + * @return pop log size. + */ +int LOG_Pop(uint8_t *buf, size_t size); + +#if defined(__cplusplus) +} +#endif /* __cplusplus */ + +/*! @} */ + +#endif diff --git a/utilities/fsl_str.c b/utilities/fsl_str.c new file mode 100644 index 0000000..d34e41a --- /dev/null +++ b/utilities/fsl_str.c @@ -0,0 +1,1327 @@ +/* + * The Clear BSD License + * Copyright 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: + * + * o Redistributions of source code must retain the above copyright notice, this list + * of conditions and the following disclaimer. + * + * o 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. + * + * o Neither the name of Freescale Semiconductor, Inc. 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 EPRESS 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, EEMPLARY, 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. + * + */ +#include +#include +#include +#include "fsl_str.h" +#include "fsl_debug_console_conf.h" + +/******************************************************************************* + * Definitions + ******************************************************************************/ + +/*! @brief The overflow value.*/ +#ifndef HUGE_VAL +#define HUGE_VAL (99.e99) +#endif /* HUGE_VAL */ + +#if SCANF_FLOAT_ENABLE +static double fnum = 0.0; +#endif /* SCANF_FLOAT_ENABLE */ + +#if PRINTF_ADVANCED_ENABLE +/*! @brief Specification modifier flags for printf. */ +enum _debugconsole_printf_flag +{ + kPRINTF_Minus = 0x01U, /*!< Minus FLag. */ + kPRINTF_Plus = 0x02U, /*!< Plus Flag. */ + kPRINTF_Space = 0x04U, /*!< Space Flag. */ + kPRINTF_Zero = 0x08U, /*!< Zero Flag. */ + kPRINTF_Pound = 0x10U, /*!< Pound Flag. */ + kPRINTF_LengthChar = 0x20U, /*!< Length: Char Flag. */ + kPRINTF_LengthShortInt = 0x40U, /*!< Length: Short Int Flag. */ + kPRINTF_LengthLongInt = 0x80U, /*!< Length: Long Int Flag. */ + kPRINTF_LengthLongLongInt = 0x100U, /*!< Length: Long Long Int Flag. */ +}; +#endif /* PRINTF_ADVANCED_ENABLE */ + +/*! @brief Specification modifier flags for scanf. */ +enum _debugconsole_scanf_flag +{ + kSCANF_Suppress = 0x2U, /*!< Suppress Flag. */ + kSCANF_DestMask = 0x7cU, /*!< Destination Mask. */ + kSCANF_DestChar = 0x4U, /*!< Destination Char Flag. */ + kSCANF_DestString = 0x8U, /*!< Destination String FLag. */ + kSCANF_DestSet = 0x10U, /*!< Destination Set Flag. */ + kSCANF_DestInt = 0x20U, /*!< Destination Int Flag. */ + kSCANF_DestFloat = 0x30U, /*!< Destination Float Flag. */ + kSCANF_LengthMask = 0x1f00U, /*!< Length Mask Flag. */ +#if SCANF_ADVANCED_ENABLE + kSCANF_LengthChar = 0x100U, /*!< Length Char Flag. */ + kSCANF_LengthShortInt = 0x200U, /*!< Length ShortInt Flag. */ + kSCANF_LengthLongInt = 0x400U, /*!< Length LongInt Flag. */ + kSCANF_LengthLongLongInt = 0x800U, /*!< Length LongLongInt Flag. */ +#endif /* SCANF_ADVANCED_ENABLE */ +#if PRINTF_FLOAT_ENABLE + kSCANF_LengthLongLongDouble = 0x1000U, /*!< Length LongLongDuoble Flag. */ +#endif /*PRINTF_FLOAT_ENABLE */ + kSCANF_TypeSinged = 0x2000U, /*!< TypeSinged Flag. */ +}; + +/*! @brief Keil: suppress ellipsis warning in va_arg usage below. */ +#if defined(__CC_ARM) +#pragma diag_suppress 1256 +#endif /* __CC_ARM */ + +/******************************************************************************* + * Prototypes + ******************************************************************************/ +/*! + * @brief Scanline function which ignores white spaces. + * + * @param[in] s The address of the string pointer to update. + * @return String without white spaces. + */ +static uint32_t ScanIgnoreWhiteSpace(const char **s); + +/*! + * @brief Converts a radix number to a string and return its length. + * + * @param[in] numstr Converted string of the number. + * @param[in] nump Pointer to the number. + * @param[in] neg Polarity of the number. + * @param[in] radix The radix to be converted to. + * @param[in] use_caps Used to identify %x/X output format. + + * @return Length of the converted string. + */ +static int32_t ConvertRadixNumToString(char *numstr, void *nump, int32_t neg, int32_t radix, bool use_caps); + +#if PRINTF_FLOAT_ENABLE +/*! + * @brief Converts a floating radix number to a string and return its length. + * + * @param[in] numstr Converted string of the number. + * @param[in] nump Pointer to the number. + * @param[in] radix The radix to be converted to. + * @param[in] precision_width Specify the precision width. + + * @return Length of the converted string. + */ +static int32_t ConvertFloatRadixNumToString(char *numstr, void *nump, int32_t radix, uint32_t precision_width); +#endif /* PRINTF_FLOAT_ENABLE */ + +/*! +* + */ +double modf(double input_dbl, double *intpart_ptr); + +/*************Code for process formatted data*******************************/ + +static uint32_t ScanIgnoreWhiteSpace(const char **s) +{ + uint8_t count = 0; + uint8_t c; + + c = **s; + while ((c == ' ') || (c == '\t') || (c == '\n') || (c == '\r') || (c == '\v') || (c == '\f')) + { + count++; + (*s)++; + c = **s; + } + return count; +} + +static int32_t ConvertRadixNumToString(char *numstr, void *nump, int32_t neg, int32_t radix, bool use_caps) +{ +#if PRINTF_ADVANCED_ENABLE + int64_t a; + int64_t b; + int64_t c; + + uint64_t ua; + uint64_t ub; + uint64_t uc; +#else + int32_t a; + int32_t b; + int32_t c; + + uint32_t ua; + uint32_t ub; + uint32_t uc; +#endif /* PRINTF_ADVANCED_ENABLE */ + + int32_t nlen; + char *nstrp; + + nlen = 0; + nstrp = numstr; + *nstrp++ = '\0'; + + if (neg) + { +#if PRINTF_ADVANCED_ENABLE + a = *(int64_t *)nump; +#else + a = *(int32_t *)nump; +#endif /* PRINTF_ADVANCED_ENABLE */ + if (a == 0) + { + *nstrp = '0'; + ++nlen; + return nlen; + } + while (a != 0) + { +#if PRINTF_ADVANCED_ENABLE + b = (int64_t)a / (int64_t)radix; + c = (int64_t)a - ((int64_t)b * (int64_t)radix); + if (c < 0) + { + uc = (uint64_t)c; + c = (int64_t)(~uc) + 1 + '0'; + } +#else + b = a / radix; + c = a - (b * radix); + if (c < 0) + { + uc = (uint32_t)c; + c = (uint32_t)(~uc) + 1 + '0'; + } +#endif /* PRINTF_ADVANCED_ENABLE */ + else + { + c = c + '0'; + } + a = b; + *nstrp++ = (char)c; + ++nlen; + } + } + else + { +#if PRINTF_ADVANCED_ENABLE + ua = *(uint64_t *)nump; +#else + ua = *(uint32_t *)nump; +#endif /* PRINTF_ADVANCED_ENABLE */ + if (ua == 0) + { + *nstrp = '0'; + ++nlen; + return nlen; + } + while (ua != 0) + { +#if PRINTF_ADVANCED_ENABLE + ub = (uint64_t)ua / (uint64_t)radix; + uc = (uint64_t)ua - ((uint64_t)ub * (uint64_t)radix); +#else + ub = ua / (uint32_t)radix; + uc = ua - (ub * (uint32_t)radix); +#endif /* PRINTF_ADVANCED_ENABLE */ + + if (uc < 10) + { + uc = uc + '0'; + } + else + { + uc = uc - 10 + (use_caps ? 'A' : 'a'); + } + ua = ub; + *nstrp++ = (char)uc; + ++nlen; + } + } + return nlen; +} + +#if PRINTF_FLOAT_ENABLE +static int32_t ConvertFloatRadixNumToString(char *numstr, void *nump, int32_t radix, uint32_t precision_width) +{ + int32_t a; + int32_t b; + int32_t c; + int32_t i; + uint32_t uc; + double fa; + double dc; + double fb; + double r; + double fractpart; + double intpart; + + int32_t nlen; + char *nstrp; + nlen = 0; + nstrp = numstr; + *nstrp++ = '\0'; + r = *(double *)nump; + if (!r) + { + *nstrp = '0'; + ++nlen; + return nlen; + } + fractpart = modf((double)r, (double *)&intpart); + /* Process fractional part. */ + for (i = 0; i < precision_width; i++) + { + fractpart *= radix; + } + if (r >= 0) + { + fa = fractpart + (double)0.5; + if (fa >= pow(10, precision_width)) + { + intpart++; + } + } + else + { + fa = fractpart - (double)0.5; + if (fa <= -pow(10, precision_width)) + { + intpart--; + } + } + for (i = 0; i < precision_width; i++) + { + fb = fa / (int32_t)radix; + dc = (fa - (int64_t)fb * (int32_t)radix); + c = (int32_t)dc; + if (c < 0) + { + uc = (uint32_t)c; + c = (int32_t)(~uc) + 1 + '0'; + } + else + { + c = c + '0'; + } + fa = fb; + *nstrp++ = (char)c; + ++nlen; + } + *nstrp++ = (char)'.'; + ++nlen; + a = (int32_t)intpart; + if (a == 0) + { + *nstrp++ = '0'; + ++nlen; + } + else + { + while (a != 0) + { + b = (int32_t)a / (int32_t)radix; + c = (int32_t)a - ((int32_t)b * (int32_t)radix); + if (c < 0) + { + uc = (uint32_t)c; + c = (int32_t)(~uc) + 1 + '0'; + } + else + { + c = c + '0'; + } + a = b; + *nstrp++ = (char)c; + ++nlen; + } + } + return nlen; +} +#endif /* PRINTF_FLOAT_ENABLE */ + +int StrFormatPrintf(const char *fmt, va_list ap, char *buf, printfCb cb) +{ + /* va_list ap; */ + char *p; + int32_t c; + + char vstr[33]; + char *vstrp = NULL; + int32_t vlen = 0; + + int32_t done; + int32_t count = 0; + + uint32_t field_width; + uint32_t precision_width; + char *sval; + int32_t cval; + bool use_caps; + uint8_t radix = 0; + +#if PRINTF_ADVANCED_ENABLE + uint32_t flags_used; + int32_t schar, dschar; + int64_t ival; + uint64_t uval = 0; + bool valid_precision_width; +#else + int32_t ival; + uint32_t uval = 0; +#endif /* PRINTF_ADVANCED_ENABLE */ + +#if PRINTF_FLOAT_ENABLE + double fval; +#endif /* PRINTF_FLOAT_ENABLE */ + + /* Start parsing apart the format string and display appropriate formats and data. */ + for (p = (char *)fmt; (c = *p) != 0; p++) + { + /* + * All formats begin with a '%' marker. Special chars like + * '\n' or '\t' are normally converted to the appropriate + * character by the __compiler__. Thus, no need for this + * routine to account for the '\' character. + */ + if (c != '%') + { + cb(buf, &count, c, 1); + /* By using 'continue', the next iteration of the loop is used, skipping the code that follows. */ + continue; + } + + use_caps = true; + +#if PRINTF_ADVANCED_ENABLE + /* First check for specification modifier flags. */ + flags_used = 0; + done = false; + while (!done) + { + switch (*++p) + { + case '-': + flags_used |= kPRINTF_Minus; + break; + case '+': + flags_used |= kPRINTF_Plus; + break; + case ' ': + flags_used |= kPRINTF_Space; + break; + case '0': + flags_used |= kPRINTF_Zero; + break; + case '#': + flags_used |= kPRINTF_Pound; + break; + default: + /* We've gone one char too far. */ + --p; + done = true; + break; + } + } +#endif /* PRINTF_ADVANCED_ENABLE */ + + /* Next check for minimum field width. */ + field_width = 0; + done = false; + while (!done) + { + c = *++p; + if ((c >= '0') && (c <= '9')) + { + field_width = (field_width * 10) + (c - '0'); + } +#if PRINTF_ADVANCED_ENABLE + else if (c == '*') + { + field_width = (uint32_t)va_arg(ap, uint32_t); + } +#endif /* PRINTF_ADVANCED_ENABLE */ + else + { + /* We've gone one char too far. */ + --p; + done = true; + } + } + /* Next check for the width and precision field separator. */ + precision_width = 6; +#if PRINTF_ADVANCED_ENABLE + valid_precision_width = false; +#endif /* PRINTF_ADVANCED_ENABLE */ + if (*++p == '.') + { + /* Must get precision field width, if present. */ + precision_width = 0; + done = false; + while (!done) + { + c = *++p; + if ((c >= '0') && (c <= '9')) + { + precision_width = (precision_width * 10) + (c - '0'); +#if PRINTF_ADVANCED_ENABLE + valid_precision_width = true; +#endif /* PRINTF_ADVANCED_ENABLE */ + } +#if PRINTF_ADVANCED_ENABLE + else if (c == '*') + { + precision_width = (uint32_t)va_arg(ap, uint32_t); + valid_precision_width = true; + } +#endif /* PRINTF_ADVANCED_ENABLE */ + else + { + /* We've gone one char too far. */ + --p; + done = true; + } + } + } + else + { + /* We've gone one char too far. */ + --p; + } +#if PRINTF_ADVANCED_ENABLE + /* + * Check for the length modifier. + */ + switch (/* c = */ *++p) + { + case 'h': + if (*++p != 'h') + { + flags_used |= kPRINTF_LengthShortInt; + --p; + } + else + { + flags_used |= kPRINTF_LengthChar; + } + break; + case 'l': + if (*++p != 'l') + { + flags_used |= kPRINTF_LengthLongInt; + --p; + } + else + { + flags_used |= kPRINTF_LengthLongLongInt; + } + break; + default: + /* we've gone one char too far */ + --p; + break; + } +#endif /* PRINTF_ADVANCED_ENABLE */ + /* Now we're ready to examine the format. */ + c = *++p; + { + if ((c == 'd') || (c == 'i') || (c == 'f') || (c == 'F') || (c == 'x') || (c == 'X') || (c == 'o') || + (c == 'b') || (c == 'p') || (c == 'u')) + { + if ((c == 'd') || (c == 'i')) + { +#if PRINTF_ADVANCED_ENABLE + if (flags_used & kPRINTF_LengthLongLongInt) + { + ival = (int64_t)va_arg(ap, int64_t); + } + else +#endif /* PRINTF_ADVANCED_ENABLE */ + { + ival = (int32_t)va_arg(ap, int32_t); + } + vlen = ConvertRadixNumToString(vstr, &ival, true, 10, use_caps); + vstrp = &vstr[vlen]; +#if PRINTF_ADVANCED_ENABLE + if (ival < 0) + { + schar = '-'; + ++vlen; + } + else + { + if (flags_used & kPRINTF_Plus) + { + schar = '+'; + ++vlen; + } + else + { + if (flags_used & kPRINTF_Space) + { + schar = ' '; + ++vlen; + } + else + { + schar = 0; + } + } + } + dschar = false; + /* Do the ZERO pad. */ + if (flags_used & kPRINTF_Zero) + { + if (schar) + { + cb(buf, &count, schar, 1); + } + dschar = true; + + cb(buf, &count, '0', field_width - vlen); + vlen = field_width; + } + else + { + if (!(flags_used & kPRINTF_Minus)) + { + cb(buf, &count, ' ', field_width - vlen); + if (schar) + { + cb(buf, &count, schar, 1); + } + dschar = true; + } + } + /* The string was built in reverse order, now display in correct order. */ + if ((!dschar) && schar) + { + cb(buf, &count, schar, 1); + } +#endif /* PRINTF_ADVANCED_ENABLE */ + } + +#if PRINTF_FLOAT_ENABLE + if ((c == 'f') || (c == 'F')) + { + fval = (double)va_arg(ap, double); + vlen = ConvertFloatRadixNumToString(vstr, &fval, 10, precision_width); + vstrp = &vstr[vlen]; + +#if PRINTF_ADVANCED_ENABLE + if (fval < 0) + { + schar = '-'; + ++vlen; + } + else + { + if (flags_used & kPRINTF_Plus) + { + schar = '+'; + ++vlen; + } + else + { + if (flags_used & kPRINTF_Space) + { + schar = ' '; + ++vlen; + } + else + { + schar = 0; + } + } + } + dschar = false; + if (flags_used & kPRINTF_Zero) + { + if (schar) + { + cb(buf, &count, schar, 1); + } + dschar = true; + cb(buf, &count, '0', field_width - vlen); + vlen = field_width; + } + else + { + if (!(flags_used & kPRINTF_Minus)) + { + cb(buf, &count, ' ', field_width - vlen); + if (schar) + { + cb(buf, &count, schar, 1); + } + dschar = true; + } + } + if ((!dschar) && schar) + { + cb(buf, &count, schar, 1); + } +#endif /* PRINTF_ADVANCED_ENABLE */ + } +#endif /* PRINTF_FLOAT_ENABLE */ + if ((c == 'X') || (c == 'x')) + { + if (c == 'x') + { + use_caps = false; + } +#if PRINTF_ADVANCED_ENABLE + if (flags_used & kPRINTF_LengthLongLongInt) + { + uval = (uint64_t)va_arg(ap, uint64_t); + } + else +#endif /* PRINTF_ADVANCED_ENABLE */ + { + uval = (uint32_t)va_arg(ap, uint32_t); + } + vlen = ConvertRadixNumToString(vstr, &uval, false, 16, use_caps); + vstrp = &vstr[vlen]; + +#if PRINTF_ADVANCED_ENABLE + dschar = false; + if (flags_used & kPRINTF_Zero) + { + if (flags_used & kPRINTF_Pound) + { + cb(buf, &count, '0', 1); + cb(buf, &count, (use_caps ? 'X' : 'x'), 1); + dschar = true; + } + cb(buf, &count, '0', field_width - vlen); + vlen = field_width; + } + else + { + if (!(flags_used & kPRINTF_Minus)) + { + if (flags_used & kPRINTF_Pound) + { + vlen += 2; + } + cb(buf, &count, ' ', field_width - vlen); + if (flags_used & kPRINTF_Pound) + { + cb(buf, &count, '0', 1); + cb(buf, &count, (use_caps ? 'X' : 'x'), 1); + dschar = true; + } + } + } + + if ((flags_used & kPRINTF_Pound) && (!dschar)) + { + cb(buf, &count, '0', 1); + cb(buf, &count, (use_caps ? 'X' : 'x'), 1); + vlen += 2; + } +#endif /* PRINTF_ADVANCED_ENABLE */ + } + if ((c == 'o') || (c == 'b') || (c == 'p') || (c == 'u')) + { +#if PRINTF_ADVANCED_ENABLE + if (flags_used & kPRINTF_LengthLongLongInt) + { + uval = (uint64_t)va_arg(ap, uint64_t); + } + else +#endif /* PRINTF_ADVANCED_ENABLE */ + { + uval = (uint32_t)va_arg(ap, uint32_t); + } + + if (c == 'o') + { + radix = 8; + } + else if (c == 'b') + { + radix = 2; + } + else if (c == 'p') + { + radix = 16; + } + else + { + radix = 10; + } + + vlen = ConvertRadixNumToString(vstr, &uval, false, radix, use_caps); + vstrp = &vstr[vlen]; +#if PRINTF_ADVANCED_ENABLE + if (flags_used & kPRINTF_Zero) + { + cb(buf, &count, '0', field_width - vlen); + vlen = field_width; + } + else + { + if (!(flags_used & kPRINTF_Minus)) + { + cb(buf, &count, ' ', field_width - vlen); + } + } +#endif /* PRINTF_ADVANCED_ENABLE */ + } +#if !PRINTF_ADVANCED_ENABLE + cb(buf, &count, ' ', field_width - vlen); +#endif /* !PRINTF_ADVANCED_ENABLE */ + if (vstrp != NULL) + { + while (*vstrp) + { + cb(buf, &count, *vstrp--, 1); + } + } +#if PRINTF_ADVANCED_ENABLE + if (flags_used & kPRINTF_Minus) + { + cb(buf, &count, ' ', field_width - vlen); + } +#endif /* PRINTF_ADVANCED_ENABLE */ + } + else if (c == 'c') + { + cval = (char)va_arg(ap, uint32_t); + cb(buf, &count, cval, 1); + } + else if (c == 's') + { + sval = (char *)va_arg(ap, char *); + if (sval) + { +#if PRINTF_ADVANCED_ENABLE + if (valid_precision_width) + { + vlen = precision_width; + } + else + { + vlen = strlen(sval); + } +#else + vlen = strlen(sval); +#endif /* PRINTF_ADVANCED_ENABLE */ +#if PRINTF_ADVANCED_ENABLE + if (!(flags_used & kPRINTF_Minus)) +#endif /* PRINTF_ADVANCED_ENABLE */ + { + cb(buf, &count, ' ', field_width - vlen); + } + +#if PRINTF_ADVANCED_ENABLE + if (valid_precision_width) + { + while ((*sval) && (vlen > 0)) + { + cb(buf, &count, *sval++, 1); + vlen--; + } + /* In case that vlen sval is shorter than vlen */ + vlen = precision_width - vlen; + } + else + { +#endif /* PRINTF_ADVANCED_ENABLE */ + while (*sval) + { + cb(buf, &count, *sval++, 1); + } +#if PRINTF_ADVANCED_ENABLE + } +#endif /* PRINTF_ADVANCED_ENABLE */ + +#if PRINTF_ADVANCED_ENABLE + if (flags_used & kPRINTF_Minus) + { + cb(buf, &count, ' ', field_width - vlen); + } +#endif /* PRINTF_ADVANCED_ENABLE */ + } + } + else + { + cb(buf, &count, c, 1); + } + } + } + + return count; +} + +int StrFormatScanf(const char *line_ptr, char *format, va_list args_ptr) +{ + uint8_t base; + int8_t neg; + /* Identifier for the format string. */ + char *c = format; + char temp; + char *buf; + /* Flag telling the conversion specification. */ + uint32_t flag = 0; + /* Filed width for the matching input streams. */ + uint32_t field_width; + /* How many arguments are assigned except the suppress. */ + uint32_t nassigned = 0; + /* How many characters are read from the input streams. */ + uint32_t n_decode = 0; + + int32_t val; + + const char *s; + /* Identifier for the input string. */ + const char *p = line_ptr; + + /* Return EOF error before any conversion. */ + if (*p == '\0') + { + return -1; + } + + /* Decode directives. */ + while ((*c) && (*p)) + { + /* Ignore all white-spaces in the format strings. */ + if (ScanIgnoreWhiteSpace((const char **)&c)) + { + n_decode += ScanIgnoreWhiteSpace(&p); + } + else if ((*c != '%') || ((*c == '%') && (*(c + 1) == '%'))) + { + /* Ordinary characters. */ + c++; + if (*p == *c) + { + n_decode++; + p++; + c++; + } + else + { + /* Match failure. Misalignment with C99, the unmatched characters need to be pushed back to stream. + * However, it is deserted now. */ + break; + } + } + else + { + /* convernsion specification */ + c++; + /* Reset. */ + flag = 0; + field_width = 0; + base = 0; + + /* Loop to get full conversion specification. */ + while ((*c) && (!(flag & kSCANF_DestMask))) + { + switch (*c) + { +#if SCANF_ADVANCED_ENABLE + case '*': + if (flag & kSCANF_Suppress) + { + /* Match failure. */ + return nassigned; + } + flag |= kSCANF_Suppress; + c++; + break; + case 'h': + if (flag & kSCANF_LengthMask) + { + /* Match failure. */ + return nassigned; + } + + if (c[1] == 'h') + { + flag |= kSCANF_LengthChar; + c++; + } + else + { + flag |= kSCANF_LengthShortInt; + } + c++; + break; + case 'l': + if (flag & kSCANF_LengthMask) + { + /* Match failure. */ + return nassigned; + } + + if (c[1] == 'l') + { + flag |= kSCANF_LengthLongLongInt; + c++; + } + else + { + flag |= kSCANF_LengthLongInt; + } + c++; + break; +#endif /* SCANF_ADVANCED_ENABLE */ +#if SCANF_FLOAT_ENABLE + case 'L': + if (flag & kSCANF_LengthMask) + { + /* Match failure. */ + return nassigned; + } + flag |= kSCANF_LengthLongLongDouble; + c++; + break; +#endif /* SCANF_FLOAT_ENABLE */ + case '0': + case '1': + case '2': + case '3': + case '4': + case '5': + case '6': + case '7': + case '8': + case '9': + if (field_width) + { + /* Match failure. */ + return nassigned; + } + do + { + field_width = field_width * 10 + *c - '0'; + c++; + } while ((*c >= '0') && (*c <= '9')); + break; + case 'd': + base = 10; + flag |= kSCANF_TypeSinged; + flag |= kSCANF_DestInt; + c++; + break; + case 'u': + base = 10; + flag |= kSCANF_DestInt; + c++; + break; + case 'o': + base = 8; + flag |= kSCANF_DestInt; + c++; + break; + case 'x': + case 'X': + base = 16; + flag |= kSCANF_DestInt; + c++; + break; + case 'i': + base = 0; + flag |= kSCANF_DestInt; + c++; + break; +#if SCANF_FLOAT_ENABLE + case 'a': + case 'A': + case 'e': + case 'E': + case 'f': + case 'F': + case 'g': + case 'G': + flag |= kSCANF_DestFloat; + c++; + break; +#endif /* SCANF_FLOAT_ENABLE */ + case 'c': + flag |= kSCANF_DestChar; + if (!field_width) + { + field_width = 1; + } + c++; + break; + case 's': + flag |= kSCANF_DestString; + c++; + break; + default: + return nassigned; + } + } + + if (!(flag & kSCANF_DestMask)) + { + /* Format strings are exhausted. */ + return nassigned; + } + + if (!field_width) + { + /* Large than length of a line. */ + field_width = 99; + } + + /* Matching strings in input streams and assign to argument. */ + switch (flag & kSCANF_DestMask) + { + case kSCANF_DestChar: + s = (const char *)p; + buf = va_arg(args_ptr, char *); + while ((field_width--) && (*p)) + { + if (!(flag & kSCANF_Suppress)) + { + *buf++ = *p++; + } + else + { + p++; + } + n_decode++; + } + + if ((!(flag & kSCANF_Suppress)) && (s != p)) + { + nassigned++; + } + break; + case kSCANF_DestString: + n_decode += ScanIgnoreWhiteSpace(&p); + s = p; + buf = va_arg(args_ptr, char *); + while ((field_width--) && (*p != '\0') && (*p != ' ') && (*p != '\t') && (*p != '\n') && + (*p != '\r') && (*p != '\v') && (*p != '\f')) + { + if (flag & kSCANF_Suppress) + { + p++; + } + else + { + *buf++ = *p++; + } + n_decode++; + } + + if ((!(flag & kSCANF_Suppress)) && (s != p)) + { + /* Add NULL to end of string. */ + *buf = '\0'; + nassigned++; + } + break; + case kSCANF_DestInt: + n_decode += ScanIgnoreWhiteSpace(&p); + s = p; + val = 0; + if ((base == 0) || (base == 16)) + { + if ((s[0] == '0') && ((s[1] == 'x') || (s[1] == 'X'))) + { + base = 16; + if (field_width >= 1) + { + p += 2; + n_decode += 2; + field_width -= 2; + } + } + } + + if (base == 0) + { + if (s[0] == '0') + { + base = 8; + } + else + { + base = 10; + } + } + + neg = 1; + switch (*p) + { + case '-': + neg = -1; + n_decode++; + p++; + field_width--; + break; + case '+': + neg = 1; + n_decode++; + p++; + field_width--; + break; + default: + break; + } + + while ((*p) && (field_width--)) + { + if ((*p <= '9') && (*p >= '0')) + { + temp = *p - '0'; + } + else if ((*p <= 'f') && (*p >= 'a')) + { + temp = *p - 'a' + 10; + } + else if ((*p <= 'F') && (*p >= 'A')) + { + temp = *p - 'A' + 10; + } + else + { + temp = base; + } + + if (temp >= base) + { + break; + } + else + { + val = base * val + temp; + } + p++; + n_decode++; + } + val *= neg; + if (!(flag & kSCANF_Suppress)) + { +#if SCANF_ADVANCED_ENABLE + switch (flag & kSCANF_LengthMask) + { + case kSCANF_LengthChar: + if (flag & kSCANF_TypeSinged) + { + *va_arg(args_ptr, signed char *) = (signed char)val; + } + else + { + *va_arg(args_ptr, unsigned char *) = (unsigned char)val; + } + break; + case kSCANF_LengthShortInt: + if (flag & kSCANF_TypeSinged) + { + *va_arg(args_ptr, signed short *) = (signed short)val; + } + else + { + *va_arg(args_ptr, unsigned short *) = (unsigned short)val; + } + break; + case kSCANF_LengthLongInt: + if (flag & kSCANF_TypeSinged) + { + *va_arg(args_ptr, signed long int *) = (signed long int)val; + } + else + { + *va_arg(args_ptr, unsigned long int *) = (unsigned long int)val; + } + break; + case kSCANF_LengthLongLongInt: + if (flag & kSCANF_TypeSinged) + { + *va_arg(args_ptr, signed long long int *) = (signed long long int)val; + } + else + { + *va_arg(args_ptr, unsigned long long int *) = (unsigned long long int)val; + } + break; + default: + /* The default type is the type int. */ + if (flag & kSCANF_TypeSinged) + { + *va_arg(args_ptr, signed int *) = (signed int)val; + } + else + { + *va_arg(args_ptr, unsigned int *) = (unsigned int)val; + } + break; + } +#else + /* The default type is the type int. */ + if (flag & kSCANF_TypeSinged) + { + *va_arg(args_ptr, signed int *) = (signed int)val; + } + else + { + *va_arg(args_ptr, unsigned int *) = (unsigned int)val; + } +#endif /* SCANF_ADVANCED_ENABLE */ + nassigned++; + } + break; +#if SCANF_FLOAT_ENABLE + case kSCANF_DestFloat: + n_decode += ScanIgnoreWhiteSpace(&p); + fnum = strtod(p, (char **)&s); + + if ((fnum >= HUGE_VAL) || (fnum <= -HUGE_VAL)) + { + break; + } + + n_decode += (int)(s) - (int)(p); + p = s; + if (!(flag & kSCANF_Suppress)) + { + if (flag & kSCANF_LengthLongLongDouble) + { + *va_arg(args_ptr, double *) = fnum; + } + else + { + *va_arg(args_ptr, float *) = (float)fnum; + } + nassigned++; + } + break; +#endif /* SCANF_FLOAT_ENABLE */ + default: + return nassigned; + } + } + } + return nassigned; +} diff --git a/utilities/fsl_str.h b/utilities/fsl_str.h new file mode 100644 index 0000000..47d835e --- /dev/null +++ b/utilities/fsl_str.h @@ -0,0 +1,92 @@ +/* + * The Clear BSD License + * Copyright 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: + * + * o Redistributions of source code must retain the above copyright notice, this list + * of conditions and the following disclaimer. + * + * o 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. + * + * o Neither the name of Freescale Semiconductor, Inc. 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 EPRESS 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, EEMPLARY, 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_STR_H +#define _FSL_STR_H + +#include "fsl_common.h" + +/*! + * @addtogroup debugconsole + * @{ + */ + +/******************************************************************************* + * Prototypes + ******************************************************************************/ +#if defined(__cplusplus) +extern "C" { +#endif /* __cplusplus */ + +/*! + * @brief A function pointer which is used when format printf log. + */ +typedef void (*printfCb)(char *buf, int32_t *indicator, char val, int len); + +/*! + * @brief This function outputs its parameters according to a formatted string. + * + * @note I/O is performed by calling given function pointer using following + * (*func_ptr)(c); + * + * @param[in] fmt_ptr Format string for printf. + * @param[in] args_ptr Arguments to printf. + * @param[in] buf pointer to the buffer + * @param cb print callbck function pointer + * + * @return Number of characters to be print + */ +int StrFormatPrintf(const char *fmt, va_list ap, char *buf, printfCb cb); + +/*! + * @brief Converts an input line of ASCII characters based upon a provided + * string format. + * + * @param[in] line_ptr The input line of ASCII data. + * @param[in] format Format first points to the format string. + * @param[in] args_ptr The list of parameters. + * + * @return Number of input items converted and assigned. + * @retval IO_EOF When line_ptr is empty string "". + */ +int StrFormatScanf(const char *line_ptr, char *format, va_list args_ptr); + +#if defined(__cplusplus) +} +#endif /* __cplusplus */ + +/*! @} */ + +#endif /* _FSL_STR_H */ -- cgit v1.2.3-8-gadcc