[RT1602xB] support nxp rt1602xb board, support for uart

This commit is contained in:
张超杰 2025-05-26 17:09:18 +08:00
parent 871671b8bf
commit 535b5fa116
123 changed files with 90377 additions and 1 deletions

View File

@ -6,7 +6,7 @@ MAKEFLAGS += --no-print-directory
riscv_support := kd233 maix-go hifive1-rev-B gapuino gd32vf103-rvstar rv32m1-vega aiit-riscv64-board xidatong-riscv64 edu-riscv64 ch32v307vct6 ch32v208rbt6 ch569w
arm_support += stm32f407-st-discovery stm32f407zgt6 stm32f103-nano nuvoton-m2354 ok1052-c imxrt1176-sbc aiit-arm32-board xidatong-arm32 xiwangtong-arm32 edu-arm32 xishutong-arm32 rzv2l-m33 rzg2ul-m33 imx8mp
arm_support += stm32f407-st-discovery stm32f407zgt6 stm32f103-nano nuvoton-m2354 ok1052-c rt1062xb imxrt1176-sbc aiit-arm32-board xidatong-arm32 xiwangtong-arm32 edu-arm32 xishutong-arm32 rzv2l-m33 rzg2ul-m33 imx8mp
emulator_support += hifive1-emulator k210-emulator cortex-m0-emulator cortex-m3-emulator cortex-m4-emulator cortex-m7-emulator
support := $(riscv_support) $(arm_support) $(emulator_support)

View File

@ -0,0 +1,43 @@
mainmenu "XiZi_IIoT Project Configuration"
config BSP_DIR
string
option env="BSP_ROOT"
default "."
config KERNEL_DIR
string
option env="KERNEL_ROOT"
default "../.."
config BOARD_CORTEX_M7_EVB
bool
select ARCH_ARM
default y
source "$KERNEL_DIR/arch/Kconfig"
menu "rt1062xb feature"
source "$BSP_DIR/third_party_driver/Kconfig"
menu "config default board resources"
menu "config board app name"
config BOARD_APP_NAME
string "config board app name"
default "/XiUOS_rt1062xb_app.bin"
endmenu
endmenu
config __STACKSIZE__
int "stack size for interrupt"
default 4096
endmenu
menu "Hardware feature"
source "$KERNEL_DIR/resources/Kconfig"
endmenu
source "$KERNEL_DIR/Kconfig"

View File

@ -0,0 +1,5 @@
SRC_DIR := third_party_driver xip
SRC_FILES := board.c
include $(KERNEL_ROOT)/compiler.mk

View File

@ -0,0 +1,216 @@
/**
* @file board.c
* @brief relative configure for rt1602xb board
* @version 1.0
* @author AIIT XUOS Lab
* @date 2025.05.23
*/
/*************************************************
File name: board.c
Description: support rt1602xb board init function
Others: take SDK_25_03_00_MIMXR for references
History:
1. Date: 2025-05-23
Author: AIIT XUOS Lab
Modification:
1. support rt1602xb board MPU, Clock, Memory init
2. support rt1602xb board uart
*************************************************/
#include "board.h"
/* MPU configuration. */
void BOARD_ConfigMPU(void)
{
#if defined(__CC_ARM) || defined(__ARMCC_VERSION)
extern uint32_t Image$$RW_m_ncache$$Base[];
/* RW_m_ncache_unused is a auxiliary region which is used to get the whole size of noncache section */
extern uint32_t Image$$RW_m_ncache_unused$$Base[];
extern uint32_t Image$$RW_m_ncache_unused$$ZI$$Limit[];
uint32_t nonCacheStart = (uint32_t)Image$$RW_m_ncache$$Base;
uint32_t size = ((uint32_t)Image$$RW_m_ncache_unused$$Base == nonCacheStart) ?
0 :
((uint32_t)Image$$RW_m_ncache_unused$$ZI$$Limit - nonCacheStart);
#elif defined(__MCUXPRESSO)
extern uint32_t __base_NCACHE_REGION;
extern uint32_t __top_NCACHE_REGION;
uint32_t nonCacheStart = (uint32_t)(&__base_NCACHE_REGION);
uint32_t size = (uint32_t)(&__top_NCACHE_REGION) - nonCacheStart;
#elif defined(__ICCARM__) || defined(__GNUC__)
extern uint32_t __NCACHE_REGION_START[];
extern uint32_t __NCACHE_REGION_SIZE[];
uint32_t nonCacheStart = (uint32_t)__NCACHE_REGION_START;
uint32_t size = (uint32_t)__NCACHE_REGION_SIZE;
#endif
volatile uint32_t i = 0;
/* Disable I cache and D cache */
if (SCB_CCR_IC_Msk == (SCB_CCR_IC_Msk & SCB->CCR))
{
SCB_DisableICache();
}
if (SCB_CCR_DC_Msk == (SCB_CCR_DC_Msk & SCB->CCR))
{
SCB_DisableDCache();
}
/* Disable MPU */
ARM_MPU_Disable();
/* MPU configure:
* Use ARM_MPU_RASR(DisableExec, AccessPermission, TypeExtField, IsShareable, IsCacheable, IsBufferable,
* SubRegionDisable, Size)
* API in mpu_armv7.h.
* param DisableExec Instruction access (XN) disable bit,0=instruction fetches enabled, 1=instruction fetches
* disabled.
* param AccessPermission Data access permissions, allows you to configure read/write access for User and
* Privileged mode.
* Use MACROS defined in mpu_armv7.h:
* ARM_MPU_AP_NONE/ARM_MPU_AP_PRIV/ARM_MPU_AP_URO/ARM_MPU_AP_FULL/ARM_MPU_AP_PRO/ARM_MPU_AP_RO
* Combine TypeExtField/IsShareable/IsCacheable/IsBufferable to configure MPU memory access attributes.
* TypeExtField IsShareable IsCacheable IsBufferable Memory Attribute Shareability Cache
* 0 x 0 0 Strongly Ordered shareable
* 0 x 0 1 Device shareable
* 0 0 1 0 Normal not shareable Outer and inner write
* through no write allocate
* 0 0 1 1 Normal not shareable Outer and inner write
* back no write allocate
* 0 1 1 0 Normal shareable Outer and inner write
* through no write allocate
* 0 1 1 1 Normal shareable Outer and inner write
* back no write allocate
* 1 0 0 0 Normal not shareable outer and inner
* noncache
* 1 1 0 0 Normal shareable outer and inner
* noncache
* 1 0 1 1 Normal not shareable outer and inner write
* back write/read acllocate
* 1 1 1 1 Normal shareable outer and inner write
* back write/read acllocate
* 2 x 0 0 Device not shareable
* Above are normal use settings, if your want to see more details or want to config different inner/outer cache
* policy.
* please refer to Table 4-55 /4-56 in arm cortex-M7 generic user guide <dui0646b_cortex_m7_dgug.pdf>
* param SubRegionDisable Sub-region disable field. 0=sub-region is enabled, 1=sub-region is disabled.
* param Size Region size of the region to be configured. use ARM_MPU_REGION_SIZE_xxx MACRO in
* mpu_armv7.h.
*/
/*
* Add default region to deny access to whole address space to workaround speculative prefetch.
* Refer to Arm errata 1013783-B for more details.
*
*/
/* Region 0 setting: Instruction access disabled, No data access permission. */
MPU->RBAR = ARM_MPU_RBAR(0, 0x00000000U);
MPU->RASR = ARM_MPU_RASR(1, ARM_MPU_AP_NONE, 0, 0, 0, 0, 0, ARM_MPU_REGION_SIZE_4GB);
/* Region 1 setting: Memory with Device type, not shareable, non-cacheable. */
MPU->RBAR = ARM_MPU_RBAR(1, 0x80000000U);
MPU->RASR = ARM_MPU_RASR(0, ARM_MPU_AP_FULL, 2, 0, 0, 0, 0, ARM_MPU_REGION_SIZE_512MB);
/* Region 2 setting: Memory with Device type, not shareable, non-cacheable. */
MPU->RBAR = ARM_MPU_RBAR(2, 0x60000000U);
MPU->RASR = ARM_MPU_RASR(0, ARM_MPU_AP_FULL, 2, 0, 0, 0, 0, ARM_MPU_REGION_SIZE_512MB);
#if defined(XIP_EXTERNAL_FLASH) && (XIP_EXTERNAL_FLASH == 1)
/* Region 3 setting: Memory with Normal type, not shareable, outer/inner write back. */
MPU->RBAR = ARM_MPU_RBAR(3, 0x60000000U);
MPU->RASR = ARM_MPU_RASR(0, ARM_MPU_AP_RO, 0, 0, 1, 1, 0, ARM_MPU_REGION_SIZE_8MB);
#endif
/* Region 4 setting: Memory with Device type, not shareable, non-cacheable. */
MPU->RBAR = ARM_MPU_RBAR(4, 0x00000000U);
MPU->RASR = ARM_MPU_RASR(0, ARM_MPU_AP_FULL, 2, 0, 0, 0, 0, ARM_MPU_REGION_SIZE_1GB);
/* Region 5 setting: Memory with Normal type, not shareable, outer/inner write back */
MPU->RBAR = ARM_MPU_RBAR(5, 0x00000000U);
MPU->RASR = ARM_MPU_RASR(0, ARM_MPU_AP_FULL, 0, 0, 1, 1, 0, ARM_MPU_REGION_SIZE_128KB);
/* Region 6 setting: Memory with Normal type, not shareable, outer/inner write back */
MPU->RBAR = ARM_MPU_RBAR(6, 0x20000000U);
MPU->RASR = ARM_MPU_RASR(0, ARM_MPU_AP_FULL, 0, 0, 1, 1, 0, ARM_MPU_REGION_SIZE_128KB);
/* Region 7 setting: Memory with Normal type, not shareable, outer/inner write back */
MPU->RBAR = ARM_MPU_RBAR(7, 0x20200000U);
MPU->RASR = ARM_MPU_RASR(0, ARM_MPU_AP_FULL, 0, 0, 1, 1, 0, ARM_MPU_REGION_SIZE_512KB);
/* Region 8 setting: Memory with Normal type, not shareable, outer/inner write back */
MPU->RBAR = ARM_MPU_RBAR(8, 0x20280000U);
MPU->RASR = ARM_MPU_RASR(0, ARM_MPU_AP_FULL, 0, 0, 1, 1, 0, ARM_MPU_REGION_SIZE_256KB);
/* When cache is enabled, Cortex-M7 core may perform speculative accesses
* to those memory with Normal type, even software doesn't require explicitly.
* So, must not set SDRAM region as Normal type for those cases whose SDRAM
* is not initialized, otherwise there may be unpredictable bus hang and finally
* system crach.
* More details about speculative accesses can be seen on Arm errata 1013783-B.
* Here, SKIP_SYSCLK_INIT is used to determine if SDRAM is initialized(accessable).
*/
#ifdef SKIP_SYSCLK_INIT
/* Region 9 setting: Memory with Normal type, not shareable, outer/inner write back */
MPU->RBAR = ARM_MPU_RBAR(9, 0x80000000U);
MPU->RASR = ARM_MPU_RASR(0, ARM_MPU_AP_FULL, 0, 0, 1, 1, 0, ARM_MPU_REGION_SIZE_32MB);
#endif
while ((size >> i) > 0x1U)
{
i++;
}
if (i != 0)
{
/* The MPU region size should be 2^N, 5<=N<=32, region base should be multiples of size. */
assert(!(nonCacheStart % size));
assert(size == (uint32_t)(1 << i));
assert(i >= 5);
/* Region 10 setting: Memory with Normal type, not shareable, non-cacheable */
MPU->RBAR = ARM_MPU_RBAR(10, nonCacheStart);
MPU->RASR = ARM_MPU_RASR(0, ARM_MPU_AP_FULL, 1, 0, 0, 0, 0, i - 1);
}
/* Region 10 setting: Memory with Device type, not shareable, non-cacheable */
MPU->RBAR = ARM_MPU_RBAR(11, 0x40000000);
MPU->RASR = ARM_MPU_RASR(0, ARM_MPU_AP_FULL, 2, 0, 0, 0, 0, ARM_MPU_REGION_SIZE_4MB);
/* Region 12 setting: Memory with Device type, not shareable, non-cacheable */
MPU->RBAR = ARM_MPU_RBAR(12, 0x42000000);
MPU->RASR = ARM_MPU_RASR(0, ARM_MPU_AP_FULL, 2, 0, 0, 0, 0, ARM_MPU_REGION_SIZE_1MB);
/* Enable MPU */
ARM_MPU_Enable(MPU_CTRL_PRIVDEFENA_Msk | MPU_CTRL_HFNMIENA_Msk);
/* Enable I cache and D cache */
SCB_EnableDCache();
SCB_EnableICache();
}
/* This is the timer interrupt service routine. */
void SysTick_Handler(int irqn, void *arg)
{
TickAndTaskTimesliceUpdate();
}
/**
* This function will initial rt1050 board.
*/
void InitBoardHardware()
{
BOARD_ConfigMPU();
BOARD_InitBootPins();
BOARD_InitBootClocks();
/* Just enable the trace clock, leave coresight initialization to IDE debugger */
SystemCoreClockUpdate();
CLOCK_EnableClock(kCLOCK_Trace);
#ifdef BSP_USING_LPUART
HwUsartInit();
#endif
InitBoardMemory((void *)HEAP_BEGIN, (void *)HEAP_END);
InstallConsole(KERNEL_CONSOLE_BUS_NAME, KERNEL_CONSOLE_DRV_NAME, KERNEL_CONSOLE_DEVICE_NAME);
}

View File

@ -0,0 +1,16 @@
export CROSS_COMPILE ?=/usr/bin/arm-none-eabi-
export CFLAGS := -mcpu=cortex-m7 -mthumb -ffunction-sections -fdata-sections -Dgcc -O0 -gdwarf-2 -g -fgnu89-inline -Wa,-mimplicit-it=thumb
export AFLAGS := -c -mcpu=cortex-m7 -mthumb -ffunction-sections -fdata-sections -x assembler-with-cpp -Wa,-mimplicit-it=thumb -gdwarf-2
export LFLAGS := -mcpu=cortex-m7 -mthumb -ffunction-sections -fdata-sections -Wl,--gc-sections,-Map=XiZi-rt1062xb-c.map,-cref,-u,Reset_Handler -T $(BSP_ROOT)/link.lds
export CXXFLAGS := -mcpu=cortex-m7 -mthumb -ffunction-sections -fdata-sections -Dgcc -O0 -gdwarf-2 -g
export APPLFLAGS := -mcpu=cortex-m7 -mthumb -ffunction-sections -fdata-sections -Wl,--gc-sections,-Map=XiZi-app.map,-cref,-u, -T $(BSP_ROOT)/link_userspace.lds
export DEFINES := -DHAVE_CCONFIG_H -DCPU_MIMXRT1062CVL5A -DSKIP_SYSCLK_INIT -DEVK_MCIMXRM -DFSL_SDK_ENABLE_DRIVER_CACHE_CONTROL=1 -DXIP_EXTERNAL_FLASH=1 -D__STARTUP_INITIALIZE_NONCACHEDATA -D__STARTUP_CLEAR_BSS
export ARCH = arm
export MCU = cortex-m7

View File

@ -0,0 +1,208 @@
/*************************************************
File name: board.h
Description: define rt1062xb board init function and struct
Others:
History:
1. Date: 2025-05-23
Author: AIIT XUOS Lab
Modification:
1. define rt1062xb InitBoardHardware
2. define rt1062xb heap struct
*************************************************/
#ifndef __BOARD_H__
#define __BOARD_H__
#include "fsl_common.h"
#include "fsl_iomuxc.h"
#include "fsl_gpio.h"
#include "fsl_clock.h"
#include "pin_mux.h"
#include "clock_config.h"
#include <arch_interrupt.h>
#include "xs_ktick.h"
#include "connect_usart.h"
extern int heap_start;
extern int heap_end;
#define HEAP_BEGIN (&heap_start)
#define HEAP_END (&heap_end)
#define HEAP_SIZE ((uint32_t)HEAP_END - (uint32_t)HEAP_BEGIN)
void InitBoardHardware(void);
/*******************************************************************************
* Definitions
******************************************************************************/
/*! @brief The board name */
#define BOARD_NAME "MIMXRT1060-EVKB"
/* The UART to use for debug messages. */
/*! @brief The USER_LED used for board */
#define LOGIC_LED_ON (0U)
#define LOGIC_LED_OFF (1U)
#ifndef BOARD_USER_LED_GPIO
#define BOARD_USER_LED_GPIO GPIO1
#endif
#ifndef BOARD_USER_LED_GPIO_PIN
#define BOARD_USER_LED_GPIO_PIN 8U
#endif
#define USER_LED_INIT(output) \
GPIO_PinWrite(BOARD_USER_LED_GPIO, BOARD_USER_LED_GPIO_PIN, output); \
BOARD_USER_LED_GPIO->GDIR |= (1U << BOARD_USER_LED_GPIO_PIN) /*!< Enable target USER_LED */
#define USER_LED_ON() GPIO_PortSet(BOARD_USER_LED_GPIO, 1U << BOARD_USER_LED_GPIO_PIN) /*!<Turn on target USER_LED*/
#define USER_LED_OFF() \
GPIO_PortClear(BOARD_USER_LED_GPIO, 1U << BOARD_USER_LED_GPIO_PIN) /*!< Turn off target USER_LED */
#define USER_LED_TOGGLE() \
GPIO_PinWrite(BOARD_USER_LED_GPIO, BOARD_USER_LED_GPIO_PIN, \
0x1 ^ GPIO_PinRead(BOARD_USER_LED_GPIO, BOARD_USER_LED_GPIO_PIN)) /*!< Toggle target USER_LED */
/*! @brief Define the port interrupt number for the board switches */
#ifndef BOARD_USER_BUTTON_GPIO
#define BOARD_USER_BUTTON_GPIO GPIO5
#endif
#ifndef BOARD_USER_BUTTON_GPIO_PIN
#define BOARD_USER_BUTTON_GPIO_PIN (0U)
#endif
#define BOARD_USER_BUTTON_IRQ GPIO5_Combined_0_15_IRQn
#define BOARD_USER_BUTTON_IRQ_HANDLER GPIO5_Combined_0_15_IRQHandler
#define BOARD_USER_BUTTON_NAME "SW5"
/*! @brief The board flash size */
#define BOARD_FLASH_SIZE (0x800000U)
/*! @brief The ENET PHY address. */
#define BOARD_ENET0_PHY_ADDRESS (0x02U) /* Phy address of enet port 0. */
/* USB PHY condfiguration */
#define BOARD_USB_PHY_D_CAL (0x0CU)
#define BOARD_USB_PHY_TXCAL45DP (0x06U)
#define BOARD_USB_PHY_TXCAL45DM (0x06U)
#define BOARD_ARDUINO_INT_IRQ (GPIO1_INT3_IRQn)
#define BOARD_ARDUINO_I2C_IRQ (LPI2C1_IRQn)
#define BOARD_ARDUINO_I2C_INDEX (1)
/* @Brief Board accelerator sensor configuration */
#define BOARD_ACCEL_I2C_BASEADDR LPI2C1
/* Select USB1 PLL (480 MHz) as LPI2C's clock source */
#define BOARD_ACCEL_I2C_CLOCK_SOURCE_SELECT (0U)
/* Clock divider for LPI2C clock source */
#define BOARD_ACCEL_I2C_CLOCK_SOURCE_DIVIDER (5U)
#define BOARD_ACCEL_I2C_CLOCK_FREQ (CLOCK_GetFreq(kCLOCK_Usb1PllClk) / 8 / (BOARD_ACCEL_I2C_CLOCK_SOURCE_DIVIDER + 1U))
#define BOARD_CODEC_I2C_BASEADDR LPI2C1
#define BOARD_CODEC_I2C_INSTANCE 1U
#define BOARD_CODEC_I2C_CLOCK_SOURCE_SELECT (0U)
#define BOARD_CODEC_I2C_CLOCK_SOURCE_DIVIDER (5U)
#define BOARD_CODEC_I2C_CLOCK_FREQ (10000000U)
/* @Brief Board CAMERA configuration */
#define BOARD_CAMERA_I2C_BASEADDR LPI2C1
#define BOARD_CAMERA_I2C_CLOCK_SOURCE_DIVIDER (5U)
#define BOARD_CAMERA_I2C_CLOCK_SOURCE_SELECT (0U) /* Select USB1 PLL (480 MHz) as LPI2C's clock source */
#define BOARD_CAMERA_I2C_CLOCK_FREQ \
(CLOCK_GetFreq(kCLOCK_Usb1PllClk) / 8 / (BOARD_CAMERA_I2C_CLOCK_SOURCE_DIVIDER + 1U))
#define BOARD_CAMERA_I2C_SCL_GPIO GPIO1
#define BOARD_CAMERA_I2C_SCL_PIN 16
#define BOARD_CAMERA_I2C_SDA_GPIO GPIO1
#define BOARD_CAMERA_I2C_SDA_PIN 17
#define BOARD_CAMERA_PWDN_GPIO GPIO1
#define BOARD_CAMERA_PWDN_PIN 18
/* @Brief Board touch panel configuration */
#define BOARD_TOUCH_I2C_BASEADDR LPI2C1
#define BOARD_TOUCH_RST_GPIO GPIO1
#define BOARD_TOUCH_RST_PIN 2
#define BOARD_TOUCH_INT_GPIO GPIO1
#define BOARD_TOUCH_INT_PIN 11
/* @Brief Board Bluetooth HCI UART configuration */
#define BOARD_BT_UART_BASEADDR LPUART3
#define BOARD_BT_UART_INSTANCE 3
#define BOARD_BT_UART_BAUDRATE 3000000
#define BOARD_BT_UART_CLK_FREQ BOARD_DebugConsoleSrcFreq()
#define BOARD_BT_UART_IRQ LPUART3_IRQn
#define BOARD_BT_UART_IRQ_HANDLER LPUART3_IRQHandler
/*! @brief board has sdcard */
#define BOARD_HAS_SDCARD (1U)
#if defined(__cplusplus)
extern "C" {
#endif /* __cplusplus */
/*******************************************************************************
* API
******************************************************************************/
uint32_t BOARD_DebugConsoleSrcFreq(void);
void BOARD_InitDebugConsole(void);
void BOARD_ConfigMPU(void);
#if defined(SDK_I2C_BASED_COMPONENT_USED) && SDK_I2C_BASED_COMPONENT_USED
void BOARD_LPI2C_Init(LPI2C_Type *base, uint32_t clkSrc_Hz);
status_t BOARD_LPI2C_Send(LPI2C_Type *base,
uint8_t deviceAddress,
uint32_t subAddress,
uint8_t subaddressSize,
uint8_t *txBuff,
uint8_t txBuffSize);
status_t BOARD_LPI2C_Receive(LPI2C_Type *base,
uint8_t deviceAddress,
uint32_t subAddress,
uint8_t subaddressSize,
uint8_t *rxBuff,
uint8_t rxBuffSize);
status_t BOARD_LPI2C_SendSCCB(LPI2C_Type *base,
uint8_t deviceAddress,
uint32_t subAddress,
uint8_t subaddressSize,
uint8_t *txBuff,
uint8_t txBuffSize);
status_t BOARD_LPI2C_ReceiveSCCB(LPI2C_Type *base,
uint8_t deviceAddress,
uint32_t subAddress,
uint8_t subaddressSize,
uint8_t *rxBuff,
uint8_t rxBuffSize);
void BOARD_Accel_I2C_Init(void);
status_t BOARD_Accel_I2C_Send(uint8_t deviceAddress, uint32_t subAddress, uint8_t subaddressSize, uint32_t txBuff);
status_t BOARD_Accel_I2C_Receive(
uint8_t deviceAddress, uint32_t subAddress, uint8_t subaddressSize, uint8_t *rxBuff, uint8_t rxBuffSize);
void BOARD_Codec_I2C_Init(void);
status_t BOARD_Codec_I2C_Send(
uint8_t deviceAddress, uint32_t subAddress, uint8_t subAddressSize, const uint8_t *txBuff, uint8_t txBuffSize);
status_t BOARD_Codec_I2C_Receive(
uint8_t deviceAddress, uint32_t subAddress, uint8_t subAddressSize, uint8_t *rxBuff, uint8_t rxBuffSize);
void BOARD_Camera_I2C_Init(void);
status_t BOARD_Camera_I2C_Send(
uint8_t deviceAddress, uint32_t subAddress, uint8_t subAddressSize, const uint8_t *txBuff, uint8_t txBuffSize);
status_t BOARD_Camera_I2C_Receive(
uint8_t deviceAddress, uint32_t subAddress, uint8_t subAddressSize, uint8_t *rxBuff, uint8_t rxBuffSize);
status_t BOARD_Camera_I2C_SendSCCB(
uint8_t deviceAddress, uint32_t subAddress, uint8_t subAddressSize, const uint8_t *txBuff, uint8_t txBuffSize);
status_t BOARD_Camera_I2C_ReceiveSCCB(
uint8_t deviceAddress, uint32_t subAddress, uint8_t subAddressSize, uint8_t *rxBuff, uint8_t rxBuffSize);
status_t BOARD_Touch_I2C_Send(
uint8_t deviceAddress, uint32_t subAddress, uint8_t subAddressSize, const uint8_t *txBuff, uint8_t txBuffSize);
status_t BOARD_Touch_I2C_Receive(
uint8_t deviceAddress, uint32_t subAddress, uint8_t subAddressSize, uint8_t *rxBuff, uint8_t rxBuffSize);
#endif /* SDK_I2C_BASED_COMPONENT_USED */
void BOARD_SD_Pin_Config(uint32_t speed, uint32_t strength);
void BOARD_MMC_Pin_Config(uint32_t speed, uint32_t strength);
#if defined(__cplusplus)
}
#endif /* __cplusplus */
#endif /* _BOARD_H_ */

View File

@ -0,0 +1,211 @@
#ifndef _CLOCK_CONFIG_H_
#define _CLOCK_CONFIG_H_
#include "fsl_common.h"
/*******************************************************************************
* Definitions
******************************************************************************/
#define BOARD_XTAL0_CLK_HZ 24000000U /*!< Board xtal0 frequency in Hz */
#define BOARD_XTAL32K_CLK_HZ 32768U /*!< Board xtal32k frequency in Hz */
/*******************************************************************************
************************ 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 600000000U /*!< Core clock frequency: 600000000Hz */
/* Clock outputs (values are in Hz): */
#define BOARD_BOOTCLOCKRUN_AHB_CLK_ROOT 600000000UL /* Clock consumers of AHB_CLK_ROOT output : AIPSTZ1, AIPSTZ2, AIPSTZ3, AIPSTZ4, ARM, FLEXIO3, FLEXSPI, FLEXSPI2, GPIO6, GPIO7, GPIO8, GPIO9 */
#define BOARD_BOOTCLOCKRUN_CAN_CLK_ROOT 40000000UL /* Clock consumers of CAN_CLK_ROOT output : CAN1, CAN2, CAN3 */
#define BOARD_BOOTCLOCKRUN_CKIL_SYNC_CLK_ROOT 32768UL /* Clock consumers of CKIL_SYNC_CLK_ROOT output : CSU, EWM, GPT1, GPT2, KPP, PIT, RTWDOG, SNVS, SPDIF, TEMPMON, TSC, USB1, USB2, WDOG1, WDOG2 */
#define BOARD_BOOTCLOCKRUN_CLKO1_CLK 0UL /* Clock consumers of CLKO1_CLK output : N/A */
#define BOARD_BOOTCLOCKRUN_CLKO2_CLK 0UL /* Clock consumers of CLKO2_CLK output : N/A */
#define BOARD_BOOTCLOCKRUN_CLK_1M 1000000UL /* Clock consumers of CLK_1M output : EWM, RTWDOG */
#define BOARD_BOOTCLOCKRUN_CLK_24M 24000000UL /* Clock consumers of CLK_24M output : GPT1, GPT2 */
#define BOARD_BOOTCLOCKRUN_CSI_CLK_ROOT 12000000UL /* Clock consumers of CSI_CLK_ROOT output : CSI */
#define BOARD_BOOTCLOCKRUN_ENET2_125M_CLK 1200000UL /* Clock consumers of ENET2_125M_CLK output : N/A */
#define BOARD_BOOTCLOCKRUN_ENET2_REF_CLK 0UL /* Clock consumers of ENET2_REF_CLK output : ENET2 */
#define BOARD_BOOTCLOCKRUN_ENET2_TX_CLK 0UL /* Clock consumers of ENET2_TX_CLK output : ENET2 */
#define BOARD_BOOTCLOCKRUN_ENET_125M_CLK 2400000UL /* Clock consumers of ENET_125M_CLK output : N/A */
#define BOARD_BOOTCLOCKRUN_ENET_25M_REF_CLK 1200000UL /* Clock consumers of ENET_25M_REF_CLK output : ENET, ENET2 */
#define BOARD_BOOTCLOCKRUN_ENET_REF_CLK 0UL /* Clock consumers of ENET_REF_CLK output : ENET */
#define BOARD_BOOTCLOCKRUN_ENET_TX_CLK 0UL /* Clock consumers of ENET_TX_CLK output : ENET */
#define BOARD_BOOTCLOCKRUN_FLEXIO1_CLK_ROOT 30000000UL /* Clock consumers of FLEXIO1_CLK_ROOT output : FLEXIO1 */
#define BOARD_BOOTCLOCKRUN_FLEXIO2_CLK_ROOT 30000000UL /* Clock consumers of FLEXIO2_CLK_ROOT output : FLEXIO2, FLEXIO3 */
#define BOARD_BOOTCLOCKRUN_FLEXSPI2_CLK_ROOT 130909090UL /* Clock consumers of FLEXSPI2_CLK_ROOT output : FLEXSPI2 */
#define BOARD_BOOTCLOCKRUN_FLEXSPI_CLK_ROOT 130909090UL /* Clock consumers of FLEXSPI_CLK_ROOT output : FLEXSPI */
#define BOARD_BOOTCLOCKRUN_GPT1_IPG_CLK_HIGHFREQ 75000000UL /* Clock consumers of GPT1_ipg_clk_highfreq output : GPT1 */
#define BOARD_BOOTCLOCKRUN_GPT2_IPG_CLK_HIGHFREQ 75000000UL /* Clock consumers of GPT2_ipg_clk_highfreq output : GPT2 */
#define BOARD_BOOTCLOCKRUN_IPG_CLK_ROOT 150000000UL /* Clock consumers of IPG_CLK_ROOT output : ADC1, ADC2, ADC_ETC, AOI1, AOI2, ARM, BEE, CAN1, CAN2, CAN3, CCM, CMP1, CMP2, CMP3, CMP4, CSI, CSU, DCDC, DCP, DMA0, DMAMUX, ENC1, ENC2, ENC3, ENC4, ENET, ENET2, EWM, FLEXIO1, FLEXIO2, FLEXIO3, FLEXRAM, FLEXSPI, FLEXSPI2, GPC, GPIO1, GPIO10, GPIO2, GPIO3, GPIO4, GPIO5, IOMUXC, KPP, LCDIF, LPI2C1, LPI2C2, LPI2C3, LPI2C4, LPSPI1, LPSPI2, LPSPI3, LPSPI4, LPUART1, LPUART2, LPUART3, LPUART4, LPUART5, LPUART6, LPUART7, LPUART8, NVIC, OCOTP, PMU, PWM1, PWM2, PWM3, PWM4, PXP, ROMC, RTWDOG, SAI1, SAI2, SAI3, SNVS, SPDIF, SRC, TEMPMON, TMR1, TMR2, TMR3, TMR4, TRNG, TSC, USB1, USB2, USDHC1, USDHC2, WDOG1, WDOG2, XBARA1, XBARB2, XBARB3 */
#define BOARD_BOOTCLOCKRUN_LCDIF_CLK_ROOT 67500000UL /* Clock consumers of LCDIF_CLK_ROOT output : LCDIF */
#define BOARD_BOOTCLOCKRUN_LPI2C_CLK_ROOT 60000000UL /* Clock consumers of LPI2C_CLK_ROOT output : LPI2C1, LPI2C2, LPI2C3, LPI2C4 */
#define BOARD_BOOTCLOCKRUN_LPSPI_CLK_ROOT 105600000UL /* Clock consumers of LPSPI_CLK_ROOT output : LPSPI1, LPSPI2, LPSPI3, LPSPI4 */
#define BOARD_BOOTCLOCKRUN_LVDS1_CLK 1200000000UL /* Clock consumers of LVDS1_CLK output : N/A */
#define BOARD_BOOTCLOCKRUN_MQS_MCLK 63529411UL /* Clock consumers of MQS_MCLK output : N/A */
#define BOARD_BOOTCLOCKRUN_PERCLK_CLK_ROOT 75000000UL /* Clock consumers of PERCLK_CLK_ROOT output : GPT1, GPT2, PIT */
#define BOARD_BOOTCLOCKRUN_PLL7_MAIN_CLK 24000000UL /* Clock consumers of PLL7_MAIN_CLK output : N/A */
#define BOARD_BOOTCLOCKRUN_SAI1_CLK_ROOT 63529411UL /* Clock consumers of SAI1_CLK_ROOT output : N/A */
#define BOARD_BOOTCLOCKRUN_SAI1_MCLK1 63529411UL /* Clock consumers of SAI1_MCLK1 output : SAI1 */
#define BOARD_BOOTCLOCKRUN_SAI1_MCLK2 63529411UL /* Clock consumers of SAI1_MCLK2 output : SAI1 */
#define BOARD_BOOTCLOCKRUN_SAI1_MCLK3 30000000UL /* Clock consumers of SAI1_MCLK3 output : SAI1 */
#define BOARD_BOOTCLOCKRUN_SAI2_CLK_ROOT 63529411UL /* Clock consumers of SAI2_CLK_ROOT output : N/A */
#define BOARD_BOOTCLOCKRUN_SAI2_MCLK1 63529411UL /* Clock consumers of SAI2_MCLK1 output : SAI2 */
#define BOARD_BOOTCLOCKRUN_SAI2_MCLK2 0UL /* Clock consumers of SAI2_MCLK2 output : SAI2 */
#define BOARD_BOOTCLOCKRUN_SAI2_MCLK3 30000000UL /* Clock consumers of SAI2_MCLK3 output : SAI2 */
#define BOARD_BOOTCLOCKRUN_SAI3_CLK_ROOT 63529411UL /* Clock consumers of SAI3_CLK_ROOT output : N/A */
#define BOARD_BOOTCLOCKRUN_SAI3_MCLK1 63529411UL /* Clock consumers of SAI3_MCLK1 output : SAI3 */
#define BOARD_BOOTCLOCKRUN_SAI3_MCLK2 0UL /* Clock consumers of SAI3_MCLK2 output : SAI3 */
#define BOARD_BOOTCLOCKRUN_SAI3_MCLK3 30000000UL /* Clock consumers of SAI3_MCLK3 output : SAI3 */
#define BOARD_BOOTCLOCKRUN_SEMC_CLK_ROOT 75000000UL /* Clock consumers of SEMC_CLK_ROOT output : SEMC */
#define BOARD_BOOTCLOCKRUN_SPDIF0_CLK_ROOT 30000000UL /* Clock consumers of SPDIF0_CLK_ROOT output : SPDIF */
#define BOARD_BOOTCLOCKRUN_SPDIF0_EXTCLK_OUT 0UL /* Clock consumers of SPDIF0_EXTCLK_OUT output : SPDIF */
#define BOARD_BOOTCLOCKRUN_TRACE_CLK_ROOT 132000000UL /* Clock consumers of TRACE_CLK_ROOT output : ARM */
#define BOARD_BOOTCLOCKRUN_UART_CLK_ROOT 80000000UL /* Clock consumers of UART_CLK_ROOT output : LPUART1, LPUART2, LPUART3, LPUART4, LPUART5, LPUART6, LPUART7, LPUART8 */
#define BOARD_BOOTCLOCKRUN_USBPHY1_CLK 0UL /* Clock consumers of USBPHY1_CLK output : TEMPMON, USB1 */
#define BOARD_BOOTCLOCKRUN_USBPHY2_CLK 0UL /* Clock consumers of USBPHY2_CLK output : USB2 */
#define BOARD_BOOTCLOCKRUN_USDHC1_CLK_ROOT 198000000UL /* Clock consumers of USDHC1_CLK_ROOT output : USDHC1 */
#define BOARD_BOOTCLOCKRUN_USDHC2_CLK_ROOT 198000000UL /* Clock consumers of USDHC2_CLK_ROOT output : USDHC2 */
/*! @brief Arm PLL set for BOARD_BootClockRUN configuration.
*/
extern const clock_arm_pll_config_t armPllConfig_BOARD_BootClockRUN;
/*! @brief Usb1 PLL set for BOARD_BootClockRUN configuration.
*/
extern const clock_usb_pll_config_t usb1PllConfig_BOARD_BootClockRUN;
/*! @brief Sys PLL for BOARD_BootClockRUN configuration.
*/
extern const clock_sys_pll_config_t sysPllConfig_BOARD_BootClockRUN;
/*! @brief Video PLL set for BOARD_BootClockRUN configuration.
*/
extern const clock_video_pll_config_t videoPllConfig_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*/
/*******************************************************************************
******************* Configuration BOARD_BootClockRUN_528M *********************
******************************************************************************/
/*******************************************************************************
* Definitions for BOARD_BootClockRUN_528M configuration
******************************************************************************/
#define BOARD_BOOTCLOCKRUN_528M_CORE_CLOCK 528000000U /*!< Core clock frequency: 528000000Hz */
/* Clock outputs (values are in Hz): */
#define BOARD_BOOTCLOCKRUN_528M_AHB_CLK_ROOT 528000000UL /* Clock consumers of AHB_CLK_ROOT output : AIPSTZ1, AIPSTZ2, AIPSTZ3, AIPSTZ4, ARM, FLEXIO3, FLEXSPI, FLEXSPI2, GPIO6, GPIO7, GPIO8, GPIO9 */
#define BOARD_BOOTCLOCKRUN_528M_CAN_CLK_ROOT 40000000UL /* Clock consumers of CAN_CLK_ROOT output : CAN1, CAN2, CAN3 */
#define BOARD_BOOTCLOCKRUN_528M_CKIL_SYNC_CLK_ROOT 32768UL /* Clock consumers of CKIL_SYNC_CLK_ROOT output : CSU, EWM, GPT1, GPT2, KPP, PIT, RTWDOG, SNVS, SPDIF, TEMPMON, TSC, USB1, USB2, WDOG1, WDOG2 */
#define BOARD_BOOTCLOCKRUN_528M_CLKO1_CLK 0UL /* Clock consumers of CLKO1_CLK output : N/A */
#define BOARD_BOOTCLOCKRUN_528M_CLKO2_CLK 0UL /* Clock consumers of CLKO2_CLK output : N/A */
#define BOARD_BOOTCLOCKRUN_528M_CLK_1M 1000000UL /* Clock consumers of CLK_1M output : EWM, RTWDOG */
#define BOARD_BOOTCLOCKRUN_528M_CLK_24M 24000000UL /* Clock consumers of CLK_24M output : GPT1, GPT2 */
#define BOARD_BOOTCLOCKRUN_528M_CSI_CLK_ROOT 12000000UL /* Clock consumers of CSI_CLK_ROOT output : CSI */
#define BOARD_BOOTCLOCKRUN_528M_ENET2_125M_CLK 1200000UL /* Clock consumers of ENET2_125M_CLK output : N/A */
#define BOARD_BOOTCLOCKRUN_528M_ENET2_REF_CLK 0UL /* Clock consumers of ENET2_REF_CLK output : ENET2 */
#define BOARD_BOOTCLOCKRUN_528M_ENET2_TX_CLK 0UL /* Clock consumers of ENET2_TX_CLK output : ENET2 */
#define BOARD_BOOTCLOCKRUN_528M_ENET_125M_CLK 2400000UL /* Clock consumers of ENET_125M_CLK output : N/A */
#define BOARD_BOOTCLOCKRUN_528M_ENET_25M_REF_CLK 1200000UL /* Clock consumers of ENET_25M_REF_CLK output : ENET, ENET2 */
#define BOARD_BOOTCLOCKRUN_528M_ENET_REF_CLK 0UL /* Clock consumers of ENET_REF_CLK output : ENET */
#define BOARD_BOOTCLOCKRUN_528M_ENET_TX_CLK 0UL /* Clock consumers of ENET_TX_CLK output : ENET */
#define BOARD_BOOTCLOCKRUN_528M_FLEXIO1_CLK_ROOT 30000000UL /* Clock consumers of FLEXIO1_CLK_ROOT output : FLEXIO1 */
#define BOARD_BOOTCLOCKRUN_528M_FLEXIO2_CLK_ROOT 30000000UL /* Clock consumers of FLEXIO2_CLK_ROOT output : FLEXIO2, FLEXIO3 */
#define BOARD_BOOTCLOCKRUN_528M_FLEXSPI2_CLK_ROOT 130909090UL /* Clock consumers of FLEXSPI2_CLK_ROOT output : FLEXSPI2 */
#define BOARD_BOOTCLOCKRUN_528M_FLEXSPI_CLK_ROOT 130909090UL /* Clock consumers of FLEXSPI_CLK_ROOT output : FLEXSPI */
#define BOARD_BOOTCLOCKRUN_528M_GPT1_IPG_CLK_HIGHFREQ 66000000UL /* Clock consumers of GPT1_ipg_clk_highfreq output : GPT1 */
#define BOARD_BOOTCLOCKRUN_528M_GPT2_IPG_CLK_HIGHFREQ 66000000UL /* Clock consumers of GPT2_ipg_clk_highfreq output : GPT2 */
#define BOARD_BOOTCLOCKRUN_528M_IPG_CLK_ROOT 132000000UL /* Clock consumers of IPG_CLK_ROOT output : ADC1, ADC2, ADC_ETC, AOI1, AOI2, ARM, BEE, CAN1, CAN2, CAN3, CCM, CMP1, CMP2, CMP3, CMP4, CSI, CSU, DCDC, DCP, DMA0, DMAMUX, ENC1, ENC2, ENC3, ENC4, ENET, ENET2, EWM, FLEXIO1, FLEXIO2, FLEXIO3, FLEXRAM, FLEXSPI, FLEXSPI2, GPC, GPIO1, GPIO10, GPIO2, GPIO3, GPIO4, GPIO5, IOMUXC, KPP, LCDIF, LPI2C1, LPI2C2, LPI2C3, LPI2C4, LPSPI1, LPSPI2, LPSPI3, LPSPI4, LPUART1, LPUART2, LPUART3, LPUART4, LPUART5, LPUART6, LPUART7, LPUART8, NVIC, OCOTP, PMU, PWM1, PWM2, PWM3, PWM4, PXP, ROMC, RTWDOG, SAI1, SAI2, SAI3, SNVS, SPDIF, SRC, TEMPMON, TMR1, TMR2, TMR3, TMR4, TRNG, TSC, USB1, USB2, USDHC1, USDHC2, WDOG1, WDOG2, XBARA1, XBARB2, XBARB3 */
#define BOARD_BOOTCLOCKRUN_528M_LCDIF_CLK_ROOT 67500000UL /* Clock consumers of LCDIF_CLK_ROOT output : LCDIF */
#define BOARD_BOOTCLOCKRUN_528M_LPI2C_CLK_ROOT 60000000UL /* Clock consumers of LPI2C_CLK_ROOT output : LPI2C1, LPI2C2, LPI2C3, LPI2C4 */
#define BOARD_BOOTCLOCKRUN_528M_LPSPI_CLK_ROOT 105600000UL /* Clock consumers of LPSPI_CLK_ROOT output : LPSPI1, LPSPI2, LPSPI3, LPSPI4 */
#define BOARD_BOOTCLOCKRUN_528M_LVDS1_CLK 1200000000UL /* Clock consumers of LVDS1_CLK output : N/A */
#define BOARD_BOOTCLOCKRUN_528M_MQS_MCLK 63529411UL /* Clock consumers of MQS_MCLK output : N/A */
#define BOARD_BOOTCLOCKRUN_528M_PERCLK_CLK_ROOT 66000000UL /* Clock consumers of PERCLK_CLK_ROOT output : GPT1, GPT2, PIT */
#define BOARD_BOOTCLOCKRUN_528M_PLL7_MAIN_CLK 24000000UL /* Clock consumers of PLL7_MAIN_CLK output : N/A */
#define BOARD_BOOTCLOCKRUN_528M_SAI1_CLK_ROOT 63529411UL /* Clock consumers of SAI1_CLK_ROOT output : N/A */
#define BOARD_BOOTCLOCKRUN_528M_SAI1_MCLK1 63529411UL /* Clock consumers of SAI1_MCLK1 output : SAI1 */
#define BOARD_BOOTCLOCKRUN_528M_SAI1_MCLK2 63529411UL /* Clock consumers of SAI1_MCLK2 output : SAI1 */
#define BOARD_BOOTCLOCKRUN_528M_SAI1_MCLK3 30000000UL /* Clock consumers of SAI1_MCLK3 output : SAI1 */
#define BOARD_BOOTCLOCKRUN_528M_SAI2_CLK_ROOT 63529411UL /* Clock consumers of SAI2_CLK_ROOT output : N/A */
#define BOARD_BOOTCLOCKRUN_528M_SAI2_MCLK1 63529411UL /* Clock consumers of SAI2_MCLK1 output : SAI2 */
#define BOARD_BOOTCLOCKRUN_528M_SAI2_MCLK2 0UL /* Clock consumers of SAI2_MCLK2 output : SAI2 */
#define BOARD_BOOTCLOCKRUN_528M_SAI2_MCLK3 30000000UL /* Clock consumers of SAI2_MCLK3 output : SAI2 */
#define BOARD_BOOTCLOCKRUN_528M_SAI3_CLK_ROOT 63529411UL /* Clock consumers of SAI3_CLK_ROOT output : N/A */
#define BOARD_BOOTCLOCKRUN_528M_SAI3_MCLK1 63529411UL /* Clock consumers of SAI3_MCLK1 output : SAI3 */
#define BOARD_BOOTCLOCKRUN_528M_SAI3_MCLK2 0UL /* Clock consumers of SAI3_MCLK2 output : SAI3 */
#define BOARD_BOOTCLOCKRUN_528M_SAI3_MCLK3 30000000UL /* Clock consumers of SAI3_MCLK3 output : SAI3 */
#define BOARD_BOOTCLOCKRUN_528M_SEMC_CLK_ROOT 66000000UL /* Clock consumers of SEMC_CLK_ROOT output : SEMC */
#define BOARD_BOOTCLOCKRUN_528M_SPDIF0_CLK_ROOT 30000000UL /* Clock consumers of SPDIF0_CLK_ROOT output : SPDIF */
#define BOARD_BOOTCLOCKRUN_528M_SPDIF0_EXTCLK_OUT 0UL /* Clock consumers of SPDIF0_EXTCLK_OUT output : SPDIF */
#define BOARD_BOOTCLOCKRUN_528M_TRACE_CLK_ROOT 132000000UL /* Clock consumers of TRACE_CLK_ROOT output : ARM */
#define BOARD_BOOTCLOCKRUN_528M_UART_CLK_ROOT 80000000UL /* Clock consumers of UART_CLK_ROOT output : LPUART1, LPUART2, LPUART3, LPUART4, LPUART5, LPUART6, LPUART7, LPUART8 */
#define BOARD_BOOTCLOCKRUN_528M_USBPHY1_CLK 0UL /* Clock consumers of USBPHY1_CLK output : TEMPMON, USB1 */
#define BOARD_BOOTCLOCKRUN_528M_USBPHY2_CLK 0UL /* Clock consumers of USBPHY2_CLK output : USB2 */
#define BOARD_BOOTCLOCKRUN_528M_USDHC1_CLK_ROOT 198000000UL /* Clock consumers of USDHC1_CLK_ROOT output : USDHC1 */
#define BOARD_BOOTCLOCKRUN_528M_USDHC2_CLK_ROOT 198000000UL /* Clock consumers of USDHC2_CLK_ROOT output : USDHC2 */
/*! @brief Arm PLL set for BOARD_BootClockRUN_528M configuration.
*/
extern const clock_arm_pll_config_t armPllConfig_BOARD_BootClockRUN_528M;
/*! @brief Usb1 PLL set for BOARD_BootClockRUN_528M configuration.
*/
extern const clock_usb_pll_config_t usb1PllConfig_BOARD_BootClockRUN_528M;
/*! @brief Sys PLL for BOARD_BootClockRUN_528M configuration.
*/
extern const clock_sys_pll_config_t sysPllConfig_BOARD_BootClockRUN_528M;
/*! @brief Video PLL set for BOARD_BootClockRUN_528M configuration.
*/
extern const clock_video_pll_config_t videoPllConfig_BOARD_BootClockRUN_528M;
/*******************************************************************************
* API for BOARD_BootClockRUN_528M configuration
******************************************************************************/
#if defined(__cplusplus)
extern "C" {
#endif /* __cplusplus*/
/*!
* @brief This function executes configuration of clocks.
*
*/
void BOARD_BootClockRUN_528M(void);
#if defined(__cplusplus)
}
#endif /* __cplusplus*/
#endif /* _CLOCK_CONFIG_H_ */

View File

@ -0,0 +1,88 @@
/***********************************************************************************************************************
* 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_
/***********************************************************************************************************************
* Definitions
**********************************************************************************************************************/
/*! @brief Direction type */
typedef enum _pin_mux_direction
{
kPIN_MUX_DirectionInput = 0U, /* Input direction */
kPIN_MUX_DirectionOutput = 1U, /* Output direction */
kPIN_MUX_DirectionInputOrOutput = 2U /* Input or output direction */
} pin_mux_direction_t;
/*!
* @addtogroup pin_mux
* @{
*/
/***********************************************************************************************************************
* API
**********************************************************************************************************************/
#if defined(__cplusplus)
extern "C" {
#endif
/*!
* @brief Calls initialization functions.
*
*/
void BOARD_InitBootPins(void);
#define BOARD_INITPINS_IOMUXC_GPR_GPR27_GPIO_MUX2_GPIO_SEL_MASK 0x80U /*!< GPIO2 and GPIO7 share same IO MUX function, GPIO_MUX2 selects one GPIO function: affected bits mask */
/* GPIO_AD_B0_13 (coord L14), UART1_RXD/J11[2] */
/* Routed pin properties */
#define BOARD_INITPINS_UART1_RXD_PERIPHERAL LPUART1 /*!< Peripheral name */
#define BOARD_INITPINS_UART1_RXD_SIGNAL RX /*!< Signal name */
/* GPIO_AD_B0_12 (coord K14), UART1_TXD/J13[2] */
/* Routed pin properties */
#define BOARD_INITPINS_UART1_TXD_PERIPHERAL LPUART1 /*!< Peripheral name */
#define BOARD_INITPINS_UART1_TXD_SIGNAL TX /*!< Signal name */
/* GPIO_AD_B0_10 (coord G13), JTAG_TDO/J2[13]/J3[2]/ENET_INT/U18[21]/INT1_COMBO/U12[11]/DC_I2S2_MCLK/J19[1]/J16[6] */
/* Routed pin properties */
#define BOARD_INITPINS_INT1_COMBO_PERIPHERAL ARM /*!< Peripheral name */
#define BOARD_INITPINS_INT1_COMBO_SIGNAL arm_trace_swo /*!< Signal name */
/* GPIO_B0_07 (coord A9), LCDIF_D3/BT_CFG[3]/J49[A27] */
/* Routed pin properties */
#define BOARD_INITPINS_LCDIF_D3_PERIPHERAL GPIO2 /*!< Peripheral name */
#define BOARD_INITPINS_LCDIF_D3_SIGNAL gpio_io /*!< Signal name */
#define BOARD_INITPINS_LCDIF_D3_CHANNEL 7U /*!< Signal channel */
/* Symbols to be used with GPIO driver */
#define BOARD_INITPINS_LCDIF_D3_GPIO GPIO2 /*!< GPIO peripheral base pointer */
#define BOARD_INITPINS_LCDIF_D3_GPIO_PIN 7U /*!< GPIO pin number */
#define BOARD_INITPINS_LCDIF_D3_GPIO_PIN_MASK (1U << 7U) /*!< GPIO pin mask */
#define BOARD_INITPINS_LCDIF_D3_PORT GPIO2 /*!< PORT peripheral base pointer */
#define BOARD_INITPINS_LCDIF_D3_PIN 7U /*!< PORT pin number */
#define BOARD_INITPINS_LCDIF_D3_PIN_MASK (1U << 7U) /*!< PORT pin mask */
/*!
* @brief Configures pin routing and optionally pin electrical features.
*
*/
void BOARD_InitPins(void);
#if defined(__cplusplus)
}
#endif
/*!
* @}
*/
#endif /* _PIN_MUX_H_ */
/***********************************************************************************************************************
* EOF
**********************************************************************************************************************/

View File

@ -0,0 +1,297 @@
/*
** ###################################################################
** Processors: MIMXRT1062CVJ5A
** MIMXRT1062CVJ5B
** MIMXRT1062CVL5A
** MIMXRT1062CVL5B
** MIMXRT1062DVJ6A
** MIMXRT1062DVJ6B
** MIMXRT1062DVL6A
** MIMXRT1062DVL6B
** MIMXRT1062DVN6B
** MIMXRT1062XVN5B
**
** Compiler: GNU C Compiler
** Reference manual: IMXRT1060RM Rev.3, 07/2021 | IMXRT106XSRM Rev.0
** Version: rev. 0.2, 2022-03-25
** Build: b241024
**
** Abstract:
** Linker file for the GNU C Compiler
**
** Copyright 2016 Freescale Semiconductor, Inc.
** Copyright 2016-2024 NXP
** SPDX-License-Identifier: BSD-3-Clause
**
** http: www.nxp.com
** mail: support@nxp.com
**
** ###################################################################
*/
/* Entry Point */
ENTRY(Reset_Handler)
HEAP_SIZE = DEFINED(__heap_size__) ? __heap_size__ : 0x0400;
STACK_SIZE = DEFINED(__stack_size__) ? __stack_size__ : 0x0400;
VECTOR_RAM_SIZE = DEFINED(__ram_vector_table__) ? 0x00000400 : 0;
TEXT_SIZE = DEFINED(__use_flash16MB__) ? 0x00FFDC00 : 0x007FDC00;
/* Specify the memory areas */
MEMORY
{
m_flash_config (RX) : ORIGIN = 0x60000000, LENGTH = 0x00001000
m_ivt (RX) : ORIGIN = 0x60001000, LENGTH = 0x00001000
m_interrupts (RX) : ORIGIN = 0x60002000, LENGTH = 0x00000400
m_text (RX) : ORIGIN = 0x60002400, LENGTH = TEXT_SIZE
m_qacode (RX) : ORIGIN = 0x00000000, LENGTH = 0x00020000
m_data (RW) : ORIGIN = 0x20000000, LENGTH = 0x00020000
m_data2 (RW) : ORIGIN = 0x20200000, LENGTH = 0x000C0000
}
/* Define output sections */
SECTIONS
{
__NCACHE_REGION_START = ORIGIN(m_data2);
__NCACHE_REGION_SIZE = 0;
.flash_config :
{
. = ALIGN(4);
__FLASH_BASE = .;
KEEP(* (.boot_hdr.conf)) /* flash config section */
. = ALIGN(4);
} > m_flash_config
ivt_begin = ORIGIN(m_flash_config) + LENGTH(m_flash_config);
.ivt : AT(ivt_begin)
{
. = ALIGN(4);
KEEP(* (.boot_hdr.ivt)) /* ivt section */
KEEP(* (.boot_hdr.boot_data)) /* boot section */
KEEP(* (.boot_hdr.dcd_data)) /* dcd section */
. = ALIGN(4);
} > m_ivt
/* The startup code goes first into internal RAM */
.interrupts :
{
__VECTOR_TABLE = .;
__Vectors = .;
. = ALIGN(4);
KEEP(*(.isr_vector)) /* Startup code */
. = ALIGN(4);
} > m_interrupts
/* The program code and other data goes into internal RAM */
.text :
{
. = ALIGN(4);
*(.text) /* .text sections (code) */
*(.text*) /* .text* sections (code) */
*(.rodata) /* .rodata sections (constants, strings, etc.) */
*(.rodata*) /* .rodata* sections (constants, strings, etc.) */
*(.glue_7) /* glue arm to thumb code */
*(.glue_7t) /* glue thumb to arm code */
*(.eh_frame)
KEEP (*(.init))
KEEP (*(.fini))
. = ALIGN(4);
/* section information for shell */
. = ALIGN(4);
_shell_command_start = .;
KEEP (*(shellCommand))
_shell_command_end = .;
. = ALIGN(4);
__isrtbl_idx_start = .;
KEEP(*(.isrtbl.idx))
__isrtbl_start = .;
KEEP(*(.isrtbl))
__isrtbl_end = .;
. = ALIGN(4);
PROVIDE(g_service_table_start = ABSOLUTE(.));
KEEP(*(.g_service_table))
PROVIDE(g_service_table_end = ABSOLUTE(.));
} > m_text
.ARM.extab :
{
*(.ARM.extab* .gnu.linkonce.armextab.*)
} > m_text
.ARM :
{
__exidx_start = .;
*(.ARM.exidx*)
__exidx_end = .;
} > m_text
.ctors :
{
__CTOR_LIST__ = .;
/* gcc uses crtbegin.o to find the start of
the constructors, so we make sure it is
first. Because this is a wildcard, it
doesn't matter if the user does not
actually link against crtbegin.o; the
linker won't look for a file to match a
wildcard. The wildcard also means that it
doesn't matter which directory crtbegin.o
is in. */
KEEP (*crtbegin.o(.ctors))
KEEP (*crtbegin?.o(.ctors))
/* We don't want to include the .ctor section from
from the crtend.o file until after the sorted ctors.
The .ctor section from the crtend file contains the
end of ctors marker and it must be last */
KEEP (*(EXCLUDE_FILE(*crtend?.o *crtend.o) .ctors))
KEEP (*(SORT(.ctors.*)))
KEEP (*(.ctors))
__CTOR_END__ = .;
} > m_text
.dtors :
{
__DTOR_LIST__ = .;
KEEP (*crtbegin.o(.dtors))
KEEP (*crtbegin?.o(.dtors))
KEEP (*(EXCLUDE_FILE(*crtend?.o *crtend.o) .dtors))
KEEP (*(SORT(.dtors.*)))
KEEP (*(.dtors))
__DTOR_END__ = .;
} > m_text
.preinit_array :
{
PROVIDE_HIDDEN (__preinit_array_start = .);
KEEP (*(.preinit_array*))
PROVIDE_HIDDEN (__preinit_array_end = .);
} > m_text
.init_array :
{
PROVIDE_HIDDEN (__init_array_start = .);
KEEP (*(SORT(.init_array.*)))
KEEP (*(.init_array*))
PROVIDE_HIDDEN (__init_array_end = .);
} > m_text
.fini_array :
{
PROVIDE_HIDDEN (__fini_array_start = .);
KEEP (*(SORT(.fini_array.*)))
KEEP (*(.fini_array*))
PROVIDE_HIDDEN (__fini_array_end = .);
} > m_text
__etext = .; /* define a global symbol at end of code */
__DATA_ROM = .; /* Symbol is used by startup for data initialization */
.interrupts_ram :
{
. = ALIGN(4);
__VECTOR_RAM__ = .;
__interrupts_ram_start__ = .; /* Create a global symbol at data start */
*(.m_interrupts_ram) /* This is a user defined section */
. += VECTOR_RAM_SIZE;
. = ALIGN(4);
__interrupts_ram_end__ = .; /* Define a global symbol at data end */
} > m_data
__VECTOR_RAM = DEFINED(__ram_vector_table__) ? __VECTOR_RAM__ : ORIGIN(m_interrupts);
__RAM_VECTOR_TABLE_SIZE_BYTES = DEFINED(__ram_vector_table__) ? (__interrupts_ram_end__ - __interrupts_ram_start__) : 0x0;
.data : AT(__DATA_ROM)
{
. = ALIGN(4);
__DATA_RAM = .;
__data_start__ = .; /* create a global symbol at data start */
*(.data) /* .data sections */
*(.data*) /* .data* sections */
*(DataQuickAccess) /* quick access data section */
KEEP(*(.jcr*))
. = ALIGN(4);
__data_end__ = .; /* define a global symbol at data end */
} > m_data
__ram_function_flash_start = __DATA_ROM + (__data_end__ - __data_start__); /* Symbol is used by startup for TCM data initialization */
.ram_function : AT(__ram_function_flash_start)
{
. = ALIGN(32);
__ram_function_start__ = .;
*(CodeQuickAccess)
. = ALIGN(128);
__ram_function_end__ = .;
} > m_qacode
__NDATA_ROM = __ram_function_flash_start + (__ram_function_end__ - __ram_function_start__);
.ncache.init : AT(__NDATA_ROM)
{
__noncachedata_start__ = .; /* create a global symbol at ncache data start */
*(NonCacheable.init)
. = ALIGN(4);
__noncachedata_init_end__ = .; /* create a global symbol at initialized ncache data end */
} > m_data
. = __noncachedata_init_end__;
.ncache :
{
*(NonCacheable)
. = ALIGN(4);
__noncachedata_end__ = .; /* define a global symbol at ncache data end */
} > m_data
__DATA_END = __NDATA_ROM + (__noncachedata_init_end__ - __noncachedata_start__);
text_end = ORIGIN(m_text) + LENGTH(m_text);
ASSERT(__DATA_END <= text_end, "region m_text overflowed with text and data")
/* Uninitialized data section */
.bss :
{
/* This is used by the startup in order to initialize the .bss section */
. = ALIGN(4);
__START_BSS = .;
__bss_start__ = .;
*(.bss)
*(.bss*)
*(COMMON)
. = ALIGN(4);
__bss_end__ = .;
__END_BSS = .;
} > m_data
.heap :
{
. = ALIGN(8);
__end__ = .;
PROVIDE(end = .);
__HeapBase = .;
. += HEAP_SIZE;
__HeapLimit = .;
__heap_limit = .; /* Add for _sbrk */
} > m_data
.stack :
{
. = ALIGN(8);
stack_start = .;
. += STACK_SIZE;
stack_end = .;
} > m_data
/* Initializes stack on the end of block */
__StackTop = ORIGIN(m_data) + LENGTH(m_data);
__StackLimit = __StackTop - STACK_SIZE;
PROVIDE(__stack = __StackTop);
heap_start = ORIGIN(m_data2);
PROVIDE(heap_end = ORIGIN(m_data2) + LENGTH(m_data2));
.ARM.attributes 0 : { *(.ARM.attributes) }
ASSERT(__StackLimit >= __HeapLimit, "region m_data overflowed with stack and heap")
}

View File

@ -0,0 +1,11 @@
# Add set(CONFIG_USE_CMSIS_Include_core_cm true) in config.cmake to use this component
include_guard(GLOBAL)
message("${CMAKE_CURRENT_LIST_FILE} component is included.")
target_include_directories(${MCUX_SDK_PROJECT_NAME} PUBLIC
${CMAKE_CURRENT_LIST_DIR}/
${CMAKE_CURRENT_LIST_DIR}/m-profile
)

View File

@ -0,0 +1,292 @@
/*
* Copyright (c) 2009-2023 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.
*/
/*
* CMSIS Compiler Generic Header File
*/
#ifndef __CMSIS_COMPILER_H
#define __CMSIS_COMPILER_H
#include <stdint.h>
/*
* Arm Compiler above 6.10.1 (armclang)
*/
#if defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6100100)
#include "cmsis_armclang.h"
/*
* TI Arm Clang Compiler (tiarmclang)
*/
#elif defined (__ti__)
#include "cmsis_tiarmclang.h"
/*
* LLVM/Clang Compiler
*/
#elif defined ( __clang__ )
#include "cmsis_clang.h"
/*
* GNU Compiler
*/
#elif defined ( __GNUC__ )
#include "cmsis_gcc.h"
/*
* IAR Compiler
*/
#elif defined ( __ICCARM__ )
#if __ARM_ARCH_PROFILE == 'A'
#include "a-profile/cmsis_iccarm_a.h"
#elif __ARM_ARCH_PROFILE == 'R'
#include "r-profile/cmsis_iccarm_r.h"
#elif __ARM_ARCH_PROFILE == 'M'
#include "m-profile/cmsis_iccarm_m.h"
#else
#error "Unknown Arm architecture profile"
#endif
/*
* TI Arm Compiler (armcl)
*/
#elif defined ( __TI_ARM__ )
#include <cmsis_ccs.h>
#ifndef __ASM
#define __ASM __asm
#endif
#ifndef __INLINE
#define __INLINE inline
#endif
#ifndef __STATIC_INLINE
#define __STATIC_INLINE static inline
#endif
#ifndef __STATIC_FORCEINLINE
#define __STATIC_FORCEINLINE __STATIC_INLINE
#endif
#ifndef __NO_RETURN
#define __NO_RETURN __attribute__((noreturn))
#endif
#ifndef __USED
#define __USED __attribute__((used))
#endif
#ifndef __WEAK
#define __WEAK __attribute__((weak))
#endif
#ifndef __PACKED
#define __PACKED __attribute__((packed))
#endif
#ifndef __PACKED_STRUCT
#define __PACKED_STRUCT struct __attribute__((packed))
#endif
#ifndef __PACKED_UNION
#define __PACKED_UNION union __attribute__((packed))
#endif
#ifndef __UNALIGNED_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
#define __RESTRICT __restrict
#endif
#ifndef __COMPILER_BARRIER
#warning No compiler specific solution for __COMPILER_BARRIER. __COMPILER_BARRIER is ignored.
#define __COMPILER_BARRIER() (void)0
#endif
#ifndef __NO_INIT
#define __NO_INIT __attribute__ ((section (".noinit")))
#endif
#ifndef __ALIAS
#define __ALIAS(x) __attribute__ ((alias(x)))
#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_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
#ifndef __COMPILER_BARRIER
#warning No compiler specific solution for __COMPILER_BARRIER. __COMPILER_BARRIER is ignored.
#define __COMPILER_BARRIER() (void)0
#endif
#ifndef __NO_INIT
#define __NO_INIT __attribute__ ((section (".noinit")))
#endif
#ifndef __ALIAS
#define __ALIAS(x) __attribute__ ((alias(x)))
#endif
/*
* COSMIC Compiler
*/
#elif defined ( __CSMC__ )
#include <cmsis_csm.h>
#ifndef __ASM
#define __ASM _asm
#endif
#ifndef __INLINE
#define __INLINE inline
#endif
#ifndef __STATIC_INLINE
#define __STATIC_INLINE static inline
#endif
#ifndef __STATIC_FORCEINLINE
#define __STATIC_FORCEINLINE __STATIC_INLINE
#endif
#ifndef __NO_RETURN
// NO RETURN is automatically detected hence no warning here
#define __NO_RETURN
#endif
#ifndef __USED
#warning No compiler specific solution for __USED. __USED is ignored.
#define __USED
#endif
#ifndef __WEAK
#define __WEAK __weak
#endif
#ifndef __PACKED
#define __PACKED @packed
#endif
#ifndef __PACKED_STRUCT
#define __PACKED_STRUCT @packed struct
#endif
#ifndef __PACKED_UNION
#define __PACKED_UNION @packed union
#endif
#ifndef __UNALIGNED_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
#ifndef __COMPILER_BARRIER
#warning No compiler specific solution for __COMPILER_BARRIER. __COMPILER_BARRIER is ignored.
#define __COMPILER_BARRIER() (void)0
#endif
#ifndef __NO_INIT
#define __NO_INIT __attribute__ ((section (".noinit")))
#endif
#ifndef __ALIAS
#define __ALIAS(x) __attribute__ ((alias(x)))
#endif
#else
#error Unknown compiler.
#endif
#endif /* __CMSIS_COMPILER_H */

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,44 @@
/*
* Copyright (c) 2009-2023 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.
*/
/*
* CMSIS Core Version Definitions
*/
#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-Core(M) Version definitions */
#define __CM_CMSIS_VERSION_MAIN ( 6U) /*!< \brief [31:16] CMSIS-Core(M) main version */
#define __CM_CMSIS_VERSION_SUB ( 1U) /*!< \brief [15:0] CMSIS-Core(M) sub version */
#define __CM_CMSIS_VERSION ((__CM_CMSIS_VERSION_MAIN << 16U) | \
__CM_CMSIS_VERSION_SUB ) /*!< \brief CMSIS Core(M) version number */
/* CMSIS-Core(A) Version definitions */
#define __CA_CMSIS_VERSION_MAIN ( 6U) /*!< \brief [31:16] CMSIS-Core(A) main version */
#define __CA_CMSIS_VERSION_SUB ( 1U) /*!< \brief [15:0] CMSIS-Core(A) sub version */
#define __CA_CMSIS_VERSION ((__CA_CMSIS_VERSION_MAIN << 16U) | \
__CA_CMSIS_VERSION_SUB ) /*!< \brief CMSIS-Core(A) version number */
#endif

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,439 @@
/*
* Copyright (c) 2020-2021 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.
*/
/*
* CMSIS-Core(M) Level 1 Cache API for Armv7-M and later
*/
#ifndef ARM_ARMV7M_CACHEL1_H
#define ARM_ARMV7M_CACHEL1_H
#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
/**
\ingroup CMSIS_Core_FunctionInterface
\defgroup CMSIS_Core_CacheFunctions Cache Functions
\brief Functions that configure Instruction and Data cache.
@{
*/
/* Cache Size ID Register Macros */
#define CCSIDR_WAYS(x) (((x) & SCB_CCSIDR_ASSOCIATIVITY_Msk) >> SCB_CCSIDR_ASSOCIATIVITY_Pos)
#define CCSIDR_SETS(x) (((x) & SCB_CCSIDR_NUMSETS_Msk ) >> SCB_CCSIDR_NUMSETS_Pos )
#ifndef __SCB_DCACHE_LINE_SIZE
#define __SCB_DCACHE_LINE_SIZE 32U /*!< Cortex-M7 cache line size is fixed to 32 bytes (8 words). See also register SCB_CCSIDR */
#endif
#ifndef __SCB_ICACHE_LINE_SIZE
#define __SCB_ICACHE_LINE_SIZE 32U /*!< Cortex-M7 cache line size is fixed to 32 bytes (8 words). See also register SCB_CCSIDR */
#endif
/**
\brief Enable I-Cache
\details Turns on I-Cache
*/
__STATIC_FORCEINLINE void SCB_EnableICache (void)
{
#if defined (__ICACHE_PRESENT) && (__ICACHE_PRESENT == 1U)
if (SCB->CCR & SCB_CCR_IC_Msk) return; /* return if ICache is already enabled */
__DSB();
__ISB();
SCB->ICIALLU = 0UL; /* invalidate I-Cache */
__DSB();
__ISB();
SCB->CCR |= (uint32_t)SCB_CCR_IC_Msk; /* enable I-Cache */
__DSB();
__ISB();
#endif
}
/**
\brief Disable I-Cache
\details Turns off I-Cache
*/
__STATIC_FORCEINLINE void SCB_DisableICache (void)
{
#if defined (__ICACHE_PRESENT) && (__ICACHE_PRESENT == 1U)
__DSB();
__ISB();
SCB->CCR &= ~(uint32_t)SCB_CCR_IC_Msk; /* disable I-Cache */
SCB->ICIALLU = 0UL; /* invalidate I-Cache */
__DSB();
__ISB();
#endif
}
/**
\brief Invalidate I-Cache
\details Invalidates I-Cache
*/
__STATIC_FORCEINLINE void SCB_InvalidateICache (void)
{
#if defined (__ICACHE_PRESENT) && (__ICACHE_PRESENT == 1U)
__DSB();
__ISB();
SCB->ICIALLU = 0UL;
__DSB();
__ISB();
#endif
}
/**
\brief I-Cache Invalidate by address
\details Invalidates I-Cache for the given address.
I-Cache is invalidated starting from a 32 byte aligned address in 32 byte granularity.
I-Cache memory blocks which are part of given address + given size are invalidated.
\param[in] addr address
\param[in] isize size of memory block (in number of bytes)
*/
__STATIC_FORCEINLINE void SCB_InvalidateICache_by_Addr (volatile void *addr, int32_t isize)
{
#if defined (__ICACHE_PRESENT) && (__ICACHE_PRESENT == 1U)
if ( isize > 0 ) {
int32_t op_size = isize + (((uint32_t)addr) & (__SCB_ICACHE_LINE_SIZE - 1U));
uint32_t op_addr = (uint32_t)addr /* & ~(__SCB_ICACHE_LINE_SIZE - 1U) */;
__DSB();
do {
SCB->ICIMVAU = op_addr; /* register accepts only 32byte aligned values, only bits 31..5 are valid */
op_addr += __SCB_ICACHE_LINE_SIZE;
op_size -= __SCB_ICACHE_LINE_SIZE;
} while ( op_size > 0 );
__DSB();
__ISB();
}
#endif
}
/**
\brief Enable D-Cache
\details Turns on D-Cache
*/
__STATIC_FORCEINLINE void SCB_EnableDCache (void)
{
#if defined (__DCACHE_PRESENT) && (__DCACHE_PRESENT == 1U)
uint32_t ccsidr;
uint32_t sets;
uint32_t ways;
if (SCB->CCR & SCB_CCR_DC_Msk) return; /* return if DCache is already enabled */
SCB->CSSELR = 0U; /* select Level 1 data cache */
__DSB();
ccsidr = SCB->CCSIDR;
/* invalidate D-Cache */
sets = (uint32_t)(CCSIDR_SETS(ccsidr));
do {
ways = (uint32_t)(CCSIDR_WAYS(ccsidr));
do {
SCB->DCISW = (((sets << SCB_DCISW_SET_Pos) & SCB_DCISW_SET_Msk) |
((ways << SCB_DCISW_WAY_Pos) & SCB_DCISW_WAY_Msk) );
#if defined ( __CC_ARM )
__schedule_barrier();
#endif
} while (ways-- != 0U);
} while(sets-- != 0U);
__DSB();
SCB->CCR |= (uint32_t)SCB_CCR_DC_Msk; /* enable D-Cache */
__DSB();
__ISB();
#endif
}
/**
\brief Disable D-Cache
\details Turns off D-Cache
*/
__STATIC_FORCEINLINE void SCB_DisableDCache (void)
{
#if defined (__DCACHE_PRESENT) && (__DCACHE_PRESENT == 1U)
struct {
uint32_t ccsidr;
uint32_t sets;
uint32_t ways;
} locals
#if ((defined(__GNUC__) || defined(__clang__)) && !defined(__OPTIMIZE__))
__ALIGNED(__SCB_DCACHE_LINE_SIZE)
#endif
;
SCB->CSSELR = 0U; /* select Level 1 data cache */
__DSB();
SCB->CCR &= ~(uint32_t)SCB_CCR_DC_Msk; /* disable D-Cache */
__DSB();
#if !defined(__OPTIMIZE__)
/*
* For the endless loop issue with no optimization builds.
* More details, see https://github.com/ARM-software/CMSIS_5/issues/620
*
* The issue only happens when local variables are in stack. If
* local variables are saved in general purpose register, then the function
* is OK.
*
* When local variables are in stack, after disabling the cache, flush the
* local variables cache line for data consistency.
*/
/* Clean and invalidate the local variable cache. */
#if defined(__ICCARM__)
/* As we can't align the stack to the cache line size, invalidate each of the variables */
SCB->DCCIMVAC = (uint32_t)&locals.sets;
SCB->DCCIMVAC = (uint32_t)&locals.ways;
SCB->DCCIMVAC = (uint32_t)&locals.ccsidr;
#else
SCB->DCCIMVAC = (uint32_t)&locals;
#endif
__DSB();
__ISB();
#endif
locals.ccsidr = SCB->CCSIDR;
/* clean & invalidate D-Cache */
locals.sets = (uint32_t)(CCSIDR_SETS(locals.ccsidr));
do {
locals.ways = (uint32_t)(CCSIDR_WAYS(locals.ccsidr));
do {
SCB->DCCISW = (((locals.sets << SCB_DCCISW_SET_Pos) & SCB_DCCISW_SET_Msk) |
((locals.ways << SCB_DCCISW_WAY_Pos) & SCB_DCCISW_WAY_Msk) );
#if defined ( __CC_ARM )
__schedule_barrier();
#endif
} while (locals.ways-- != 0U);
} while(locals.sets-- != 0U);
__DSB();
__ISB();
#endif
}
/**
\brief Invalidate D-Cache
\details Invalidates D-Cache
*/
__STATIC_FORCEINLINE void SCB_InvalidateDCache (void)
{
#if defined (__DCACHE_PRESENT) && (__DCACHE_PRESENT == 1U)
uint32_t ccsidr;
uint32_t sets;
uint32_t ways;
SCB->CSSELR = 0U; /* select Level 1 data cache */
__DSB();
ccsidr = SCB->CCSIDR;
/* invalidate D-Cache */
sets = (uint32_t)(CCSIDR_SETS(ccsidr));
do {
ways = (uint32_t)(CCSIDR_WAYS(ccsidr));
do {
SCB->DCISW = (((sets << SCB_DCISW_SET_Pos) & SCB_DCISW_SET_Msk) |
((ways << SCB_DCISW_WAY_Pos) & SCB_DCISW_WAY_Msk) );
#if defined ( __CC_ARM )
__schedule_barrier();
#endif
} while (ways-- != 0U);
} while(sets-- != 0U);
__DSB();
__ISB();
#endif
}
/**
\brief Clean D-Cache
\details Cleans D-Cache
*/
__STATIC_FORCEINLINE void SCB_CleanDCache (void)
{
#if defined (__DCACHE_PRESENT) && (__DCACHE_PRESENT == 1U)
uint32_t ccsidr;
uint32_t sets;
uint32_t ways;
SCB->CSSELR = 0U; /* select Level 1 data cache */
__DSB();
ccsidr = SCB->CCSIDR;
/* clean D-Cache */
sets = (uint32_t)(CCSIDR_SETS(ccsidr));
do {
ways = (uint32_t)(CCSIDR_WAYS(ccsidr));
do {
SCB->DCCSW = (((sets << SCB_DCCSW_SET_Pos) & SCB_DCCSW_SET_Msk) |
((ways << SCB_DCCSW_WAY_Pos) & SCB_DCCSW_WAY_Msk) );
#if defined ( __CC_ARM )
__schedule_barrier();
#endif
} while (ways-- != 0U);
} while(sets-- != 0U);
__DSB();
__ISB();
#endif
}
/**
\brief Clean & Invalidate D-Cache
\details Cleans and Invalidates D-Cache
*/
__STATIC_FORCEINLINE void SCB_CleanInvalidateDCache (void)
{
#if defined (__DCACHE_PRESENT) && (__DCACHE_PRESENT == 1U)
uint32_t ccsidr;
uint32_t sets;
uint32_t ways;
SCB->CSSELR = 0U; /* select Level 1 data cache */
__DSB();
ccsidr = SCB->CCSIDR;
/* clean & invalidate D-Cache */
sets = (uint32_t)(CCSIDR_SETS(ccsidr));
do {
ways = (uint32_t)(CCSIDR_WAYS(ccsidr));
do {
SCB->DCCISW = (((sets << SCB_DCCISW_SET_Pos) & SCB_DCCISW_SET_Msk) |
((ways << SCB_DCCISW_WAY_Pos) & SCB_DCCISW_WAY_Msk) );
#if defined ( __CC_ARM )
__schedule_barrier();
#endif
} while (ways-- != 0U);
} while(sets-- != 0U);
__DSB();
__ISB();
#endif
}
/**
\brief D-Cache Invalidate by address
\details Invalidates D-Cache for the given address.
D-Cache is invalidated starting from a 32 byte aligned address in 32 byte granularity.
D-Cache memory blocks which are part of given address + given size are invalidated.
\param[in] addr address
\param[in] dsize size of memory block (in number of bytes)
*/
__STATIC_FORCEINLINE void SCB_InvalidateDCache_by_Addr (volatile void *addr, int32_t dsize)
{
#if defined (__DCACHE_PRESENT) && (__DCACHE_PRESENT == 1U)
if ( dsize > 0 ) {
int32_t op_size = dsize + (((uint32_t)addr) & (__SCB_DCACHE_LINE_SIZE - 1U));
uint32_t op_addr = (uint32_t)addr /* & ~(__SCB_DCACHE_LINE_SIZE - 1U) */;
__DSB();
do {
SCB->DCIMVAC = op_addr; /* register accepts only 32byte aligned values, only bits 31..5 are valid */
op_addr += __SCB_DCACHE_LINE_SIZE;
op_size -= __SCB_DCACHE_LINE_SIZE;
} while ( op_size > 0 );
__DSB();
__ISB();
}
#endif
}
/**
\brief D-Cache Clean by address
\details Cleans D-Cache for the given address
D-Cache is cleaned starting from a 32 byte aligned address in 32 byte granularity.
D-Cache memory blocks which are part of given address + given size are cleaned.
\param[in] addr address
\param[in] dsize size of memory block (in number of bytes)
*/
__STATIC_FORCEINLINE void SCB_CleanDCache_by_Addr (volatile void *addr, int32_t dsize)
{
#if defined (__DCACHE_PRESENT) && (__DCACHE_PRESENT == 1U)
if ( dsize > 0 ) {
int32_t op_size = dsize + (((uint32_t)addr) & (__SCB_DCACHE_LINE_SIZE - 1U));
uint32_t op_addr = (uint32_t)addr /* & ~(__SCB_DCACHE_LINE_SIZE - 1U) */;
__DSB();
do {
SCB->DCCMVAC = op_addr; /* register accepts only 32byte aligned values, only bits 31..5 are valid */
op_addr += __SCB_DCACHE_LINE_SIZE;
op_size -= __SCB_DCACHE_LINE_SIZE;
} while ( op_size > 0 );
__DSB();
__ISB();
}
#endif
}
/**
\brief D-Cache Clean and Invalidate by address
\details Cleans and invalidates D_Cache for the given address
D-Cache is cleaned and invalidated starting from a 32 byte aligned address in 32 byte granularity.
D-Cache memory blocks which are part of given address + given size are cleaned and invalidated.
\param[in] addr address (aligned to 32-byte boundary)
\param[in] dsize size of memory block (in number of bytes)
*/
__STATIC_FORCEINLINE void SCB_CleanInvalidateDCache_by_Addr (volatile void *addr, int32_t dsize)
{
#if defined (__DCACHE_PRESENT) && (__DCACHE_PRESENT == 1U)
if ( dsize > 0 ) {
int32_t op_size = dsize + (((uint32_t)addr) & (__SCB_DCACHE_LINE_SIZE - 1U));
uint32_t op_addr = (uint32_t)addr /* & ~(__SCB_DCACHE_LINE_SIZE - 1U) */;
__DSB();
do {
SCB->DCCIMVAC = op_addr; /* register accepts only 32byte aligned values, only bits 31..5 are valid */
op_addr += __SCB_DCACHE_LINE_SIZE;
op_size -= __SCB_DCACHE_LINE_SIZE;
} while ( op_size > 0 );
__DSB();
__ISB();
}
#endif
}
/*@} end of CMSIS_Core_CacheFunctions */
#endif /* ARM_ARMV7M_CACHEL1_H */

View File

@ -0,0 +1,273 @@
/*
* Copyright (c) 2017-2020 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.
*/
/*
* CMSIS-Core(M) MPU API for Armv7-M MPU
*/
#ifndef ARM_MPU_ARMV7_H
#define ARM_MPU_ARMV7_H
#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
#define ARM_MPU_REGION_SIZE_32B ((uint8_t)0x04U) ///!< MPU Region Size 32 Bytes
#define ARM_MPU_REGION_SIZE_64B ((uint8_t)0x05U) ///!< MPU Region Size 64 Bytes
#define ARM_MPU_REGION_SIZE_128B ((uint8_t)0x06U) ///!< MPU Region Size 128 Bytes
#define ARM_MPU_REGION_SIZE_256B ((uint8_t)0x07U) ///!< MPU Region Size 256 Bytes
#define ARM_MPU_REGION_SIZE_512B ((uint8_t)0x08U) ///!< MPU Region Size 512 Bytes
#define ARM_MPU_REGION_SIZE_1KB ((uint8_t)0x09U) ///!< MPU Region Size 1 KByte
#define ARM_MPU_REGION_SIZE_2KB ((uint8_t)0x0AU) ///!< MPU Region Size 2 KBytes
#define ARM_MPU_REGION_SIZE_4KB ((uint8_t)0x0BU) ///!< MPU Region Size 4 KBytes
#define ARM_MPU_REGION_SIZE_8KB ((uint8_t)0x0CU) ///!< MPU Region Size 8 KBytes
#define ARM_MPU_REGION_SIZE_16KB ((uint8_t)0x0DU) ///!< MPU Region Size 16 KBytes
#define ARM_MPU_REGION_SIZE_32KB ((uint8_t)0x0EU) ///!< MPU Region Size 32 KBytes
#define ARM_MPU_REGION_SIZE_64KB ((uint8_t)0x0FU) ///!< MPU Region Size 64 KBytes
#define ARM_MPU_REGION_SIZE_128KB ((uint8_t)0x10U) ///!< MPU Region Size 128 KBytes
#define ARM_MPU_REGION_SIZE_256KB ((uint8_t)0x11U) ///!< MPU Region Size 256 KBytes
#define ARM_MPU_REGION_SIZE_512KB ((uint8_t)0x12U) ///!< MPU Region Size 512 KBytes
#define ARM_MPU_REGION_SIZE_1MB ((uint8_t)0x13U) ///!< MPU Region Size 1 MByte
#define ARM_MPU_REGION_SIZE_2MB ((uint8_t)0x14U) ///!< MPU Region Size 2 MBytes
#define ARM_MPU_REGION_SIZE_4MB ((uint8_t)0x15U) ///!< MPU Region Size 4 MBytes
#define ARM_MPU_REGION_SIZE_8MB ((uint8_t)0x16U) ///!< MPU Region Size 8 MBytes
#define ARM_MPU_REGION_SIZE_16MB ((uint8_t)0x17U) ///!< MPU Region Size 16 MBytes
#define ARM_MPU_REGION_SIZE_32MB ((uint8_t)0x18U) ///!< MPU Region Size 32 MBytes
#define ARM_MPU_REGION_SIZE_64MB ((uint8_t)0x19U) ///!< MPU Region Size 64 MBytes
#define ARM_MPU_REGION_SIZE_128MB ((uint8_t)0x1AU) ///!< MPU Region Size 128 MBytes
#define ARM_MPU_REGION_SIZE_256MB ((uint8_t)0x1BU) ///!< MPU Region Size 256 MBytes
#define ARM_MPU_REGION_SIZE_512MB ((uint8_t)0x1CU) ///!< MPU Region Size 512 MBytes
#define ARM_MPU_REGION_SIZE_1GB ((uint8_t)0x1DU) ///!< MPU Region Size 1 GByte
#define ARM_MPU_REGION_SIZE_2GB ((uint8_t)0x1EU) ///!< MPU Region Size 2 GBytes
#define ARM_MPU_REGION_SIZE_4GB ((uint8_t)0x1FU) ///!< MPU Region Size 4 GBytes
#define ARM_MPU_AP_NONE 0U ///!< MPU Access Permission no access
#define ARM_MPU_AP_PRIV 1U ///!< MPU Access Permission privileged access only
#define ARM_MPU_AP_URO 2U ///!< MPU Access Permission unprivileged access read-only
#define ARM_MPU_AP_FULL 3U ///!< MPU Access Permission full access
#define ARM_MPU_AP_PRO 5U ///!< MPU Access Permission privileged access read-only
#define ARM_MPU_AP_RO 6U ///!< MPU Access Permission read-only access
/** 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 Memory Access Attributes
*
* \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.
*/
#define ARM_MPU_ACCESS_(TypeExtField, IsShareable, IsCacheable, IsBufferable) \
((((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))
/**
* 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 AccessAttributes Memory access attribution, see \ref ARM_MPU_ACCESS_.
* \param SubRegionDisable Sub-region disable field.
* \param Size Region size of the region to be configured, for example 4K, 8K.
*/
#define ARM_MPU_RASR_EX(DisableExec, AccessPermission, AccessAttributes, SubRegionDisable, Size) \
((((DisableExec) << MPU_RASR_XN_Pos) & MPU_RASR_XN_Msk) | \
(((AccessPermission) << MPU_RASR_AP_Pos) & MPU_RASR_AP_Msk) | \
(((AccessAttributes) & (MPU_RASR_TEX_Msk | MPU_RASR_S_Msk | MPU_RASR_C_Msk | 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))))
/**
* 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) \
ARM_MPU_RASR_EX(DisableExec, AccessPermission, ARM_MPU_ACCESS_(TypeExtField, IsShareable, IsCacheable, IsBufferable), SubRegionDisable, Size)
/**
* MPU Memory Access Attribute for strongly ordered memory.
* - TEX: 000b
* - Shareable
* - Non-cacheable
* - Non-bufferable
*/
#define ARM_MPU_ACCESS_ORDERED ARM_MPU_ACCESS_(0U, 1U, 0U, 0U)
/**
* MPU Memory Access Attribute for device memory.
* - TEX: 000b (if shareable) or 010b (if non-shareable)
* - Shareable or non-shareable
* - Non-cacheable
* - Bufferable (if shareable) or non-bufferable (if non-shareable)
*
* \param IsShareable Configures the device memory as shareable or non-shareable.
*/
#define ARM_MPU_ACCESS_DEVICE(IsShareable) ((IsShareable) ? ARM_MPU_ACCESS_(0U, 1U, 0U, 1U) : ARM_MPU_ACCESS_(2U, 0U, 0U, 0U))
/**
* MPU Memory Access Attribute for normal memory.
* - TEX: 1BBb (reflecting outer cacheability rules)
* - Shareable or non-shareable
* - Cacheable or non-cacheable (reflecting inner cacheability rules)
* - Bufferable or non-bufferable (reflecting inner cacheability rules)
*
* \param OuterCp Configures the outer cache policy.
* \param InnerCp Configures the inner cache policy.
* \param IsShareable Configures the memory as shareable or non-shareable.
*/
#define ARM_MPU_ACCESS_NORMAL(OuterCp, InnerCp, IsShareable) ARM_MPU_ACCESS_((4U | (OuterCp)), IsShareable, ((InnerCp) >> 1U), ((InnerCp) & 1U))
/**
* MPU Memory Access Attribute non-cacheable policy.
*/
#define ARM_MPU_CACHEP_NOCACHE 0U
/**
* MPU Memory Access Attribute write-back, write and read allocate policy.
*/
#define ARM_MPU_CACHEP_WB_WRA 1U
/**
* MPU Memory Access Attribute write-through, no write allocate policy.
*/
#define ARM_MPU_CACHEP_WT_NWA 2U
/**
* MPU Memory Access Attribute write-back, no write allocate policy.
*/
#define ARM_MPU_CACHEP_WB_NWA 3U
/**
* 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)
{
__DMB();
MPU->CTRL = MPU_Control | MPU_CTRL_ENABLE_Msk;
#ifdef SCB_SHCSR_MEMFAULTENA_Msk
SCB->SHCSR |= SCB_SHCSR_MEMFAULTENA_Msk;
#endif
__DSB();
__ISB();
}
/** Disable the MPU.
*/
__STATIC_INLINE void ARM_MPU_Disable(void)
{
__DMB();
#ifdef SCB_SHCSR_MEMFAULTENA_Msk
SCB->SHCSR &= ~SCB_SHCSR_MEMFAULTENA_Msk;
#endif
MPU->CTRL &= ~MPU_CTRL_ENABLE_Msk;
__DSB();
__ISB();
}
/** 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 rasr Value for RASR 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 rasr Value for RASR 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;
}
/** Memcpy with strictly ordered memory access, e.g. used by code in ARM_MPU_Load().
* \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 ARM_MPU_OrderedMemcpy(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) {
ARM_MPU_OrderedMemcpy(&(MPU->RBAR), &(table->RBAR), MPU_TYPE_RALIASES*rowWordSize);
table += MPU_TYPE_RALIASES;
cnt -= MPU_TYPE_RALIASES;
}
ARM_MPU_OrderedMemcpy(&(MPU->RBAR), &(table->RBAR), cnt*rowWordSize);
}
#endif

View File

@ -0,0 +1,717 @@
/*
* Copyright (c) 2009-2023 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.
*/
/*
* CMSIS-Core(M) Compiler GCC Header File
*/
#ifndef __CMSIS_GCC_M_H
#define __CMSIS_GCC_M_H
#ifndef __CMSIS_GCC_H
#error "This file must not be included directly"
#endif
#include <arm_acle.h>
/* ######################### Startup and Lowlevel Init ######################## */
#ifndef __PROGRAM_START
/**
\brief Initializes data and bss sections
\details This default implementations initialized all data and additional bss
sections relying on .copy.table and .zero.table specified properly
in the used linker script.
*/
__STATIC_FORCEINLINE __NO_RETURN void __cmsis_start(void)
{
extern void _start(void) __NO_RETURN;
typedef struct __copy_table {
uint32_t const* src;
uint32_t* dest;
uint32_t wlen;
} __copy_table_t;
typedef struct __zero_table {
uint32_t* dest;
uint32_t wlen;
} __zero_table_t;
extern const __copy_table_t __copy_table_start__;
extern const __copy_table_t __copy_table_end__;
extern const __zero_table_t __zero_table_start__;
extern const __zero_table_t __zero_table_end__;
for (__copy_table_t const* pTable = &__copy_table_start__; pTable < &__copy_table_end__; ++pTable) {
for(uint32_t i=0u; i<pTable->wlen; ++i) {
pTable->dest[i] = pTable->src[i];
}
}
for (__zero_table_t const* pTable = &__zero_table_start__; pTable < &__zero_table_end__; ++pTable) {
for(uint32_t i=0u; i<pTable->wlen; ++i) {
pTable->dest[i] = 0u;
}
}
_start();
}
#define __PROGRAM_START __cmsis_start
#endif
#ifndef __INITIAL_SP
#define __INITIAL_SP __StackTop
#endif
#ifndef __STACK_LIMIT
#define __STACK_LIMIT __StackLimit
#endif
#ifndef __VECTOR_TABLE
#define __VECTOR_TABLE __Vectors
#endif
#ifndef __VECTOR_TABLE_ATTRIBUTE
#define __VECTOR_TABLE_ATTRIBUTE __attribute__((used, section(".vectors")))
#endif
#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3)
#ifndef __STACK_SEAL
#define __STACK_SEAL __StackSeal
#endif
#ifndef __TZ_STACK_SEAL_SIZE
#define __TZ_STACK_SEAL_SIZE 8U
#endif
#ifndef __TZ_STACK_SEAL_VALUE
#define __TZ_STACK_SEAL_VALUE 0xFEF5EDA5FEF5EDA5ULL
#endif
__STATIC_FORCEINLINE void __TZ_set_STACKSEAL_S (uint32_t* stackTop) {
*((uint64_t *)stackTop) = __TZ_STACK_SEAL_VALUE;
}
#endif
/* ########################### Core Function Access ########################### */
/** \ingroup CMSIS_Core_FunctionInterface
\defgroup CMSIS_Core_RegAccFunctions CMSIS Core Register Access Functions
@{
*/
/**
\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");
__ISB();
}
#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");
__ISB();
}
#endif
/**
\brief Get IPSR Register
\details Returns the content of the IPSR Register.
\return IPSR Register value
*/
__STATIC_FORCEINLINE uint32_t __get_IPSR(void)
{
uint32_t result;
__ASM volatile ("MRS %0, ipsr" : "=r" (result) );
return (result);
}
/**
\brief Get APSR Register
\details Returns the content of the APSR Register.
\return APSR Register value
*/
__STATIC_FORCEINLINE uint32_t __get_APSR(void)
{
uint32_t result;
__ASM volatile ("MRS %0, apsr" : "=r" (result) );
return (result);
}
/**
\brief Get xPSR Register
\details Returns the content of the xPSR Register.
\return xPSR Register value
*/
__STATIC_FORCEINLINE uint32_t __get_xPSR(void)
{
uint32_t result;
__ASM volatile ("MRS %0, xpsr" : "=r" (result) );
return (result);
}
/**
\brief Get Process Stack Pointer
\details Returns the current value of the Process Stack Pointer (PSP).
\return PSP Register value
*/
__STATIC_FORCEINLINE uint32_t __get_PSP(void)
{
uint32_t result;
__ASM volatile ("MRS %0, psp" : "=r" (result) );
return (result);
}
#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3)
/**
\brief Get Process Stack Pointer (non-secure)
\details Returns the current value of the non-secure Process Stack Pointer (PSP) when in secure state.
\return PSP Register value
*/
__STATIC_FORCEINLINE uint32_t __TZ_get_PSP_NS(void)
{
uint32_t result;
__ASM volatile ("MRS %0, psp_ns" : "=r" (result) );
return (result);
}
#endif
/**
\brief Set Process Stack Pointer
\details Assigns the given value to the Process Stack Pointer (PSP).
\param [in] topOfProcStack Process Stack Pointer value to set
*/
__STATIC_FORCEINLINE void __set_PSP(uint32_t topOfProcStack)
{
__ASM volatile ("MSR psp, %0" : : "r" (topOfProcStack) : );
}
#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3)
/**
\brief Set Process Stack Pointer (non-secure)
\details Assigns the given value to the non-secure Process Stack Pointer (PSP) when in secure state.
\param [in] topOfProcStack Process Stack Pointer value to set
*/
__STATIC_FORCEINLINE void __TZ_set_PSP_NS(uint32_t topOfProcStack)
{
__ASM volatile ("MSR psp_ns, %0" : : "r" (topOfProcStack) : );
}
#endif
/**
\brief Get Main Stack Pointer
\details Returns the current value of the Main Stack Pointer (MSP).
\return MSP Register value
*/
__STATIC_FORCEINLINE uint32_t __get_MSP(void)
{
uint32_t result;
__ASM volatile ("MRS %0, msp" : "=r" (result) );
return (result);
}
#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3)
/**
\brief Get Main Stack Pointer (non-secure)
\details Returns the current value of the non-secure Main Stack Pointer (MSP) when in secure state.
\return MSP Register value
*/
__STATIC_FORCEINLINE uint32_t __TZ_get_MSP_NS(void)
{
uint32_t result;
__ASM volatile ("MRS %0, msp_ns" : "=r" (result) );
return (result);
}
#endif
/**
\brief Set Main Stack Pointer
\details Assigns the given value to the Main Stack Pointer (MSP).
\param [in] topOfMainStack Main Stack Pointer value to set
*/
__STATIC_FORCEINLINE void __set_MSP(uint32_t topOfMainStack)
{
__ASM volatile ("MSR msp, %0" : : "r" (topOfMainStack) : );
}
#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3)
/**
\brief Set Main Stack Pointer (non-secure)
\details Assigns the given value to the non-secure Main Stack Pointer (MSP) when in secure state.
\param [in] topOfMainStack Main Stack Pointer value to set
*/
__STATIC_FORCEINLINE void __TZ_set_MSP_NS(uint32_t topOfMainStack)
{
__ASM volatile ("MSR msp_ns, %0" : : "r" (topOfMainStack) : );
}
#endif
#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3)
/**
\brief Get Stack Pointer (non-secure)
\details Returns the current value of the non-secure Stack Pointer (SP) when in secure state.
\return SP Register value
*/
__STATIC_FORCEINLINE uint32_t __TZ_get_SP_NS(void)
{
uint32_t result;
__ASM volatile ("MRS %0, sp_ns" : "=r" (result) );
return (result);
}
/**
\brief Set Stack Pointer (non-secure)
\details Assigns the given value to the non-secure Stack Pointer (SP) when in secure state.
\param [in] topOfStack Stack Pointer value to set
*/
__STATIC_FORCEINLINE void __TZ_set_SP_NS(uint32_t topOfStack)
{
__ASM volatile ("MSR sp_ns, %0" : : "r" (topOfStack) : );
}
#endif
/**
\brief Get Priority Mask
\details Returns the current state of the priority mask bit from the Priority Mask Register.
\return Priority Mask value
*/
__STATIC_FORCEINLINE uint32_t __get_PRIMASK(void)
{
uint32_t result;
__ASM volatile ("MRS %0, primask" : "=r" (result) );
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 (__ARM_ARCH_ISA_THUMB >= 2)
/**
\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 /* (__ARM_ARCH_ISA_THUMB >= 2) */
#if (__ARM_ARCH >= 8)
/**
\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_ARCH_8_1M_MAIN__ ) && (__ARM_ARCH_8_1M_MAIN__ == 1)) && \
(!defined (__ARM_FEATURE_CMSE ) || (__ARM_FEATURE_CMSE < 3)))
/* without main extensions, the non-secure PSPLIM is RAZ/WI */
return (0U);
#else
uint32_t result;
__ASM volatile ("MRS %0, psplim" : "=r" (result) );
return (result);
#endif
}
#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3)
/**
\brief Get Process Stack Pointer Limit (non-secure)
Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure
Stack Pointer Limit register hence zero is returned always.
\details Returns the current value of the non-secure Process Stack Pointer Limit (PSPLIM) when in secure state.
\return PSPLIM Register value
*/
__STATIC_FORCEINLINE uint32_t __TZ_get_PSPLIM_NS(void)
{
#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \
!(defined (__ARM_ARCH_8_1M_MAIN__ ) && (__ARM_ARCH_8_1M_MAIN__ == 1)))
/* without main extensions, the non-secure PSPLIM is RAZ/WI */
return (0U);
#else
uint32_t result;
__ASM volatile ("MRS %0, psplim_ns" : "=r" (result) );
return (result);
#endif
}
#endif
/**
\brief Set Process Stack Pointer Limit
Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure
Stack Pointer Limit register hence the write is silently ignored in non-secure
mode.
\details Assigns the given value to the Process Stack Pointer Limit (PSPLIM).
\param [in] ProcStackPtrLimit Process Stack Pointer Limit value to set
*/
__STATIC_FORCEINLINE void __set_PSPLIM(uint32_t ProcStackPtrLimit)
{
#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \
!(defined (__ARM_ARCH_8_1M_MAIN__ ) && (__ARM_ARCH_8_1M_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)) && \
!(defined (__ARM_ARCH_8_1M_MAIN__ ) && (__ARM_ARCH_8_1M_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_ARCH_8_1M_MAIN__ ) && (__ARM_ARCH_8_1M_MAIN__ == 1)) && \
(!defined (__ARM_FEATURE_CMSE ) || (__ARM_FEATURE_CMSE < 3)))
/* without main extensions, the non-secure MSPLIM is RAZ/WI */
return (0U);
#else
uint32_t result;
__ASM volatile ("MRS %0, msplim" : "=r" (result) );
return (result);
#endif
}
#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3)
/**
\brief Get Main Stack Pointer Limit (non-secure)
Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure
Stack Pointer Limit register hence zero is returned always.
\details Returns the current value of the non-secure Main Stack Pointer Limit(MSPLIM) when in secure state.
\return MSPLIM Register value
*/
__STATIC_FORCEINLINE uint32_t __TZ_get_MSPLIM_NS(void)
{
#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \
!(defined (__ARM_ARCH_8_1M_MAIN__ ) && (__ARM_ARCH_8_1M_MAIN__ == 1)))
/* without main extensions, the non-secure MSPLIM is RAZ/WI */
return (0U);
#else
uint32_t result;
__ASM volatile ("MRS %0, msplim_ns" : "=r" (result) );
return (result);
#endif
}
#endif
/**
\brief Set Main Stack Pointer Limit
Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure
Stack Pointer Limit register hence the write is silently ignored.
\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_ARCH_8_1M_MAIN__ ) && (__ARM_ARCH_8_1M_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)) && \
!(defined (__ARM_ARCH_8_1M_MAIN__ ) && (__ARM_ARCH_8_1M_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 /* (__ARM_ARCH >= 8) */
/*@} end of CMSIS_Core_RegAccFunctions */
#endif /* __CMSIS_GCC_M_H */

View File

@ -0,0 +1,7 @@
menuconfig BSP_USING_LPUART
bool "Using UART device"
default y
select RESOURCES_SERIAL
if BSP_USING_LPUART
source "$BSP_DIR/third_party_driver/uart/Kconfig"
endif

View File

@ -0,0 +1,7 @@
SRC_DIR := common
ifeq ($(CONFIG_BSP_USING_LPUART),y)
SRC_DIR += uart
endif
include $(KERNEL_ROOT)/compiler.mk

View File

@ -0,0 +1,3 @@
SRC_FILES := system_MIMXRT1062.c fsl_cache.c fsl_clock.c fsl_common.c pin_mux.c clock_config.c fsl_gpio.c fsl_lpuart.c
include $(KERNEL_ROOT)/compiler.mk

View File

@ -0,0 +1,956 @@
/*
* How to setup clock using clock driver functions:
*
* 1. Call CLOCK_InitXXXPLL() to configure corresponding PLL clock.
*
* 2. Call CLOCK_InitXXXpfd() to configure corresponding PLL pfd clock.
*
* 3. Call CLOCK_SetMux() to configure corresponding clock source for target clock out.
*
* 4. Call CLOCK_SetDiv() to configure corresponding clock divider for target clock out.
*
* 5. Call CLOCK_SetXtalFreq() to set XTAL frequency based on board settings.
*
*/
/* TEXT BELOW IS USED AS SETTING FOR TOOLS *************************************
!!GlobalInfo
product: Clocks v16.0
processor: MIMXRT1062xxxxB
package_id: MIMXRT1062DVL6B
mcu_data: ksdk2_0
processor_version: 25.03.10
board: MIMXRT1060-EVKB
* BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR TOOLS **********/
#include "clock_config.h"
#include "fsl_iomuxc.h"
/*******************************************************************************
* Definitions
******************************************************************************/
/*******************************************************************************
* Variables
******************************************************************************/
/*******************************************************************************
************************ BOARD_InitBootClocks function ************************
******************************************************************************/
void BOARD_InitBootClocks(void)
{
BOARD_BootClockRUN();
}
/*******************************************************************************
********************** Configuration BOARD_BootClockRUN ***********************
******************************************************************************/
/* TEXT BELOW IS USED AS SETTING FOR TOOLS *************************************
!!Configuration
name: BOARD_BootClockRUN
called_from_default_init: true
outputs:
- {id: AHB_CLK_ROOT.outFreq, value: 600 MHz}
- {id: CAN_CLK_ROOT.outFreq, value: 40 MHz}
- {id: CKIL_SYNC_CLK_ROOT.outFreq, value: 32.768 kHz}
- {id: CLK_1M.outFreq, value: 1 MHz}
- {id: CLK_24M.outFreq, value: 24 MHz}
- {id: CSI_CLK_ROOT.outFreq, value: 12 MHz}
- {id: ENET2_125M_CLK.outFreq, value: 1.2 MHz}
- {id: ENET_125M_CLK.outFreq, value: 2.4 MHz}
- {id: ENET_25M_REF_CLK.outFreq, value: 1.2 MHz}
- {id: FLEXIO1_CLK_ROOT.outFreq, value: 30 MHz}
- {id: FLEXIO2_CLK_ROOT.outFreq, value: 30 MHz}
- {id: FLEXSPI2_CLK_ROOT.outFreq, value: 1440/11 MHz}
- {id: FLEXSPI_CLK_ROOT.outFreq, value: 1440/11 MHz}
- {id: GPT1_ipg_clk_highfreq.outFreq, value: 75 MHz}
- {id: GPT2_ipg_clk_highfreq.outFreq, value: 75 MHz}
- {id: IPG_CLK_ROOT.outFreq, value: 150 MHz}
- {id: LCDIF_CLK_ROOT.outFreq, value: 67.5 MHz}
- {id: LPI2C_CLK_ROOT.outFreq, value: 60 MHz}
- {id: LPSPI_CLK_ROOT.outFreq, value: 105.6 MHz}
- {id: LVDS1_CLK.outFreq, value: 1.2 GHz}
- {id: MQS_MCLK.outFreq, value: 1080/17 MHz}
- {id: PERCLK_CLK_ROOT.outFreq, value: 75 MHz}
- {id: PLL7_MAIN_CLK.outFreq, value: 24 MHz}
- {id: SAI1_CLK_ROOT.outFreq, value: 1080/17 MHz}
- {id: SAI1_MCLK1.outFreq, value: 1080/17 MHz}
- {id: SAI1_MCLK2.outFreq, value: 1080/17 MHz}
- {id: SAI1_MCLK3.outFreq, value: 30 MHz}
- {id: SAI2_CLK_ROOT.outFreq, value: 1080/17 MHz}
- {id: SAI2_MCLK1.outFreq, value: 1080/17 MHz}
- {id: SAI2_MCLK3.outFreq, value: 30 MHz}
- {id: SAI3_CLK_ROOT.outFreq, value: 1080/17 MHz}
- {id: SAI3_MCLK1.outFreq, value: 1080/17 MHz}
- {id: SAI3_MCLK3.outFreq, value: 30 MHz}
- {id: SEMC_CLK_ROOT.outFreq, value: 75 MHz}
- {id: SPDIF0_CLK_ROOT.outFreq, value: 30 MHz}
- {id: TRACE_CLK_ROOT.outFreq, value: 132 MHz}
- {id: UART_CLK_ROOT.outFreq, value: 80 MHz}
- {id: USDHC1_CLK_ROOT.outFreq, value: 198 MHz}
- {id: USDHC2_CLK_ROOT.outFreq, value: 198 MHz}
settings:
- {id: CCM.AHB_PODF.scale, value: '1', locked: true}
- {id: CCM.ARM_PODF.scale, value: '2', locked: true}
- {id: CCM.FLEXSPI2_PODF.scale, value: '2', locked: true}
- {id: CCM.FLEXSPI2_SEL.sel, value: CCM_ANALOG.PLL3_PFD0_CLK}
- {id: CCM.FLEXSPI_PODF.scale, value: '2', locked: true}
- {id: CCM.FLEXSPI_SEL.sel, value: CCM_ANALOG.PLL3_PFD0_CLK}
- {id: CCM.LCDIF_PODF.scale, value: '4', locked: true}
- {id: CCM.LCDIF_PRED.scale, value: '2', locked: true}
- {id: CCM.LPSPI_PODF.scale, value: '5', locked: true}
- {id: CCM.PERCLK_PODF.scale, value: '2', locked: true}
- {id: CCM.SEMC_PODF.scale, value: '8'}
- {id: CCM.TRACE_CLK_SEL.sel, value: CCM_ANALOG.PLL2_MAIN_CLK}
- {id: CCM.TRACE_PODF.scale, value: '4', locked: true}
- {id: CCM_ANALOG.PLL1_BYPASS.sel, value: CCM_ANALOG.PLL1}
- {id: CCM_ANALOG.PLL1_PREDIV.scale, value: '1', locked: true}
- {id: CCM_ANALOG.PLL1_VDIV.scale, value: '50', locked: true}
- {id: CCM_ANALOG.PLL2.denom, value: '1', locked: true}
- {id: CCM_ANALOG.PLL2.num, value: '0', locked: true}
- {id: CCM_ANALOG.PLL2_BYPASS.sel, value: CCM_ANALOG.PLL2_OUT_CLK}
- {id: CCM_ANALOG.PLL2_PFD0_BYPASS.sel, value: CCM_ANALOG.PLL2_PFD0}
- {id: CCM_ANALOG.PLL2_PFD1_BYPASS.sel, value: CCM_ANALOG.PLL2_PFD1}
- {id: CCM_ANALOG.PLL2_PFD2_BYPASS.sel, value: CCM_ANALOG.PLL2_PFD2}
- {id: CCM_ANALOG.PLL2_PFD3_BYPASS.sel, value: CCM_ANALOG.PLL2_PFD3}
- {id: CCM_ANALOG.PLL3_BYPASS.sel, value: CCM_ANALOG.PLL3}
- {id: CCM_ANALOG.PLL3_PFD0_BYPASS.sel, value: CCM_ANALOG.PLL3_PFD0}
- {id: CCM_ANALOG.PLL3_PFD0_DIV.scale, value: '33', locked: true}
- {id: CCM_ANALOG.PLL3_PFD0_MUL.scale, value: '18', locked: true}
- {id: CCM_ANALOG.PLL3_PFD1_BYPASS.sel, value: CCM_ANALOG.PLL3_PFD1}
- {id: CCM_ANALOG.PLL3_PFD2_BYPASS.sel, value: CCM_ANALOG.PLL3_PFD2}
- {id: CCM_ANALOG.PLL3_PFD3_BYPASS.sel, value: CCM_ANALOG.PLL3_PFD3}
- {id: CCM_ANALOG.PLL4.denom, value: '50'}
- {id: CCM_ANALOG.PLL4.div, value: '47'}
- {id: CCM_ANALOG.PLL5.denom, value: '1'}
- {id: CCM_ANALOG.PLL5.div, value: '31', locked: true}
- {id: CCM_ANALOG.PLL5.num, value: '0'}
- {id: CCM_ANALOG.PLL5_BYPASS.sel, value: CCM_ANALOG.PLL5_POST_DIV}
- {id: CCM_ANALOG.PLL5_POST_DIV.scale, value: '2', locked: true}
- {id: CCM_ANALOG.VIDEO_DIV.scale, value: '4', locked: true}
- {id: CCM_ANALOG_PLL_ENET_POWERDOWN_CFG, value: 'Yes'}
- {id: CCM_ANALOG_PLL_USB1_POWER_CFG, value: 'Yes'}
- {id: CCM_ANALOG_PLL_VIDEO_POWERDOWN_CFG, value: 'No'}
sources:
- {id: XTALOSC24M.RTC_OSC.outFreq, value: 32.768 kHz, enabled: true}
* BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR TOOLS **********/
/*******************************************************************************
* Variables for BOARD_BootClockRUN configuration
******************************************************************************/
const clock_arm_pll_config_t armPllConfig_BOARD_BootClockRUN =
{
.loopDivider = 100, /* PLL loop divider, Fout = Fin * 50 */
.src = 0, /* Bypass clock source, 0 - OSC 24M, 1 - CLK1_P and CLK1_N */
};
const clock_sys_pll_config_t sysPllConfig_BOARD_BootClockRUN =
{
.loopDivider = 1, /* PLL loop divider, Fout = Fin * ( 20 + loopDivider*2 + numerator / denominator ) */
.numerator = 0, /* 30 bit numerator of fractional loop divider */
.denominator = 1, /* 30 bit denominator of fractional loop divider */
.src = 0, /* Bypass clock source, 0 - OSC 24M, 1 - CLK1_P and CLK1_N */
};
const clock_usb_pll_config_t usb1PllConfig_BOARD_BootClockRUN =
{
.loopDivider = 0, /* PLL loop divider, Fout = Fin * 20 */
.src = 0, /* Bypass clock source, 0 - OSC 24M, 1 - CLK1_P and CLK1_N */
};
const clock_video_pll_config_t videoPllConfig_BOARD_BootClockRUN =
{
.loopDivider = 31, /* PLL loop divider, Fout = Fin * ( loopDivider + numerator / denominator ) */
.postDivider = 8, /* Divider after PLL */
.numerator = 0, /* 30 bit numerator of fractional loop divider, Fout = Fin * ( loopDivider + numerator / denominator ) */
.denominator = 1, /* 30 bit denominator of fractional loop divider, Fout = Fin * ( loopDivider + numerator / denominator ) */
.src = 0, /* Bypass clock source, 0 - OSC 24M, 1 - CLK1_P and CLK1_N */
};
/*******************************************************************************
* Code for BOARD_BootClockRUN configuration
******************************************************************************/
void BOARD_BootClockRUN(void)
{
/* Init RTC OSC clock frequency. */
CLOCK_SetRtcXtalFreq(32768U);
/* Enable 1MHz clock output. */
XTALOSC24M->OSC_CONFIG2 |= XTALOSC24M_OSC_CONFIG2_ENABLE_1M_MASK;
/* Use free 1MHz clock output. */
XTALOSC24M->OSC_CONFIG2 &= ~XTALOSC24M_OSC_CONFIG2_MUX_1M_MASK;
/* Set XTAL 24MHz clock frequency. */
CLOCK_SetXtalFreq(24000000U);
/* Enable XTAL 24MHz clock source. */
CLOCK_InitExternalClk(0);
/* Enable internal RC. */
CLOCK_InitRcOsc24M();
/* Switch clock source to external OSC. */
CLOCK_SwitchOsc(kCLOCK_XtalOsc);
/* Set Oscillator ready counter value. */
CCM->CCR = (CCM->CCR & (~CCM_CCR_OSCNT_MASK)) | CCM_CCR_OSCNT(127);
/* Setting PeriphClk2Mux and PeriphMux to provide stable clock before PLLs are initialed */
CLOCK_SetMux(kCLOCK_PeriphClk2Mux, 1); /* Set PERIPH_CLK2 MUX to OSC */
CLOCK_SetMux(kCLOCK_PeriphMux, 1); /* Set PERIPH_CLK MUX to PERIPH_CLK2 */
/* Setting the VDD_SOC to 1.275V. It is necessary to config AHB to 600Mhz. */
DCDC->REG3 = (DCDC->REG3 & (~DCDC_REG3_TRG_MASK)) | DCDC_REG3_TRG(0x13);
/* Waiting for DCDC_STS_DC_OK bit is asserted */
while (DCDC_REG0_STS_DC_OK_MASK != (DCDC_REG0_STS_DC_OK_MASK & DCDC->REG0))
{
}
/* Set AHB_PODF. */
CLOCK_SetDiv(kCLOCK_AhbDiv, 0);
/* Disable IPG clock gate. */
CLOCK_DisableClock(kCLOCK_Adc1);
CLOCK_DisableClock(kCLOCK_Adc2);
CLOCK_DisableClock(kCLOCK_Xbar1);
CLOCK_DisableClock(kCLOCK_Xbar2);
CLOCK_DisableClock(kCLOCK_Xbar3);
/* Set IPG_PODF. */
CLOCK_SetDiv(kCLOCK_IpgDiv, 3);
/* Set ARM_PODF. */
CLOCK_SetDiv(kCLOCK_ArmDiv, 1);
/* Set PERIPH_CLK2_PODF. */
CLOCK_SetDiv(kCLOCK_PeriphClk2Div, 0);
/* Disable PERCLK clock gate. */
CLOCK_DisableClock(kCLOCK_Gpt1);
CLOCK_DisableClock(kCLOCK_Gpt1S);
CLOCK_DisableClock(kCLOCK_Gpt2);
CLOCK_DisableClock(kCLOCK_Gpt2S);
CLOCK_DisableClock(kCLOCK_Pit);
/* Set PERCLK_PODF. */
CLOCK_SetDiv(kCLOCK_PerclkDiv, 1);
/* Disable USDHC1 clock gate. */
CLOCK_DisableClock(kCLOCK_Usdhc1);
/* Set USDHC1_PODF. */
CLOCK_SetDiv(kCLOCK_Usdhc1Div, 1);
/* Set Usdhc1 clock source. */
CLOCK_SetMux(kCLOCK_Usdhc1Mux, 0);
/* Disable USDHC2 clock gate. */
CLOCK_DisableClock(kCLOCK_Usdhc2);
/* Set USDHC2_PODF. */
CLOCK_SetDiv(kCLOCK_Usdhc2Div, 1);
/* Set Usdhc2 clock source. */
CLOCK_SetMux(kCLOCK_Usdhc2Mux, 0);
/* In SDK projects, SDRAM (configured by SEMC) will be initialized in either debug script or dcd.
* With this macro SKIP_SYSCLK_INIT, system pll (selected to be SEMC source clock in SDK projects) will be left unchanged.
* Note: If another clock source is selected for SEMC, user may want to avoid changing that clock as well.*/
#ifndef SKIP_SYSCLK_INIT
/* Disable Semc clock gate. */
CLOCK_DisableClock(kCLOCK_Semc);
/* Set SEMC_PODF. */
CLOCK_SetDiv(kCLOCK_SemcDiv, 7);
/* Set Semc alt clock source. */
CLOCK_SetMux(kCLOCK_SemcAltMux, 0);
/* Set Semc clock source. */
CLOCK_SetMux(kCLOCK_SemcMux, 0);
#endif
/* In SDK projects, external flash (configured by FLEXSPI) will be initialized by dcd.
* With this macro XIP_EXTERNAL_FLASH, usb1 pll (selected to be FLEXSPI clock source in SDK projects) will be left unchanged.
* Note: If another clock source is selected for FLEXSPI, user may want to avoid changing that clock as well.*/
#if !(defined(XIP_EXTERNAL_FLASH) && (XIP_EXTERNAL_FLASH == 1))
/* Disable Flexspi clock gate. */
CLOCK_DisableClock(kCLOCK_FlexSpi);
/* Set FLEXSPI_PODF. */
CLOCK_SetDiv(kCLOCK_FlexspiDiv, 1);
/* Set Flexspi clock source. */
CLOCK_SetMux(kCLOCK_FlexspiMux, 3);
#endif
/* Disable Flexspi2 clock gate. */
CLOCK_DisableClock(kCLOCK_FlexSpi2);
/* Set FLEXSPI2_PODF. */
CLOCK_SetDiv(kCLOCK_Flexspi2Div, 1);
/* Set Flexspi2 clock source. */
CLOCK_SetMux(kCLOCK_Flexspi2Mux, 1);
/* Disable CSI clock gate. */
CLOCK_DisableClock(kCLOCK_Csi);
/* Set CSI_PODF. */
CLOCK_SetDiv(kCLOCK_CsiDiv, 1);
/* Set Csi clock source. */
CLOCK_SetMux(kCLOCK_CsiMux, 0);
/* Disable LPSPI clock gate. */
CLOCK_DisableClock(kCLOCK_Lpspi1);
CLOCK_DisableClock(kCLOCK_Lpspi2);
CLOCK_DisableClock(kCLOCK_Lpspi3);
CLOCK_DisableClock(kCLOCK_Lpspi4);
/* Set LPSPI_PODF. */
CLOCK_SetDiv(kCLOCK_LpspiDiv, 4);
/* Set Lpspi clock source. */
CLOCK_SetMux(kCLOCK_LpspiMux, 2);
/* Disable TRACE clock gate. */
CLOCK_DisableClock(kCLOCK_Trace);
/* Set TRACE_PODF. */
CLOCK_SetDiv(kCLOCK_TraceDiv, 3);
/* Set Trace clock source. */
CLOCK_SetMux(kCLOCK_TraceMux, 0);
/* Disable SAI1 clock gate. */
CLOCK_DisableClock(kCLOCK_Sai1);
/* Set SAI1_CLK_PRED. */
CLOCK_SetDiv(kCLOCK_Sai1PreDiv, 3);
/* Set SAI1_CLK_PODF. */
CLOCK_SetDiv(kCLOCK_Sai1Div, 1);
/* Set Sai1 clock source. */
CLOCK_SetMux(kCLOCK_Sai1Mux, 0);
/* Disable SAI2 clock gate. */
CLOCK_DisableClock(kCLOCK_Sai2);
/* Set SAI2_CLK_PRED. */
CLOCK_SetDiv(kCLOCK_Sai2PreDiv, 3);
/* Set SAI2_CLK_PODF. */
CLOCK_SetDiv(kCLOCK_Sai2Div, 1);
/* Set Sai2 clock source. */
CLOCK_SetMux(kCLOCK_Sai2Mux, 0);
/* Disable SAI3 clock gate. */
CLOCK_DisableClock(kCLOCK_Sai3);
/* Set SAI3_CLK_PRED. */
CLOCK_SetDiv(kCLOCK_Sai3PreDiv, 3);
/* Set SAI3_CLK_PODF. */
CLOCK_SetDiv(kCLOCK_Sai3Div, 1);
/* Set Sai3 clock source. */
CLOCK_SetMux(kCLOCK_Sai3Mux, 0);
/* Disable Lpi2c clock gate. */
CLOCK_DisableClock(kCLOCK_Lpi2c1);
CLOCK_DisableClock(kCLOCK_Lpi2c2);
CLOCK_DisableClock(kCLOCK_Lpi2c3);
/* Set LPI2C_CLK_PODF. */
CLOCK_SetDiv(kCLOCK_Lpi2cDiv, 0);
/* Set Lpi2c clock source. */
CLOCK_SetMux(kCLOCK_Lpi2cMux, 0);
/* Disable CAN clock gate. */
CLOCK_DisableClock(kCLOCK_Can1);
CLOCK_DisableClock(kCLOCK_Can2);
CLOCK_DisableClock(kCLOCK_Can3);
CLOCK_DisableClock(kCLOCK_Can1S);
CLOCK_DisableClock(kCLOCK_Can2S);
CLOCK_DisableClock(kCLOCK_Can3S);
/* Set CAN_CLK_PODF. */
CLOCK_SetDiv(kCLOCK_CanDiv, 1);
/* Set Can clock source. */
CLOCK_SetMux(kCLOCK_CanMux, 2);
/* Disable UART clock gate. */
CLOCK_DisableClock(kCLOCK_Lpuart1);
CLOCK_DisableClock(kCLOCK_Lpuart2);
CLOCK_DisableClock(kCLOCK_Lpuart3);
CLOCK_DisableClock(kCLOCK_Lpuart4);
CLOCK_DisableClock(kCLOCK_Lpuart5);
CLOCK_DisableClock(kCLOCK_Lpuart6);
CLOCK_DisableClock(kCLOCK_Lpuart7);
CLOCK_DisableClock(kCLOCK_Lpuart8);
/* Set UART_CLK_PODF. */
CLOCK_SetDiv(kCLOCK_UartDiv, 0);
/* Set Uart clock source. */
CLOCK_SetMux(kCLOCK_UartMux, 0);
/* Disable LCDIF clock gate. */
CLOCK_DisableClock(kCLOCK_LcdPixel);
/* Set LCDIF_PRED. */
CLOCK_SetDiv(kCLOCK_LcdifPreDiv, 1);
/* Set LCDIF_CLK_PODF. */
CLOCK_SetDiv(kCLOCK_LcdifDiv, 3);
/* Set Lcdif pre clock source. */
CLOCK_SetMux(kCLOCK_LcdifPreMux, 5);
/* Disable SPDIF clock gate. */
CLOCK_DisableClock(kCLOCK_Spdif);
/* Set SPDIF0_CLK_PRED. */
CLOCK_SetDiv(kCLOCK_Spdif0PreDiv, 1);
/* Set SPDIF0_CLK_PODF. */
CLOCK_SetDiv(kCLOCK_Spdif0Div, 7);
/* Set Spdif clock source. */
CLOCK_SetMux(kCLOCK_SpdifMux, 3);
/* Disable Flexio1 clock gate. */
CLOCK_DisableClock(kCLOCK_Flexio1);
/* Set FLEXIO1_CLK_PRED. */
CLOCK_SetDiv(kCLOCK_Flexio1PreDiv, 1);
/* Set FLEXIO1_CLK_PODF. */
CLOCK_SetDiv(kCLOCK_Flexio1Div, 7);
/* Set Flexio1 clock source. */
CLOCK_SetMux(kCLOCK_Flexio1Mux, 3);
/* Disable Flexio2 clock gate. */
CLOCK_DisableClock(kCLOCK_Flexio2);
/* Set FLEXIO2_CLK_PRED. */
CLOCK_SetDiv(kCLOCK_Flexio2PreDiv, 1);
/* Set FLEXIO2_CLK_PODF. */
CLOCK_SetDiv(kCLOCK_Flexio2Div, 7);
/* Set Flexio2 clock source. */
CLOCK_SetMux(kCLOCK_Flexio2Mux, 3);
/* Set Pll3 sw clock source. */
CLOCK_SetMux(kCLOCK_Pll3SwMux, 0);
/* Init ARM PLL. */
CLOCK_InitArmPll(&armPllConfig_BOARD_BootClockRUN);
/* In SDK projects, SDRAM (configured by SEMC) will be initialized in either debug script or dcd.
* With this macro SKIP_SYSCLK_INIT, system pll (selected to be SEMC source clock in SDK projects) will be left unchanged.
* Note: If another clock source is selected for SEMC, user may want to avoid changing that clock as well.*/
#ifndef SKIP_SYSCLK_INIT
#if defined(XIP_BOOT_HEADER_DCD_ENABLE) && (XIP_BOOT_HEADER_DCD_ENABLE == 1)
#warning "SKIP_SYSCLK_INIT should be defined to keep system pll (selected to be SEMC source clock in SDK projects) unchanged."
#endif
/* Init System PLL. */
CLOCK_InitSysPll(&sysPllConfig_BOARD_BootClockRUN);
/* Init System pfd0. */
CLOCK_InitSysPfd(kCLOCK_Pfd0, 27);
/* Init System pfd1. */
CLOCK_InitSysPfd(kCLOCK_Pfd1, 16);
/* Init System pfd2. */
CLOCK_InitSysPfd(kCLOCK_Pfd2, 24);
/* Init System pfd3. */
CLOCK_InitSysPfd(kCLOCK_Pfd3, 16);
#endif
/* In SDK projects, external flash (configured by FLEXSPI) will be initialized by dcd.
* With this macro XIP_EXTERNAL_FLASH, usb1 pll (selected to be FLEXSPI clock source in SDK projects) will be left unchanged.
* Note: If another clock source is selected for FLEXSPI, user may want to avoid changing that clock as well.*/
#if !(defined(XIP_EXTERNAL_FLASH) && (XIP_EXTERNAL_FLASH == 1))
/* Init Usb1 PLL. */
CLOCK_InitUsb1Pll(&usb1PllConfig_BOARD_BootClockRUN);
/* Init Usb1 pfd0. */
CLOCK_InitUsb1Pfd(kCLOCK_Pfd0, 33);
/* Init Usb1 pfd1. */
CLOCK_InitUsb1Pfd(kCLOCK_Pfd1, 16);
/* Init Usb1 pfd2. */
CLOCK_InitUsb1Pfd(kCLOCK_Pfd2, 17);
/* Init Usb1 pfd3. */
CLOCK_InitUsb1Pfd(kCLOCK_Pfd3, 19);
/* Disable Usb1 PLL output for USBPHY1. */
CCM_ANALOG->PLL_USB1 &= ~CCM_ANALOG_PLL_USB1_EN_USB_CLKS_MASK;
#endif
/* DeInit Audio PLL. */
CLOCK_DeinitAudioPll();
/* Bypass Audio PLL. */
CLOCK_SetPllBypass(CCM_ANALOG, kCLOCK_PllAudio, 1);
/* Set divider for Audio PLL. */
CCM_ANALOG->MISC2 &= ~CCM_ANALOG_MISC2_AUDIO_DIV_LSB_MASK;
CCM_ANALOG->MISC2 &= ~CCM_ANALOG_MISC2_AUDIO_DIV_MSB_MASK;
/* Enable Audio PLL output. */
CCM_ANALOG->PLL_AUDIO |= CCM_ANALOG_PLL_AUDIO_ENABLE_MASK;
/* Init Video PLL. */
uint32_t pllVideo;
/* Disable Video PLL output before initial Video PLL. */
CCM_ANALOG->PLL_VIDEO &= ~CCM_ANALOG_PLL_VIDEO_ENABLE_MASK;
/* Bypass PLL first */
CCM_ANALOG->PLL_VIDEO = (CCM_ANALOG->PLL_VIDEO & (~CCM_ANALOG_PLL_VIDEO_BYPASS_CLK_SRC_MASK)) |
CCM_ANALOG_PLL_VIDEO_BYPASS_MASK | CCM_ANALOG_PLL_VIDEO_BYPASS_CLK_SRC(0);
CCM_ANALOG->PLL_VIDEO_NUM = CCM_ANALOG_PLL_VIDEO_NUM_A(0);
CCM_ANALOG->PLL_VIDEO_DENOM = CCM_ANALOG_PLL_VIDEO_DENOM_B(1);
pllVideo = (CCM_ANALOG->PLL_VIDEO & (~(CCM_ANALOG_PLL_VIDEO_DIV_SELECT_MASK | CCM_ANALOG_PLL_VIDEO_POWERDOWN_MASK))) |
CCM_ANALOG_PLL_VIDEO_ENABLE_MASK |CCM_ANALOG_PLL_VIDEO_DIV_SELECT(31);
pllVideo |= CCM_ANALOG_PLL_VIDEO_POST_DIV_SELECT(1);
CCM_ANALOG->MISC2 = (CCM_ANALOG->MISC2 & (~CCM_ANALOG_MISC2_VIDEO_DIV_MASK)) | CCM_ANALOG_MISC2_VIDEO_DIV(3);
CCM_ANALOG->PLL_VIDEO = pllVideo;
while ((CCM_ANALOG->PLL_VIDEO & CCM_ANALOG_PLL_VIDEO_LOCK_MASK) == 0)
{
}
/* Disable bypass for Video PLL. */
CLOCK_SetPllBypass(CCM_ANALOG, kCLOCK_PllVideo, 0);
/* DeInit Enet PLL. */
CLOCK_DeinitEnetPll();
/* Bypass Enet PLL. */
CLOCK_SetPllBypass(CCM_ANALOG, kCLOCK_PllEnet, 1);
/* Set Enet output divider. */
CCM_ANALOG->PLL_ENET = (CCM_ANALOG->PLL_ENET & (~CCM_ANALOG_PLL_ENET_DIV_SELECT_MASK)) | CCM_ANALOG_PLL_ENET_DIV_SELECT(1);
/* Enable Enet output. */
CCM_ANALOG->PLL_ENET |= CCM_ANALOG_PLL_ENET_ENABLE_MASK;
/* Set Enet2 output divider. */
CCM_ANALOG->PLL_ENET = (CCM_ANALOG->PLL_ENET & (~CCM_ANALOG_PLL_ENET_ENET2_DIV_SELECT_MASK)) | CCM_ANALOG_PLL_ENET_ENET2_DIV_SELECT(0);
/* Enable Enet2 output. */
CCM_ANALOG->PLL_ENET |= CCM_ANALOG_PLL_ENET_ENET2_REF_EN_MASK;
/* Enable Enet25M output. */
CCM_ANALOG->PLL_ENET |= CCM_ANALOG_PLL_ENET_ENET_25M_REF_EN_MASK;
/* DeInit Usb2 PLL. */
CLOCK_DeinitUsb2Pll();
/* Bypass Usb2 PLL. */
CLOCK_SetPllBypass(CCM_ANALOG, kCLOCK_PllUsb2, 1);
/* Enable Usb2 PLL output. */
CCM_ANALOG->PLL_USB2 |= CCM_ANALOG_PLL_USB2_ENABLE_MASK;
/* Set preperiph clock source. */
CLOCK_SetMux(kCLOCK_PrePeriphMux, 3);
/* Set periph clock source. */
CLOCK_SetMux(kCLOCK_PeriphMux, 0);
/* Set periph clock2 clock source. */
CLOCK_SetMux(kCLOCK_PeriphClk2Mux, 0);
/* Set per clock source. */
CLOCK_SetMux(kCLOCK_PerclkMux, 0);
/* Set lvds1 clock source. */
CCM_ANALOG->MISC1 = (CCM_ANALOG->MISC1 & (~CCM_ANALOG_MISC1_LVDS1_CLK_SEL_MASK)) | CCM_ANALOG_MISC1_LVDS1_CLK_SEL(0);
/* Set clock out1 divider. */
CCM->CCOSR = (CCM->CCOSR & (~CCM_CCOSR_CLKO1_DIV_MASK)) | CCM_CCOSR_CLKO1_DIV(0);
/* Set clock out1 source. */
CCM->CCOSR = (CCM->CCOSR & (~CCM_CCOSR_CLKO1_SEL_MASK)) | CCM_CCOSR_CLKO1_SEL(1);
/* Set clock out2 divider. */
CCM->CCOSR = (CCM->CCOSR & (~CCM_CCOSR_CLKO2_DIV_MASK)) | CCM_CCOSR_CLKO2_DIV(0);
/* Set clock out2 source. */
CCM->CCOSR = (CCM->CCOSR & (~CCM_CCOSR_CLKO2_SEL_MASK)) | CCM_CCOSR_CLKO2_SEL(18);
/* Set clock out1 drives clock out1. */
CCM->CCOSR &= ~CCM_CCOSR_CLK_OUT_SEL_MASK;
/* Disable clock out1. */
CCM->CCOSR &= ~CCM_CCOSR_CLKO1_EN_MASK;
/* Disable clock out2. */
CCM->CCOSR &= ~CCM_CCOSR_CLKO2_EN_MASK;
/* Set SAI1 MCLK1 clock source. */
IOMUXC_SetSaiMClkClockSource(IOMUXC_GPR, kIOMUXC_GPR_SAI1MClk1Sel, 0);
/* Set SAI1 MCLK2 clock source. */
IOMUXC_SetSaiMClkClockSource(IOMUXC_GPR, kIOMUXC_GPR_SAI1MClk2Sel, 0);
/* Set SAI1 MCLK3 clock source. */
IOMUXC_SetSaiMClkClockSource(IOMUXC_GPR, kIOMUXC_GPR_SAI1MClk3Sel, 0);
/* Set SAI2 MCLK3 clock source. */
IOMUXC_SetSaiMClkClockSource(IOMUXC_GPR, kIOMUXC_GPR_SAI2MClk3Sel, 0);
/* Set SAI3 MCLK3 clock source. */
IOMUXC_SetSaiMClkClockSource(IOMUXC_GPR, kIOMUXC_GPR_SAI3MClk3Sel, 0);
/* Set MQS configuration. */
IOMUXC_MQSConfig(IOMUXC_GPR,kIOMUXC_MqsPwmOverSampleRate32, 0);
/* Set ENET Ref clock source. */
IOMUXC_GPR->GPR1 &= ~IOMUXC_GPR_GPR1_ENET1_TX_CLK_DIR_MASK;
/* Set ENET2 Ref clock source. */
IOMUXC_GPR->GPR1 &= ~IOMUXC_GPR_GPR1_ENET2_TX_CLK_DIR_MASK;
/* Set GPT1 High frequency reference clock source. */
IOMUXC_GPR->GPR5 &= ~IOMUXC_GPR_GPR5_VREF_1M_CLK_GPT1_MASK;
/* Set GPT2 High frequency reference clock source. */
IOMUXC_GPR->GPR5 &= ~IOMUXC_GPR_GPR5_VREF_1M_CLK_GPT2_MASK;
/* Set SystemCoreClock variable. */
SystemCoreClock = BOARD_BOOTCLOCKRUN_CORE_CLOCK;
}
/*******************************************************************************
******************* Configuration BOARD_BootClockRUN_528M *********************
******************************************************************************/
/* TEXT BELOW IS USED AS SETTING FOR TOOLS *************************************
!!Configuration
name: BOARD_BootClockRUN_528M
outputs:
- {id: AHB_CLK_ROOT.outFreq, value: 528 MHz}
- {id: CAN_CLK_ROOT.outFreq, value: 40 MHz}
- {id: CKIL_SYNC_CLK_ROOT.outFreq, value: 32.768 kHz}
- {id: CLK_1M.outFreq, value: 1 MHz}
- {id: CLK_24M.outFreq, value: 24 MHz}
- {id: CSI_CLK_ROOT.outFreq, value: 12 MHz}
- {id: ENET2_125M_CLK.outFreq, value: 1.2 MHz}
- {id: ENET_125M_CLK.outFreq, value: 2.4 MHz}
- {id: ENET_25M_REF_CLK.outFreq, value: 1.2 MHz}
- {id: FLEXIO1_CLK_ROOT.outFreq, value: 30 MHz}
- {id: FLEXIO2_CLK_ROOT.outFreq, value: 30 MHz}
- {id: FLEXSPI2_CLK_ROOT.outFreq, value: 1440/11 MHz}
- {id: FLEXSPI_CLK_ROOT.outFreq, value: 1440/11 MHz}
- {id: GPT1_ipg_clk_highfreq.outFreq, value: 66 MHz}
- {id: GPT2_ipg_clk_highfreq.outFreq, value: 66 MHz}
- {id: IPG_CLK_ROOT.outFreq, value: 132 MHz}
- {id: LCDIF_CLK_ROOT.outFreq, value: 67.5 MHz}
- {id: LPI2C_CLK_ROOT.outFreq, value: 60 MHz}
- {id: LPSPI_CLK_ROOT.outFreq, value: 105.6 MHz}
- {id: LVDS1_CLK.outFreq, value: 1.2 GHz}
- {id: MQS_MCLK.outFreq, value: 1080/17 MHz}
- {id: PERCLK_CLK_ROOT.outFreq, value: 66 MHz}
- {id: PLL7_MAIN_CLK.outFreq, value: 24 MHz}
- {id: SAI1_CLK_ROOT.outFreq, value: 1080/17 MHz}
- {id: SAI1_MCLK1.outFreq, value: 1080/17 MHz}
- {id: SAI1_MCLK2.outFreq, value: 1080/17 MHz}
- {id: SAI1_MCLK3.outFreq, value: 30 MHz}
- {id: SAI2_CLK_ROOT.outFreq, value: 1080/17 MHz}
- {id: SAI2_MCLK1.outFreq, value: 1080/17 MHz}
- {id: SAI2_MCLK3.outFreq, value: 30 MHz}
- {id: SAI3_CLK_ROOT.outFreq, value: 1080/17 MHz}
- {id: SAI3_MCLK1.outFreq, value: 1080/17 MHz}
- {id: SAI3_MCLK3.outFreq, value: 30 MHz}
- {id: SEMC_CLK_ROOT.outFreq, value: 66 MHz}
- {id: SPDIF0_CLK_ROOT.outFreq, value: 30 MHz}
- {id: TRACE_CLK_ROOT.outFreq, value: 132 MHz}
- {id: UART_CLK_ROOT.outFreq, value: 80 MHz}
- {id: USDHC1_CLK_ROOT.outFreq, value: 198 MHz}
- {id: USDHC2_CLK_ROOT.outFreq, value: 198 MHz}
settings:
- {id: CCM.AHB_PODF.scale, value: '1', locked: true}
- {id: CCM.ARM_PODF.scale, value: '2', locked: true}
- {id: CCM.FLEXSPI2_PODF.scale, value: '2', locked: true}
- {id: CCM.FLEXSPI2_SEL.sel, value: CCM_ANALOG.PLL3_PFD0_CLK}
- {id: CCM.FLEXSPI_PODF.scale, value: '2', locked: true}
- {id: CCM.FLEXSPI_SEL.sel, value: CCM_ANALOG.PLL3_PFD0_CLK}
- {id: CCM.LCDIF_PODF.scale, value: '4', locked: true}
- {id: CCM.LCDIF_PRED.scale, value: '2', locked: true}
- {id: CCM.LPSPI_PODF.scale, value: '5', locked: true}
- {id: CCM.PERCLK_PODF.scale, value: '2', locked: true}
- {id: CCM.PRE_PERIPH_CLK_SEL.sel, value: CCM_ANALOG.PLL2_MAIN_CLK}
- {id: CCM.SEMC_PODF.scale, value: '8'}
- {id: CCM.TRACE_CLK_SEL.sel, value: CCM_ANALOG.PLL2_MAIN_CLK}
- {id: CCM.TRACE_PODF.scale, value: '4', locked: true}
- {id: CCM_ANALOG.PLL1_BYPASS.sel, value: CCM_ANALOG.PLL1}
- {id: CCM_ANALOG.PLL1_PREDIV.scale, value: '1', locked: true}
- {id: CCM_ANALOG.PLL1_VDIV.scale, value: '50', locked: true}
- {id: CCM_ANALOG.PLL2.denom, value: '1', locked: true}
- {id: CCM_ANALOG.PLL2.num, value: '0', locked: true}
- {id: CCM_ANALOG.PLL2_BYPASS.sel, value: CCM_ANALOG.PLL2_OUT_CLK}
- {id: CCM_ANALOG.PLL2_PFD0_BYPASS.sel, value: CCM_ANALOG.PLL2_PFD0}
- {id: CCM_ANALOG.PLL2_PFD1_BYPASS.sel, value: CCM_ANALOG.PLL2_PFD1}
- {id: CCM_ANALOG.PLL2_PFD2_BYPASS.sel, value: CCM_ANALOG.PLL2_PFD2}
- {id: CCM_ANALOG.PLL2_PFD3_BYPASS.sel, value: CCM_ANALOG.PLL2_PFD3}
- {id: CCM_ANALOG.PLL3_BYPASS.sel, value: CCM_ANALOG.PLL3}
- {id: CCM_ANALOG.PLL3_PFD0_BYPASS.sel, value: CCM_ANALOG.PLL3_PFD0}
- {id: CCM_ANALOG.PLL3_PFD0_DIV.scale, value: '33', locked: true}
- {id: CCM_ANALOG.PLL3_PFD0_MUL.scale, value: '18', locked: true}
- {id: CCM_ANALOG.PLL3_PFD1_BYPASS.sel, value: CCM_ANALOG.PLL3_PFD1}
- {id: CCM_ANALOG.PLL3_PFD2_BYPASS.sel, value: CCM_ANALOG.PLL3_PFD2}
- {id: CCM_ANALOG.PLL3_PFD3_BYPASS.sel, value: CCM_ANALOG.PLL3_PFD3}
- {id: CCM_ANALOG.PLL4.denom, value: '50'}
- {id: CCM_ANALOG.PLL4.div, value: '47'}
- {id: CCM_ANALOG.PLL5.denom, value: '1'}
- {id: CCM_ANALOG.PLL5.div, value: '31', locked: true}
- {id: CCM_ANALOG.PLL5.num, value: '0'}
- {id: CCM_ANALOG.PLL5_BYPASS.sel, value: CCM_ANALOG.PLL5_POST_DIV}
- {id: CCM_ANALOG.PLL5_POST_DIV.scale, value: '2', locked: true}
- {id: CCM_ANALOG.VIDEO_DIV.scale, value: '4', locked: true}
- {id: CCM_ANALOG_PLL_ENET_POWERDOWN_CFG, value: 'Yes'}
- {id: CCM_ANALOG_PLL_USB1_POWER_CFG, value: 'Yes'}
- {id: CCM_ANALOG_PLL_VIDEO_POWERDOWN_CFG, value: 'No'}
sources:
- {id: XTALOSC24M.RTC_OSC.outFreq, value: 32.768 kHz, enabled: true}
* BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR TOOLS **********/
/*******************************************************************************
* Variables for BOARD_BootClockRUN_528M configuration
******************************************************************************/
const clock_arm_pll_config_t armPllConfig_BOARD_BootClockRUN_528M =
{
.loopDivider = 100, /* PLL loop divider, Fout = Fin * 50 */
.src = 0, /* Bypass clock source, 0 - OSC 24M, 1 - CLK1_P and CLK1_N */
};
const clock_sys_pll_config_t sysPllConfig_BOARD_BootClockRUN_528M =
{
.loopDivider = 1, /* PLL loop divider, Fout = Fin * ( 20 + loopDivider*2 + numerator / denominator ) */
.numerator = 0, /* 30 bit numerator of fractional loop divider */
.denominator = 1, /* 30 bit denominator of fractional loop divider */
.src = 0, /* Bypass clock source, 0 - OSC 24M, 1 - CLK1_P and CLK1_N */
};
const clock_usb_pll_config_t usb1PllConfig_BOARD_BootClockRUN_528M =
{
.loopDivider = 0, /* PLL loop divider, Fout = Fin * 20 */
.src = 0, /* Bypass clock source, 0 - OSC 24M, 1 - CLK1_P and CLK1_N */
};
const clock_video_pll_config_t videoPllConfig_BOARD_BootClockRUN_528M =
{
.loopDivider = 31, /* PLL loop divider, Fout = Fin * ( loopDivider + numerator / denominator ) */
.postDivider = 8, /* Divider after PLL */
.numerator = 0, /* 30 bit numerator of fractional loop divider, Fout = Fin * ( loopDivider + numerator / denominator ) */
.denominator = 1, /* 30 bit denominator of fractional loop divider, Fout = Fin * ( loopDivider + numerator / denominator ) */
.src = 0, /* Bypass clock source, 0 - OSC 24M, 1 - CLK1_P and CLK1_N */
};
/*******************************************************************************
* Code for BOARD_BootClockRUN_528M configuration
******************************************************************************/
void BOARD_BootClockRUN_528M(void)
{
/* Init RTC OSC clock frequency. */
CLOCK_SetRtcXtalFreq(32768U);
/* Enable 1MHz clock output. */
XTALOSC24M->OSC_CONFIG2 |= XTALOSC24M_OSC_CONFIG2_ENABLE_1M_MASK;
/* Use free 1MHz clock output. */
XTALOSC24M->OSC_CONFIG2 &= ~XTALOSC24M_OSC_CONFIG2_MUX_1M_MASK;
/* Set XTAL 24MHz clock frequency. */
CLOCK_SetXtalFreq(24000000U);
/* Enable XTAL 24MHz clock source. */
CLOCK_InitExternalClk(0);
/* Enable internal RC. */
CLOCK_InitRcOsc24M();
/* Switch clock source to external OSC. */
CLOCK_SwitchOsc(kCLOCK_XtalOsc);
/* Set Oscillator ready counter value. */
CCM->CCR = (CCM->CCR & (~CCM_CCR_OSCNT_MASK)) | CCM_CCR_OSCNT(127);
/* Setting PeriphClk2Mux and PeriphMux to provide stable clock before PLLs are initialed */
CLOCK_SetMux(kCLOCK_PeriphClk2Mux, 1); /* Set PERIPH_CLK2 MUX to OSC */
CLOCK_SetMux(kCLOCK_PeriphMux, 1); /* Set PERIPH_CLK MUX to PERIPH_CLK2 */
/* Set AHB_PODF. */
CLOCK_SetDiv(kCLOCK_AhbDiv, 0);
/* Disable IPG clock gate. */
CLOCK_DisableClock(kCLOCK_Adc1);
CLOCK_DisableClock(kCLOCK_Adc2);
CLOCK_DisableClock(kCLOCK_Xbar1);
CLOCK_DisableClock(kCLOCK_Xbar2);
CLOCK_DisableClock(kCLOCK_Xbar3);
/* Set IPG_PODF. */
CLOCK_SetDiv(kCLOCK_IpgDiv, 3);
/* Set ARM_PODF. */
CLOCK_SetDiv(kCLOCK_ArmDiv, 1);
/* Set PERIPH_CLK2_PODF. */
CLOCK_SetDiv(kCLOCK_PeriphClk2Div, 0);
/* Disable PERCLK clock gate. */
CLOCK_DisableClock(kCLOCK_Gpt1);
CLOCK_DisableClock(kCLOCK_Gpt1S);
CLOCK_DisableClock(kCLOCK_Gpt2);
CLOCK_DisableClock(kCLOCK_Gpt2S);
CLOCK_DisableClock(kCLOCK_Pit);
/* Set PERCLK_PODF. */
CLOCK_SetDiv(kCLOCK_PerclkDiv, 1);
/* Disable USDHC1 clock gate. */
CLOCK_DisableClock(kCLOCK_Usdhc1);
/* Set USDHC1_PODF. */
CLOCK_SetDiv(kCLOCK_Usdhc1Div, 1);
/* Set Usdhc1 clock source. */
CLOCK_SetMux(kCLOCK_Usdhc1Mux, 0);
/* Disable USDHC2 clock gate. */
CLOCK_DisableClock(kCLOCK_Usdhc2);
/* Set USDHC2_PODF. */
CLOCK_SetDiv(kCLOCK_Usdhc2Div, 1);
/* Set Usdhc2 clock source. */
CLOCK_SetMux(kCLOCK_Usdhc2Mux, 0);
/* In SDK projects, SDRAM (configured by SEMC) will be initialized in either debug script or dcd.
* With this macro SKIP_SYSCLK_INIT, system pll (selected to be SEMC source clock in SDK projects) will be left unchanged.
* Note: If another clock source is selected for SEMC, user may want to avoid changing that clock as well.*/
#ifndef SKIP_SYSCLK_INIT
/* Disable Semc clock gate. */
CLOCK_DisableClock(kCLOCK_Semc);
/* Set SEMC_PODF. */
CLOCK_SetDiv(kCLOCK_SemcDiv, 7);
/* Set Semc alt clock source. */
CLOCK_SetMux(kCLOCK_SemcAltMux, 0);
/* Set Semc clock source. */
CLOCK_SetMux(kCLOCK_SemcMux, 0);
#endif
/* In SDK projects, external flash (configured by FLEXSPI) will be initialized by dcd.
* With this macro XIP_EXTERNAL_FLASH, usb1 pll (selected to be FLEXSPI clock source in SDK projects) will be left unchanged.
* Note: If another clock source is selected for FLEXSPI, user may want to avoid changing that clock as well.*/
#if !(defined(XIP_EXTERNAL_FLASH) && (XIP_EXTERNAL_FLASH == 1))
/* Disable Flexspi clock gate. */
CLOCK_DisableClock(kCLOCK_FlexSpi);
/* Set FLEXSPI_PODF. */
CLOCK_SetDiv(kCLOCK_FlexspiDiv, 1);
/* Set Flexspi clock source. */
CLOCK_SetMux(kCLOCK_FlexspiMux, 3);
#endif
/* Disable Flexspi2 clock gate. */
CLOCK_DisableClock(kCLOCK_FlexSpi2);
/* Set FLEXSPI2_PODF. */
CLOCK_SetDiv(kCLOCK_Flexspi2Div, 1);
/* Set Flexspi2 clock source. */
CLOCK_SetMux(kCLOCK_Flexspi2Mux, 1);
/* Disable CSI clock gate. */
CLOCK_DisableClock(kCLOCK_Csi);
/* Set CSI_PODF. */
CLOCK_SetDiv(kCLOCK_CsiDiv, 1);
/* Set Csi clock source. */
CLOCK_SetMux(kCLOCK_CsiMux, 0);
/* Disable LPSPI clock gate. */
CLOCK_DisableClock(kCLOCK_Lpspi1);
CLOCK_DisableClock(kCLOCK_Lpspi2);
CLOCK_DisableClock(kCLOCK_Lpspi3);
CLOCK_DisableClock(kCLOCK_Lpspi4);
/* Set LPSPI_PODF. */
CLOCK_SetDiv(kCLOCK_LpspiDiv, 4);
/* Set Lpspi clock source. */
CLOCK_SetMux(kCLOCK_LpspiMux, 2);
/* Disable TRACE clock gate. */
CLOCK_DisableClock(kCLOCK_Trace);
/* Set TRACE_PODF. */
CLOCK_SetDiv(kCLOCK_TraceDiv, 3);
/* Set Trace clock source. */
CLOCK_SetMux(kCLOCK_TraceMux, 0);
/* Disable SAI1 clock gate. */
CLOCK_DisableClock(kCLOCK_Sai1);
/* Set SAI1_CLK_PRED. */
CLOCK_SetDiv(kCLOCK_Sai1PreDiv, 3);
/* Set SAI1_CLK_PODF. */
CLOCK_SetDiv(kCLOCK_Sai1Div, 1);
/* Set Sai1 clock source. */
CLOCK_SetMux(kCLOCK_Sai1Mux, 0);
/* Disable SAI2 clock gate. */
CLOCK_DisableClock(kCLOCK_Sai2);
/* Set SAI2_CLK_PRED. */
CLOCK_SetDiv(kCLOCK_Sai2PreDiv, 3);
/* Set SAI2_CLK_PODF. */
CLOCK_SetDiv(kCLOCK_Sai2Div, 1);
/* Set Sai2 clock source. */
CLOCK_SetMux(kCLOCK_Sai2Mux, 0);
/* Disable SAI3 clock gate. */
CLOCK_DisableClock(kCLOCK_Sai3);
/* Set SAI3_CLK_PRED. */
CLOCK_SetDiv(kCLOCK_Sai3PreDiv, 3);
/* Set SAI3_CLK_PODF. */
CLOCK_SetDiv(kCLOCK_Sai3Div, 1);
/* Set Sai3 clock source. */
CLOCK_SetMux(kCLOCK_Sai3Mux, 0);
/* Disable Lpi2c clock gate. */
CLOCK_DisableClock(kCLOCK_Lpi2c1);
CLOCK_DisableClock(kCLOCK_Lpi2c2);
CLOCK_DisableClock(kCLOCK_Lpi2c3);
/* Set LPI2C_CLK_PODF. */
CLOCK_SetDiv(kCLOCK_Lpi2cDiv, 0);
/* Set Lpi2c clock source. */
CLOCK_SetMux(kCLOCK_Lpi2cMux, 0);
/* Disable CAN clock gate. */
CLOCK_DisableClock(kCLOCK_Can1);
CLOCK_DisableClock(kCLOCK_Can2);
CLOCK_DisableClock(kCLOCK_Can3);
CLOCK_DisableClock(kCLOCK_Can1S);
CLOCK_DisableClock(kCLOCK_Can2S);
CLOCK_DisableClock(kCLOCK_Can3S);
/* Set CAN_CLK_PODF. */
CLOCK_SetDiv(kCLOCK_CanDiv, 1);
/* Set Can clock source. */
CLOCK_SetMux(kCLOCK_CanMux, 2);
/* Disable UART clock gate. */
CLOCK_DisableClock(kCLOCK_Lpuart1);
CLOCK_DisableClock(kCLOCK_Lpuart2);
CLOCK_DisableClock(kCLOCK_Lpuart3);
CLOCK_DisableClock(kCLOCK_Lpuart4);
CLOCK_DisableClock(kCLOCK_Lpuart5);
CLOCK_DisableClock(kCLOCK_Lpuart6);
CLOCK_DisableClock(kCLOCK_Lpuart7);
CLOCK_DisableClock(kCLOCK_Lpuart8);
/* Set UART_CLK_PODF. */
CLOCK_SetDiv(kCLOCK_UartDiv, 0);
/* Set Uart clock source. */
CLOCK_SetMux(kCLOCK_UartMux, 0);
/* Disable LCDIF clock gate. */
CLOCK_DisableClock(kCLOCK_LcdPixel);
/* Set LCDIF_PRED. */
CLOCK_SetDiv(kCLOCK_LcdifPreDiv, 1);
/* Set LCDIF_CLK_PODF. */
CLOCK_SetDiv(kCLOCK_LcdifDiv, 3);
/* Set Lcdif pre clock source. */
CLOCK_SetMux(kCLOCK_LcdifPreMux, 5);
/* Disable SPDIF clock gate. */
CLOCK_DisableClock(kCLOCK_Spdif);
/* Set SPDIF0_CLK_PRED. */
CLOCK_SetDiv(kCLOCK_Spdif0PreDiv, 1);
/* Set SPDIF0_CLK_PODF. */
CLOCK_SetDiv(kCLOCK_Spdif0Div, 7);
/* Set Spdif clock source. */
CLOCK_SetMux(kCLOCK_SpdifMux, 3);
/* Disable Flexio1 clock gate. */
CLOCK_DisableClock(kCLOCK_Flexio1);
/* Set FLEXIO1_CLK_PRED. */
CLOCK_SetDiv(kCLOCK_Flexio1PreDiv, 1);
/* Set FLEXIO1_CLK_PODF. */
CLOCK_SetDiv(kCLOCK_Flexio1Div, 7);
/* Set Flexio1 clock source. */
CLOCK_SetMux(kCLOCK_Flexio1Mux, 3);
/* Disable Flexio2 clock gate. */
CLOCK_DisableClock(kCLOCK_Flexio2);
/* Set FLEXIO2_CLK_PRED. */
CLOCK_SetDiv(kCLOCK_Flexio2PreDiv, 1);
/* Set FLEXIO2_CLK_PODF. */
CLOCK_SetDiv(kCLOCK_Flexio2Div, 7);
/* Set Flexio2 clock source. */
CLOCK_SetMux(kCLOCK_Flexio2Mux, 3);
/* Set Pll3 sw clock source. */
CLOCK_SetMux(kCLOCK_Pll3SwMux, 0);
/* Init ARM PLL. */
CLOCK_InitArmPll(&armPllConfig_BOARD_BootClockRUN_528M);
/* In SDK projects, SDRAM (configured by SEMC) will be initialized in either debug script or dcd.
* With this macro SKIP_SYSCLK_INIT, system pll (selected to be SEMC source clock in SDK projects) will be left unchanged.
* Note: If another clock source is selected for SEMC, user may want to avoid changing that clock as well.*/
#ifndef SKIP_SYSCLK_INIT
#if defined(XIP_BOOT_HEADER_DCD_ENABLE) && (XIP_BOOT_HEADER_DCD_ENABLE == 1)
#warning "SKIP_SYSCLK_INIT should be defined to keep system pll (selected to be SEMC source clock in SDK projects) unchanged."
#endif
/* Init System PLL. */
CLOCK_InitSysPll(&sysPllConfig_BOARD_BootClockRUN_528M);
/* Init System pfd0. */
CLOCK_InitSysPfd(kCLOCK_Pfd0, 27);
/* Init System pfd1. */
CLOCK_InitSysPfd(kCLOCK_Pfd1, 16);
/* Init System pfd2. */
CLOCK_InitSysPfd(kCLOCK_Pfd2, 24);
/* Init System pfd3. */
CLOCK_InitSysPfd(kCLOCK_Pfd3, 16);
#endif
/* In SDK projects, external flash (configured by FLEXSPI) will be initialized by dcd.
* With this macro XIP_EXTERNAL_FLASH, usb1 pll (selected to be FLEXSPI clock source in SDK projects) will be left unchanged.
* Note: If another clock source is selected for FLEXSPI, user may want to avoid changing that clock as well.*/
#if !(defined(XIP_EXTERNAL_FLASH) && (XIP_EXTERNAL_FLASH == 1))
/* Init Usb1 PLL. */
CLOCK_InitUsb1Pll(&usb1PllConfig_BOARD_BootClockRUN_528M);
/* Init Usb1 pfd0. */
CLOCK_InitUsb1Pfd(kCLOCK_Pfd0, 33);
/* Init Usb1 pfd1. */
CLOCK_InitUsb1Pfd(kCLOCK_Pfd1, 16);
/* Init Usb1 pfd2. */
CLOCK_InitUsb1Pfd(kCLOCK_Pfd2, 17);
/* Init Usb1 pfd3. */
CLOCK_InitUsb1Pfd(kCLOCK_Pfd3, 19);
/* Disable Usb1 PLL output for USBPHY1. */
CCM_ANALOG->PLL_USB1 &= ~CCM_ANALOG_PLL_USB1_EN_USB_CLKS_MASK;
#endif
/* DeInit Audio PLL. */
CLOCK_DeinitAudioPll();
/* Bypass Audio PLL. */
CLOCK_SetPllBypass(CCM_ANALOG, kCLOCK_PllAudio, 1);
/* Set divider for Audio PLL. */
CCM_ANALOG->MISC2 &= ~CCM_ANALOG_MISC2_AUDIO_DIV_LSB_MASK;
CCM_ANALOG->MISC2 &= ~CCM_ANALOG_MISC2_AUDIO_DIV_MSB_MASK;
/* Enable Audio PLL output. */
CCM_ANALOG->PLL_AUDIO |= CCM_ANALOG_PLL_AUDIO_ENABLE_MASK;
/* Init Video PLL. */
uint32_t pllVideo;
/* Disable Video PLL output before initial Video PLL. */
CCM_ANALOG->PLL_VIDEO &= ~CCM_ANALOG_PLL_VIDEO_ENABLE_MASK;
/* Bypass PLL first */
CCM_ANALOG->PLL_VIDEO = (CCM_ANALOG->PLL_VIDEO & (~CCM_ANALOG_PLL_VIDEO_BYPASS_CLK_SRC_MASK)) |
CCM_ANALOG_PLL_VIDEO_BYPASS_MASK | CCM_ANALOG_PLL_VIDEO_BYPASS_CLK_SRC(0);
CCM_ANALOG->PLL_VIDEO_NUM = CCM_ANALOG_PLL_VIDEO_NUM_A(0);
CCM_ANALOG->PLL_VIDEO_DENOM = CCM_ANALOG_PLL_VIDEO_DENOM_B(1);
pllVideo = (CCM_ANALOG->PLL_VIDEO & (~(CCM_ANALOG_PLL_VIDEO_DIV_SELECT_MASK | CCM_ANALOG_PLL_VIDEO_POWERDOWN_MASK))) |
CCM_ANALOG_PLL_VIDEO_ENABLE_MASK |CCM_ANALOG_PLL_VIDEO_DIV_SELECT(31);
pllVideo |= CCM_ANALOG_PLL_VIDEO_POST_DIV_SELECT(1);
CCM_ANALOG->MISC2 = (CCM_ANALOG->MISC2 & (~CCM_ANALOG_MISC2_VIDEO_DIV_MASK)) | CCM_ANALOG_MISC2_VIDEO_DIV(3);
CCM_ANALOG->PLL_VIDEO = pllVideo;
while ((CCM_ANALOG->PLL_VIDEO & CCM_ANALOG_PLL_VIDEO_LOCK_MASK) == 0)
{
}
/* Disable bypass for Video PLL. */
CLOCK_SetPllBypass(CCM_ANALOG, kCLOCK_PllVideo, 0);
/* DeInit Enet PLL. */
CLOCK_DeinitEnetPll();
/* Bypass Enet PLL. */
CLOCK_SetPllBypass(CCM_ANALOG, kCLOCK_PllEnet, 1);
/* Set Enet output divider. */
CCM_ANALOG->PLL_ENET = (CCM_ANALOG->PLL_ENET & (~CCM_ANALOG_PLL_ENET_DIV_SELECT_MASK)) | CCM_ANALOG_PLL_ENET_DIV_SELECT(1);
/* Enable Enet output. */
CCM_ANALOG->PLL_ENET |= CCM_ANALOG_PLL_ENET_ENABLE_MASK;
/* Set Enet2 output divider. */
CCM_ANALOG->PLL_ENET = (CCM_ANALOG->PLL_ENET & (~CCM_ANALOG_PLL_ENET_ENET2_DIV_SELECT_MASK)) | CCM_ANALOG_PLL_ENET_ENET2_DIV_SELECT(0);
/* Enable Enet2 output. */
CCM_ANALOG->PLL_ENET |= CCM_ANALOG_PLL_ENET_ENET2_REF_EN_MASK;
/* Enable Enet25M output. */
CCM_ANALOG->PLL_ENET |= CCM_ANALOG_PLL_ENET_ENET_25M_REF_EN_MASK;
/* DeInit Usb2 PLL. */
CLOCK_DeinitUsb2Pll();
/* Bypass Usb2 PLL. */
CLOCK_SetPllBypass(CCM_ANALOG, kCLOCK_PllUsb2, 1);
/* Enable Usb2 PLL output. */
CCM_ANALOG->PLL_USB2 |= CCM_ANALOG_PLL_USB2_ENABLE_MASK;
/* Set preperiph clock source. */
CLOCK_SetMux(kCLOCK_PrePeriphMux, 0);
/* Set periph clock source. */
CLOCK_SetMux(kCLOCK_PeriphMux, 0);
/* Set periph clock2 clock source. */
CLOCK_SetMux(kCLOCK_PeriphClk2Mux, 0);
/* Set per clock source. */
CLOCK_SetMux(kCLOCK_PerclkMux, 0);
/* Set lvds1 clock source. */
CCM_ANALOG->MISC1 = (CCM_ANALOG->MISC1 & (~CCM_ANALOG_MISC1_LVDS1_CLK_SEL_MASK)) | CCM_ANALOG_MISC1_LVDS1_CLK_SEL(0);
/* Set clock out1 divider. */
CCM->CCOSR = (CCM->CCOSR & (~CCM_CCOSR_CLKO1_DIV_MASK)) | CCM_CCOSR_CLKO1_DIV(0);
/* Set clock out1 source. */
CCM->CCOSR = (CCM->CCOSR & (~CCM_CCOSR_CLKO1_SEL_MASK)) | CCM_CCOSR_CLKO1_SEL(1);
/* Set clock out2 divider. */
CCM->CCOSR = (CCM->CCOSR & (~CCM_CCOSR_CLKO2_DIV_MASK)) | CCM_CCOSR_CLKO2_DIV(0);
/* Set clock out2 source. */
CCM->CCOSR = (CCM->CCOSR & (~CCM_CCOSR_CLKO2_SEL_MASK)) | CCM_CCOSR_CLKO2_SEL(18);
/* Set clock out1 drives clock out1. */
CCM->CCOSR &= ~CCM_CCOSR_CLK_OUT_SEL_MASK;
/* Disable clock out1. */
CCM->CCOSR &= ~CCM_CCOSR_CLKO1_EN_MASK;
/* Disable clock out2. */
CCM->CCOSR &= ~CCM_CCOSR_CLKO2_EN_MASK;
/* Set SAI1 MCLK1 clock source. */
IOMUXC_SetSaiMClkClockSource(IOMUXC_GPR, kIOMUXC_GPR_SAI1MClk1Sel, 0);
/* Set SAI1 MCLK2 clock source. */
IOMUXC_SetSaiMClkClockSource(IOMUXC_GPR, kIOMUXC_GPR_SAI1MClk2Sel, 0);
/* Set SAI1 MCLK3 clock source. */
IOMUXC_SetSaiMClkClockSource(IOMUXC_GPR, kIOMUXC_GPR_SAI1MClk3Sel, 0);
/* Set SAI2 MCLK3 clock source. */
IOMUXC_SetSaiMClkClockSource(IOMUXC_GPR, kIOMUXC_GPR_SAI2MClk3Sel, 0);
/* Set SAI3 MCLK3 clock source. */
IOMUXC_SetSaiMClkClockSource(IOMUXC_GPR, kIOMUXC_GPR_SAI3MClk3Sel, 0);
/* Set MQS configuration. */
IOMUXC_MQSConfig(IOMUXC_GPR,kIOMUXC_MqsPwmOverSampleRate32, 0);
/* Set ENET Ref clock source. */
IOMUXC_GPR->GPR1 &= ~IOMUXC_GPR_GPR1_ENET1_TX_CLK_DIR_MASK;
/* Set ENET2 Ref clock source. */
IOMUXC_GPR->GPR1 &= ~IOMUXC_GPR_GPR1_ENET2_TX_CLK_DIR_MASK;
/* Set GPT1 High frequency reference clock source. */
IOMUXC_GPR->GPR5 &= ~IOMUXC_GPR_GPR5_VREF_1M_CLK_GPT1_MASK;
/* Set GPT2 High frequency reference clock source. */
IOMUXC_GPR->GPR5 &= ~IOMUXC_GPR_GPR5_VREF_1M_CLK_GPT2_MASK;
/* Set SystemCoreClock variable. */
SystemCoreClock = BOARD_BOOTCLOCKRUN_528M_CORE_CLOCK;
}

View File

@ -0,0 +1,602 @@
/*
* Copyright 2016-2021 NXP
* All rights reserved.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#include "fsl_cache.h"
/*******************************************************************************
* Definitions
******************************************************************************/
/* Component ID definition, used by tools. */
#ifndef FSL_COMPONENT_ID
#define FSL_COMPONENT_ID "platform.drivers.cache_armv7_m7"
#endif
#if defined(FSL_FEATURE_SOC_L2CACHEC_COUNT) && FSL_FEATURE_SOC_L2CACHEC_COUNT
#define L2CACHE_OPERATION_TIMEOUT 0xFFFFFU
#define L2CACHE_8WAYS_MASK 0xFFU
#define L2CACHE_16WAYS_MASK 0xFFFFU
#define L2CACHE_SMALLWAYS_NUM 8U
#define L2CACHE_1KBCOVERTOB 1024U
#define L2CACHE_SAMLLWAYS_SIZE 16U
#define L2CACHE_LOCKDOWN_REGNUM 8 /*!< Lock down register numbers.*/
/*******************************************************************************
* Prototypes
******************************************************************************/
/*!
* @brief Set for all ways and waiting for the operation finished.
* This is provided for all the background operations.
*
* @param auxCtlReg The auxiliary control register.
* @param regAddr The register address to be operated.
*/
static void L2CACHE_SetAndWaitBackGroundOperate(uint32_t auxCtlReg, uint32_t regAddr);
/*!
* @brief Invalidates the Level 2 cache line by physical address.
* This function invalidates a cache line by physcial address.
*
* @param address The physical addderss of the cache.
* The format of the address shall be :
* bit 31 ~ bit n+1 | bitn ~ bit5 | bit4 ~ bit0
* Tag | index | 0
* Note: the physical address shall be aligned to the line size - 32B (256 bit).
* so keep the last 5 bits (bit 4 ~ bit 0) of the physical address always be zero.
* If the input address is not aligned, it will be changed to 32-byte aligned address.
* The n is varies according to the index width.
* @return The actual 32-byte aligned physical address be operated.
*/
static uint32_t L2CACHE_InvalidateLineByAddr(uint32_t address);
/*!
* @brief Cleans the Level 2 cache line based on the physical address.
* This function cleans a cache line based on a physcial address.
*
* @param address The physical addderss of the cache.
* The format of the address shall be :
* bit 31 ~ bit n+1 | bitn ~ bit5 | bit4 ~ bit0
* Tag | index | 0
* Note: the physical address shall be aligned to the line size - 32B (256 bit).
* so keep the last 5 bits (bit 4 ~ bit 0) of the physical address always be zero.
* If the input address is not aligned, it will be changed to 32-byte aligned address.
* The n is varies according to the index width.
* @return The actual 32-byte aligned physical address be operated.
*/
static uint32_t L2CACHE_CleanLineByAddr(uint32_t address);
/*!
* @brief Cleans and invalidates the Level 2 cache line based on the physical address.
* This function cleans and invalidates a cache line based on a physcial address.
*
* @param address The physical addderss of the cache.
* The format of the address shall be :
* bit 31 ~ bit n+1 | bitn ~ bit5 | bit4 ~ bit0
* Tag | index | 0
* Note: the physical address shall be aligned to the line size - 32B (256 bit).
* so keep the last 5 bits (bit 4 ~ bit 0) of the physical address always be zero.
* If the input address is not aligned, it will be changed to 32-byte aligned address.
* The n is varies according to the index width.
* @return The actual 32-byte aligned physical address be operated.
*/
static uint32_t L2CACHE_CleanInvalidateLineByAddr(uint32_t address);
/*!
* @brief Gets the number of the Level 2 cache and the way size.
* This function cleans and invalidates a cache line based on a physcial address.
*
* @param num_ways The number of the cache way.
* @param size_way The way size.
*/
static void L2CACHE_GetWayNumSize(uint32_t *num_ways, uint32_t *size_way);
/*******************************************************************************
* Code
******************************************************************************/
static void L2CACHE_SetAndWaitBackGroundOperate(uint32_t auxCtlReg, uint32_t regAddr)
{
uint16_t mask = L2CACHE_8WAYS_MASK;
uint32_t timeout = L2CACHE_OPERATION_TIMEOUT;
/* Check the ways used at first. */
if (auxCtlReg & L2CACHEC_REG1_AUX_CONTROL_ASSOCIATIVITY_MASK)
{
mask = L2CACHE_16WAYS_MASK;
}
/* Set the opeartion for all ways/entries of the cache. */
*(uint32_t *)regAddr = mask;
/* Waiting for until the operation is complete. */
while ((*(volatile uint32_t *)regAddr & mask) && timeout)
{
__ASM("nop");
timeout--;
}
}
static uint32_t L2CACHE_InvalidateLineByAddr(uint32_t address)
{
/* Align the address first. */
address &= ~(uint32_t)(FSL_FEATURE_L2CACHE_LINESIZE_BYTE - 1);
/* Invalidate the cache line by physical address. */
L2CACHEC->REG7_INV_PA = address;
return address;
}
static uint32_t L2CACHE_CleanLineByAddr(uint32_t address)
{
/* Align the address first. */
address &= ~(uint32_t)(FSL_FEATURE_L2CACHE_LINESIZE_BYTE - 1);
/* Invalidate the cache line by physical address. */
L2CACHEC->REG7_CLEAN_PA = address;
return address;
}
static uint32_t L2CACHE_CleanInvalidateLineByAddr(uint32_t address)
{
/* Align the address first. */
address &= ~(uint32_t)(FSL_FEATURE_L2CACHE_LINESIZE_BYTE - 1);
/* Clean and invalidate the cache line by physical address. */
L2CACHEC->REG7_CLEAN_INV_PA = address;
return address;
}
static void L2CACHE_GetWayNumSize(uint32_t *num_ways, uint32_t *size_way)
{
assert(num_ways);
assert(size_way);
uint32_t number = (L2CACHEC->REG1_AUX_CONTROL & L2CACHEC_REG1_AUX_CONTROL_ASSOCIATIVITY_MASK) >>
L2CACHEC_REG1_AUX_CONTROL_ASSOCIATIVITY_SHIFT;
uint32_t size = (L2CACHEC->REG1_AUX_CONTROL & L2CACHEC_REG1_AUX_CONTROL_WAYSIZE_MASK) >>
L2CACHEC_REG1_AUX_CONTROL_WAYSIZE_SHIFT;
*num_ways = (number + 1) * L2CACHE_SMALLWAYS_NUM;
if (!size)
{
/* 0 internally mapped to the same size as 1 - 16KB.*/
size += 1;
}
*size_way = (1 << (size - 1)) * L2CACHE_SAMLLWAYS_SIZE * L2CACHE_1KBCOVERTOB;
}
/*!
* brief Initializes the level 2 cache controller module.
*
* param config Pointer to configuration structure. See "l2cache_config_t".
*/
void L2CACHE_Init(l2cache_config_t *config)
{
assert(config);
uint16_t waysNum = 0xFFU; /* Default use the 8-way mask. */
uint8_t count;
uint32_t auxReg = 0;
/*The aux register must be configured when the cachec is disabled
* So disable first if the cache controller is enabled.
*/
if (L2CACHEC->REG1_CONTROL & L2CACHEC_REG1_CONTROL_CE_MASK)
{
L2CACHE_Disable();
}
/* Unlock all entries. */
if (L2CACHEC->REG1_AUX_CONTROL & L2CACHEC_REG1_AUX_CONTROL_ASSOCIATIVITY_MASK)
{
waysNum = 0xFFFFU;
}
for (count = 0; count < L2CACHE_LOCKDOWN_REGNUM; count++)
{
L2CACHE_LockdownByWayEnable(count, waysNum, false);
}
/* Set the ways and way-size etc. */
auxReg = L2CACHEC_REG1_AUX_CONTROL_ASSOCIATIVITY(config->wayNum) |
L2CACHEC_REG1_AUX_CONTROL_WAYSIZE(config->waySize) | L2CACHEC_REG1_AUX_CONTROL_CRP(config->repacePolicy) |
L2CACHEC_REG1_AUX_CONTROL_IPE(config->istrPrefetchEnable) |
L2CACHEC_REG1_AUX_CONTROL_DPE(config->dataPrefetchEnable) |
L2CACHEC_REG1_AUX_CONTROL_NLE(config->nsLockdownEnable) |
L2CACHEC_REG1_AUX_CONTROL_FWA(config->writeAlloc) | L2CACHEC_REG1_AUX_CONTROL_HPSDRE(config->writeAlloc);
L2CACHEC->REG1_AUX_CONTROL = auxReg;
/* Set the tag/data ram latency. */
if (config->lateConfig)
{
uint32_t data = 0;
/* Tag latency. */
data = L2CACHEC_REG1_TAG_RAM_CONTROL_SL(config->lateConfig->tagSetupLate) |
L2CACHEC_REG1_TAG_RAM_CONTROL_SL(config->lateConfig->tagSetupLate) |
L2CACHEC_REG1_TAG_RAM_CONTROL_RAL(config->lateConfig->tagReadLate) |
L2CACHEC_REG1_TAG_RAM_CONTROL_WAL(config->lateConfig->dataWriteLate);
L2CACHEC->REG1_TAG_RAM_CONTROL = data;
/* Data latency. */
data = L2CACHEC_REG1_DATA_RAM_CONTROL_SL(config->lateConfig->dataSetupLate) |
L2CACHEC_REG1_DATA_RAM_CONTROL_SL(config->lateConfig->dataSetupLate) |
L2CACHEC_REG1_DATA_RAM_CONTROL_RAL(config->lateConfig->dataReadLate) |
L2CACHEC_REG1_DATA_RAM_CONTROL_WAL(config->lateConfig->dataWriteLate);
L2CACHEC->REG1_DATA_RAM_CONTROL = data;
}
}
/*!
* brief Gets an available default settings for the cache controller.
*
* This function initializes the cache controller configuration structure with default settings.
* The default values are:
* code
* config->waysNum = kL2CACHE_8ways;
* config->waySize = kL2CACHE_32KbSize;
* config->repacePolicy = kL2CACHE_Roundrobin;
* config->lateConfig = NULL;
* config->istrPrefetchEnable = false;
* config->dataPrefetchEnable = false;
* config->nsLockdownEnable = false;
* config->writeAlloc = kL2CACHE_UseAwcache;
* endcode
* param config Pointer to the configuration structure.
*/
void L2CACHE_GetDefaultConfig(l2cache_config_t *config)
{
assert(config);
/* Initializes the configure structure to zero. */
memset(config, 0, sizeof(*config));
uint32_t number = (L2CACHEC->REG1_AUX_CONTROL & L2CACHEC_REG1_AUX_CONTROL_ASSOCIATIVITY_MASK) >>
L2CACHEC_REG1_AUX_CONTROL_ASSOCIATIVITY_SHIFT;
uint32_t size = (L2CACHEC->REG1_AUX_CONTROL & L2CACHEC_REG1_AUX_CONTROL_WAYSIZE_MASK) >>
L2CACHEC_REG1_AUX_CONTROL_WAYSIZE_SHIFT;
/* Get the default value */
config->wayNum = (l2cache_way_num_t)number;
config->waySize = (l2cache_way_size)size;
config->repacePolicy = kL2CACHE_Roundrobin;
config->lateConfig = NULL;
config->istrPrefetchEnable = false;
config->dataPrefetchEnable = false;
config->nsLockdownEnable = false;
config->writeAlloc = kL2CACHE_UseAwcache;
}
/*!
* brief Enables the level 2 cache controller.
* This function enables the cache controller. Must be written using a secure access.
* If write with a Non-secure access will cause a DECERR response.
*
*/
void L2CACHE_Enable(void)
{
/* Invalidate first. */
L2CACHE_Invalidate();
/* Enable the level 2 cache controller. */
L2CACHEC->REG1_CONTROL = L2CACHEC_REG1_CONTROL_CE_MASK;
}
/*!
* brief Disables the level 2 cache controller.
* This function disables the cache controller. Must be written using a secure access.
* If write with a Non-secure access will cause a DECERR response.
*
*/
void L2CACHE_Disable(void)
{
/* First CleanInvalidate all enties in the cache. */
L2CACHE_CleanInvalidate();
/* Disable the level 2 cache controller. */
L2CACHEC->REG1_CONTROL &= ~L2CACHEC_REG1_CONTROL_CE_MASK;
/* DSB - data sync barrier.*/
__DSB();
}
/*!
* brief Invalidates the Level 2 cache.
* This function invalidates all entries in cache.
*
*/
void L2CACHE_Invalidate(void)
{
/* Invalidate all entries in cache. */
L2CACHE_SetAndWaitBackGroundOperate(L2CACHEC->REG1_AUX_CONTROL, (uint32_t)&L2CACHEC->REG7_INV_WAY);
/* Cache sync. */
L2CACHEC->REG7_CACHE_SYNC = 0;
}
/*!
* brief Cleans the level 2 cache controller.
* This function cleans all entries in the level 2 cache controller.
*
*/
void L2CACHE_Clean(void)
{
/* Clean all entries of the cache. */
L2CACHE_SetAndWaitBackGroundOperate(L2CACHEC->REG1_AUX_CONTROL, (uint32_t)&L2CACHEC->REG7_CLEAN_WAY);
/* Cache sync. */
L2CACHEC->REG7_CACHE_SYNC = 0;
}
/*!
* brief Cleans and invalidates the level 2 cache controller.
* This function cleans and invalidates all entries in the level 2 cache controller.
*
*/
void L2CACHE_CleanInvalidate(void)
{
/* Clean all entries of the cache. */
L2CACHE_SetAndWaitBackGroundOperate(L2CACHEC->REG1_AUX_CONTROL, (uint32_t)&L2CACHEC->REG7_CLEAN_INV_WAY);
/* Cache sync. */
L2CACHEC->REG7_CACHE_SYNC = 0;
}
/*!
* brief Invalidates the Level 2 cache lines in the range of two physical addresses.
* This function invalidates all cache lines between two physical addresses.
*
* param address The start address of the memory to be invalidated.
* param size_byte The memory size.
* note The start address and size_byte should be 32-byte(FSL_FEATURE_L2CACHE_LINESIZE_BYTE) aligned.
* The startAddr here will be forced to align to L2 line size if startAddr
* is not aligned. For the size_byte, application should make sure the
* alignment or make sure the right operation order if the size_byte is not aligned.
*/
void L2CACHE_InvalidateByRange(uint32_t address, uint32_t size_byte)
{
uint32_t endAddr = address + size_byte;
/* Invalidate addresses in the range. */
while (address < endAddr)
{
address = L2CACHE_InvalidateLineByAddr(address);
/* Update the size. */
address += FSL_FEATURE_L2CACHE_LINESIZE_BYTE;
}
/* Cache sync. */
L2CACHEC->REG7_CACHE_SYNC = 0;
}
/*!
* brief Cleans the Level 2 cache lines in the range of two physical addresses.
* This function cleans all cache lines between two physical addresses.
*
* param address The start address of the memory to be cleaned.
* param size_byte The memory size.
* note The start address and size_byte should be 32-byte(FSL_FEATURE_L2CACHE_LINESIZE_BYTE) aligned.
* The startAddr here will be forced to align to L2 line size if startAddr
* is not aligned. For the size_byte, application should make sure the
* alignment or make sure the right operation order if the size_byte is not aligned.
*/
void L2CACHE_CleanByRange(uint32_t address, uint32_t size_byte)
{
uint32_t num_ways = 0;
uint32_t size_way = 0;
uint32_t endAddr = address + size_byte;
/* Get the number and size of the cache way. */
L2CACHE_GetWayNumSize(&num_ways, &size_way);
/* Check if the clean size is over the cache size. */
if ((endAddr - address) > num_ways * size_way)
{
L2CACHE_Clean();
return;
}
/* Clean addresses in the range. */
while ((address & ~(uint32_t)(FSL_FEATURE_L2CACHE_LINESIZE_BYTE - 1)) < endAddr)
{
/* Clean the address in the range. */
address = L2CACHE_CleanLineByAddr(address);
address += FSL_FEATURE_L2CACHE_LINESIZE_BYTE;
}
L2CACHEC->REG7_CACHE_SYNC = 0;
}
/*!
* brief Cleans and invalidates the Level 2 cache lines in the range of two physical addresses.
* This function cleans and invalidates all cache lines between two physical addresses.
*
* param address The start address of the memory to be cleaned and invalidated.
* param size_byte The memory size.
* note The start address and size_byte should be 32-byte(FSL_FEATURE_L2CACHE_LINESIZE_BYTE) aligned.
* The startAddr here will be forced to align to L2 line size if startAddr
* is not aligned. For the size_byte, application should make sure the
* alignment or make sure the right operation order if the size_byte is not aligned.
*/
void L2CACHE_CleanInvalidateByRange(uint32_t address, uint32_t size_byte)
{
uint32_t num_ways = 0;
uint32_t size_way = 0;
uint32_t endAddr = address + size_byte;
/* Get the number and size of the cache way. */
L2CACHE_GetWayNumSize(&num_ways, &size_way);
/* Check if the clean size is over the cache size. */
if ((endAddr - address) > num_ways * size_way)
{
L2CACHE_CleanInvalidate();
return;
}
/* Clean addresses in the range. */
while ((address & ~(uint32_t)(FSL_FEATURE_L2CACHE_LINESIZE_BYTE - 1)) < endAddr)
{
/* Clean the address in the range. */
address = L2CACHE_CleanInvalidateLineByAddr(address);
address += FSL_FEATURE_L2CACHE_LINESIZE_BYTE;
}
L2CACHEC->REG7_CACHE_SYNC = 0;
}
/*!
* brief Enables or disables to lock down the data and instruction by way.
* This function locks down the cached instruction/data by way and prevent the adresses from
* being allocated and prevent dara from being evicted out of the level 2 cache.
* But the normal cache maintenance operations that invalidate, clean or clean
* and validate cache contents affect the locked-down cache lines as normal.
*
* param masterId The master id, range from 0 ~ 7.
* param mask The ways to be enabled or disabled to lockdown.
* each bit in value is related to each way of the cache. for example:
* value: bit 0 ------ way 0.
* value: bit 1 ------ way 1.
* --------------------------
* value: bit 15 ------ way 15.
* Note: please make sure the value setting is align with your supported ways.
* param enable True enable the lockdown, false to disable the lockdown.
*/
void L2CACHE_LockdownByWayEnable(uint32_t masterId, uint32_t mask, bool enable)
{
uint8_t num_ways = (L2CACHEC->REG1_AUX_CONTROL & L2CACHEC_REG1_AUX_CONTROL_ASSOCIATIVITY_MASK) >>
L2CACHEC_REG1_AUX_CONTROL_ASSOCIATIVITY_SHIFT;
num_ways = (num_ways + 1) * L2CACHE_SMALLWAYS_NUM;
assert(mask < (1U << num_ways));
assert(masterId < L2CACHE_LOCKDOWN_REGNUM);
uint32_t dataReg = L2CACHEC->LOCKDOWN[masterId].REG9_D_LOCKDOWN;
uint32_t istrReg = L2CACHEC->LOCKDOWN[masterId].REG9_I_LOCKDOWN;
if (enable)
{
/* Data lockdown. */
L2CACHEC->LOCKDOWN[masterId].REG9_D_LOCKDOWN = dataReg | mask;
/* Instruction lockdown. */
L2CACHEC->LOCKDOWN[masterId].REG9_I_LOCKDOWN = istrReg | mask;
}
else
{
/* Data lockdown. */
L2CACHEC->LOCKDOWN[masterId].REG9_D_LOCKDOWN = dataReg & ~mask;
/* Instruction lockdown. */
L2CACHEC->LOCKDOWN[masterId].REG9_I_LOCKDOWN = istrReg & ~mask;
}
}
#endif /* FSL_FEATURE_SOC_L2CACHEC_COUNT */
/*!
* brief Invalidate cortex-m7 L1 instruction cache by range.
*
* param address The start address of the memory to be invalidated.
* param size_byte The memory size.
* note The start address and size_byte should be 32-byte(FSL_FEATURE_L1ICACHE_LINESIZE_BYTE) aligned.
* The startAddr here will be forced to align to L1 I-cache line size if
* startAddr is not aligned. For the size_byte, application should make sure the
* alignment or make sure the right operation order if the size_byte is not aligned.
*/
void L1CACHE_InvalidateICacheByRange(uint32_t address, uint32_t size_byte)
{
#if (__DCACHE_PRESENT == 1U)
uint32_t addr = address & ~((uint32_t)FSL_FEATURE_L1ICACHE_LINESIZE_BYTE - 1U);
uint32_t align_len = address - addr;
int32_t size = (int32_t)size_byte + (int32_t)align_len;
__DSB();
while (size > 0)
{
SCB->ICIMVAU = addr;
addr += (uint32_t)FSL_FEATURE_L1ICACHE_LINESIZE_BYTE;
size -= (int32_t)FSL_FEATURE_L1ICACHE_LINESIZE_BYTE;
}
__DSB();
__ISB();
#endif
}
/*!
* brief Invalidates all instruction caches by range.
*
* Both cortex-m7 L1 cache line and L2 PL310 cache line length is 32-byte.
*
* param address The physical address.
* param size_byte size of the memory to be invalidated.
* note address and size should be aligned to cache line size
* 32-Byte due to the cache operation unit is one cache line. The startAddr here will be forced
* to align to the cache line size if startAddr is not aligned. For the size_byte, application should
* make sure the alignment or make sure the right operation order if the size_byte is not aligned.
*/
void ICACHE_InvalidateByRange(uint32_t address, uint32_t size_byte)
{
#if defined(FSL_FEATURE_SOC_L2CACHEC_COUNT) && FSL_FEATURE_SOC_L2CACHEC_COUNT
#if defined(FSL_SDK_DISBLE_L2CACHE_PRESENT) && !FSL_SDK_DISBLE_L2CACHE_PRESENT
L2CACHE_InvalidateByRange(address, size_byte);
#endif /* !FSL_SDK_DISBLE_L2CACHE_PRESENT */
#endif /* FSL_FEATURE_SOC_L2CACHEC_COUNT */
L1CACHE_InvalidateICacheByRange(address, size_byte);
}
/*!
* brief Invalidates all data caches by range.
*
* Both cortex-m7 L1 cache line and L2 PL310 cache line length is 32-byte.
*
* param address The physical address.
* param size_byte size of the memory to be invalidated.
* note address and size should be aligned to cache line size
* 32-Byte due to the cache operation unit is one cache line. The startAddr here will be forced
* to align to the cache line size if startAddr is not aligned. For the size_byte, application should
* make sure the alignment or make sure the right operation order if the size_byte is not aligned.
*/
void DCACHE_InvalidateByRange(uint32_t address, uint32_t size_byte)
{
#if defined(FSL_FEATURE_SOC_L2CACHEC_COUNT) && FSL_FEATURE_SOC_L2CACHEC_COUNT
#if defined(FSL_SDK_DISBLE_L2CACHE_PRESENT) && !FSL_SDK_DISBLE_L2CACHE_PRESENT
L2CACHE_InvalidateByRange(address, size_byte);
#endif /* !FSL_SDK_DISBLE_L2CACHE_PRESENT */
#endif /* FSL_FEATURE_SOC_L2CACHEC_COUNT */
L1CACHE_InvalidateDCacheByRange(address, size_byte);
}
/*!
* brief Cleans all data caches by range.
*
* Both cortex-m7 L1 cache line and L2 PL310 cache line length is 32-byte.
*
* param address The physical address.
* param size_byte size of the memory to be cleaned.
* note address and size should be aligned to cache line size
* 32-Byte due to the cache operation unit is one cache line. The startAddr here will be forced
* to align to the cache line size if startAddr is not aligned. For the size_byte, application should
* make sure the alignment or make sure the right operation order if the size_byte is not aligned.
*/
void DCACHE_CleanByRange(uint32_t address, uint32_t size_byte)
{
L1CACHE_CleanDCacheByRange(address, size_byte);
#if defined(FSL_FEATURE_SOC_L2CACHEC_COUNT) && FSL_FEATURE_SOC_L2CACHEC_COUNT
#if defined(FSL_SDK_DISBLE_L2CACHE_PRESENT) && !FSL_SDK_DISBLE_L2CACHE_PRESENT
L2CACHE_CleanByRange(address, size_byte);
#endif /* !FSL_SDK_DISBLE_L2CACHE_PRESENT */
#endif /* FSL_FEATURE_SOC_L2CACHEC_COUNT */
}
/*!
* brief Cleans and Invalidates all data caches by range.
*
* Both cortex-m7 L1 cache line and L2 PL310 cache line length is 32-byte.
*
* param address The physical address.
* param size_byte size of the memory to be cleaned and invalidated.
* note address and size should be aligned to cache line size
* 32-Byte due to the cache operation unit is one cache line. The startAddr here will be forced
* to align to the cache line size if startAddr is not aligned. For the size_byte, application should
* make sure the alignment or make sure the right operation order if the size_byte is not aligned.
*/
void DCACHE_CleanInvalidateByRange(uint32_t address, uint32_t size_byte)
{
L1CACHE_CleanInvalidateDCacheByRange(address, size_byte);
#if defined(FSL_FEATURE_SOC_L2CACHEC_COUNT) && FSL_FEATURE_SOC_L2CACHEC_COUNT
#if defined(FSL_SDK_DISBLE_L2CACHE_PRESENT) && !FSL_SDK_DISBLE_L2CACHE_PRESENT
L2CACHE_CleanInvalidateByRange(address, size_byte);
#endif /* !FSL_SDK_DISBLE_L2CACHE_PRESENT */
#endif /* FSL_FEATURE_SOC_L2CACHEC_COUNT */
}

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,85 @@
/*
* Copyright (c) 2015-2016, Freescale Semiconductor, Inc.
* Copyright 2016-2021 NXP
* All rights reserved.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#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 address 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
#if !((defined(__DSC__) && defined(__CW__)))
void *SDK_Malloc(size_t size, size_t alignbytes)
{
mem_align_cb_t *p_cb = NULL;
uint32_t alignedsize;
/* Check overflow. */
alignedsize = (uint32_t)(unsigned int)SDK_SIZEALIGN(size, alignbytes);
if (alignedsize < size)
{
return NULL;
}
if (alignedsize > SIZE_MAX - alignbytes - sizeof(mem_align_cb_t))
{
return NULL;
}
alignedsize += alignbytes + (uint32_t)sizeof(mem_align_cb_t);
union
{
void *pointer_value;
uintptr_t unsigned_value;
} p_align_addr, p_addr;
p_addr.pointer_value = malloc((size_t)alignedsize);
if (p_addr.pointer_value == NULL)
{
return NULL;
}
p_align_addr.unsigned_value = SDK_SIZEALIGN(p_addr.unsigned_value + sizeof(mem_align_cb_t), alignbytes);
p_cb = (mem_align_cb_t *)(p_align_addr.unsigned_value - 4U);
p_cb->identifier = SDK_MEM_MAGIC_NUMBER;
p_cb->offset = (uint16_t)(p_align_addr.unsigned_value - p_addr.unsigned_value);
return p_align_addr.pointer_value;
}
void SDK_Free(void *ptr)
{
union
{
void *pointer_value;
uintptr_t unsigned_value;
} p_free;
p_free.pointer_value = ptr;
mem_align_cb_t *p_cb = (mem_align_cb_t *)(p_free.unsigned_value - 4U);
if (p_cb->identifier != SDK_MEM_MAGIC_NUMBER)
{
return;
}
p_free.unsigned_value = p_free.unsigned_value - p_cb->offset;
free(p_free.pointer_value);
}
#endif

View File

@ -0,0 +1,364 @@
/*
* Copyright (c) 2015-2016, Freescale Semiconductor, Inc.
* Copyright 2016-2021,2023,2024 NXP
* All rights reserved.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#include "fsl_common.h"
/* Component ID definition, used by tools. */
#ifndef FSL_COMPONENT_ID
#define FSL_COMPONENT_ID "platform.drivers.common_arm"
#endif
#ifndef __GIC_PRIO_BITS
#if defined(ENABLE_RAM_VECTOR_TABLE)
uint32_t InstallIRQHandler(IRQn_Type irq, uint32_t irqHandler)
{
#ifdef __VECTOR_TABLE
#undef __VECTOR_TABLE
#endif
/* Addresses for VECTOR_TABLE and VECTOR_RAM come from the linker file */
#if defined(__CC_ARM) || defined(__ARMCC_VERSION)
extern uint32_t Image$$VECTOR_ROM$$Base[];
extern uint32_t Image$$VECTOR_RAM$$Base[];
extern uint32_t Image$$VECTOR_RAM$$ZI$$Limit[];
#define __VECTOR_TABLE Image$$VECTOR_ROM$$Base
#define __VECTOR_RAM Image$$VECTOR_RAM$$Base
#define __RAM_VECTOR_TABLE_SIZE (((uint32_t)Image$$VECTOR_RAM$$ZI$$Limit - (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) || defined(__ARMCC_VERSION) */
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[(int32_t)irq + 16];
/* make sure the __VECTOR_RAM is noncachable */
__VECTOR_RAM[(int32_t)irq + 16] = irqHandler;
EnableGlobalIRQ(irqMaskValue);
return ret;
}
#endif /* ENABLE_RAM_VECTOR_TABLE. */
#endif /* __GIC_PRIO_BITS. */
#if (defined(FSL_FEATURE_SOC_SYSCON_COUNT) && (FSL_FEATURE_SOC_SYSCON_COUNT > 0))
/*
* When FSL_FEATURE_POWERLIB_EXTEND is defined to non-zero value,
* powerlib should be used instead of these functions.
*/
#if !(defined(FSL_FEATURE_POWERLIB_EXTEND) && (FSL_FEATURE_POWERLIB_EXTEND != 0))
/*
* When the SYSCON STARTER registers are discontinuous, these functions are
* implemented in fsl_power.c.
*/
#if !(defined(FSL_FEATURE_SYSCON_STARTER_DISCONTINUOUS) && FSL_FEATURE_SYSCON_STARTER_DISCONTINUOUS)
void EnableDeepSleepIRQ(IRQn_Type interrupt)
{
uint32_t intNumber = (uint32_t)interrupt;
uint32_t index = 0;
while (intNumber >= 32u)
{
index++;
intNumber -= 32u;
}
SYSCON->STARTERSET[index] = 1UL << intNumber;
(void)EnableIRQ(interrupt); /* also enable interrupt at NVIC */
}
void DisableDeepSleepIRQ(IRQn_Type interrupt)
{
uint32_t intNumber = (uint32_t)interrupt;
(void)DisableIRQ(interrupt); /* also disable interrupt at NVIC */
uint32_t index = 0;
while (intNumber >= 32u)
{
index++;
intNumber -= 32u;
}
SYSCON->STARTERCLR[index] = 1UL << intNumber;
}
#endif /* FSL_FEATURE_SYSCON_STARTER_DISCONTINUOUS */
#endif /* FSL_FEATURE_POWERLIB_EXTEND */
#endif /* FSL_FEATURE_SOC_SYSCON_COUNT */
#if defined(DWT)
/* Use WDT. */
void MSDK_EnableCpuCycleCounter(void)
{
/* Make sure the DWT trace fucntion is enabled. */
if (CoreDebug_DEMCR_TRCENA_Msk != (CoreDebug_DEMCR_TRCENA_Msk & CoreDebug->DEMCR))
{
CoreDebug->DEMCR |= CoreDebug_DEMCR_TRCENA_Msk;
}
/* CYCCNT not supported on this device. */
assert(DWT_CTRL_NOCYCCNT_Msk != (DWT->CTRL & DWT_CTRL_NOCYCCNT_Msk));
/* Read CYCCNT directly if CYCCENT has already been enabled, otherwise enable CYCCENT first. */
if (DWT_CTRL_CYCCNTENA_Msk != (DWT_CTRL_CYCCNTENA_Msk & DWT->CTRL))
{
DWT->CTRL |= DWT_CTRL_CYCCNTENA_Msk;
}
}
uint32_t MSDK_GetCpuCycleCount(void)
{
return DWT->CYCCNT;
}
#endif /* defined(DWT) */
#if !(defined(SDK_DELAY_USE_DWT) && defined(DWT))
/* Use software loop. */
#if defined(__CC_ARM) /* This macro is arm v5 specific */
/* clang-format off */
__ASM static void DelayLoop(uint32_t count)
{
loop
SUBS R0, R0, #1
CMP R0, #0
BNE loop
BX LR
}
#elif defined(__ARM_ARCH_8A__) /* This macro is ARMv8-A specific */
static void DelayLoop(uint32_t count)
{
__ASM volatile(" MOV X0, %0" : : "r"(count));
__ASM volatile(
"loop%=: \n"
" SUB X0, X0, #1 \n"
" CMP X0, #0 \n"
" BNE loop%= \n"
:
:
: "r0");
}
/* clang-format on */
#elif defined(__ARMCC_VERSION) || defined(__ICCARM__) || defined(__GNUC__)
/* Cortex-M0 has a smaller instruction set, SUBS isn't supported in thumb-16 mode reported from __GNUC__ compiler,
* use SUB and CMP here for compatibility */
static void DelayLoop(uint32_t count)
{
__ASM volatile(" MOV R0, %0" : : "r"(count));
__ASM volatile(
"loop%=: \n"
#if defined(__GNUC__) && !defined(__ARMCC_VERSION)
" SUB R0, R0, #1 \n"
#else
" SUBS R0, R0, #1 \n"
#endif
" CMP R0, #0 \n"
" BNE loop%= \n"
:
:
: "r0");
}
#endif /* defined(__CC_ARM) */
#endif /* defined(SDK_DELAY_USE_DWT) && defined(DWT) */
/*!
* @brief Delay at least for some time.
* Please note that, if not uses DWT, this API will use while loop for delay, different run-time environments have
* effect on the delay time. If precise delay is needed, please enable DWT delay. The two parmeters delayTime_us and
* coreClock_Hz have limitation. For example, in the platform with 1GHz coreClock_Hz, the delayTime_us only supports
* up to 4294967 in current code. If long time delay is needed, please implement a new delay function.
*
* @param delayTime_us Delay time in unit of microsecond.
* @param coreClock_Hz Core clock frequency with Hz.
*/
void SDK_DelayAtLeastUs(uint32_t delayTime_us, uint32_t coreClock_Hz)
{
uint64_t count;
if (delayTime_us > 0U)
{
count = USEC_TO_COUNT(delayTime_us, coreClock_Hz);
assert(count <= UINT32_MAX);
#if defined(SDK_DELAY_USE_DWT) && defined(DWT) /* Use DWT for better accuracy */
MSDK_EnableCpuCycleCounter();
/* Calculate the count ticks. */
count += MSDK_GetCpuCycleCount();
if (count > UINT32_MAX)
{
count -= UINT32_MAX;
/* Wait for cyccnt overflow. */
while (count < MSDK_GetCpuCycleCount())
{
}
}
/* Wait for cyccnt reach count value. */
while (count > MSDK_GetCpuCycleCount())
{
}
#else
#if defined(__CORTEX_Axx) && ((__CORTEX_Axx == 53) || (__CORTEX_Axx == 55))
/*
* Cortex-A53/A55 execution throughput:
* - SUB/CMP: 2 instructions per cycle
* - BNE: 1 instruction per cycle
* So, each loop takes 2 CPU cycles.
*/
count = count / 2U;
#elif (__CORTEX_M == 7)
/* Divide value may be different in various environment to ensure delay is precise.
* Every loop count includes three instructions, due to Cortex-M7 sometimes executes
* two instructions in one period, through test here set divide 1.5. Other M cores use
* divide 4. By the way, divide 1.5 or 4 could let the count lose precision, but it does
* not matter because other instructions outside while loop is enough to fill the time.
*/
count = count / 3U * 2U;
#else
count = count / 4U;
#endif
DelayLoop((uint32_t)count);
#endif /* defined(SDK_DELAY_USE_DWT) && defined(DWT) */
}
}
#if defined(FSL_FEATURE_MEASURE_CRITICAL_SECTION) && FSL_FEATURE_MEASURE_CRITICAL_SECTION
/* Use shall define their own IDs, FSL_FEATURE_CRITICAL_SECTION_MAX_ID and FSL_FEATURE_CRITICAL_SECTION_INVALID_ID
for the critical sections if want to use the critical section measurement.
*/
#ifndef FSL_FEATURE_CRITICAL_SECTION_MAX_ID
#define FSL_FEATURE_CRITICAL_SECTION_MAX_ID 0xFFU
#endif
#ifndef FSL_FEATURE_CRITICAL_SECTION_INVALID_ID
#define FSL_FEATURE_CRITICAL_SECTION_INVALID_ID 0U
#endif
typedef struct
{
uint32_t id; /*!< The id of the critical section, defined by user. */
uint32_t startTime; /*!< The timestamp for the start of the critical section. */
uint32_t dur_max[FSL_FEATURE_CRITICAL_SECTION_MAX_ID]; /*!< The maximum duration of the section's previous executions. */
uint32_t execution_times[FSL_FEATURE_CRITICAL_SECTION_MAX_ID]; /*!< How many times the section is executed. */
getTimestamp_t getTimestamp; /*!< Function to get the current time stamp. */
} critical_section_measurement_t;
static critical_section_measurement_t s_critical_section_measurement_context;
/*!
* brief Initialize the context of the critical section measurement and assign
* the function to get the current timestamp.
*
* param func The function to get the current timestamp.
*/
void InitCriticalSectionMeasurementContext(getTimestamp_t func)
{
assert(func != NULL);
(void)memset(&s_critical_section_measurement_context, 0, sizeof(critical_section_measurement_t));
s_critical_section_measurement_context.getTimestamp = func;
}
/*!
* brief Disable the global IRQ with critical section ID
*
* Extended function of DisableGlobalIRQ. Apart from the standard operation, also check
* the id of the protected critical section and mark the begining for timer.
* User is required to provided the primask register for the EnableGlobalIRQEx.
*
* param id The id for critical section.
* return Current primask value.
*/
uint32_t DisableGlobalIRQEx(uint32_t id)
{
uint32_t primask = DisableGlobalIRQ();
if (primask != 0U)
{
#ifdef FSL_FEATURE_MEASURE_CRITICAL_SECTION_DEBUG
/* Check for the critical section id. */
assert(id != FSL_FEATURE_CRITICAL_SECTION_INVALID_ID);
assert(id < FSL_FEATURE_CRITICAL_SECTION_MAX_ID);
assert(s_critical_section_measurement_context.id == FSL_FEATURE_CRITICAL_SECTION_INVALID_ID);
#endif
if (s_critical_section_measurement_context.getTimestamp != NULL)
{
s_critical_section_measurement_context.id = id;
s_critical_section_measurement_context.startTime = s_critical_section_measurement_context.getTimestamp();
}
}
return primask;
}
/*!
* brief Enable the global IRQ and calculate the execution time of critical section
*
* Extended function of EnableGlobalIRQ. Apart from the standard operation, also
* marks the exit of the critical section and calculate the execution time for the section.
* User is required to use the DisableGlobalIRQEx and EnableGlobalIRQEx in pair.
*
* param primask value of primask register to be restored. The primask value is supposed to be provided by the
* DisableGlobalIRQEx().
*/
void EnableGlobalIRQEx(uint32_t primask)
{
if (primask != 0U)
{
#ifdef FSL_FEATURE_MEASURE_CRITICAL_SECTION_DEBUG
/* Check for the critical section id. */
assert(s_critical_section_measurement_context.id != FSL_FEATURE_CRITICAL_SECTION_INVALID_ID);
assert(s_critical_section_measurement_context.id < FSL_FEATURE_CRITICAL_SECTION_MAX_ID);
#endif
if (s_critical_section_measurement_context.getTimestamp != NULL)
{
/* Calculate the critical section duration. */
uint32_t dur = s_critical_section_measurement_context.getTimestamp() - s_critical_section_measurement_context.startTime;
if (dur > s_critical_section_measurement_context.dur_max[s_critical_section_measurement_context.id])
{
s_critical_section_measurement_context.dur_max[s_critical_section_measurement_context.id] = dur;
}
s_critical_section_measurement_context.execution_times[s_critical_section_measurement_context.id]++;
}
#ifdef FSL_FEATURE_MEASURE_CRITICAL_SECTION_DEBUG
/* Exit the critical section, set the id to invalid. In this case when entering critical
section again DisableGlobalIRQEx has to be called first to avoid assertion. */
s_critical_section_measurement_context.id = FSL_FEATURE_CRITICAL_SECTION_INVALID_ID;
#endif
}
EnableGlobalIRQ(primask);
}
#endif /* FSL_FEATURE_MEASURE_CRITICAL_SECTION */

View File

@ -0,0 +1,913 @@
/*
* Copyright 2017-2021, NXP
* All rights reserved.
*
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#include "fsl_dcdc.h"
/* Component ID definition, used by tools. */
#ifndef FSL_COMPONENT_ID
#define FSL_COMPONENT_ID "platform.drivers.dcdc_1"
#endif
/*******************************************************************************
* Prototypes
******************************************************************************/
/*!
* @brief Get instance number for DCDC module.
*
* @param base DCDC peripheral base address
*/
static uint32_t DCDC_GetInstance(DCDC_Type *base);
#if (defined(DCDC_REG4_ENABLE_SP_MASK) && DCDC_REG4_ENABLE_SP_MASK)
/*!
* @brief Convert the byte array to word.
*
* @param ptrArray Pointer to the byte array.
* @return The converted result.
*/
static uint32_t DCDC_ConvertByteArrayToWord(uint8_t *ptrArray);
#endif /* DCDC_REG4_ENABLE_SP_MASK */
/*******************************************************************************
* Variables
******************************************************************************/
/*! @brief Pointers to DCDC bases for each instance. */
static DCDC_Type *const s_dcdcBases[] = DCDC_BASE_PTRS;
#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
/*! @brief Pointers to DCDC clocks for each instance. */
static const clock_ip_name_t s_dcdcClocks[] = DCDC_CLOCKS;
#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
/*******************************************************************************
* Code
******************************************************************************/
static uint32_t DCDC_GetInstance(DCDC_Type *base)
{
uint32_t instance;
/* Find the instance index from base address mappings. */
for (instance = 0; instance < ARRAY_SIZE(s_dcdcBases); instance++)
{
if (MSDK_REG_SECURE_ADDR(s_dcdcBases[instance]) == MSDK_REG_SECURE_ADDR(base))
{
break;
}
}
assert(instance < ARRAY_SIZE(s_dcdcBases));
return instance;
}
#if (defined(DCDC_REG4_ENABLE_SP_MASK) && DCDC_REG4_ENABLE_SP_MASK)
static uint32_t DCDC_ConvertByteArrayToWord(uint8_t *ptrArray)
{
assert(ptrArray != NULL);
uint32_t temp32 = 0UL;
uint8_t index;
for (index = 0U; index < 4U; index++)
{
temp32 |= ptrArray[index] << ((index % 4U) * 8U);
}
return temp32;
}
#endif /* DCDC_REG4_ENABLE_SP_MASK */
#if defined(FSL_FEATURE_DCDC_HAS_CTRL_REG) && FSL_FEATURE_DCDC_HAS_CTRL_REG
/*!
* brief Enable the access to DCDC registers.
*
* param base DCDC peripheral base address.
* param config Pointer to the configuration structure.
*/
void DCDC_Init(DCDC_Type *base, dcdc_config_t *config)
{
#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
/* Enable the clock. */
CLOCK_EnableClock(s_dcdcClocks[DCDC_GetInstance(base)]);
#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
uint32_t tmp32 = base->CTRL0;
tmp32 |= DCDC_CTRL0_CONTROL_MODE(config->controlMode) | DCDC_CTRL0_TRIM_HOLD(config->trimInputMode);
if (config->enableDcdcTimeout)
{
tmp32 |= DCDC_CTRL0_ENABLE_DCDC_CNT_MASK;
}
if (config->enableSwitchingConverterOutput)
{
tmp32 |= DCDC_CTRL0_DIG_EN_MASK;
}
base->CTRL0 |= DCDC_CTRL0_ENABLE_MASK;
base->CTRL0 = tmp32;
}
#else
/*!
* brief Enable the access to DCDC registers.
*
* param base DCDC peripheral base address.
*/
void DCDC_Init(DCDC_Type *base)
{
#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
/* Enable the clock. */
CLOCK_EnableClock(s_dcdcClocks[DCDC_GetInstance(base)]);
#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
}
#endif /* FSL_FEATURE_DCDC_HAS_CTRL_REG */
/*!
* brief Disable the access to DCDC registers.
*
* param base DCDC peripheral base address.
*/
void DCDC_Deinit(DCDC_Type *base)
{
#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
/* Disable the clock. */
CLOCK_DisableClock(s_dcdcClocks[DCDC_GetInstance(base)]);
#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
}
#if defined(FSL_FEATURE_DCDC_HAS_CTRL_REG) && FSL_FEATURE_DCDC_HAS_CTRL_REG
/*!
* brief Get the default setting for DCDC user configuration structure.
*
* This function initializes the user configuration structure to a default value. The default values are:
* code
* config->controlMode = kDCDC_StaticControl;
* config->trimInputMode = kDCDC_SampleTrimInput;
* config->enableDcdcTimeout = false;
* config->enableSwitchingConverterOutput = false;
* endcode
*
* param config Pointer to configuration structure. See to "dcdc_config_t"
*/
void DCDC_GetDefaultConfig(DCDC_Type *base, dcdc_config_t *config)
{
assert(NULL != config);
/* Initializes the configure structure to zero. */
(void)memset(config, 0, sizeof(*config));
config->controlMode = kDCDC_StaticControl;
config->trimInputMode = kDCDC_SampleTrimInput;
config->enableDcdcTimeout = false;
config->enableSwitchingConverterOutput = false;
}
/*!
* @brief Make DCDC enter into low power modes.
*
* @param base DCDC peripheral base address.
* @param mode DCDC low power mode selection. See to "_dcdc_low_power_mode"
*/
void DCDC_EnterLowPowerMode(DCDC_Type *base, dcdc_low_power_mode_t mode)
{
switch (mode)
{
case kDCDC_StandbyMode:
base->CTRL0 |= DCDC_CTRL0_STBY_EN_MASK;
break;
case kDCDC_LowPowerMode:
base->CTRL0 |= DCDC_CTRL0_LP_MODE_EN_MASK;
break;
case kDCDC_GpcStandbyLowPowerMode:
base->CTRL0 |= DCDC_CTRL0_STBY_LP_MODE_EN_MASK;
break;
default:
assert(false);
break;
}
}
#endif /* FSL_FEATURE_DCDC_HAS_CTRL_REG */
/*!
* brief Configure the DCDC clock source.
*
* param base DCDC peripheral base address.
* param clockSource Clock source for DCDC. See to "dcdc_clock_source_t".
*/
void DCDC_SetClockSource(DCDC_Type *base, dcdc_clock_source_t clockSource)
{
uint32_t tmp32;
/* Configure the DCDC_REG0 register. */
tmp32 = base->REG0 & ~(DCDC_REG0_XTAL_24M_OK_MASK | DCDC_REG0_DISABLE_AUTO_CLK_SWITCH_MASK |
DCDC_REG0_SEL_CLK_MASK | DCDC_REG0_PWD_OSC_INT_MASK);
switch (clockSource)
{
case kDCDC_ClockInternalOsc:
tmp32 |= DCDC_REG0_DISABLE_AUTO_CLK_SWITCH_MASK;
break;
case kDCDC_ClockExternalOsc:
/* Choose the external clock and disable the internal clock. */
tmp32 |= DCDC_REG0_DISABLE_AUTO_CLK_SWITCH_MASK | DCDC_REG0_SEL_CLK_MASK | DCDC_REG0_PWD_OSC_INT_MASK;
break;
case kDCDC_ClockAutoSwitch:
/* Set to switch from internal ring osc to xtal 24M if auto mode is enabled. */
tmp32 |= DCDC_REG0_XTAL_24M_OK_MASK;
break;
default:
assert(false);
break;
}
base->REG0 = tmp32;
}
/*!
* brief Get the default setting for detection configuration.
*
* The default configuration are set according to responding registers' setting when powered on.
* They are:
* code
* config->enableXtalokDetection = false;
* config->powerDownOverVoltageDetection = true;
* config->powerDownLowVlotageDetection = false;
* config->powerDownOverCurrentDetection = true;
* config->powerDownPeakCurrentDetection = true;
* config->powerDownZeroCrossDetection = true;
* config->OverCurrentThreshold = kDCDC_OverCurrentThresholdAlt0;
* config->PeakCurrentThreshold = kDCDC_PeakCurrentThresholdAlt0;
* endcode
*
* param config Pointer to configuration structure. See to "dcdc_detection_config_t"
*/
void DCDC_GetDefaultDetectionConfig(dcdc_detection_config_t *config)
{
assert(NULL != config);
/* Initializes the configure structure to zero. */
(void)memset(config, 0, sizeof(*config));
config->enableXtalokDetection = false;
#if (defined(FSL_FEATURE_DCDC_VDD_OUTPUT_COUNT) && (FSL_FEATURE_DCDC_VDD_OUTPUT_COUNT == 2))
config->powerDownOverVoltageVdd1P8Detection = true;
config->powerDownOverVoltageVdd1P0Detection = true;
#else
config->powerDownOverVoltageDetection = true;
#endif /* FSL_FEATURE_DCDC_VDD_OUTPUT_COUNT */
config->powerDownLowVlotageDetection = false;
config->powerDownOverCurrentDetection = true;
config->powerDownPeakCurrentDetection = true;
config->powerDownZeroCrossDetection = true;
config->OverCurrentThreshold = kDCDC_OverCurrentThresholdAlt0;
config->PeakCurrentThreshold = kDCDC_PeakCurrentThresholdAlt0;
}
/*!
* breif Configure the DCDC detection.
*
* param base DCDC peripheral base address.
* param config Pointer to configuration structure. See to "dcdc_detection_config_t"
*/
void DCDC_SetDetectionConfig(DCDC_Type *base, const dcdc_detection_config_t *config)
{
assert(NULL != config);
uint32_t tmp32;
/* Configure the DCDC_REG0 register. */
tmp32 = base->REG0 & ~(DCDC_REG0_XTALOK_DISABLE_MASK
#if (defined(FSL_FEATURE_DCDC_VDD_OUTPUT_COUNT) && (FSL_FEATURE_DCDC_VDD_OUTPUT_COUNT == 2))
| DCDC_REG0_PWD_HIGH_VDD1P8_DET_MASK | DCDC_REG0_PWD_HIGH_VDD1P0_DET_MASK
#else
| DCDC_REG0_PWD_HIGH_VOLT_DET_MASK
#endif /* FSL_FEATURE_DCDC_VDD_OUTPUT_COUNT */
#if defined(FSL_FEATURE_DCDC_HAS_REG0_DCDC_IN_DET) && FSL_FEATURE_DCDC_HAS_REG0_DCDC_IN_DET
| DCDC_REG0_PWD_CMP_DCDC_IN_DET_MASK
#else
| DCDC_REG0_PWD_CMP_BATT_DET_MASK
#endif /* FSL_FEATURE_DCDC_HAS_REG0_DCDC_IN_DET */
| DCDC_REG0_PWD_OVERCUR_DET_MASK | DCDC_REG0_PWD_CUR_SNS_CMP_MASK | DCDC_REG0_PWD_ZCD_MASK |
DCDC_REG0_CUR_SNS_THRSH_MASK | DCDC_REG0_OVERCUR_TRIG_ADJ_MASK);
tmp32 |= DCDC_REG0_CUR_SNS_THRSH(config->PeakCurrentThreshold) |
DCDC_REG0_OVERCUR_TRIG_ADJ(config->OverCurrentThreshold);
if (false == config->enableXtalokDetection)
{
tmp32 |= DCDC_REG0_XTALOK_DISABLE_MASK;
}
#if (defined(FSL_FEATURE_DCDC_VDD_OUTPUT_COUNT) && (FSL_FEATURE_DCDC_VDD_OUTPUT_COUNT == 2))
if (config->powerDownOverVoltageVdd1P8Detection)
{
tmp32 |= DCDC_REG0_PWD_HIGH_VDD1P8_DET_MASK;
}
if (config->powerDownOverVoltageVdd1P0Detection)
{
tmp32 |= DCDC_REG0_PWD_HIGH_VDD1P0_DET_MASK;
}
#else
if (config->powerDownOverVoltageDetection)
{
tmp32 |= DCDC_REG0_PWD_HIGH_VOLT_DET_MASK;
}
#endif /* FSL_FEATURE_DCDC_VDD_OUTPUT_COUNT */
if (config->powerDownLowVlotageDetection)
{
#if defined(FSL_FEATURE_DCDC_HAS_REG0_DCDC_IN_DET) && FSL_FEATURE_DCDC_HAS_REG0_DCDC_IN_DET
tmp32 |= DCDC_REG0_PWD_CMP_DCDC_IN_DET_MASK;
#else
tmp32 |= DCDC_REG0_PWD_CMP_BATT_DET_MASK;
#endif /* FSL_FEATURE_DCDC_HAS_REG0_DCDC_IN_DET */
}
if (config->powerDownOverCurrentDetection)
{
tmp32 |= DCDC_REG0_PWD_OVERCUR_DET_MASK;
}
if (config->powerDownPeakCurrentDetection)
{
tmp32 |= DCDC_REG0_PWD_CUR_SNS_CMP_MASK;
}
if (config->powerDownZeroCrossDetection)
{
tmp32 |= DCDC_REG0_PWD_ZCD_MASK;
}
base->REG0 = tmp32;
}
/*!
* brief Get the default setting for low power configuration.
*
* The default configuration are set according to responding registers' setting when powered on.
* They are:
* code
* config->enableOverloadDetection = true;
* config->enableAdjustHystereticValue = false;
* config->countChargingTimePeriod = kDCDC_CountChargingTimePeriod8Cycle;
* config->countChargingTimeThreshold = kDCDC_CountChargingTimeThreshold32;
* endcode
*
* param config Pointer to configuration structure. See to "dcdc_low_power_config_t"
*/
void DCDC_GetDefaultLowPowerConfig(dcdc_low_power_config_t *config)
{
assert(NULL != config);
/* Initializes the configure structure to zero. */
(void)memset(config, 0, sizeof(*config));
#if !(defined(FSL_FEATURE_DCDC_HAS_NO_REG0_EN_LP_OVERLOAD_SNS) && FSL_FEATURE_DCDC_HAS_NO_REG0_EN_LP_OVERLOAD_SNS)
config->enableOverloadDetection = true;
#endif /* FSL_FEATURE_DCDC_HAS_NO_REG0_EN_LP_OVERLOAD_SNS */
config->enableAdjustHystereticValue = false;
config->countChargingTimePeriod = kDCDC_CountChargingTimePeriod8Cycle;
config->countChargingTimeThreshold = kDCDC_CountChargingTimeThreshold32;
}
/*!
* brief Configure the DCDC low power.
*
* param base DCDC peripheral base address.
* param config Pointer to configuration structure. See to "dcdc_low_power_config_t".
*/
void DCDC_SetLowPowerConfig(DCDC_Type *base, const dcdc_low_power_config_t *config)
{
assert(NULL != config);
uint32_t tmp32;
/* Configure the DCDC_REG0 register. */
tmp32 = base->REG0 &
~(DCDC_REG0_LP_HIGH_HYS_MASK | DCDC_REG0_LP_OVERLOAD_FREQ_SEL_MASK | DCDC_REG0_LP_OVERLOAD_THRSH_MASK
#if !(defined(FSL_FEATURE_DCDC_HAS_NO_REG0_EN_LP_OVERLOAD_SNS) && FSL_FEATURE_DCDC_HAS_NO_REG0_EN_LP_OVERLOAD_SNS)
| DCDC_REG0_EN_LP_OVERLOAD_SNS_MASK
#endif /* FSL_FEATURE_DCDC_HAS_NO_REG0_EN_LP_OVERLOAD_SNS */
);
tmp32 |= DCDC_REG0_LP_OVERLOAD_FREQ_SEL(config->countChargingTimePeriod) |
DCDC_REG0_LP_OVERLOAD_THRSH(config->countChargingTimeThreshold);
#if !(defined(FSL_FEATURE_DCDC_HAS_NO_REG0_EN_LP_OVERLOAD_SNS) && FSL_FEATURE_DCDC_HAS_NO_REG0_EN_LP_OVERLOAD_SNS)
if (config->enableOverloadDetection)
{
tmp32 |= DCDC_REG0_EN_LP_OVERLOAD_SNS_MASK;
}
#endif /* FSL_FEATURE_DCDC_HAS_NO_REG0_EN_LP_OVERLOAD_SNS */
if (config->enableAdjustHystereticValue)
{
tmp32 |= DCDC_REG0_LP_HIGH_HYS_MASK;
}
base->REG0 = tmp32;
}
/*!
* brief Get DCDC status flags.
*
* param base peripheral base address.
* return Mask of asserted status flags. See to "_dcdc_status_flags_t".
*/
uint32_t DCDC_GetstatusFlags(DCDC_Type *base)
{
uint32_t tmp32 = 0U;
if (DCDC_REG0_STS_DC_OK_MASK == (DCDC_REG0_STS_DC_OK_MASK & base->REG0))
{
tmp32 |= (uint32_t)kDCDC_LockedOKStatus;
}
return tmp32;
}
#if !(defined(FSL_FEATURE_DCDC_HAS_NO_CURRENT_ALERT_FUNC) && FSL_FEATURE_DCDC_HAS_NO_CURRENT_ALERT_FUNC)
/*!
* brief Reset current alert signal. Alert signal is generate by peak current detection.
*
* param base DCDC peripheral base address.
* param enable Switcher to reset signal. True means reset signal. False means don't reset signal.
*/
void DCDC_ResetCurrentAlertSignal(DCDC_Type *base, bool enable)
{
if (enable)
{
base->REG0 |= DCDC_REG0_CURRENT_ALERT_RESET_MASK;
}
else
{
base->REG0 &= ~DCDC_REG0_CURRENT_ALERT_RESET_MASK;
}
}
#endif /* FSL_FEATURE_DCDC_HAS_NO_CURRENT_ALERT_FUNC */
/*!
* brief Get the default setting for loop control configuration.
*
* The default configuration are set according to responding registers' setting when powered on.
* They are:
* code
* config->enableCommonHysteresis = false;
* config->enableCommonThresholdDetection = false;
* config->enableInvertHysteresisSign = false;
* config->enableRCThresholdDetection = false;
* config->enableRCScaleCircuit = 0U;
* config->complementFeedForwardStep = 0U;
* endcode
*
* param config Pointer to configuration structure. See to "dcdc_loop_control_config_t"
*/
void DCDC_GetDefaultLoopControlConfig(dcdc_loop_control_config_t *config)
{
assert(NULL != config);
/* Initializes the configure structure to zero. */
(void)memset(config, 0, sizeof(*config));
config->enableCommonHysteresis = false;
config->enableCommonThresholdDetection = false;
config->enableInvertHysteresisSign = false;
config->enableRCThresholdDetection = false;
config->enableRCScaleCircuit = 0U;
config->complementFeedForwardStep = 0U;
}
/*!
* brief Configure the DCDC loop control.
*
* param base DCDC peripheral base address.
* param config Pointer to configuration structure. See to "dcdc_loop_control_config_t".
*/
void DCDC_SetLoopControlConfig(DCDC_Type *base, const dcdc_loop_control_config_t *config)
{
assert(NULL != config);
uint32_t tmp32;
/* Configure the DCDC_REG1 register. */
#if defined(FSL_FEATURE_DCDC_HAS_SWITCHING_CONVERTER_DIFFERENTIAL_MODE) && \
FSL_FEATURE_DCDC_HAS_SWITCHING_CONVERTER_DIFFERENTIAL_MODE
tmp32 = base->REG1 & ~(DCDC_REG1_LOOPCTRL_EN_DF_HYST_MASK | DCDC_REG1_LOOPCTRL_EN_CM_HYST_MASK |
DCDC_REG1_LOOPCTRL_DF_HST_THRESH_MASK | DCDC_REG1_LOOPCTRL_CM_HST_THRESH_MASK);
if (config->enableCommonHysteresis)
{
tmp32 |= DCDC_REG1_LOOPCTRL_EN_CM_HYST_MASK;
}
if (config->enableCommonThresholdDetection)
{
tmp32 |= DCDC_REG1_LOOPCTRL_CM_HST_THRESH_MASK;
}
if (config->enableDifferentialHysteresis)
{
tmp32 |= DCDC_REG1_LOOPCTRL_EN_DF_HYST_MASK;
}
if (config->enableDifferentialThresholdDetection)
{
tmp32 |= DCDC_REG1_LOOPCTRL_DF_HST_THRESH_MASK;
}
#else
tmp32 = base->REG1 & ~(DCDC_REG1_LOOPCTRL_EN_HYST_MASK | DCDC_REG1_LOOPCTRL_HST_THRESH_MASK);
if (config->enableCommonHysteresis)
{
tmp32 |= DCDC_REG1_LOOPCTRL_EN_HYST_MASK;
}
if (config->enableCommonThresholdDetection)
{
tmp32 |= DCDC_REG1_LOOPCTRL_HST_THRESH_MASK;
}
#endif /* FSL_FEATURE_DCDC_HAS_SWITCHING_CONVERTER_DIFFERENTIAL_MODE */
base->REG1 = tmp32;
/* configure the DCDC_REG2 register. */
tmp32 = base->REG2 & ~(DCDC_REG2_LOOPCTRL_HYST_SIGN_MASK | DCDC_REG2_LOOPCTRL_RCSCALE_THRSH_MASK |
DCDC_REG2_LOOPCTRL_EN_RCSCALE_MASK | DCDC_REG2_LOOPCTRL_DC_FF_MASK);
tmp32 |= DCDC_REG2_LOOPCTRL_DC_FF(config->complementFeedForwardStep) |
DCDC_REG2_LOOPCTRL_EN_RCSCALE(config->enableRCScaleCircuit);
if (config->enableInvertHysteresisSign)
{
tmp32 |= DCDC_REG2_LOOPCTRL_HYST_SIGN_MASK;
}
if (config->enableRCThresholdDetection)
{
tmp32 |= DCDC_REG2_LOOPCTRL_RCSCALE_THRSH_MASK;
}
base->REG2 = tmp32;
}
/*!
* brief Configure for the min power.
*
* param base DCDC peripheral base address.
* param config Pointer to configuration structure. See to "dcdc_min_power_config_t".
*/
void DCDC_SetMinPowerConfig(DCDC_Type *base, const dcdc_min_power_config_t *config)
{
assert(NULL != config);
uint32_t tmp32;
tmp32 = base->REG3 & ~DCDC_REG3_MINPWR_DC_HALFCLK_MASK;
if (config->enableUseHalfFreqForContinuous)
{
tmp32 |= DCDC_REG3_MINPWR_DC_HALFCLK_MASK;
}
base->REG3 = tmp32;
}
#if (defined(FSL_FEATURE_DCDC_VDD_OUTPUT_COUNT) && (FSL_FEATURE_DCDC_VDD_OUTPUT_COUNT == 2))
/*!
* brief Adjust the target voltage of VDD_SOC in run mode and low power mode.
* Do not use this function. It has been superceded by DCDC_AdjustRunTargetVoltage
* and DCDC_AdjustLowPowerTargetVoltage.
*
* This function is to adjust the target voltage of DCDC output. Change them and finally wait until the output is
* stabled.
* Set the target value of run mode the same as low power mode before entering power save mode, because DCDC will switch
* back to run mode if it detects the current loading is larger than about 50 mA(typical value).
*
* param base DCDC peripheral base address.
* param VDDRun Target value in run mode. 25 mV each step from 0x00 to 0x1F. 00 is for 0.8V, 0x1F is for 1.575V.
* param VDDStandby Target value in low power mode. 25 mV each step from 0x00 to 0x4. 00 is for 0.9V, 0x4 is for 1.0V.
* param sel sel DCDC target voltage output selection. See to "_dcdc_voltage_output_sel".
*/
void DCDC_AdjustTargetVoltage(DCDC_Type *base, uint32_t VDDRun, uint32_t VDDStandby, dcdc_voltage_output_sel_t sel)
{
uint32_t tmp32;
if (sel == kDCDC_VoltageOutput1P8)
{
/* Unlock the step for the VDD 1P8. */
base->REG3 &= ~DCDC_REG3_VDD1P8CTRL_DISABLE_STEP_MASK;
/* Configure the DCDC_CTRL1 register. */
tmp32 = base->CTRL1 & ~(DCDC_CTRL1_VDD1P8CTRL_STBY_TRG_MASK | DCDC_CTRL1_VDD1P8CTRL_TRG_MASK);
tmp32 |= DCDC_CTRL1_VDD1P8CTRL_STBY_TRG(VDDStandby) | DCDC_CTRL1_VDD1P8CTRL_TRG(VDDRun);
base->CTRL1 = tmp32;
}
else if (sel == kDCDC_VoltageOutput1P0)
{
/* Unlock the step for the VDD 1P0. */
base->REG3 &= ~DCDC_REG3_VDD1P0CTRL_DISABLE_STEP_MASK;
/* Configure the DCDC_CTRL1 register. */
tmp32 = base->CTRL1 & ~(DCDC_CTRL1_VDD1P0CTRL_STBY_TRG_MASK | DCDC_CTRL1_VDD1P0CTRL_TRG_MASK);
tmp32 |= DCDC_CTRL1_VDD1P0CTRL_STBY_TRG(VDDStandby) | DCDC_CTRL1_VDD1P0CTRL_TRG(VDDRun);
base->CTRL1 = tmp32;
}
else
{
; /* Intentional empty */
}
/* DCDC_STS_DC_OK bit will be de-asserted after target register changes. After output voltage is set to new
* target value, DCDC_STS_DC_OK will be asserted. */
while (DCDC_REG0_STS_DC_OK_MASK != (DCDC_REG0_STS_DC_OK_MASK & base->REG0))
{
}
}
/*!
* brief Adjust the target voltage of VDD_SOC in run mode.
*
* This function is to adjust the target voltage of DCDC output. Change them and finally wait until the output is
* stabled.
* Set the target value of run mode the same as low power mode before entering power save mode, because DCDC will switch
* back to run mode if it detects the current loading is larger than about 50 mA(typical value).
*
* param base DCDC peripheral base address.
* param VDDRun Target value in run mode. 25 mV each step from 0x00 to 0x1F. 00 is for 0.8V, 0x1F is for 1.575V.
* param sel sel DCDC target voltage output selection. See to "_dcdc_voltage_output_sel".
*/
void DCDC_AdjustRunTargetVoltage(DCDC_Type *base, uint32_t VDDRun, dcdc_voltage_output_sel_t sel)
{
uint32_t tmp32;
if (sel == kDCDC_VoltageOutput1P8)
{
/* Unlock the step for the VDD 1P8. */
base->REG3 &= ~DCDC_REG3_VDD1P8CTRL_DISABLE_STEP_MASK;
/* Configure the DCDC_CTRL1 register. */
tmp32 = base->CTRL1 & ~DCDC_CTRL1_VDD1P8CTRL_TRG_MASK;
tmp32 |= DCDC_CTRL1_VDD1P8CTRL_TRG(VDDRun);
base->CTRL1 = tmp32;
}
else if (sel == kDCDC_VoltageOutput1P0)
{
/* Unlock the step for the VDD 1P0. */
base->REG3 &= ~DCDC_REG3_VDD1P0CTRL_DISABLE_STEP_MASK;
/* Configure the DCDC_CTRL1 register. */
tmp32 = base->CTRL1 & ~DCDC_CTRL1_VDD1P0CTRL_TRG_MASK;
tmp32 |= DCDC_CTRL1_VDD1P0CTRL_TRG(VDDRun);
base->CTRL1 = tmp32;
}
else
{
; /* Intentional empty */
}
/* DCDC_STS_DC_OK bit will be de-asserted after target register changes. After output voltage is set to new
* target value, DCDC_STS_DC_OK will be asserted. */
while (DCDC_REG0_STS_DC_OK_MASK != (DCDC_REG0_STS_DC_OK_MASK & base->REG0))
{
}
}
/*!
* brief Adjust the target voltage of VDD_SOC in low power mode.
*
* This function is to adjust the target voltage of DCDC output. Change them and finally wait until the output is
* stabled.
* Set the target value of run mode the same as low power mode before entering power save mode, because DCDC will switch
* back to run mode if it detects the current loading is larger than about 50 mA(typical value).
*
* param base DCDC peripheral base address.
* param VDDStandby Target value in low power mode. 25 mV each step from 0x00 to 0x4. 00 is for 0.9V, 0x4 is for 1.0V.
* param sel sel DCDC target voltage output selection. See to "_dcdc_voltage_output_sel".
*/
void DCDC_AdjustLowPowerTargetVoltage(DCDC_Type *base, uint32_t VDDStandby, dcdc_voltage_output_sel_t sel)
{
uint32_t tmp32;
if (sel == kDCDC_VoltageOutput1P8)
{
/* Unlock the step for the VDD 1P8. */
base->REG3 &= ~DCDC_REG3_VDD1P8CTRL_DISABLE_STEP_MASK;
/* Configure the DCDC_CTRL1 register. */
tmp32 = base->CTRL1 & ~(DCDC_CTRL1_VDD1P8CTRL_STBY_TRG_MASK);
tmp32 |= DCDC_CTRL1_VDD1P8CTRL_STBY_TRG(VDDStandby);
base->CTRL1 = tmp32;
}
else if (sel == kDCDC_VoltageOutput1P0)
{
/* Unlock the step for the VDD 1P0. */
base->REG3 &= ~DCDC_REG3_VDD1P0CTRL_DISABLE_STEP_MASK;
/* Configure the DCDC_CTRL1 register. */
tmp32 = base->CTRL1 & ~(DCDC_CTRL1_VDD1P0CTRL_STBY_TRG_MASK);
tmp32 |= DCDC_CTRL1_VDD1P0CTRL_STBY_TRG(VDDStandby);
base->CTRL1 = tmp32;
}
else
{
; /* Intentional empty */
}
/* DCDC_STS_DC_OK bit will be de-asserted after target register changes. After output voltage is set to new
* target value, DCDC_STS_DC_OK will be asserted. */
while (DCDC_REG0_STS_DC_OK_MASK != (DCDC_REG0_STS_DC_OK_MASK & base->REG0))
{
}
}
#else
/*!
* brief Adjust the target voltage of VDD_SOC in run mode and low power mode.
* Do not use this function. It has been superceded by DCDC_AdjustRunTargetVoltage
* and DCDC_AdjustLowPowerTargetVoltage
*
* This function is to adjust the target voltage of DCDC output. Change them and finally wait until the output is
* stabled.
* Set the target value of run mode the same as low power mode before entering power save mode, because DCDC will switch
* back to run mode if it detects the current loading is larger than about 50 mA(typical value).
*
* param base DCDC peripheral base address.
* param VDDRun Target value in run mode. 25 mV each step from 0x00 to 0x1F. 00 is for 0.8V, 0x1F is for 1.575V.
* param VDDStandby Target value in low power mode. 25 mV each step from 0x00 to 0x4. 00 is for 0.9V, 0x4 is for 1.0V.
*/
void DCDC_AdjustTargetVoltage(DCDC_Type *base, uint32_t VDDRun, uint32_t VDDStandby)
{
uint32_t tmp32;
/* Unlock the step for the output. */
base->REG3 &= ~DCDC_REG3_DISABLE_STEP_MASK;
/* Configure the DCDC_REG3 register. */
tmp32 = base->REG3 & ~(DCDC_REG3_TARGET_LP_MASK | DCDC_REG3_TRG_MASK);
tmp32 |= DCDC_REG3_TARGET_LP(VDDStandby) | DCDC_REG3_TRG(VDDRun);
base->REG3 = tmp32;
/* DCDC_STS_DC_OK bit will be de-asserted after target register changes. After output voltage is set to new
* target value, DCDC_STS_DC_OK will be asserted. */
while (DCDC_REG0_STS_DC_OK_MASK != (DCDC_REG0_STS_DC_OK_MASK & base->REG0))
{
}
}
/*!
* brief Adjust the target voltage of VDD_SOC in run mode.
*
* This function is to adjust the target voltage of DCDC output. Change them and finally wait until the output is
* stabled.
* Set the target value of run mode the same as low power mode before entering power save mode, because DCDC will switch
* back to run mode if it detects the current loading is larger than about 50 mA(typical value).
*
* param base DCDC peripheral base address.
* param VDDRun Target value in run mode. 25 mV each step from 0x00 to 0x1F. 00 is for 0.8V, 0x1F is for 1.575V.
*/
void DCDC_AdjustRunTargetVoltage(DCDC_Type *base, uint32_t VDDRun)
{
uint32_t tmp32;
/* Unlock the step for the output. */
base->REG3 &= ~DCDC_REG3_DISABLE_STEP_MASK;
/* Configure the DCDC_REG3 register. */
tmp32 = base->REG3 & ~DCDC_REG3_TRG_MASK;
tmp32 |= DCDC_REG3_TRG(VDDRun);
base->REG3 = tmp32;
/* DCDC_STS_DC_OK bit will be de-asserted after target register changes. After output voltage is set to new
* target value, DCDC_STS_DC_OK will be asserted. */
while (DCDC_REG0_STS_DC_OK_MASK != (DCDC_REG0_STS_DC_OK_MASK & base->REG0))
{
}
}
/*!
* brief Adjust the target voltage of VDD_SOC in low power mode.
*
* This function is to adjust the target voltage of DCDC output. Change them and finally wait until the output is
* stabled.
* Set the target value of run mode the same as low power mode before entering power save mode, because DCDC will switch
* back to run mode if it detects the current loading is larger than about 50 mA(typical value).
*
* param base DCDC peripheral base address.
* param VDDStandby Target value in low power mode. 25 mV each step from 0x00 to 0x4. 00 is for 0.9V, 0x4 is for 1.0V.
*/
void DCDC_AdjustLowPowerTargetVoltage(DCDC_Type *base, uint32_t VDDStandby)
{
uint32_t tmp32;
/* Unlock the step for the output. */
base->REG3 &= ~DCDC_REG3_DISABLE_STEP_MASK;
/* Configure the DCDC_REG3 register. */
tmp32 = base->REG3 & ~DCDC_REG3_TARGET_LP_MASK;
tmp32 |= DCDC_REG3_TARGET_LP(VDDStandby);
base->REG3 = tmp32;
/* DCDC_STS_DC_OK bit will be de-asserted after target register changes. After output voltage is set to new
* target value, DCDC_STS_DC_OK will be asserted. */
while (DCDC_REG0_STS_DC_OK_MASK != (DCDC_REG0_STS_DC_OK_MASK & base->REG0))
{
}
}
#endif /* FSL_FEATURE_DCDC_VDD_OUTPUT_COUNT == 2 */
/*!
* brief Configure the DCDC internal regulator.
*
* param base DCDC peripheral base address.
* param config Pointer to configuration structure. See to "dcdc_internal_regulator_config_t".
*/
void DCDC_SetInternalRegulatorConfig(DCDC_Type *base, const dcdc_internal_regulator_config_t *config)
{
assert(NULL != config);
uint32_t tmp32;
#if (defined(FSL_FEATURE_DCDC_HAS_REG3_FBK_SEL) && FSL_FEATURE_DCDC_HAS_REG3_FBK_SEL)
tmp32 = base->REG3 & ~DCDC_REG3_REG_FBK_SEL_MASK;
tmp32 |= DCDC_REG3_REG_FBK_SEL(config->feedbackPoint);
base->REG3 = tmp32;
tmp32 = base->REG1 & ~DCDC_REG1_REG_RLOAD_SW_MASK;
#else
/* Configure the DCDC_REG1 register. */
tmp32 = base->REG1 & ~(DCDC_REG1_REG_FBK_SEL_MASK | DCDC_REG1_REG_RLOAD_SW_MASK);
tmp32 |= DCDC_REG1_REG_FBK_SEL(config->feedbackPoint);
#endif /* FSL_FEATURE_DCDC_HAS_REG3_FBK_SEL */
if (config->enableLoadResistor)
{
tmp32 |= DCDC_REG1_REG_RLOAD_SW_MASK;
}
base->REG1 = tmp32;
}
#if (defined(DCDC_REG4_ENABLE_SP_MASK) && DCDC_REG4_ENABLE_SP_MASK)
/*!
* brief Init DCDC module when the control mode selected as setpoint mode.
*
* note The function should be invoked in the initial step to config the
* DCDC via setpoint control mode.
*
* param base DCDC peripheral base address.
* param config The pointer to the structure @ref dcdc_setpoint_config_t.
*/
void DCDC_SetPointInit(DCDC_Type *base, const dcdc_setpoint_config_t *config)
{
assert(config != NULL);
/* Enable DCDC Dig Logic. */
base->REG5 = config->enableDigLogicMap;
/* Set DCDC power mode. */
base->REG6 = config->lowpowerMap;
base->REG7 = config->standbyMap;
base->REG7P = config->standbyLowpowerMap;
/* Set target voltage of VDD1P8 in buck mode. */
base->REG8 = DCDC_ConvertByteArrayToWord(config->buckVDD1P8TargetVoltage);
base->REG9 = DCDC_ConvertByteArrayToWord(config->buckVDD1P8TargetVoltage + 4U);
base->REG10 = DCDC_ConvertByteArrayToWord(config->buckVDD1P8TargetVoltage + 8U);
base->REG11 = DCDC_ConvertByteArrayToWord(config->buckVDD1P8TargetVoltage + 12U);
/* Set target voltage of VDD1P0 in buck mode. */
base->REG12 = DCDC_ConvertByteArrayToWord(config->buckVDD1P0TargetVoltage);
base->REG13 = DCDC_ConvertByteArrayToWord(config->buckVDD1P0TargetVoltage + 4U);
base->REG14 = DCDC_ConvertByteArrayToWord(config->buckVDD1P0TargetVoltage + 8U);
base->REG15 = DCDC_ConvertByteArrayToWord(config->buckVDD1P0TargetVoltage + 12U);
/* Set target voltage of VDD1P8 in low power mode. */
base->REG16 = DCDC_ConvertByteArrayToWord(config->standbyVDD1P8TargetVoltage);
base->REG17 = DCDC_ConvertByteArrayToWord(config->standbyVDD1P8TargetVoltage + 4U);
base->REG18 = DCDC_ConvertByteArrayToWord(config->standbyVDD1P8TargetVoltage + 8U);
base->REG19 = DCDC_ConvertByteArrayToWord(config->standbyVDD1P8TargetVoltage + 12U);
/* Set target voltage of VDD1P0 in low power mode. */
base->REG20 = DCDC_ConvertByteArrayToWord(config->standbyVDD1P0TargetVoltage);
base->REG21 = DCDC_ConvertByteArrayToWord(config->standbyVDD1P0TargetVoltage + 4U);
base->REG22 = DCDC_ConvertByteArrayToWord(config->standbyVDD1P0TargetVoltage + 8U);
base->REG23 = DCDC_ConvertByteArrayToWord(config->standbyVDD1P0TargetVoltage + 12U);
/* Enable DCDC module. */
base->REG4 = config->enableDCDCMap;
}
#endif /* DCDC_REG4_ENABLE_SP_MASK */
/*!
* brief Boot DCDC into DCM(discontinous conduction mode).
*
* pwd_zcd=0x0;
* pwd_cmp_offset=0x0;
* dcdc_loopctrl_en_rcscale= 0x5;
* DCM_set_ctrl=1'b1;
*
* param base DCDC peripheral base address.
*/
void DCDC_BootIntoDCM(DCDC_Type *base)
{
base->REG0 &= ~(DCDC_REG0_PWD_ZCD_MASK | DCDC_REG0_PWD_CMP_OFFSET_MASK);
base->REG2 = (~DCDC_REG2_LOOPCTRL_EN_RCSCALE_MASK & base->REG2) | DCDC_REG2_LOOPCTRL_EN_RCSCALE(0x5U) |
DCDC_REG2_DCM_SET_CTRL_MASK;
}
/*!
* brief Boot DCDC into CCM(continous conduction mode).
*
* pwd_zcd=0x1;
* pwd_cmp_offset=0x0;
* dcdc_loopctrl_en_rcscale=0x3;
*
* param base DCDC peripheral base address.
*/
void DCDC_BootIntoCCM(DCDC_Type *base)
{
base->REG0 = (~DCDC_REG0_PWD_CMP_OFFSET_MASK & base->REG0) | DCDC_REG0_PWD_ZCD_MASK;
base->REG2 = (~DCDC_REG2_LOOPCTRL_EN_RCSCALE_MASK & base->REG2) | DCDC_REG2_LOOPCTRL_EN_RCSCALE(0x3U);
}

View File

@ -0,0 +1,103 @@
/*
* Copyright (c) 2016, Freescale Semiconductor, Inc.
* Copyright 2016-2019 NXP
* All rights reserved.
*
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#include "fsl_gpc.h"
/* Component ID definition, used by tools. */
#ifndef FSL_COMPONENT_ID
#define FSL_COMPONENT_ID "platform.drivers.gpc_1"
#endif
/*!
* brief Enable the IRQ.
*
* param base GPC peripheral base address.
* param irqId ID number of IRQ to be enabled, available range is 32-159. 0-31 is available in some platforms.
*/
void GPC_EnableIRQ(GPC_Type *base, uint32_t irqId)
{
uint32_t irqRegNum = irqId / 32U;
uint32_t irqRegShiftNum = irqId % 32U;
assert(irqRegNum <= GPC_IMR_COUNT);
#if ((defined FSL_FEATURE_GPC_HAS_IRQ_0_31) && FSL_FEATURE_GPC_HAS_IRQ_0_31)
if (irqRegNum == GPC_IMR_COUNT)
{
base->IMR5 &= ~(1UL << irqRegShiftNum);
}
else
{
base->IMR[irqRegNum] &= ~(1UL << irqRegShiftNum);
}
#else
assert(irqRegNum > 0U);
base->IMR[irqRegNum - 1UL] &= ~(1UL << irqRegShiftNum);
#endif /* FSL_FEATURE_GPC_HAS_IRQ_0_31 */
}
/*!
* brief Disable the IRQ.
*
* param base GPC peripheral base address.
* param irqId ID number of IRQ to be disabled, available range is 32-159. 0-31 is available in some platforms.
*/
void GPC_DisableIRQ(GPC_Type *base, uint32_t irqId)
{
uint32_t irqRegNum = irqId / 32U;
uint32_t irqRegShiftNum = irqId % 32U;
assert(irqRegNum <= GPC_IMR_COUNT);
#if ((defined FSL_FEATURE_GPC_HAS_IRQ_0_31) && FSL_FEATURE_GPC_HAS_IRQ_0_31)
if (irqRegNum == GPC_IMR_COUNT)
{
base->IMR5 |= (1UL << irqRegShiftNum);
}
else
{
base->IMR[irqRegNum] |= (1UL << irqRegShiftNum);
}
#else
assert(irqRegNum > 0U);
base->IMR[irqRegNum - 1UL] |= (1UL << irqRegShiftNum);
#endif /* FSL_FEATURE_GPC_HAS_IRQ_0_31 */
}
/*!
* brief Get the IRQ/Event flag.
*
* param base GPC peripheral base address.
* param irqId ID number of IRQ to be enabled, available range is 32-159. 0-31 is available in some platforms.
* return Indicated IRQ/Event is asserted or not.
*/
bool GPC_GetIRQStatusFlag(GPC_Type *base, uint32_t irqId)
{
uint32_t irqRegNum = irqId / 32U;
uint32_t irqRegShiftNum = irqId % 32U;
uint32_t ret;
assert(irqRegNum <= GPC_IMR_COUNT);
#if ((defined FSL_FEATURE_GPC_HAS_IRQ_0_31) && FSL_FEATURE_GPC_HAS_IRQ_0_31)
if (irqRegNum == GPC_IMR_COUNT)
{
ret = base->ISR5 & (1UL << irqRegShiftNum);
}
else
{
ret = base->ISR[irqRegNum] & (1UL << irqRegShiftNum);
}
#else
assert(irqRegNum > 0U);
ret = base->ISR[irqRegNum - 1UL] & (1UL << irqRegShiftNum);
#endif /* FSL_FEATURE_GPC_HAS_IRQ_0_31 */
return (1UL << irqRegShiftNum) == ret;
}

View File

@ -0,0 +1,183 @@
/*
* Copyright (c) 2016, Freescale Semiconductor, Inc.
* Copyright 2016-2017, 2020-2021 NXP
* All rights reserved.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#include "fsl_gpio.h"
/* Component ID definition, used by tools. */
#ifndef FSL_COMPONENT_ID
#define FSL_COMPONENT_ID "platform.drivers.igpio"
#endif
/*******************************************************************************
* Variables
******************************************************************************/
#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
/* Array of GPIO peripheral base address. */
static GPIO_Type *const s_gpioBases[] = GPIO_BASE_PTRS;
#endif
#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
/* Array of GPIO clock name. */
static const clock_ip_name_t s_gpioClock[] = GPIO_CLOCKS;
#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
/*******************************************************************************
* Prototypes
******************************************************************************/
#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
/*!
* @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);
/*******************************************************************************
* Code
******************************************************************************/
static uint32_t GPIO_GetInstance(GPIO_Type *base)
{
uint32_t instance;
/* Find the instance index from base address mappings. */
for (instance = 0U; instance < ARRAY_SIZE(s_gpioBases); instance++)
{
if (MSDK_REG_SECURE_ADDR(s_gpioBases[instance]) == MSDK_REG_SECURE_ADDR(base))
{
break;
}
}
assert(instance < ARRAY_SIZE(s_gpioBases));
return instance;
}
#endif
/*!
* brief Initializes the GPIO peripheral according to the specified
* parameters in the initConfig.
*
* param base GPIO base pointer.
* param pin Specifies the pin number
* param initConfig pointer to a ref gpio_pin_config_t structure that
* contains the configuration information.
*/
void GPIO_PinInit(GPIO_Type *base, uint32_t pin, const gpio_pin_config_t *Config)
{
#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
/* Enable GPIO clock. */
uint32_t instance = GPIO_GetInstance(base);
/* If The clock IP is valid, enable the clock gate. */
if ((instance < ARRAY_SIZE(s_gpioClock)) && (kCLOCK_IpInvalid != s_gpioClock[instance]))
{
(void)CLOCK_EnableClock(s_gpioClock[instance]);
}
#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
/* Register reset to default value */
base->IMR &= ~(1UL << pin);
/* Configure GPIO pin direction */
if (Config->direction == kGPIO_DigitalInput)
{
base->GDIR &= ~(1UL << pin);
}
else
{
GPIO_PinWrite(base, pin, Config->outputLogic);
base->GDIR |= (1UL << pin);
}
/* Configure GPIO pin interrupt mode */
GPIO_SetPinInterruptConfig(base, pin, Config->interruptMode);
}
/*!
* brief Sets the output level of the individual GPIO pin to logic 1 or 0.
*
* param base GPIO base pointer.
* param pin GPIO port pin number.
* param output GPIOpin output logic level.
* - 0: corresponding pin output low-logic level.
* - 1: corresponding pin output high-logic level.
*/
void GPIO_PinWrite(GPIO_Type *base, uint32_t pin, uint8_t output)
{
assert(pin < 32U);
if (output == 0U)
{
#if (defined(FSL_FEATURE_IGPIO_HAS_DR_CLEAR) && FSL_FEATURE_IGPIO_HAS_DR_CLEAR)
base->DR_CLEAR = (1UL << pin);
#else
base->DR &= ~(1UL << pin); /* Set pin output to low level.*/
#endif
}
else
{
#if (defined(FSL_FEATURE_IGPIO_HAS_DR_SET) && FSL_FEATURE_IGPIO_HAS_DR_SET)
base->DR_SET = (1UL << pin);
#else
base->DR |= (1UL << pin); /* Set pin output to high level.*/
#endif
}
}
/*!
* brief Sets the current pin interrupt mode.
*
* param base GPIO base pointer.
* param pin GPIO port pin number.
* param pininterruptMode pointer to a ref gpio_interrupt_mode_t structure
* that contains the interrupt mode information.
*/
void GPIO_PinSetInterruptConfig(GPIO_Type *base, uint32_t pin, gpio_interrupt_mode_t pinInterruptMode)
{
volatile uint32_t *icr;
uint32_t icrShift;
icrShift = pin;
/* Register reset to default value */
base->EDGE_SEL &= ~(1UL << pin);
if (pin < 16U)
{
icr = &(base->ICR1);
}
else
{
icr = &(base->ICR2);
icrShift -= 16U;
}
switch (pinInterruptMode)
{
case (kGPIO_IntLowLevel):
*icr &= ~(3UL << (2UL * icrShift));
break;
case (kGPIO_IntHighLevel):
*icr = (*icr & (~(3UL << (2UL * icrShift)))) | (1UL << (2UL * icrShift));
break;
case (kGPIO_IntRisingEdge):
*icr = (*icr & (~(3UL << (2UL * icrShift)))) | (2UL << (2UL * icrShift));
break;
case (kGPIO_IntFallingEdge):
*icr |= (3UL << (2UL * icrShift));
break;
case (kGPIO_IntRisingOrFallingEdge):
base->EDGE_SEL |= (1UL << pin);
break;
default:; /* Intentional empty default */
break;
}
}

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,55 @@
/*
* Copyright (c) 2016, Freescale Semiconductor, Inc.
* Copyright 2016-2019 NXP
* All rights reserved.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#include "fsl_pmu.h"
/* Component ID definition, used by tools. */
#ifndef FSL_COMPONENT_ID
#define FSL_COMPONENT_ID "platform.drivers.pmu"
#endif
/*!
* name Status.
* {
*/
uint32_t PMU_GetStatusFlags(PMU_Type *base)
{
uint32_t ret = 0U;
/* For 1P1. */
if (PMU_REG_1P1_OK_VDD1P1_MASK == (PMU_REG_1P1_OK_VDD1P1_MASK & base->REG_1P1))
{
ret |= (uint32_t)kPMU_1P1RegulatorOutputOK;
}
if (PMU_REG_1P1_BO_VDD1P1_MASK == (PMU_REG_1P1_BO_VDD1P1_MASK & base->REG_1P1))
{
ret |= (uint32_t)kPMU_1P1BrownoutOnOutput;
}
/* For 3P0. */
if (PMU_REG_3P0_OK_VDD3P0_MASK == (PMU_REG_3P0_OK_VDD3P0_MASK & base->REG_3P0))
{
ret |= (uint32_t)kPMU_3P0RegulatorOutputOK;
}
if (PMU_REG_3P0_BO_VDD3P0_MASK == (PMU_REG_3P0_BO_VDD3P0_MASK & base->REG_3P0))
{
ret |= (uint32_t)kPMU_3P0BrownoutOnOutput;
}
/* For 2P5. */
if (PMU_REG_2P5_OK_VDD2P5_MASK == (PMU_REG_2P5_OK_VDD2P5_MASK & base->REG_2P5))
{
ret |= (uint32_t)kPMU_2P5RegulatorOutputOK;
}
if (PMU_REG_2P5_BO_VDD2P5_MASK == (PMU_REG_2P5_BO_VDD2P5_MASK & base->REG_2P5))
{
ret |= (uint32_t)kPMU_2P5BrownoutOnOutput;
}
return ret;
}

View File

@ -0,0 +1,49 @@
/*
* Copyright (c) 2016, Freescale Semiconductor, Inc.
* Copyright 2016-2017 NXP
* All rights reserved.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#include "fsl_src.h"
/* Component ID definition, used by tools. */
#ifndef FSL_COMPONENT_ID
#define FSL_COMPONENT_ID "platform.drivers.src"
#endif
/*******************************************************************************
* Prototypes
******************************************************************************/
/*******************************************************************************
* Variables
******************************************************************************/
/*******************************************************************************
* Code
******************************************************************************/
/*!
* brief Clear the status flags of SRC.
*
* param base SRC peripheral base address.
* param Mask value of status flags to be cleared, see to #_src_reset_status_flags.
*/
void SRC_ClearResetStatusFlags(SRC_Type *base, uint32_t flags)
{
uint32_t tmp32 = base->SRSR;
if (0U != (SRC_SRSR_TSR_MASK & flags))
{
tmp32 &= ~SRC_SRSR_TSR_MASK; /* Write 0 to clear. */
}
if (0U != (SRC_SRSR_W1C_BITS_MASK & flags))
{
tmp32 |= (SRC_SRSR_W1C_BITS_MASK & flags); /* Write 1 to clear. */
}
base->SRSR = tmp32;
}

View File

@ -0,0 +1,81 @@
/***********************************************************************************************************************
* 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.
**********************************************************************************************************************/
/*
* TEXT BELOW IS USED AS SETTING FOR TOOLS *************************************
!!GlobalInfo
product: Pins v17.0
processor: MIMXRT1062xxxxB
package_id: MIMXRT1062DVL6B
mcu_data: ksdk2_0
processor_version: 25.03.10
board: MIMXRT1060-EVKB
* BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR TOOLS ***********
*/
#include "fsl_common.h"
#include "fsl_iomuxc.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();
}
/*
* TEXT BELOW IS USED AS SETTING FOR TOOLS *************************************
BOARD_InitPins:
- options: {callFromInitBoot: 'true', coreID: core0, enableClock: 'true'}
- pin_list:
- {pin_num: L14, peripheral: LPUART1, signal: RX, pin_signal: GPIO_AD_B0_13, software_input_on: Disable, hysteresis_enable: Disable, pull_up_down_config: Pull_Down_100K_Ohm,
pull_keeper_select: Keeper, pull_keeper_enable: Enable, open_drain: Disable, speed: MHZ_100, drive_strength: R0_6, slew_rate: Slow}
- {pin_num: K14, peripheral: LPUART1, signal: TX, pin_signal: GPIO_AD_B0_12, software_input_on: Disable, hysteresis_enable: Disable, pull_up_down_config: Pull_Down_100K_Ohm,
pull_keeper_select: Keeper, pull_keeper_enable: Enable, open_drain: Disable, speed: MHZ_100, drive_strength: R0_6, slew_rate: Slow}
- {pin_num: G13, peripheral: ARM, signal: arm_trace_swo, pin_signal: GPIO_AD_B0_10, slew_rate: Fast}
- {pin_num: A9, peripheral: GPIO2, signal: 'gpio_io, 07', pin_signal: GPIO_B0_07, direction: OUTPUT, gpio_init_state: 'true', pull_up_down_config: Pull_Up_22K_Ohm}
* BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR TOOLS ***********
*/
/* FUNCTION ************************************************************************************************************
*
* Function Name : BOARD_InitPins
* Description : Configures pin routing and optionally pin electrical features.
*
* END ****************************************************************************************************************/
void BOARD_InitPins(void) {
CLOCK_EnableClock(kCLOCK_Iomuxc);
/* GPIO configuration of LCDIF_D3 on GPIO_B0_07 (pin A9) */
gpio_pin_config_t LCDIF_D3_config = {
.direction = kGPIO_DigitalOutput,
.outputLogic = 1U,
.interruptMode = kGPIO_NoIntmode
};
/* Initialize GPIO functionality on GPIO_B0_07 (pin A9) */
GPIO_PinInit(GPIO2, 7U, &LCDIF_D3_config);
IOMUXC_SetPinMux(IOMUXC_GPIO_AD_B0_10_ARM_TRACE_SWO, 0U);
IOMUXC_SetPinMux(IOMUXC_GPIO_AD_B0_12_LPUART1_TX, 0U);
IOMUXC_SetPinMux(IOMUXC_GPIO_AD_B0_13_LPUART1_RX, 0U);
IOMUXC_SetPinMux(IOMUXC_GPIO_B0_07_GPIO2_IO07, 0U);
IOMUXC_GPR->GPR27 = ((IOMUXC_GPR->GPR27 &
(~(BOARD_INITPINS_IOMUXC_GPR_GPR27_GPIO_MUX2_GPIO_SEL_MASK)))
| IOMUXC_GPR_GPR27_GPIO_MUX2_GPIO_SEL(0x00U)
);
IOMUXC_SetPinConfig(IOMUXC_GPIO_AD_B0_10_ARM_TRACE_SWO, 0x90B1U);
IOMUXC_SetPinConfig(IOMUXC_GPIO_AD_B0_12_LPUART1_TX, 0x10B0U);
IOMUXC_SetPinConfig(IOMUXC_GPIO_AD_B0_13_LPUART1_RX, 0x10B0U);
IOMUXC_SetPinConfig(IOMUXC_GPIO_B0_07_GPIO2_IO07, 0xD0B0U);
}
/***********************************************************************************************************************
* EOF
**********************************************************************************************************************/

View File

@ -0,0 +1,244 @@
/*
** ###################################################################
** Processors: MIMXRT1062CVJ5A
** MIMXRT1062CVJ5B
** MIMXRT1062CVL5A
** MIMXRT1062CVL5B
** MIMXRT1062DVJ6A
** MIMXRT1062DVJ6B
** MIMXRT1062DVL6A
** MIMXRT1062DVL6B
** MIMXRT1062DVN6B
** MIMXRT1062XVN5B
**
** Compilers: Freescale C/C++ for Embedded ARM
** GNU C Compiler
** IAR ANSI C/C++ Compiler for ARM
** Keil ARM C/C++ Compiler
** MCUXpresso Compiler
**
** Reference manual: IMXRT1060RM Rev.3, 07/2021 | IMXRT106XSRM Rev.0
** Version: rev. 1.4, 2022-03-25
** Build: b240823
**
** 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.
**
** Copyright 2016 Freescale Semiconductor, Inc.
** Copyright 2016-2024 NXP
** SPDX-License-Identifier: BSD-3-Clause
**
** http: www.nxp.com
** mail: support@nxp.com
**
** Revisions:
** - rev. 0.1 (2017-01-10)
** Initial version.
** - rev. 1.0 (2018-11-16)
** Update header files to align with IMXRT1060RM Rev.0.
** - rev. 1.1 (2018-11-27)
** Update header files to align with IMXRT1060RM Rev.1.
** - rev. 1.2 (2019-04-29)
** Add SET/CLR/TOG register group to register CTRL, STAT, CHANNELCTRL, CH0STAT, CH0OPTS, CH1STAT, CH1OPTS, CH2STAT, CH2OPTS, CH3STAT, CH3OPTS of DCP module.
** - rev. 1.3 (2021-08-10)
** Update header files to align with IMXRT1060RM Rev.3.
** - rev. 1.4 (2022-03-25)
** Add RT1060X device
**
** ###################################################################
*/
/*!
* @file MIMXRT1062
* @version 1.4
* @date 2022-03-25
* @brief Device specific configuration file for MIMXRT1062 (implementation file)
*
* Provides a system configuration function and a global variable that contains
* the system frequency. It configures the device and initializes the oscillator
* (PLL) that is part of the microcontroller device.
*/
#include <stdint.h>
#include "fsl_device_registers.h"
/* ----------------------------------------------------------------------------
-- Core clock
---------------------------------------------------------------------------- */
uint32_t SystemCoreClock = DEFAULT_SYSTEM_CLOCK;
/* ----------------------------------------------------------------------------
-- SystemInit()
---------------------------------------------------------------------------- */
void SystemInit (void) {
#if ((__FPU_PRESENT == 1) && (__FPU_USED == 1))
SCB->CPACR |= ((3UL << 10*2) | (3UL << 11*2)); /* set CP10, CP11 Full Access */
#endif /* ((__FPU_PRESENT == 1) && (__FPU_USED == 1)) */
#if defined(__MCUXPRESSO)
extern uint32_t g_pfnVectors[]; // Vector table defined in startup code
SCB->VTOR = (uint32_t)g_pfnVectors;
#endif
/* Disable Watchdog Power Down Counter */
WDOG1->WMCR &= ~(uint16_t) WDOG_WMCR_PDE_MASK;
WDOG2->WMCR &= ~(uint16_t) WDOG_WMCR_PDE_MASK;
/* Watchdog disable */
#if (DISABLE_WDOG)
if ((WDOG1->WCR & WDOG_WCR_WDE_MASK) != 0U)
{
WDOG1->WCR &= ~(uint16_t) WDOG_WCR_WDE_MASK;
}
if ((WDOG2->WCR & WDOG_WCR_WDE_MASK) != 0U)
{
WDOG2->WCR &= ~(uint16_t) WDOG_WCR_WDE_MASK;
}
if ((RTWDOG->CS & RTWDOG_CS_CMD32EN_MASK) != 0U)
{
RTWDOG->CNT = 0xD928C520U; /* 0xD928C520U is the update key */
}
else
{
RTWDOG->CNT = 0xC520U;
RTWDOG->CNT = 0xD928U;
}
RTWDOG->TOVAL = 0xFFFF;
RTWDOG->CS = (uint32_t) ((RTWDOG->CS) & ~RTWDOG_CS_EN_MASK) | RTWDOG_CS_UPDATE_MASK;
#endif /* (DISABLE_WDOG) */
/* Disable Systick which might be enabled by bootrom */
if ((SysTick->CTRL & SysTick_CTRL_ENABLE_Msk) != 0U)
{
SysTick->CTRL &= ~SysTick_CTRL_ENABLE_Msk;
}
/* Enable instruction and data caches */
#if defined(__ICACHE_PRESENT) && __ICACHE_PRESENT
if (SCB_CCR_IC_Msk != (SCB_CCR_IC_Msk & SCB->CCR)) {
SCB_EnableICache();
}
#endif
SystemInitHook();
}
/* ----------------------------------------------------------------------------
-- SystemCoreClockUpdate()
---------------------------------------------------------------------------- */
void SystemCoreClockUpdate (void) {
uint32_t freq;
uint32_t PLL1MainClock;
uint32_t PLL2MainClock;
/* Periph_clk2_clk ---> Periph_clk */
if ((CCM->CBCDR & CCM_CBCDR_PERIPH_CLK_SEL_MASK) != 0U)
{
switch (CCM->CBCMR & CCM_CBCMR_PERIPH_CLK2_SEL_MASK)
{
/* Pll3_sw_clk ---> Periph_clk2_clk ---> Periph_clk */
case CCM_CBCMR_PERIPH_CLK2_SEL(0U):
if((CCM_ANALOG->PLL_USB1 & CCM_ANALOG_PLL_USB1_BYPASS_MASK) != 0U)
{
freq = (((CCM_ANALOG->PLL_USB1 & CCM_ANALOG_PLL_USB1_BYPASS_CLK_SRC_MASK) >> CCM_ANALOG_PLL_USB1_BYPASS_CLK_SRC_SHIFT) == 0U) ?
CPU_XTAL_CLK_HZ : CPU_CLK1_HZ;
}
else
{
freq = (CPU_XTAL_CLK_HZ * (((CCM_ANALOG->PLL_USB1 & CCM_ANALOG_PLL_USB1_DIV_SELECT_MASK) != 0U) ? 22U : 20U));
}
break;
/* Osc_clk ---> Periph_clk2_clk ---> Periph_clk */
case CCM_CBCMR_PERIPH_CLK2_SEL(1U):
freq = CPU_XTAL_CLK_HZ;
break;
case CCM_CBCMR_PERIPH_CLK2_SEL(2U):
freq = (((CCM_ANALOG->PLL_SYS & CCM_ANALOG_PLL_SYS_BYPASS_CLK_SRC_MASK) >> CCM_ANALOG_PLL_SYS_BYPASS_CLK_SRC_SHIFT) == 0U) ?
CPU_XTAL_CLK_HZ : CPU_CLK1_HZ;
break;
case CCM_CBCMR_PERIPH_CLK2_SEL(3U):
default:
freq = 0U;
break;
}
freq /= (((CCM->CBCDR & CCM_CBCDR_PERIPH_CLK2_PODF_MASK) >> CCM_CBCDR_PERIPH_CLK2_PODF_SHIFT) + 1U);
}
/* Pre_Periph_clk ---> Periph_clk */
else
{
/* check if pll is bypassed */
if((CCM_ANALOG->PLL_ARM & CCM_ANALOG_PLL_ARM_BYPASS_MASK) != 0U)
{
PLL1MainClock = (((CCM_ANALOG->PLL_ARM & CCM_ANALOG_PLL_ARM_BYPASS_CLK_SRC_MASK) >> CCM_ANALOG_PLL_ARM_BYPASS_CLK_SRC_SHIFT) == 0U) ?
CPU_XTAL_CLK_HZ : CPU_CLK1_HZ;
}
else
{
PLL1MainClock = ((CPU_XTAL_CLK_HZ * ((CCM_ANALOG->PLL_ARM & CCM_ANALOG_PLL_ARM_DIV_SELECT_MASK) >>
CCM_ANALOG_PLL_ARM_DIV_SELECT_SHIFT)) >> 1U);
}
/* check if pll is bypassed */
if((CCM_ANALOG->PLL_SYS & CCM_ANALOG_PLL_SYS_BYPASS_MASK) != 0U)
{
PLL2MainClock = (((CCM_ANALOG->PLL_SYS & CCM_ANALOG_PLL_SYS_BYPASS_CLK_SRC_MASK) >> CCM_ANALOG_PLL_SYS_BYPASS_CLK_SRC_SHIFT) == 0U) ?
CPU_XTAL_CLK_HZ : CPU_CLK1_HZ;
}
else
{
PLL2MainClock = (CPU_XTAL_CLK_HZ * (((CCM_ANALOG->PLL_SYS & CCM_ANALOG_PLL_SYS_DIV_SELECT_MASK) != 0U) ? 22U : 20U));
}
PLL2MainClock += (uint32_t)(((uint64_t)CPU_XTAL_CLK_HZ * ((uint64_t)(CCM_ANALOG->PLL_SYS_NUM))) / ((uint64_t)(CCM_ANALOG->PLL_SYS_DENOM)));
switch (CCM->CBCMR & CCM_CBCMR_PRE_PERIPH_CLK_SEL_MASK)
{
/* PLL2 ---> Pre_Periph_clk ---> Periph_clk */
case CCM_CBCMR_PRE_PERIPH_CLK_SEL(0U):
freq = PLL2MainClock;
break;
/* PLL2 PFD2 ---> Pre_Periph_clk ---> Periph_clk */
case CCM_CBCMR_PRE_PERIPH_CLK_SEL(1U):
freq = PLL2MainClock / ((CCM_ANALOG->PFD_528 & CCM_ANALOG_PFD_528_PFD2_FRAC_MASK) >> CCM_ANALOG_PFD_528_PFD2_FRAC_SHIFT) * 18U;
break;
/* PLL2 PFD0 ---> Pre_Periph_clk ---> Periph_clk */
case CCM_CBCMR_PRE_PERIPH_CLK_SEL(2U):
freq = PLL2MainClock / ((CCM_ANALOG->PFD_528 & CCM_ANALOG_PFD_528_PFD0_FRAC_MASK) >> CCM_ANALOG_PFD_528_PFD0_FRAC_SHIFT) * 18U;
break;
/* PLL1 divided(/2) ---> Pre_Periph_clk ---> Periph_clk */
case CCM_CBCMR_PRE_PERIPH_CLK_SEL(3U):
freq = PLL1MainClock / (((CCM->CACRR & CCM_CACRR_ARM_PODF_MASK) >> CCM_CACRR_ARM_PODF_SHIFT) + 1U);
break;
default:
freq = 0U;
break;
}
}
SystemCoreClock = (freq / (((CCM->CBCDR & CCM_CBCDR_AHB_PODF_MASK) >> CCM_CBCDR_AHB_PODF_SHIFT) + 1U));
}
/* ----------------------------------------------------------------------------
-- SystemInitHook()
---------------------------------------------------------------------------- */
__attribute__ ((weak)) void SystemInitHook (void) {
/* Void implementation of the weak function. */
}

View File

@ -0,0 +1,125 @@
/*
** ###################################################################
** Processors: MIMXRT1062CVJ5A
** MIMXRT1062CVJ5B
** MIMXRT1062CVL5A
** MIMXRT1062CVL5B
** MIMXRT1062DVJ6A
** MIMXRT1062DVJ6B
** MIMXRT1062DVL6A
** MIMXRT1062DVL6B
** MIMXRT1062DVN6B
** MIMXRT1062XVN5B
**
** Compilers: Freescale C/C++ for Embedded ARM
** GNU C Compiler
** IAR ANSI C/C++ Compiler for ARM
** Keil ARM C/C++ Compiler
** MCUXpresso Compiler
**
** Reference manual: IMXRT1060RM Rev.3, 07/2021 | IMXRT106XSRM Rev.0
** Version: rev. 1.4, 2022-03-25
** Build: b240705
**
** Abstract:
** CMSIS Peripheral Access Layer for MIMXRT1062
**
** Copyright 1997-2016 Freescale Semiconductor, Inc.
** Copyright 2016-2024 NXP
** SPDX-License-Identifier: BSD-3-Clause
**
** http: www.nxp.com
** mail: support@nxp.com
**
** Revisions:
** - rev. 0.1 (2017-01-10)
** Initial version.
** - rev. 1.0 (2018-11-16)
** Update header files to align with IMXRT1060RM Rev.0.
** - rev. 1.1 (2018-11-27)
** Update header files to align with IMXRT1060RM Rev.1.
** - rev. 1.2 (2019-04-29)
** Add SET/CLR/TOG register group to register CTRL, STAT, CHANNELCTRL, CH0STAT, CH0OPTS, CH1STAT, CH1OPTS, CH2STAT, CH2OPTS, CH3STAT, CH3OPTS of DCP module.
** - rev. 1.3 (2021-08-10)
** Update header files to align with IMXRT1060RM Rev.3.
** - rev. 1.4 (2022-03-25)
** Add RT1060X device
**
** ###################################################################
*/
/*!
* @file MIMXRT1062.h
* @version 1.4
* @date 2022-03-25
* @brief CMSIS Peripheral Access Layer for MIMXRT1062
*
* CMSIS Peripheral Access Layer for MIMXRT1062
*/
#if !defined(MIMXRT1062_H_) /* Check if memory map has not been already included */
#define MIMXRT1062_H_
/* IP Header Files List */
#include "PERI_ADC.h"
#include "PERI_ADC_ETC.h"
#include "PERI_AIPSTZ.h"
#include "PERI_AOI.h"
#include "PERI_BEE.h"
#include "PERI_CAN.h"
#include "PERI_CCM.h"
#include "PERI_CCM_ANALOG.h"
#include "PERI_CM7_MCM.h"
#include "PERI_CMP.h"
#include "PERI_CSI.h"
#include "PERI_CSU.h"
#include "PERI_DCDC.h"
#include "PERI_DCP.h"
#include "PERI_DMA.h"
#include "PERI_DMAMUX.h"
#include "PERI_ENC.h"
#include "PERI_ENET.h"
#include "PERI_EWM.h"
#include "PERI_FLEXIO.h"
#include "PERI_FLEXRAM.h"
#include "PERI_FLEXSPI.h"
#include "PERI_GPC.h"
#include "PERI_GPIO.h"
#include "PERI_GPT.h"
#include "PERI_I2S.h"
#include "PERI_IOMUXC.h"
#include "PERI_IOMUXC_GPR.h"
#include "PERI_IOMUXC_SNVS.h"
#include "PERI_IOMUXC_SNVS_GPR.h"
#include "PERI_KPP.h"
#include "PERI_LCDIF.h"
#include "PERI_LPI2C.h"
#include "PERI_LPSPI.h"
#include "PERI_LPUART.h"
#include "PERI_OCOTP.h"
#include "PERI_PGC.h"
#include "PERI_PIT.h"
#include "PERI_PMU.h"
#include "PERI_PWM.h"
#include "PERI_PXP.h"
#include "PERI_ROMC.h"
#include "PERI_RTWDOG.h"
#include "PERI_SEMC.h"
#include "PERI_SNVS.h"
#include "PERI_SPDIF.h"
#include "PERI_SRC.h"
#include "PERI_TEMPMON.h"
#include "PERI_TMR.h"
#include "PERI_TRNG.h"
#include "PERI_TSC.h"
#include "PERI_USB.h"
#include "PERI_USBNC.h"
#include "PERI_USBPHY.h"
#include "PERI_USB_ANALOG.h"
#include "PERI_USDHC.h"
#include "PERI_WDOG.h"
#include "PERI_XBARA.h"
#include "PERI_XBARB.h"
#include "PERI_XTALOSC24M.h"
#endif /* #if !defined(MIMXRT1062_H_) */

View File

@ -0,0 +1,853 @@
/*
** ###################################################################
** Version: rev. 2.0, 2022-03-25
** Build: b241030
**
** Abstract:
** Chip specific module features.
**
** Copyright 2016 Freescale Semiconductor, Inc.
** Copyright 2016-2024 NXP
** SPDX-License-Identifier: BSD-3-Clause
**
** http: www.nxp.com
** mail: support@nxp.com
**
** Revisions:
** - rev. 0.1 (2017-01-10)
** Initial version.
** - rev. 1.0 (2018-11-16)
** Update feature files to align with IMXRT1060RM Rev.0.
** - rev. 2.0 (2022-03-25)
** Add RT1060X device
**
** ###################################################################
*/
#ifndef _MIMXRT1062_FEATURES_H_
#define _MIMXRT1062_FEATURES_H_
/* SOC module features */
/* @brief ADC availability on the SoC. */
#define FSL_FEATURE_SOC_ADC_COUNT (2)
/* @brief AIPSTZ availability on the SoC. */
#define FSL_FEATURE_SOC_AIPSTZ_COUNT (4)
/* @brief AOI availability on the SoC. */
#define FSL_FEATURE_SOC_AOI_COUNT (2)
/* @brief CCM availability on the SoC. */
#define FSL_FEATURE_SOC_CCM_COUNT (1)
/* @brief CCM_ANALOG availability on the SoC. */
#define FSL_FEATURE_SOC_CCM_ANALOG_COUNT (1)
/* @brief CMP availability on the SoC. */
#define FSL_FEATURE_SOC_CMP_COUNT (4)
/* @brief CSI availability on the SoC. */
#define FSL_FEATURE_SOC_CSI_COUNT (1)
/* @brief DCDC availability on the SoC. */
#define FSL_FEATURE_SOC_DCDC_COUNT (1)
/* @brief DCP availability on the SoC. */
#define FSL_FEATURE_SOC_DCP_COUNT (1)
/* @brief DMAMUX availability on the SoC. */
#define FSL_FEATURE_SOC_DMAMUX_COUNT (1)
/* @brief EDMA availability on the SoC. */
#define FSL_FEATURE_SOC_EDMA_COUNT (1)
/* @brief ENC availability on the SoC. */
#define FSL_FEATURE_SOC_ENC_COUNT (4)
/* @brief ENET availability on the SoC. */
#define FSL_FEATURE_SOC_ENET_COUNT (2)
/* @brief EWM availability on the SoC. */
#define FSL_FEATURE_SOC_EWM_COUNT (1)
/* @brief FLEXCAN availability on the SoC. */
#define FSL_FEATURE_SOC_FLEXCAN_COUNT (3)
/* @brief FLEXIO availability on the SoC. */
#define FSL_FEATURE_SOC_FLEXIO_COUNT (3)
/* @brief FLEXRAM availability on the SoC. */
#define FSL_FEATURE_SOC_FLEXRAM_COUNT (1)
/* @brief FLEXSPI availability on the SoC. */
#define FSL_FEATURE_SOC_FLEXSPI_COUNT (2)
/* @brief GPC availability on the SoC. */
#define FSL_FEATURE_SOC_GPC_COUNT (1)
/* @brief GPT availability on the SoC. */
#define FSL_FEATURE_SOC_GPT_COUNT (2)
/* @brief I2S availability on the SoC. */
#define FSL_FEATURE_SOC_I2S_COUNT (3)
/* @brief IGPIO availability on the SoC. */
#define FSL_FEATURE_SOC_IGPIO_COUNT (10)
/* @brief IOMUXC availability on the SoC. */
#define FSL_FEATURE_SOC_IOMUXC_COUNT (1)
/* @brief IOMUXC_GPR availability on the SoC. */
#define FSL_FEATURE_SOC_IOMUXC_GPR_COUNT (1)
/* @brief IOMUXC_SNVS availability on the SoC. */
#define FSL_FEATURE_SOC_IOMUXC_SNVS_COUNT (1)
/* @brief KPP availability on the SoC. */
#define FSL_FEATURE_SOC_KPP_COUNT (1)
/* @brief LCDIF availability on the SoC. */
#define FSL_FEATURE_SOC_LCDIF_COUNT (1)
/* @brief LPI2C availability on the SoC. */
#define FSL_FEATURE_SOC_LPI2C_COUNT (4)
/* @brief LPSPI availability on the SoC. */
#define FSL_FEATURE_SOC_LPSPI_COUNT (4)
/* @brief LPUART availability on the SoC. */
#define FSL_FEATURE_SOC_LPUART_COUNT (8)
/* @brief MPU availability on the SoC. */
#define FSL_FEATURE_SOC_MPU_COUNT (1)
/* @brief OCOTP availability on the SoC. */
#define FSL_FEATURE_SOC_OCOTP_COUNT (1)
/* @brief PIT availability on the SoC. */
#define FSL_FEATURE_SOC_PIT_COUNT (1)
/* @brief PMU availability on the SoC. */
#define FSL_FEATURE_SOC_PMU_COUNT (1)
/* @brief PWM availability on the SoC. */
#define FSL_FEATURE_SOC_PWM_COUNT (4)
/* @brief PXP availability on the SoC. */
#define FSL_FEATURE_SOC_PXP_COUNT (1)
/* @brief ROMC availability on the SoC. */
#define FSL_FEATURE_SOC_ROMC_COUNT (1)
/* @brief SEMC availability on the SoC. */
#define FSL_FEATURE_SOC_SEMC_COUNT (1)
/* @brief SNVS availability on the SoC. */
#define FSL_FEATURE_SOC_SNVS_COUNT (1)
/* @brief SPDIF availability on the SoC. */
#define FSL_FEATURE_SOC_SPDIF_COUNT (1)
/* @brief SRC availability on the SoC. */
#define FSL_FEATURE_SOC_SRC_COUNT (1)
/* @brief TEMPMON availability on the SoC. */
#define FSL_FEATURE_SOC_TEMPMON_COUNT (1)
/* @brief TMR availability on the SoC. */
#define FSL_FEATURE_SOC_TMR_COUNT (4)
/* @brief TRNG availability on the SoC. */
#define FSL_FEATURE_SOC_TRNG_COUNT (1)
/* @brief TSC availability on the SoC. */
#define FSL_FEATURE_SOC_TSC_COUNT (1)
/* @brief USBHS availability on the SoC. */
#define FSL_FEATURE_SOC_USBHS_COUNT (2)
/* @brief USBNC availability on the SoC. */
#define FSL_FEATURE_SOC_USBNC_COUNT (2)
/* @brief USBPHY availability on the SoC. */
#define FSL_FEATURE_SOC_USBPHY_COUNT (2)
/* @brief USB_ANALOG availability on the SoC. */
#define FSL_FEATURE_SOC_USB_ANALOG_COUNT (1)
/* @brief USDHC availability on the SoC. */
#define FSL_FEATURE_SOC_USDHC_COUNT (2)
/* @brief WDOG availability on the SoC. */
#define FSL_FEATURE_SOC_WDOG_COUNT (2)
/* @brief XBARA availability on the SoC. */
#define FSL_FEATURE_SOC_XBARA_COUNT (1)
/* @brief XBARB availability on the SoC. */
#define FSL_FEATURE_SOC_XBARB_COUNT (2)
/* @brief XTALOSC24M availability on the SoC. */
#define FSL_FEATURE_SOC_XTALOSC24M_COUNT (1)
/* @brief ROM API Availability */
#define FSL_FEATURE_BOOT_ROM_HAS_ROMAPI (1)
/* ADC module features */
/* @brief Remove Hardware Trigger feature. */
#define FSL_FEATURE_ADC_SUPPORT_HARDWARE_TRIGGER_REMOVE (0)
/* @brief Remove ALT Clock selection feature. */
#define FSL_FEATURE_ADC_SUPPORT_ALTCLK_REMOVE (1)
/* @brief Conversion control count (related to number of registers HCn and Rn). */
#define FSL_FEATURE_ADC_CONVERSION_CONTROL_COUNT (8)
/* ADC_ETC module features */
/* @brief Has DMA model control(bit field CTRL[DMA_MODE_SEL]). */
#define FSL_FEATURE_ADC_ETC_HAS_CTRL_DMA_MODE_SEL (1)
/* @brief Has TRIGm_CHAIN_a_b IEn_EN. */
#define FSL_FEATURE_ADC_ETC_HAS_TRIGm_CHAIN_a_b_IEn_EN (0)
/* @brief Has no TSC0 trigger related bitfields (bit field CTRL[EXT0_TRIG_ENABLE], CTRL[EXT0_TRIG_PRIORITY]). */
#define FSL_FEATURE_ADC_ETC_HAS_NO_TSC0_TRIG (0)
/* @brief Has no TSC1 trigger related bitfields (bit field CTRL[EXT1_TRIG_ENABLE], CTRL[EXT1_TRIG_PRIORITY]). */
#define FSL_FEATURE_ADC_ETC_HAS_NO_TSC1_TRIG (0)
/* AOI module features */
/* @brief Maximum value of input mux. */
#define FSL_FEATURE_AOI_MODULE_INPUTS (4)
/* @brief Number of events related to number of registers AOIx_BFCRT01n/AOIx_BFCRT23n. */
#define FSL_FEATURE_AOI_EVENT_COUNT (4)
/* FLEXCAN module features */
/* @brief Message buffer size */
#define FSL_FEATURE_FLEXCAN_HAS_MESSAGE_BUFFER_MAX_NUMBERn(x) (64)
/* @brief Has doze mode support (register bit field MCR[DOZE]). */
#define FSL_FEATURE_FLEXCAN_HAS_DOZE_MODE_SUPPORT (1)
/* @brief Insatnce has doze mode support (register bit field MCR[DOZE]). */
#define FSL_FEATURE_FLEXCAN_INSTANCE_HAS_DOZE_MODE_SUPPORTn(x) \
(((x) == CAN1) ? (0) : \
(((x) == CAN2) ? (0) : \
(((x) == CAN3) ? (1) : (-1))))
/* @brief Has a glitch filter on the receive pin (register bit field MCR[WAKSRC]). */
#define FSL_FEATURE_FLEXCAN_HAS_GLITCH_FILTER (1)
/* @brief Has extended interrupt mask and flag register (register IMASK2, IFLAG2). */
#define FSL_FEATURE_FLEXCAN_HAS_EXTENDED_FLAG_REGISTER (1)
/* @brief Instance has extended bit timing register (register CBT). */
#define FSL_FEATURE_FLEXCAN_INSTANCE_HAS_EXTENDED_TIMING_REGISTERn(x) \
(((x) == CAN1) ? (0) : \
(((x) == CAN2) ? (0) : \
(((x) == CAN3) ? (1) : (-1))))
/* @brief Has a receive FIFO DMA feature (register bit field MCR[DMA]). */
#define FSL_FEATURE_FLEXCAN_HAS_RX_FIFO_DMA (1)
/* @brief Instance has a receive FIFO DMA feature (register bit field MCR[DMA]). */
#define FSL_FEATURE_FLEXCAN_INSTANCE_HAS_RX_FIFO_DMAn(x) \
(((x) == CAN1) ? (0) : \
(((x) == CAN2) ? (0) : \
(((x) == CAN3) ? (1) : (-1))))
/* @brief Remove CAN Engine Clock Source Selection from unsupported part. */
#define FSL_FEATURE_FLEXCAN_SUPPORT_ENGINE_CLK_SEL_REMOVE (1)
/* @brief Instance remove CAN Engine Clock Source Selection from unsupported part. */
#define FSL_FEATURE_FLEXCAN_INSTANCE_SUPPORT_ENGINE_CLK_SEL_REMOVEn(x) (1)
/* @brief Is affected by errata with ID 5641 (Module does not transmit a message that is enabled to be transmitted at a specific moment during the arbitration process). */
#define FSL_FEATURE_FLEXCAN_HAS_ERRATA_5641 (0)
/* @brief Is affected by errata with ID 5829 (FlexCAN: FlexCAN does not transmit a message that is enabled to be transmitted in a specific moment during the arbitration process). */
#define FSL_FEATURE_FLEXCAN_HAS_ERRATA_5829 (1)
/* @brief Is affected by errata with ID 6032 (FlexCAN: A frame with wrong ID or payload is transmitted into the CAN bus when the Message Buffer under transmission is either aborted or deactivated while the CAN bus is in the Bus Idle state). */
#define FSL_FEATURE_FLEXCAN_HAS_ERRATA_6032 (1)
/* @brief Is affected by errata with ID 9595 (FlexCAN: Corrupt frame possible if the Freeze Mode or the Low-Power Mode are entered during a Bus-Off state). */
#define FSL_FEATURE_FLEXCAN_HAS_ERRATA_9595 (1)
/* @brief Has CAN with Flexible Data rate (CAN FD) protocol. */
#define FSL_FEATURE_FLEXCAN_HAS_FLEXIBLE_DATA_RATE (1)
/* @brief CAN instance support Flexible Data rate (CAN FD) protocol. */
#define FSL_FEATURE_FLEXCAN_INSTANCE_HAS_FLEXIBLE_DATA_RATEn(x) \
(((x) == CAN1) ? (0) : \
(((x) == CAN2) ? (0) : \
(((x) == CAN3) ? (1) : (-1))))
/* @brief Has memory error control (register MECR). */
#define FSL_FEATURE_FLEXCAN_HAS_MEMORY_ERROR_CONTROL (0)
/* @brief Has enhanced bit timing register (register EPRS, ENCBT, EDCBT and ETDC). */
#define FSL_FEATURE_FLEXCAN_HAS_ENHANCED_BIT_TIMING_REG (0)
/* @brief Has Pretended Networking mode support. */
#define FSL_FEATURE_FLEXCAN_HAS_PN_MODE (0)
/* CCM module features */
/* @brief Is affected by errata with ID 50235 (Incorrect clock setting for CAN affects by LPUART clock gate). */
#define FSL_FEATURE_CCM_HAS_ERRATA_50235 (1)
/* CMP module features */
/* @brief Has Trigger mode in CMP (register bit field CR1[TRIGM]). */
#define FSL_FEATURE_CMP_HAS_TRIGGER_MODE (0)
/* @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)
/* @brief Has COUTA out of window is zero enable. */
#define FSL_FEATURE_CMP_HAS_COWZ_BIT_FIELD (0)
/* @brief Use 16 bit registers. */
#define FSL_FEATURE_CMP_USE_16BIT_REG (0)
/* DCDC module features */
/* @brief Has CTRL register (register CTRL0/1). */
#define FSL_FEATURE_DCDC_HAS_CTRL_REG (0)
/* @brief DCDC VDD output count. */
#define FSL_FEATURE_DCDC_VDD_OUTPUT_COUNT (1)
/* @brief Has no current alert function (register bit field REG0[CURRENT_ALERT_RESET]). */
#define FSL_FEATURE_DCDC_HAS_NO_CURRENT_ALERT_FUNC (0)
/* @brief Has switching converter differential mode (register bit field REG1[LOOPCTRL_EN_DF_HYST]). */
#define FSL_FEATURE_DCDC_HAS_SWITCHING_CONVERTER_DIFFERENTIAL_MODE (0)
/* @brief Has register bit field REG0[REG_DCDC_IN_DET]. */
#define FSL_FEATURE_DCDC_HAS_REG0_DCDC_IN_DET (0)
/* @brief Has no register bit field REG0[EN_LP_OVERLOAD_SNS]. */
#define FSL_FEATURE_DCDC_HAS_NO_REG0_EN_LP_OVERLOAD_SNS (0)
/* @brief Has register bit field REG3[REG_FBK_SEL]). */
#define FSL_FEATURE_DCDC_HAS_REG3_FBK_SEL (0)
/* 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 (32)
/* @brief Total number of DMA channels on all modules. */
#define FSL_FEATURE_EDMA_DMAMUX_CHANNELS (32)
/* @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 (32)
/* @brief Channel IRQ entry shared offset. */
#define FSL_FEATURE_EDMA_MODULE_CHANNEL_IRQ_ENTRY_SHARED_OFFSET (16)
/* @brief If 8 bytes transfer supported. */
#define FSL_FEATURE_EDMA_SUPPORT_8_BYTES_TRANSFER (1)
/* @brief If 16 bytes transfer supported. */
#define FSL_FEATURE_EDMA_SUPPORT_16_BYTES_TRANSFER (0)
/* @brief If 32 bytes transfer supported. */
#define FSL_FEATURE_EDMA_SUPPORT_32_BYTES_TRANSFER (1)
/* DMAMUX module features */
/* @brief Number of DMA channels (related to number of register CHCFGn). */
#define FSL_FEATURE_DMAMUX_MODULE_CHANNEL (32)
/* @brief Total number of DMA channels on all modules. */
#define FSL_FEATURE_DMAMUX_DMAMUX_CHANNELS (32)
/* @brief Has the periodic trigger capability for the triggered DMA channel (register bit CHCFG0[TRIG]). */
#define FSL_FEATURE_DMAMUX_HAS_TRIG (1)
/* @brief Has DMA Channel Always ON function (register bit CHCFG0[A_ON]). */
#define FSL_FEATURE_DMAMUX_HAS_A_ON (1)
/* @brief Register CHCFGn width. */
#define FSL_FEATURE_DMAMUX_CHCFG_REGISTER_WIDTH (32)
/* ENC module features */
/* @brief Has no simultaneous PHASEA and PHASEB change interrupt (register bit field CTRL2[SABIE] and CTRL2[SABIRQ]). */
#define FSL_FEATURE_ENC_HAS_NO_CTRL2_SAB_INT (1)
/* @brief Has register CTRL3. */
#define FSL_FEATURE_ENC_HAS_CTRL3 (0)
/* @brief Has register LASTEDGE or LASTEDGEH. */
#define FSL_FEATURE_ENC_HAS_LASTEDGE (0)
/* @brief Has register POSDPERBFR, POSDPERH, or POSDPER. */
#define FSL_FEATURE_ENC_HAS_POSDPER (0)
/* @brief Has bitfiled FILT[FILT_PRSC]. */
#define FSL_FEATURE_ENC_HAS_FILT_PRSC (1)
/* ENET module features */
/* @brief Support Interrupt Coalesce */
#define FSL_FEATURE_ENET_HAS_INTERRUPT_COALESCE (1)
/* @brief Queue Size. */
#define FSL_FEATURE_ENET_QUEUE (1)
/* @brief Has AVB Support. */
#define FSL_FEATURE_ENET_HAS_AVB (0)
/* @brief Has Timer Pulse Width control. */
#define FSL_FEATURE_ENET_HAS_TIMER_PWCONTROL (1)
/* @brief Has Extend MDIO Support. */
#define FSL_FEATURE_ENET_HAS_EXTEND_MDIO (1)
/* @brief Has Additional 1588 Timer Channel Interrupt. */
#define FSL_FEATURE_ENET_HAS_ADD_1588_TIMER_CHN_INT (0)
/* @brief Support Interrupt Coalesce for each instance */
#define FSL_FEATURE_ENET_INSTANCE_HAS_INTERRUPT_COALESCEn(x) (1)
/* @brief Queue Size for each instance. */
#define FSL_FEATURE_ENET_INSTANCE_QUEUEn(x) (1)
/* @brief Has AVB Support for each instance. */
#define FSL_FEATURE_ENET_INSTANCE_HAS_AVBn(x) (0)
/* @brief Has Timer Pulse Width control for each instance. */
#define FSL_FEATURE_ENET_INSTANCE_HAS_TIMER_PWCONTROLn(x) (1)
/* @brief Has Extend MDIO Support for each instance. */
#define FSL_FEATURE_ENET_INSTANCE_HAS_EXTEND_MDIOn(x) (1)
/* @brief Has Additional 1588 Timer Channel Interrupt for each instance. */
#define FSL_FEATURE_ENET_INSTANCE_HAS_ADD_1588_TIMER_CHN_INTn(x) (0)
/* @brief Has threshold for the number of frames in the receive FIFO (register bit field RSEM[STAT_SECTION_EMPTY]). */
#define FSL_FEATURE_ENET_HAS_RECEIVE_STATUS_THRESHOLD (1)
/* @brief Has trasfer clock delay (register bit field ECR[TXC_DLY]). */
#define FSL_FEATURE_ENET_HAS_RGMII_TXC_DELAY (0)
/* @brief Has receive clock delay (register bit field ECR[RXC_DLY]). */
#define FSL_FEATURE_ENET_HAS_RGMII_RXC_DELAY (0)
/* @brief PTP Timestamp CAPTURE bit always returns 0 when the capture is not over. */
#define FSL_FEATURE_ENET_TIMESTAMP_CAPTURE_BIT_INVALID (0)
/* @brief ENET Has Extra Clock Gate.(RW610). */
#define FSL_FEATURE_ENET_HAS_EXTRA_CLOCK_GATE (0)
/* EWM module features */
/* @brief Has clock select (register CLKCTRL). */
#define FSL_FEATURE_EWM_HAS_CLOCK_SELECT (1)
/* @brief Has clock prescaler (register CLKPRESCALER). */
#define FSL_FEATURE_EWM_HAS_PRESCALER (1)
/* FLEXIO module features */
/* @brief Has Shifter Status Register (FLEXIO_SHIFTSTAT) */
#define FSL_FEATURE_FLEXIO_HAS_SHIFTER_STATUS (1)
/* @brief Has Pin Data Input Register (FLEXIO_PIN) */
#define FSL_FEATURE_FLEXIO_HAS_PIN_STATUS (1)
/* @brief Has pin input output related registers */
#define FSL_FEATURE_FLEXIO_HAS_PIN_REGISTER (0)
/* @brief Has Shifter Buffer N Nibble Byte Swapped Register (FLEXIO_SHIFTBUFNBSn) */
#define FSL_FEATURE_FLEXIO_HAS_SHFT_BUFFER_NIBBLE_BYTE_SWAP (1)
/* @brief Has Shifter Buffer N Half Word Swapped Register (FLEXIO_SHIFTBUFHWSn) */
#define FSL_FEATURE_FLEXIO_HAS_SHFT_BUFFER_HALF_WORD_SWAP (1)
/* @brief Has Shifter Buffer N Nibble Swapped Register (FLEXIO_SHIFTBUFNISn) */
#define FSL_FEATURE_FLEXIO_HAS_SHFT_BUFFER_NIBBLE_SWAP (1)
/* @brief Supports Shifter State Mode (FLEXIO_SHIFTCTLn[SMOD]) */
#define FSL_FEATURE_FLEXIO_HAS_STATE_MODE (1)
/* @brief Supports Shifter Logic Mode (FLEXIO_SHIFTCTLn[SMOD]) */
#define FSL_FEATURE_FLEXIO_HAS_LOGIC_MODE (1)
/* @brief Supports paralle width (FLEXIO_SHIFTCFGn[PWIDTH]) */
#define FSL_FEATURE_FLEXIO_HAS_PARALLEL_WIDTH (1)
/* @brief Reset value of the FLEXIO_VERID register */
#define FSL_FEATURE_FLEXIO_VERID_RESET_VALUE (0x1010001)
/* @brief Reset value of the FLEXIO_PARAM register */
#define FSL_FEATURE_FLEXIO_PARAM_RESET_VALUE (0x2200808)
/* @brief Represent the bit width of the TIMDCE field (FLEXIO_TIMCFGLn[TIMDEC]) */
#define FSL_FEATURE_FLEXIO_TIMCFG_TIMDCE_FIELD_WIDTH (2)
/* @brief Flexio DMA request base channel */
#define FSL_FEATURE_FLEXIO_DMA_REQUEST_BASE_CHANNEL (0)
/* FLEXRAM module features */
/* @brief Bank size */
#define FSL_FEATURE_FLEXRAM_INTERNAL_RAM_BANK_SIZE (32768)
/* @brief Total Bank numbers */
#define FSL_FEATURE_FLEXRAM_INTERNAL_RAM_TOTAL_BANK_NUMBERS (16)
/* @brief Has FLEXRAM_MAGIC_ADDR. */
#define FSL_FEATURE_FLEXRAM_HAS_MAGIC_ADDR (0)
/* @brief If FLEXRAM has ECC function. */
#define FSL_FEATURE_FLEXRAM_HAS_ECC (0)
/* @brief If FLEXRAM has ECC Error Injection function. */
#define FSL_FEATURE_FLEXRAM_HAS_ECC_ERROR_INJECTION (0)
/* FLEXSPI module features */
/* @brief FlexSPI AHB buffer count */
#define FSL_FEATURE_FLEXSPI_AHB_BUFFER_COUNTn(x) (4)
/* @brief FlexSPI has no data learn. */
#define FSL_FEATURE_FLEXSPI_HAS_NO_DATA_LEARN (1)
/* @brief There is AHBBUSERROREN bit in INTEN register. */
#define FSL_FEATURE_FLEXSPI_HAS_INTEN_AHBBUSERROREN (0)
/* @brief There is CLRAHBTX_RXBUF bit in AHBCR register. */
#define FSL_FEATURE_FLEXSPI_HAS_AHBCR_CLRAHBTX_RXBUF (1)
/* @brief FLEXSPI has no IP parallel mode. */
#define FSL_FEATURE_FLEXSPI_HAS_NO_IP_PARALLEL_MODE (0)
/* @brief FLEXSPI has no AHB parallel mode. */
#define FSL_FEATURE_FLEXSPI_HAS_NO_AHB_PARALLEL_MODE (0)
/* @brief FLEXSPI support address shift. */
#define FSL_FEATURE_FLEXSPI_SUPPORT_ADDRESS_SHIFT (0)
/* @brief FlexSPI has no MCR0 ARDFEN bit */
#define FSL_FEATURE_FLEXSPI_HAS_NO_MCR0_ARDFEN (0)
/* @brief FlexSPI has no MCR0 ATDFEN bit */
#define FSL_FEATURE_FLEXSPI_HAS_NO_MCR0_ATDFEN (0)
/* @brief FlexSPI has no STS0 DATALEARNPHASEB bit */
#define FSL_FEATURE_FLEXSPI_HAS_NO_STS0_DATALEARNPHASEB (1)
/* @brief FlexSPI AHB RX buffer size (byte) */
#define FSL_FEATURE_FLEXSPI_AHB_RX_BUFFER_SIZEn(x) (1024)
/* @brief FlexSPI Array Length */
#define FSL_FEATURE_FLEXSPI_ARRAY_LEN (3)
/* GPC module features */
/* @brief Has DVFS0 Change Request. */
#define FSL_FEATURE_GPC_HAS_CNTR_DVFS0CR (0)
/* @brief Has GPC interrupt/event masking. */
#define FSL_FEATURE_GPC_HAS_CNTR_GPCIRQM (0)
/* @brief Has L2 cache power control. */
#define FSL_FEATURE_GPC_HAS_CNTR_L2PGE (0)
/* @brief Has FLEXRAM PDRAM0(bank1-7) power control. */
#define FSL_FEATURE_GPC_HAS_CNTR_PDRAM0PGE (1)
/* @brief Has VADC power control. */
#define FSL_FEATURE_GPC_HAS_CNTR_VADC (0)
/* @brief Has Display power control. */
#define FSL_FEATURE_GPC_HAS_CNTR_DISPLAY (0)
/* @brief Supports IRQ 0-31. */
#define FSL_FEATURE_GPC_HAS_IRQ_0_31 (1)
/* IGPIO module features */
/* @brief Has data register set DR_SET. */
#define FSL_FEATURE_IGPIO_HAS_DR_SET (1)
/* @brief Has data register clear DR_CLEAR. */
#define FSL_FEATURE_IGPIO_HAS_DR_CLEAR (1)
/* @brief Has data register toggle DR_TOGGLE. */
#define FSL_FEATURE_IGPIO_HAS_DR_TOGGLE (1)
/* LCDIF module features */
/* @brief LCDIF does not support alpha support. */
#define FSL_FEATURE_LCDIF_HAS_NO_AS (1)
/* @brief LCDIF does not support output reset pin to LCD panel. */
#define FSL_FEATURE_LCDIF_HAS_NO_RESET_PIN (1)
/* @brief LCDIF supports LUT. */
#define FSL_FEATURE_LCDIF_HAS_LUT (1)
/* LPI2C module features */
/* @brief Has separate DMA RX and TX requests. */
#define FSL_FEATURE_LPI2C_HAS_SEPARATE_DMA_RX_TX_REQn(x) (0)
/* @brief Capacity (number of entries) of the transmit/receive FIFO (or zero if no FIFO is available). */
#define FSL_FEATURE_LPI2C_FIFO_SIZEn(x) (4)
/* LPSPI module features */
/* @brief Capacity (number of entries) of the transmit/receive FIFO (or zero if no FIFO is available). */
#define FSL_FEATURE_LPSPI_FIFO_SIZEn(x) (16)
/* @brief Has separate DMA RX and TX requests. */
#define FSL_FEATURE_LPSPI_HAS_SEPARATE_DMA_RX_TX_REQn(x) (1)
/* @brief Has CCR1 (related to existence of registers CCR1). */
#define FSL_FEATURE_LPSPI_HAS_CCR1 (0)
/* @brief Has no PCSCFG bit in CFGR1 register */
#define FSL_FEATURE_LPSPI_HAS_NO_PCSCFG (0)
/* @brief Has no WIDTH bits in TCR register */
#define FSL_FEATURE_LPSPI_HAS_NO_MULTI_WIDTH (0)
/* LPUART module features */
/* @brief Has receive FIFO overflow detection (bit field CFIFO[RXOFE]). */
#define FSL_FEATURE_LPUART_HAS_IRQ_EXTENDED_FUNCTIONS (0)
/* @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_LPUART_HAS_LOW_POWER_UART_SUPPORT (1)
/* @brief Has extended data register ED (or extra flags in the DATA register if the registers are 32-bit wide). */
#define FSL_FEATURE_LPUART_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_LPUART_HAS_FIFO (1)
/* @brief Has 32-bit register MODIR */
#define FSL_FEATURE_LPUART_HAS_MODIR (1)
/* @brief Hardware flow control (RTS, CTS) is supported. */
#define FSL_FEATURE_LPUART_HAS_MODEM_SUPPORT (1)
/* @brief Infrared (modulation) is supported. */
#define FSL_FEATURE_LPUART_HAS_IR_SUPPORT (1)
/* @brief 2 bits long stop bit is available. */
#define FSL_FEATURE_LPUART_HAS_STOP_BIT_CONFIG_SUPPORT (1)
/* @brief If 10-bit mode is supported. */
#define FSL_FEATURE_LPUART_HAS_10BIT_DATA_SUPPORT (1)
/* @brief If 7-bit mode is supported. */
#define FSL_FEATURE_LPUART_HAS_7BIT_DATA_SUPPORT (1)
/* @brief Baud rate fine adjustment is available. */
#define FSL_FEATURE_LPUART_HAS_BAUD_RATE_FINE_ADJUST_SUPPORT (0)
/* @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_LPUART_HAS_BAUD_RATE_OVER_SAMPLING_SUPPORT (1)
/* @brief Baud rate oversampling is available. */
#define FSL_FEATURE_LPUART_HAS_RX_RESYNC_SUPPORT (1)
/* @brief Baud rate oversampling is available. */
#define FSL_FEATURE_LPUART_HAS_BOTH_EDGE_SAMPLING_SUPPORT (1)
/* @brief Peripheral type. */
#define FSL_FEATURE_LPUART_IS_SCI (1)
/* @brief Capacity (number of entries) of the transmit/receive FIFO (or zero if no FIFO is available). */
#define FSL_FEATURE_LPUART_FIFO_SIZEn(x) (4)
/* @brief Supports two match addresses to filter incoming frames. */
#define FSL_FEATURE_LPUART_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_LPUART_HAS_DMA_ENABLE (1)
/* @brief Has transmitter/receiver DMA select bits C4[TDMAS]/C4[RDMAS], resp. C5[TDMAS]/C5[RDMAS] if IS_SCI = 0. */
#define FSL_FEATURE_LPUART_HAS_DMA_SELECT (0)
/* @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_LPUART_HAS_BIT_ORDER_SELECT (1)
/* @brief Has smart card (ISO7816 protocol) support and no improved smart card support. */
#define FSL_FEATURE_LPUART_HAS_SMART_CARD_SUPPORT (0)
/* @brief Has improved smart card (ISO7816 protocol) support. */
#define FSL_FEATURE_LPUART_HAS_IMPROVED_SMART_CARD_SUPPORT (0)
/* @brief Has local operation network (CEA709.1-B protocol) support. */
#define FSL_FEATURE_LPUART_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_LPUART_HAS_32BIT_REGISTERS (1)
/* @brief Lin break detect available (has bit BAUD[LBKDIE]). */
#define FSL_FEATURE_LPUART_HAS_LIN_BREAK_DETECT (1)
/* @brief UART stops in Wait mode available (has bit C1[UARTSWAI]). */
#define FSL_FEATURE_LPUART_HAS_WAIT_MODE_OPERATION (0)
/* @brief Has separate DMA RX and TX requests. */
#define FSL_FEATURE_LPUART_HAS_SEPARATE_DMA_RX_TX_REQn(x) (1)
/* @brief Has separate RX and TX interrupts. */
#define FSL_FEATURE_LPUART_HAS_SEPARATE_RX_TX_IRQ (0)
/* @brief Has LPAURT_PARAM. */
#define FSL_FEATURE_LPUART_HAS_PARAM (1)
/* @brief Has LPUART_VERID. */
#define FSL_FEATURE_LPUART_HAS_VERID (1)
/* @brief Has LPUART_GLOBAL. */
#define FSL_FEATURE_LPUART_HAS_GLOBAL (1)
/* @brief Has LPUART_PINCFG. */
#define FSL_FEATURE_LPUART_HAS_PINCFG (1)
/* @brief Has register MODEM Control. */
#define FSL_FEATURE_LPUART_HAS_MCR (0)
/* @brief Has register Half Duplex Control. */
#define FSL_FEATURE_LPUART_HAS_HDCR (0)
/* @brief Has register Timeout. */
#define FSL_FEATURE_LPUART_HAS_TIMEOUT (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 (157)
/* OCOTP module features */
/* @brief Has timing control, (register TIMING). */
#define FSL_FEATURE_OCOTP_HAS_TIMING_CTRL (1)
/* @brief Support lock eFuse word write lock, (CTRL[WORDLOCK]). */
#define FSL_FEATURE_OCOTP_HAS_WORDLOCK (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 (1)
/* @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 (1)
/* @brief Has timer enable control. */
#define FSL_FEATURE_PIT_HAS_MDIS (1)
/* PMU module features */
/* @brief PMU supports lower power control. */
#define FSL_FEATURE_PMU_HAS_LOWPWR_CTRL (0)
/* PWM module features */
/* @brief If (e)FlexPWM has module A channels (outputs). */
#define FSL_FEATURE_PWM_HAS_CHANNELA (1)
/* @brief If (e)FlexPWM has module B channels (outputs). */
#define FSL_FEATURE_PWM_HAS_CHANNELB (1)
/* @brief If (e)FlexPWM has module X channels (outputs). */
#define FSL_FEATURE_PWM_HAS_CHANNELX (1)
/* @brief If (e)FlexPWM has fractional feature. */
#define FSL_FEATURE_PWM_HAS_FRACTIONAL (1)
/* @brief If (e)FlexPWM has mux trigger source select bit field. */
#define FSL_FEATURE_PWM_HAS_MUX_TRIGGER_SOURCE_SEL (1)
/* @brief Number of submodules in each (e)FlexPWM module. */
#define FSL_FEATURE_PWM_SUBMODULE_COUNT (4)
/* @brief Number of fault channel in each (e)FlexPWM module. */
#define FSL_FEATURE_PWM_FAULT_CH_COUNT (1)
/* @brief (e)FlexPWM has no WAITEN Bitfield In CTRL2 Register. */
#define FSL_FEATURE_PWM_HAS_NO_WAITEN (0)
/* @brief If (e)FlexPWM has phase delay feature. */
#define FSL_FEATURE_PWM_HAS_PHASE_DELAY (0)
/* @brief If (e)FlexPWM has input filter capture feature. */
#define FSL_FEATURE_PWM_HAS_INPUT_FILTER_CAPTURE (0)
/* @brief If (e)FlexPWM has module capture functionality on A channels (inputs). */
#define FSL_FEATURE_PWM_HAS_CAPTURE_ON_CHANNELA (1)
/* @brief If (e)FlexPWM has module capture functionality on B channels (inputs). */
#define FSL_FEATURE_PWM_HAS_CAPTURE_ON_CHANNELB (1)
/* @brief If (e)FlexPWM has module capture functionality on X channels (inputs). */
#define FSL_FEATURE_PWM_HAS_CAPTURE_ON_CHANNELX (1)
/* PXP module features */
/* @brief PXP module has dither engine. */
#define FSL_FEATURE_PXP_HAS_DITHER (0)
/* @brief PXP module supports repeat run */
#define FSL_FEATURE_PXP_HAS_EN_REPEAT (1)
/* @brief PXP doesn't have CSC */
#define FSL_FEATURE_PXP_HAS_NO_CSC2 (1)
/* @brief PXP doesn't have LUT */
#define FSL_FEATURE_PXP_HAS_NO_LUT (1)
/* @brief PXP doesn't have PORTER_DUFF_CTR */
#define FSL_FEATURE_PXP_HAS_NO_PORTER_DUFF_CTRL (0)
/* @brief PXP 3.0 version */
#define FSL_FEATURE_PXP_V3 (0)
/* @brief PXP doesn't have ROT_POS */
#define FSL_FEATURE_PXP_HAS_NO_ROT_POS (1)
/* RTWDOG module features */
/* @brief Watchdog is available. */
#define FSL_FEATURE_RTWDOG_HAS_WATCHDOG (1)
/* @brief RTWDOG_CNT can be 32-bit written. */
#define FSL_FEATURE_RTWDOG_HAS_32BIT_ACCESS (1)
/* SAI module features */
/* @brief SAI has FIFO in this soc (register bit fields TCR1[TFW]. */
#define FSL_FEATURE_SAI_HAS_FIFO (1)
/* @brief Receive/transmit FIFO size in item count (register bit fields TCSR[FRDE], TCSR[FRIE], TCSR[FRF], TCR1[TFW], RCSR[FRDE], RCSR[FRIE], RCSR[FRF], RCR1[RFW], registers TFRn, RFRn). */
#define FSL_FEATURE_SAI_FIFO_COUNTn(x) (32)
/* @brief Receive/transmit channel number (register bit fields TCR3[TCE], RCR3[RCE], registers TDRn and RDRn). */
#define FSL_FEATURE_SAI_CHANNEL_COUNTn(x) \
(((x) == SAI1) ? (4) : \
(((x) == SAI2) ? (1) : \
(((x) == SAI3) ? (1) : (-1))))
/* @brief Maximum words per frame (register bit fields TCR3[WDFL], TCR4[FRSZ], TMR[TWM], RCR3[WDFL], RCR4[FRSZ], RMR[RWM]). */
#define FSL_FEATURE_SAI_MAX_WORDS_PER_FRAME (32)
/* @brief Has support of combining multiple data channel FIFOs into single channel FIFO (register bit fields TCR3[CFR], TCR4[FCOMB], TFR0[WCP], TFR1[WCP], RCR3[CFR], RCR4[FCOMB], RFR0[RCP], RFR1[RCP]). */
#define FSL_FEATURE_SAI_HAS_FIFO_COMBINE_MODE (1)
/* @brief Has packing of 8-bit and 16-bit data into each 32-bit FIFO word (register bit fields TCR4[FPACK], RCR4[FPACK]). */
#define FSL_FEATURE_SAI_HAS_FIFO_PACKING (1)
/* @brief Configures when the SAI will continue transmitting after a FIFO error has been detected (register bit fields TCR4[FCONT], RCR4[FCONT]). */
#define FSL_FEATURE_SAI_HAS_FIFO_FUNCTION_AFTER_ERROR (1)
/* @brief Configures if the frame sync is generated internally, a frame sync is only generated when the FIFO warning flag is clear or continuously (register bit fields TCR4[ONDEM], RCR4[ONDEM]). */
#define FSL_FEATURE_SAI_HAS_ON_DEMAND_MODE (1)
/* @brief Simplified bit clock source and asynchronous/synchronous mode selection (register bit fields TCR2[CLKMODE], RCR2[CLKMODE]), in comparison with the exclusively implemented TCR2[SYNC,BCS,BCI,MSEL], RCR2[SYNC,BCS,BCI,MSEL]. */
#define FSL_FEATURE_SAI_HAS_CLOCKING_MODE (0)
/* @brief Has register for configuration of the MCLK divide ratio (register bit fields MDR[FRACT], MDR[DIVIDE]). */
#define FSL_FEATURE_SAI_HAS_MCLKDIV_REGISTER (0)
/* @brief Interrupt source number */
#define FSL_FEATURE_SAI_INT_SOURCE_NUM (2)
/* @brief Has register of MCR. */
#define FSL_FEATURE_SAI_HAS_MCR (0)
/* @brief Has bit field MICS of the MCR register. */
#define FSL_FEATURE_SAI_HAS_NO_MCR_MICS (1)
/* @brief Has register of MDR */
#define FSL_FEATURE_SAI_HAS_MDR (0)
/* @brief Has support the BCLK bypass mode when BCLK = MCLK. */
#define FSL_FEATURE_SAI_HAS_BCLK_BYPASS (0)
/* @brief Has DIV bit fields of MCR register (register bit fields MCR[DIV]. */
#define FSL_FEATURE_SAI_HAS_MCR_MCLK_POST_DIV (0)
/* @brief Support Channel Mode (register bit fields TCR4[CHMOD]). */
#define FSL_FEATURE_SAI_HAS_CHANNEL_MODE (1)
/* @brief Support synchronous with another SAI. */
#define FSL_FEATURE_SAI_HAS_SYNC_WITH_ANOTHER_SAI (0)
/* SEMC module features */
/* @brief Has WDH time in NOR controller (register bit field NORCR2[WDH]). */
#define FSL_FEATURE_SEMC_HAS_NOR_WDH_TIME (0)
/* @brief Has WDS time in NOR controller (register bit field NORCR2[WDS]). */
#define FSL_FEATURE_SEMC_HAS_NOR_WDS_TIME (0)
/* @brief Has LC time in NOR controller (register bit field NORCR2[LC]). */
#define FSL_FEATURE_SEMC_HAS_NOR_LC_TIME (1)
/* @brief Has RD time in NOR controller (register bit field NORCR2[RD]). */
#define FSL_FEATURE_SEMC_HAS_NOR_RD_TIME (1)
/* @brief Has WDH time in SRAM controller (register bit field SRAMCR2[WDH] or SRAMCR6[WDH]). */
#define FSL_FEATURE_SEMC_HAS_SRAM_WDH_TIME (1)
/* @brief Has WDS time in SRAM controller (register bit field SRAMCR2[WDS] or SRAMCR6[WDS]). */
#define FSL_FEATURE_SEMC_HAS_SRAM_WDS_TIME (1)
/* @brief Has LC time in SRAM controller (register bit field SRAMCR2[LC] or SRAMCR6[LC]). */
#define FSL_FEATURE_SEMC_HAS_SRAM_LC_TIME (1)
/* @brief Has RD time in SRAM controller (register bit field SRAMCR2[RD] or SRAMCR6[RD]). */
#define FSL_FEATURE_SEMC_HAS_SRAM_RD_TIME (1)
/* @brief SRAM count SEMC can support (register BRx). */
#define FSL_FEATURE_SEMC_SUPPORT_SRAM_COUNT (1)
/* @brief If SEMC support delay chain control (register DCCR). */
#define FSL_FEATURE_SEMC_HAS_DELAY_CHAIN_CONTROL (0)
/* @brief Has read hold time feature (register bit field SRAMCR2[RDH] or SRAMCR6[RDH]). */
#define FSL_FEATURE_SEMC_HAS_SRAM_RDH_TIME (1)
/* @brief Has read hold time feature (register bit field SRAMCR0[SYNCEN] or SRAMCR4[SYNCEN]). */
#define FSL_FEATURE_SEMC_HAS_SRAM_SYNCEN (1)
/* @brief Has read hold time feature (register bit field SRAMCR0[WAITEN] or SRAMCR4[WAITEN]). */
#define FSL_FEATURE_SEMC_HAS_SRAM_WAITEN (0)
/* @brief Has read hold time feature (register bit field SRAMCR0[WAITSP] or SRAMCR4[WAITSP]). */
#define FSL_FEATURE_SEMC_HAS_SRAM_WAITSP (0)
/* @brief Has read hold time feature (register bit field SRAMCR0[ADVH] or SRAMCR4[ADVH]). */
#define FSL_FEATURE_SEMC_HAS_SRAM_ADVH (1)
/* @brief Width of SDRAMCR0[PS] bitfields. */
#define FSL_FEATURE_SEMC_SUPPORT_SDRAM_PS_BITWIDTH (1)
/* @brief If SEMC has errata 050577. */
#define FSL_FEATURE_SEMC_ERRATA_050577 (0)
/* @brief If sdram support column address 8 bit (register bit field SRAMCR0[CLO8]). */
#define FSL_FEATURE_SEMC_SDRAM_SUPPORT_COLUMN_ADDRESS_8BIT (1)
/* @brief If SEMC has register DBICR2 (register DBICR2). */
#define FSL_FEATURE_SEMC_HAS_DBICR2 (0)
/* @brief SEMC supports hardware ECC on NAND flash interface. */
#define FSL_FEATURE_SEMC_HAS_NAND_HW_ECC (0)
/* SNVS module features */
/* @brief Has Secure Real Time Counter Enabled and Valid (bit field LPCR[SRTC_ENV]). */
#define FSL_FEATURE_SNVS_HAS_SRTC (1)
/* @brief Has Passive Tamper Filter (regitser LPTGFCR). */
#define FSL_FEATURE_SNVS_PASSIVE_TAMPER_FILTER (0)
/* @brief Has Active Tampers (regitser LPATCTLR, LPATCLKR, LPATRCnR). */
#define FSL_FEATURE_SNVS_HAS_ACTIVE_TAMPERS (0)
/* @brief Number of TAMPER. */
#define FSL_FEATURE_SNVS_HAS_MULTIPLE_TAMPER (0)
/* SRC module features */
/* @brief There is MASK_WDOG3_RST bit in SCR register. */
#define FSL_FEATURE_SRC_HAS_SCR_MASK_WDOG3_RST (1)
/* @brief There is MIX_RST_STRCH bit in SCR register. */
#define FSL_FEATURE_SRC_HAS_SCR_MIX_RST_STRCH (0)
/* @brief There is DBG_RST_MSK_PG bit in SCR register. */
#define FSL_FEATURE_SRC_HAS_SCR_DBG_RST_MSK_PG (1)
/* @brief There is WDOG3_RST_OPTN bit in SCR register. */
#define FSL_FEATURE_SRC_HAS_SCR_WDOG3_RST_OPTN (0)
/* @brief There is CORES_DBG_RST bit in SCR register. */
#define FSL_FEATURE_SRC_HAS_SCR_CORES_DBG_RST (0)
/* @brief There is MTSR bit in SCR register. */
#define FSL_FEATURE_SRC_HAS_SCR_MTSR (0)
/* @brief There is CORE0_DBG_RST bit in SCR register. */
#define FSL_FEATURE_SRC_HAS_SCR_CORE0_DBG_RST (1)
/* @brief There is CORE0_RST bit in SCR register. */
#define FSL_FEATURE_SRC_HAS_SCR_CORE0_RST (1)
/* @brief There is LOCKUP_RST bit in SCR register. */
#define FSL_FEATURE_SRC_HAS_SCR_LOCKUP_RST (0)
/* @brief There is SWRC bit in SCR register. */
#define FSL_FEATURE_SRC_HAS_SCR_SWRC (0)
/* @brief There is EIM_RST bit in SCR register. */
#define FSL_FEATURE_SRC_HAS_SCR_EIM_RST (0)
/* @brief There is LUEN bit in SCR register. */
#define FSL_FEATURE_SRC_HAS_SCR_LUEN (0)
/* @brief There is no WRBC bit in SCR register. */
#define FSL_FEATURE_SRC_HAS_NO_SCR_WRBC (1)
/* @brief There is no WRE bit in SCR register. */
#define FSL_FEATURE_SRC_HAS_NO_SCR_WRE (1)
/* @brief There is SISR register. */
#define FSL_FEATURE_SRC_HAS_SISR (0)
/* @brief There is RESET_OUT bit in SRSR register. */
#define FSL_FEATURE_SRC_HAS_SRSR_RESET_OUT (0)
/* @brief There is WDOG3_RST_B bit in SRSR register. */
#define FSL_FEATURE_SRC_HAS_SRSR_WDOG3_RST_B (1)
/* @brief There is JTAG_SW_RST bit in SRSR register. */
#define FSL_FEATURE_SRC_HAS_SRSR_JTAG_SW_RST (1)
/* @brief There is SW bit in SRSR register. */
#define FSL_FEATURE_SRC_HAS_SRSR_SW (0)
/* @brief There is IPP_USER_RESET_B bit in SRSR register. */
#define FSL_FEATURE_SRC_HAS_SRSR_IPP_USER_RESET_B (1)
/* @brief There is SNVS bit in SRSR register. */
#define FSL_FEATURE_SRC_HAS_SRSR_SNVS (0)
/* @brief There is CSU_RESET_B bit in SRSR register. */
#define FSL_FEATURE_SRC_HAS_SRSR_CSU_RESET_B (1)
/* @brief There is LOCKUP bit in SRSR register. */
#define FSL_FEATURE_SRC_HAS_SRSR_LOCKUP (0)
/* @brief There is LOCKUP_SYSRESETREQ bit in SRSR register. */
#define FSL_FEATURE_SRC_HAS_SRSR_LOCKUP_SYSRESETREQ (1)
/* @brief There is POR bit in SRSR register. */
#define FSL_FEATURE_SRC_HAS_SRSR_POR (0)
/* @brief There is IPP_RESET_B bit in SRSR register. */
#define FSL_FEATURE_SRC_HAS_SRSR_IPP_RESET_B (1)
/* @brief There is no WBI bit in SCR register. */
#define FSL_FEATURE_SRC_HAS_NO_SRSR_WBI (1)
/* SCB module features */
/* @brief L1 ICACHE line size in byte. */
#define FSL_FEATURE_L1ICACHE_LINESIZE_BYTE (32)
/* @brief L1 DCACHE line size in byte. */
#define FSL_FEATURE_L1DCACHE_LINESIZE_BYTE (32)
/* TRNG module features */
/* @brief TRNG has no TRNG_ACC bitfield. */
#define FSL_FEATURE_TRNG_HAS_NO_TRNG_ACC (1)
/* USBHS module features */
/* @brief EHCI module instance count */
#define FSL_FEATURE_USBHS_EHCI_COUNT (2)
/* @brief Number of endpoints supported */
#define FSL_FEATURE_USBHS_ENDPT_COUNT (8)
/* USBPHY module features */
/* @brief USBPHY contain DCD analog module */
#define FSL_FEATURE_USBPHY_HAS_DCD_ANALOG (0)
/* @brief USBPHY has register TRIM_OVERRIDE_EN */
#define FSL_FEATURE_USBPHY_HAS_TRIM_OVERRIDE_EN (0)
/* @brief USBPHY is 28FDSOI */
#define FSL_FEATURE_USBPHY_28FDSOI (0)
/* USDHC module features */
/* @brief Has external DMA support (VEND_SPEC[EXT_DMA_EN]) */
#define FSL_FEATURE_USDHC_HAS_EXT_DMA (0)
/* @brief Has HS400 mode (MIX_CTRL[HS400_MODE]) */
#define FSL_FEATURE_USDHC_HAS_HS400_MODE (0)
/* @brief Has SDR50 support (HOST_CTRL_CAP[SDR50_SUPPORT]) */
#define FSL_FEATURE_USDHC_HAS_SDR50_MODE (1)
/* @brief Has SDR104 support (HOST_CTRL_CAP[SDR104_SUPPORT]) */
#define FSL_FEATURE_USDHC_HAS_SDR104_MODE (1)
/* @brief USDHC has reset control */
#define FSL_FEATURE_USDHC_HAS_RESET (0)
/* @brief USDHC has no bitfield WTMK_LVL[WR_BRST_LEN] and WTMK_LVL[RD_BRST_LEN] */
#define FSL_FEATURE_USDHC_HAS_NO_RW_BURST_LEN (0)
/* @brief If USDHC instance support 8 bit width */
#define FSL_FEATURE_USDHC_INSTANCE_SUPPORT_8_BIT_WIDTHn(x) \
(((x) == USDHC1) ? (0) : \
(((x) == USDHC2) ? (1) : (-1)))
/* @brief If USDHC instance support HS400 mode */
#define FSL_FEATURE_USDHC_INSTANCE_SUPPORT_HS400_MODEn(x) (0)
/* @brief If USDHC instance support 1v8 signal */
#define FSL_FEATURE_USDHC_INSTANCE_SUPPORT_1V8_SIGNALn(x) (1)
/* @brief Has no retuning time counter (HOST_CTRL_CAP[TIME_COUNT_RETURNING]) */
#define FSL_FEATURE_USDHC_REGISTER_HOST_CTRL_CAP_HAS_NO_RETUNING_TIME_COUNTER (1)
/* @brief Has no VSELECT bit in VEND_SPEC register */
#define FSL_FEATURE_USDHC_HAS_NO_VOLTAGE_SELECT (0)
/* @brief Has no VS18 bit in HOST_CTRL_CAP register */
#define FSL_FEATURE_USDHC_HAS_NO_VS18 (0)
/* XBARA module features */
/* @brief Number of interrupt requests. */
#define FSL_FEATURE_XBARA_INTERRUPT_COUNT (4)
#endif /* _MIMXRT1062_FEATURES_H_ */

View File

@ -0,0 +1,211 @@
#ifndef _CLOCK_CONFIG_H_
#define _CLOCK_CONFIG_H_
#include "fsl_common.h"
/*******************************************************************************
* Definitions
******************************************************************************/
#define BOARD_XTAL0_CLK_HZ 24000000U /*!< Board xtal0 frequency in Hz */
#define BOARD_XTAL32K_CLK_HZ 32768U /*!< Board xtal32k frequency in Hz */
/*******************************************************************************
************************ 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 600000000U /*!< Core clock frequency: 600000000Hz */
/* Clock outputs (values are in Hz): */
#define BOARD_BOOTCLOCKRUN_AHB_CLK_ROOT 600000000UL /* Clock consumers of AHB_CLK_ROOT output : AIPSTZ1, AIPSTZ2, AIPSTZ3, AIPSTZ4, ARM, FLEXIO3, FLEXSPI, FLEXSPI2, GPIO6, GPIO7, GPIO8, GPIO9 */
#define BOARD_BOOTCLOCKRUN_CAN_CLK_ROOT 40000000UL /* Clock consumers of CAN_CLK_ROOT output : CAN1, CAN2, CAN3 */
#define BOARD_BOOTCLOCKRUN_CKIL_SYNC_CLK_ROOT 32768UL /* Clock consumers of CKIL_SYNC_CLK_ROOT output : CSU, EWM, GPT1, GPT2, KPP, PIT, RTWDOG, SNVS, SPDIF, TEMPMON, TSC, USB1, USB2, WDOG1, WDOG2 */
#define BOARD_BOOTCLOCKRUN_CLKO1_CLK 0UL /* Clock consumers of CLKO1_CLK output : N/A */
#define BOARD_BOOTCLOCKRUN_CLKO2_CLK 0UL /* Clock consumers of CLKO2_CLK output : N/A */
#define BOARD_BOOTCLOCKRUN_CLK_1M 1000000UL /* Clock consumers of CLK_1M output : EWM, RTWDOG */
#define BOARD_BOOTCLOCKRUN_CLK_24M 24000000UL /* Clock consumers of CLK_24M output : GPT1, GPT2 */
#define BOARD_BOOTCLOCKRUN_CSI_CLK_ROOT 12000000UL /* Clock consumers of CSI_CLK_ROOT output : CSI */
#define BOARD_BOOTCLOCKRUN_ENET2_125M_CLK 1200000UL /* Clock consumers of ENET2_125M_CLK output : N/A */
#define BOARD_BOOTCLOCKRUN_ENET2_REF_CLK 0UL /* Clock consumers of ENET2_REF_CLK output : ENET2 */
#define BOARD_BOOTCLOCKRUN_ENET2_TX_CLK 0UL /* Clock consumers of ENET2_TX_CLK output : ENET2 */
#define BOARD_BOOTCLOCKRUN_ENET_125M_CLK 2400000UL /* Clock consumers of ENET_125M_CLK output : N/A */
#define BOARD_BOOTCLOCKRUN_ENET_25M_REF_CLK 1200000UL /* Clock consumers of ENET_25M_REF_CLK output : ENET, ENET2 */
#define BOARD_BOOTCLOCKRUN_ENET_REF_CLK 0UL /* Clock consumers of ENET_REF_CLK output : ENET */
#define BOARD_BOOTCLOCKRUN_ENET_TX_CLK 0UL /* Clock consumers of ENET_TX_CLK output : ENET */
#define BOARD_BOOTCLOCKRUN_FLEXIO1_CLK_ROOT 30000000UL /* Clock consumers of FLEXIO1_CLK_ROOT output : FLEXIO1 */
#define BOARD_BOOTCLOCKRUN_FLEXIO2_CLK_ROOT 30000000UL /* Clock consumers of FLEXIO2_CLK_ROOT output : FLEXIO2, FLEXIO3 */
#define BOARD_BOOTCLOCKRUN_FLEXSPI2_CLK_ROOT 130909090UL /* Clock consumers of FLEXSPI2_CLK_ROOT output : FLEXSPI2 */
#define BOARD_BOOTCLOCKRUN_FLEXSPI_CLK_ROOT 130909090UL /* Clock consumers of FLEXSPI_CLK_ROOT output : FLEXSPI */
#define BOARD_BOOTCLOCKRUN_GPT1_IPG_CLK_HIGHFREQ 75000000UL /* Clock consumers of GPT1_ipg_clk_highfreq output : GPT1 */
#define BOARD_BOOTCLOCKRUN_GPT2_IPG_CLK_HIGHFREQ 75000000UL /* Clock consumers of GPT2_ipg_clk_highfreq output : GPT2 */
#define BOARD_BOOTCLOCKRUN_IPG_CLK_ROOT 150000000UL /* Clock consumers of IPG_CLK_ROOT output : ADC1, ADC2, ADC_ETC, AOI1, AOI2, ARM, BEE, CAN1, CAN2, CAN3, CCM, CMP1, CMP2, CMP3, CMP4, CSI, CSU, DCDC, DCP, DMA0, DMAMUX, ENC1, ENC2, ENC3, ENC4, ENET, ENET2, EWM, FLEXIO1, FLEXIO2, FLEXIO3, FLEXRAM, FLEXSPI, FLEXSPI2, GPC, GPIO1, GPIO10, GPIO2, GPIO3, GPIO4, GPIO5, IOMUXC, KPP, LCDIF, LPI2C1, LPI2C2, LPI2C3, LPI2C4, LPSPI1, LPSPI2, LPSPI3, LPSPI4, LPUART1, LPUART2, LPUART3, LPUART4, LPUART5, LPUART6, LPUART7, LPUART8, NVIC, OCOTP, PMU, PWM1, PWM2, PWM3, PWM4, PXP, ROMC, RTWDOG, SAI1, SAI2, SAI3, SNVS, SPDIF, SRC, TEMPMON, TMR1, TMR2, TMR3, TMR4, TRNG, TSC, USB1, USB2, USDHC1, USDHC2, WDOG1, WDOG2, XBARA1, XBARB2, XBARB3 */
#define BOARD_BOOTCLOCKRUN_LCDIF_CLK_ROOT 67500000UL /* Clock consumers of LCDIF_CLK_ROOT output : LCDIF */
#define BOARD_BOOTCLOCKRUN_LPI2C_CLK_ROOT 60000000UL /* Clock consumers of LPI2C_CLK_ROOT output : LPI2C1, LPI2C2, LPI2C3, LPI2C4 */
#define BOARD_BOOTCLOCKRUN_LPSPI_CLK_ROOT 105600000UL /* Clock consumers of LPSPI_CLK_ROOT output : LPSPI1, LPSPI2, LPSPI3, LPSPI4 */
#define BOARD_BOOTCLOCKRUN_LVDS1_CLK 1200000000UL /* Clock consumers of LVDS1_CLK output : N/A */
#define BOARD_BOOTCLOCKRUN_MQS_MCLK 63529411UL /* Clock consumers of MQS_MCLK output : N/A */
#define BOARD_BOOTCLOCKRUN_PERCLK_CLK_ROOT 75000000UL /* Clock consumers of PERCLK_CLK_ROOT output : GPT1, GPT2, PIT */
#define BOARD_BOOTCLOCKRUN_PLL7_MAIN_CLK 24000000UL /* Clock consumers of PLL7_MAIN_CLK output : N/A */
#define BOARD_BOOTCLOCKRUN_SAI1_CLK_ROOT 63529411UL /* Clock consumers of SAI1_CLK_ROOT output : N/A */
#define BOARD_BOOTCLOCKRUN_SAI1_MCLK1 63529411UL /* Clock consumers of SAI1_MCLK1 output : SAI1 */
#define BOARD_BOOTCLOCKRUN_SAI1_MCLK2 63529411UL /* Clock consumers of SAI1_MCLK2 output : SAI1 */
#define BOARD_BOOTCLOCKRUN_SAI1_MCLK3 30000000UL /* Clock consumers of SAI1_MCLK3 output : SAI1 */
#define BOARD_BOOTCLOCKRUN_SAI2_CLK_ROOT 63529411UL /* Clock consumers of SAI2_CLK_ROOT output : N/A */
#define BOARD_BOOTCLOCKRUN_SAI2_MCLK1 63529411UL /* Clock consumers of SAI2_MCLK1 output : SAI2 */
#define BOARD_BOOTCLOCKRUN_SAI2_MCLK2 0UL /* Clock consumers of SAI2_MCLK2 output : SAI2 */
#define BOARD_BOOTCLOCKRUN_SAI2_MCLK3 30000000UL /* Clock consumers of SAI2_MCLK3 output : SAI2 */
#define BOARD_BOOTCLOCKRUN_SAI3_CLK_ROOT 63529411UL /* Clock consumers of SAI3_CLK_ROOT output : N/A */
#define BOARD_BOOTCLOCKRUN_SAI3_MCLK1 63529411UL /* Clock consumers of SAI3_MCLK1 output : SAI3 */
#define BOARD_BOOTCLOCKRUN_SAI3_MCLK2 0UL /* Clock consumers of SAI3_MCLK2 output : SAI3 */
#define BOARD_BOOTCLOCKRUN_SAI3_MCLK3 30000000UL /* Clock consumers of SAI3_MCLK3 output : SAI3 */
#define BOARD_BOOTCLOCKRUN_SEMC_CLK_ROOT 75000000UL /* Clock consumers of SEMC_CLK_ROOT output : SEMC */
#define BOARD_BOOTCLOCKRUN_SPDIF0_CLK_ROOT 30000000UL /* Clock consumers of SPDIF0_CLK_ROOT output : SPDIF */
#define BOARD_BOOTCLOCKRUN_SPDIF0_EXTCLK_OUT 0UL /* Clock consumers of SPDIF0_EXTCLK_OUT output : SPDIF */
#define BOARD_BOOTCLOCKRUN_TRACE_CLK_ROOT 132000000UL /* Clock consumers of TRACE_CLK_ROOT output : ARM */
#define BOARD_BOOTCLOCKRUN_UART_CLK_ROOT 80000000UL /* Clock consumers of UART_CLK_ROOT output : LPUART1, LPUART2, LPUART3, LPUART4, LPUART5, LPUART6, LPUART7, LPUART8 */
#define BOARD_BOOTCLOCKRUN_USBPHY1_CLK 0UL /* Clock consumers of USBPHY1_CLK output : TEMPMON, USB1 */
#define BOARD_BOOTCLOCKRUN_USBPHY2_CLK 0UL /* Clock consumers of USBPHY2_CLK output : USB2 */
#define BOARD_BOOTCLOCKRUN_USDHC1_CLK_ROOT 198000000UL /* Clock consumers of USDHC1_CLK_ROOT output : USDHC1 */
#define BOARD_BOOTCLOCKRUN_USDHC2_CLK_ROOT 198000000UL /* Clock consumers of USDHC2_CLK_ROOT output : USDHC2 */
/*! @brief Arm PLL set for BOARD_BootClockRUN configuration.
*/
extern const clock_arm_pll_config_t armPllConfig_BOARD_BootClockRUN;
/*! @brief Usb1 PLL set for BOARD_BootClockRUN configuration.
*/
extern const clock_usb_pll_config_t usb1PllConfig_BOARD_BootClockRUN;
/*! @brief Sys PLL for BOARD_BootClockRUN configuration.
*/
extern const clock_sys_pll_config_t sysPllConfig_BOARD_BootClockRUN;
/*! @brief Video PLL set for BOARD_BootClockRUN configuration.
*/
extern const clock_video_pll_config_t videoPllConfig_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*/
/*******************************************************************************
******************* Configuration BOARD_BootClockRUN_528M *********************
******************************************************************************/
/*******************************************************************************
* Definitions for BOARD_BootClockRUN_528M configuration
******************************************************************************/
#define BOARD_BOOTCLOCKRUN_528M_CORE_CLOCK 528000000U /*!< Core clock frequency: 528000000Hz */
/* Clock outputs (values are in Hz): */
#define BOARD_BOOTCLOCKRUN_528M_AHB_CLK_ROOT 528000000UL /* Clock consumers of AHB_CLK_ROOT output : AIPSTZ1, AIPSTZ2, AIPSTZ3, AIPSTZ4, ARM, FLEXIO3, FLEXSPI, FLEXSPI2, GPIO6, GPIO7, GPIO8, GPIO9 */
#define BOARD_BOOTCLOCKRUN_528M_CAN_CLK_ROOT 40000000UL /* Clock consumers of CAN_CLK_ROOT output : CAN1, CAN2, CAN3 */
#define BOARD_BOOTCLOCKRUN_528M_CKIL_SYNC_CLK_ROOT 32768UL /* Clock consumers of CKIL_SYNC_CLK_ROOT output : CSU, EWM, GPT1, GPT2, KPP, PIT, RTWDOG, SNVS, SPDIF, TEMPMON, TSC, USB1, USB2, WDOG1, WDOG2 */
#define BOARD_BOOTCLOCKRUN_528M_CLKO1_CLK 0UL /* Clock consumers of CLKO1_CLK output : N/A */
#define BOARD_BOOTCLOCKRUN_528M_CLKO2_CLK 0UL /* Clock consumers of CLKO2_CLK output : N/A */
#define BOARD_BOOTCLOCKRUN_528M_CLK_1M 1000000UL /* Clock consumers of CLK_1M output : EWM, RTWDOG */
#define BOARD_BOOTCLOCKRUN_528M_CLK_24M 24000000UL /* Clock consumers of CLK_24M output : GPT1, GPT2 */
#define BOARD_BOOTCLOCKRUN_528M_CSI_CLK_ROOT 12000000UL /* Clock consumers of CSI_CLK_ROOT output : CSI */
#define BOARD_BOOTCLOCKRUN_528M_ENET2_125M_CLK 1200000UL /* Clock consumers of ENET2_125M_CLK output : N/A */
#define BOARD_BOOTCLOCKRUN_528M_ENET2_REF_CLK 0UL /* Clock consumers of ENET2_REF_CLK output : ENET2 */
#define BOARD_BOOTCLOCKRUN_528M_ENET2_TX_CLK 0UL /* Clock consumers of ENET2_TX_CLK output : ENET2 */
#define BOARD_BOOTCLOCKRUN_528M_ENET_125M_CLK 2400000UL /* Clock consumers of ENET_125M_CLK output : N/A */
#define BOARD_BOOTCLOCKRUN_528M_ENET_25M_REF_CLK 1200000UL /* Clock consumers of ENET_25M_REF_CLK output : ENET, ENET2 */
#define BOARD_BOOTCLOCKRUN_528M_ENET_REF_CLK 0UL /* Clock consumers of ENET_REF_CLK output : ENET */
#define BOARD_BOOTCLOCKRUN_528M_ENET_TX_CLK 0UL /* Clock consumers of ENET_TX_CLK output : ENET */
#define BOARD_BOOTCLOCKRUN_528M_FLEXIO1_CLK_ROOT 30000000UL /* Clock consumers of FLEXIO1_CLK_ROOT output : FLEXIO1 */
#define BOARD_BOOTCLOCKRUN_528M_FLEXIO2_CLK_ROOT 30000000UL /* Clock consumers of FLEXIO2_CLK_ROOT output : FLEXIO2, FLEXIO3 */
#define BOARD_BOOTCLOCKRUN_528M_FLEXSPI2_CLK_ROOT 130909090UL /* Clock consumers of FLEXSPI2_CLK_ROOT output : FLEXSPI2 */
#define BOARD_BOOTCLOCKRUN_528M_FLEXSPI_CLK_ROOT 130909090UL /* Clock consumers of FLEXSPI_CLK_ROOT output : FLEXSPI */
#define BOARD_BOOTCLOCKRUN_528M_GPT1_IPG_CLK_HIGHFREQ 66000000UL /* Clock consumers of GPT1_ipg_clk_highfreq output : GPT1 */
#define BOARD_BOOTCLOCKRUN_528M_GPT2_IPG_CLK_HIGHFREQ 66000000UL /* Clock consumers of GPT2_ipg_clk_highfreq output : GPT2 */
#define BOARD_BOOTCLOCKRUN_528M_IPG_CLK_ROOT 132000000UL /* Clock consumers of IPG_CLK_ROOT output : ADC1, ADC2, ADC_ETC, AOI1, AOI2, ARM, BEE, CAN1, CAN2, CAN3, CCM, CMP1, CMP2, CMP3, CMP4, CSI, CSU, DCDC, DCP, DMA0, DMAMUX, ENC1, ENC2, ENC3, ENC4, ENET, ENET2, EWM, FLEXIO1, FLEXIO2, FLEXIO3, FLEXRAM, FLEXSPI, FLEXSPI2, GPC, GPIO1, GPIO10, GPIO2, GPIO3, GPIO4, GPIO5, IOMUXC, KPP, LCDIF, LPI2C1, LPI2C2, LPI2C3, LPI2C4, LPSPI1, LPSPI2, LPSPI3, LPSPI4, LPUART1, LPUART2, LPUART3, LPUART4, LPUART5, LPUART6, LPUART7, LPUART8, NVIC, OCOTP, PMU, PWM1, PWM2, PWM3, PWM4, PXP, ROMC, RTWDOG, SAI1, SAI2, SAI3, SNVS, SPDIF, SRC, TEMPMON, TMR1, TMR2, TMR3, TMR4, TRNG, TSC, USB1, USB2, USDHC1, USDHC2, WDOG1, WDOG2, XBARA1, XBARB2, XBARB3 */
#define BOARD_BOOTCLOCKRUN_528M_LCDIF_CLK_ROOT 67500000UL /* Clock consumers of LCDIF_CLK_ROOT output : LCDIF */
#define BOARD_BOOTCLOCKRUN_528M_LPI2C_CLK_ROOT 60000000UL /* Clock consumers of LPI2C_CLK_ROOT output : LPI2C1, LPI2C2, LPI2C3, LPI2C4 */
#define BOARD_BOOTCLOCKRUN_528M_LPSPI_CLK_ROOT 105600000UL /* Clock consumers of LPSPI_CLK_ROOT output : LPSPI1, LPSPI2, LPSPI3, LPSPI4 */
#define BOARD_BOOTCLOCKRUN_528M_LVDS1_CLK 1200000000UL /* Clock consumers of LVDS1_CLK output : N/A */
#define BOARD_BOOTCLOCKRUN_528M_MQS_MCLK 63529411UL /* Clock consumers of MQS_MCLK output : N/A */
#define BOARD_BOOTCLOCKRUN_528M_PERCLK_CLK_ROOT 66000000UL /* Clock consumers of PERCLK_CLK_ROOT output : GPT1, GPT2, PIT */
#define BOARD_BOOTCLOCKRUN_528M_PLL7_MAIN_CLK 24000000UL /* Clock consumers of PLL7_MAIN_CLK output : N/A */
#define BOARD_BOOTCLOCKRUN_528M_SAI1_CLK_ROOT 63529411UL /* Clock consumers of SAI1_CLK_ROOT output : N/A */
#define BOARD_BOOTCLOCKRUN_528M_SAI1_MCLK1 63529411UL /* Clock consumers of SAI1_MCLK1 output : SAI1 */
#define BOARD_BOOTCLOCKRUN_528M_SAI1_MCLK2 63529411UL /* Clock consumers of SAI1_MCLK2 output : SAI1 */
#define BOARD_BOOTCLOCKRUN_528M_SAI1_MCLK3 30000000UL /* Clock consumers of SAI1_MCLK3 output : SAI1 */
#define BOARD_BOOTCLOCKRUN_528M_SAI2_CLK_ROOT 63529411UL /* Clock consumers of SAI2_CLK_ROOT output : N/A */
#define BOARD_BOOTCLOCKRUN_528M_SAI2_MCLK1 63529411UL /* Clock consumers of SAI2_MCLK1 output : SAI2 */
#define BOARD_BOOTCLOCKRUN_528M_SAI2_MCLK2 0UL /* Clock consumers of SAI2_MCLK2 output : SAI2 */
#define BOARD_BOOTCLOCKRUN_528M_SAI2_MCLK3 30000000UL /* Clock consumers of SAI2_MCLK3 output : SAI2 */
#define BOARD_BOOTCLOCKRUN_528M_SAI3_CLK_ROOT 63529411UL /* Clock consumers of SAI3_CLK_ROOT output : N/A */
#define BOARD_BOOTCLOCKRUN_528M_SAI3_MCLK1 63529411UL /* Clock consumers of SAI3_MCLK1 output : SAI3 */
#define BOARD_BOOTCLOCKRUN_528M_SAI3_MCLK2 0UL /* Clock consumers of SAI3_MCLK2 output : SAI3 */
#define BOARD_BOOTCLOCKRUN_528M_SAI3_MCLK3 30000000UL /* Clock consumers of SAI3_MCLK3 output : SAI3 */
#define BOARD_BOOTCLOCKRUN_528M_SEMC_CLK_ROOT 66000000UL /* Clock consumers of SEMC_CLK_ROOT output : SEMC */
#define BOARD_BOOTCLOCKRUN_528M_SPDIF0_CLK_ROOT 30000000UL /* Clock consumers of SPDIF0_CLK_ROOT output : SPDIF */
#define BOARD_BOOTCLOCKRUN_528M_SPDIF0_EXTCLK_OUT 0UL /* Clock consumers of SPDIF0_EXTCLK_OUT output : SPDIF */
#define BOARD_BOOTCLOCKRUN_528M_TRACE_CLK_ROOT 132000000UL /* Clock consumers of TRACE_CLK_ROOT output : ARM */
#define BOARD_BOOTCLOCKRUN_528M_UART_CLK_ROOT 80000000UL /* Clock consumers of UART_CLK_ROOT output : LPUART1, LPUART2, LPUART3, LPUART4, LPUART5, LPUART6, LPUART7, LPUART8 */
#define BOARD_BOOTCLOCKRUN_528M_USBPHY1_CLK 0UL /* Clock consumers of USBPHY1_CLK output : TEMPMON, USB1 */
#define BOARD_BOOTCLOCKRUN_528M_USBPHY2_CLK 0UL /* Clock consumers of USBPHY2_CLK output : USB2 */
#define BOARD_BOOTCLOCKRUN_528M_USDHC1_CLK_ROOT 198000000UL /* Clock consumers of USDHC1_CLK_ROOT output : USDHC1 */
#define BOARD_BOOTCLOCKRUN_528M_USDHC2_CLK_ROOT 198000000UL /* Clock consumers of USDHC2_CLK_ROOT output : USDHC2 */
/*! @brief Arm PLL set for BOARD_BootClockRUN_528M configuration.
*/
extern const clock_arm_pll_config_t armPllConfig_BOARD_BootClockRUN_528M;
/*! @brief Usb1 PLL set for BOARD_BootClockRUN_528M configuration.
*/
extern const clock_usb_pll_config_t usb1PllConfig_BOARD_BootClockRUN_528M;
/*! @brief Sys PLL for BOARD_BootClockRUN_528M configuration.
*/
extern const clock_sys_pll_config_t sysPllConfig_BOARD_BootClockRUN_528M;
/*! @brief Video PLL set for BOARD_BootClockRUN_528M configuration.
*/
extern const clock_video_pll_config_t videoPllConfig_BOARD_BootClockRUN_528M;
/*******************************************************************************
* API for BOARD_BootClockRUN_528M configuration
******************************************************************************/
#if defined(__cplusplus)
extern "C" {
#endif /* __cplusplus*/
/*!
* @brief This function executes configuration of clocks.
*
*/
void BOARD_BootClockRUN_528M(void);
#if defined(__cplusplus)
}
#endif /* __cplusplus*/
#endif /* _CLOCK_CONFIG_H_ */

View File

@ -0,0 +1,31 @@
/**
* @file connect_uart.h
* @brief define rt1062xb usart function and struct
* @version 2.0
* @author AIIT XUOS Lab
* @date 2025-05-23
*/
#ifndef CONNECT_UART_H
#define CONNECT_UART_H
#include <device.h>
#include "fsl_common.h"
#include "MIMXRT1062_COMMON.h"
#include "fsl_lpuart.h"
#ifdef __cplusplus
extern "C"
{
#endif
#define KERNEL_CONSOLE_BUS_NAME SERIAL_BUS_NAME_1
#define KERNEL_CONSOLE_DRV_NAME SERIAL_DRV_NAME_1
#define KERNEL_CONSOLE_DEVICE_NAME SERIAL_1_DEVICE_NAME_0
int HwUsartInit(void);
#ifdef __cplusplus
}
#endif
#endif

View File

@ -0,0 +1,463 @@
/*
* Copyright 2016-2021 NXP
* All rights reserved.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#ifndef FSL_CACHE_H_
#define FSL_CACHE_H_
#include "fsl_common.h"
/*!
* @addtogroup cache_armv7_m7
* @{
*/
/*******************************************************************************
* Definitions
******************************************************************************/
/*! @name Driver version */
/*! @{ */
/*! @brief cache driver version 2.0.4. */
#define FSL_CACHE_DRIVER_VERSION (MAKE_VERSION(2, 0, 4))
/*! @} */
#if defined(FSL_FEATURE_SOC_L2CACHEC_COUNT) && FSL_FEATURE_SOC_L2CACHEC_COUNT
#ifndef FSL_SDK_DISBLE_L2CACHE_PRESENT
#define FSL_SDK_DISBLE_L2CACHE_PRESENT 0
#endif
#endif /* FSL_FEATURE_SOC_L2CACHEC_COUNT */
/*******************************************************************************
* Definitions
******************************************************************************/
#if defined(FSL_FEATURE_SOC_L2CACHEC_COUNT) && FSL_FEATURE_SOC_L2CACHEC_COUNT
/*! @brief Number of level 2 cache controller ways. */
typedef enum _l2cache_way_num
{
kL2CACHE_8ways = 0, /*!< 8 ways. */
#if defined(FSL_FEATURE_L2CACHE_SUPPORT_16_WAY_ASSOCIATIVITY) && FSL_FEATURE_L2CACHE_SUPPORT_16_WAY_ASSOCIATIVITY
kL2CACHE_16ways /*!< 16 ways. */
#endif /* FSL_FEATURE_L2CACHE_SUPPORT_16_WAY_ASSOCIATIVITY */
} l2cache_way_num_t;
/*! @brief Level 2 cache controller way size. */
typedef enum _l2cache_way_size
{
kL2CACHE_16KBSize = 1, /*!< 16 KB way size. */
kL2CACHE_32KBSize = 2, /*!< 32 KB way size. */
kL2CACHE_64KBSize = 3, /*!< 64 KB way size. */
kL2CACHE_128KBSize = 4, /*!< 128 KB way size. */
kL2CACHE_256KBSize = 5, /*!< 256 KB way size. */
kL2CACHE_512KBSize = 6 /*!< 512 KB way size. */
} l2cache_way_size;
/*! @brief Level 2 cache controller replacement policy. */
typedef enum _l2cache_replacement
{
kL2CACHE_Pseudorandom = 0U, /*!< Peseudo-random replacement policy using an lfsr. */
kL2CACHE_Roundrobin /*!< Round-robin replacemnt policy. */
} l2cache_replacement_t;
/*! @brief Level 2 cache controller force write allocate options. */
typedef enum _l2cache_writealloc
{
kL2CACHE_UseAwcache = 0, /*!< Use AWCAHE attribute for the write allocate. */
kL2CACHE_NoWriteallocate, /*!< Force no write allocate. */
kL2CACHE_forceWriteallocate /*!< Force write allocate when write misses. */
} l2cache_writealloc_t;
/*! @brief Level 2 cache controller tag/data ram latency. */
typedef enum _l2cache_latency
{
kL2CACHE_1CycleLate = 0, /*!< 1 cycle of latency. */
kL2CACHE_2CycleLate, /*!< 2 cycle of latency. */
kL2CACHE_3CycleLate, /*!< 3 cycle of latency. */
kL2CACHE_4CycleLate, /*!< 4 cycle of latency. */
kL2CACHE_5CycleLate, /*!< 5 cycle of latency. */
kL2CACHE_6CycleLate, /*!< 6 cycle of latency. */
kL2CACHE_7CycleLate, /*!< 7 cycle of latency. */
kL2CACHE_8CycleLate /*!< 8 cycle of latency. */
} l2cache_latency_t;
/*! @brief Level 2 cache controller tag/data ram latency configure structure. */
typedef struct _l2cache_latency_config
{
l2cache_latency_t tagWriteLate; /*!< Tag write latency. */
l2cache_latency_t tagReadLate; /*!< Tag Read latency. */
l2cache_latency_t tagSetupLate; /*!< Tag setup latency. */
l2cache_latency_t dataWriteLate; /*!< Data write latency. */
l2cache_latency_t dataReadLate; /*!< Data Read latency. */
l2cache_latency_t dataSetupLate; /*!< Data setup latency. */
} L2cache_latency_config_t;
/*! @brief Level 2 cache controller configure structure. */
typedef struct _l2cache_config
{
/* ------------------------ l2 cachec basic settings ---------------------------- */
l2cache_way_num_t wayNum; /*!< The number of ways. */
l2cache_way_size waySize; /*!< The way size = Cache Ram size / wayNum. */
l2cache_replacement_t repacePolicy; /*!< Replacemnet policy. */
/* ------------------------ tag/data ram latency settings ----------------------- */
L2cache_latency_config_t *lateConfig; /*!< Tag/data latency configure. Set NUll if not required. */
/* ------------------------ Prefetch enable settings ---------------------------- */
bool istrPrefetchEnable; /*!< Instruction prefetch enable. */
bool dataPrefetchEnable; /*!< Data prefetch enable. */
/* ------------------------ Non-secure access settings -------------------------- */
bool nsLockdownEnable; /*!< None-secure lockdown enable. */
/* ------------------------ other settings -------------------------------------- */
l2cache_writealloc_t writeAlloc; /*!< Write allcoate force option. */
} l2cache_config_t;
#endif /* FSL_FEATURE_SOC_L2CACHEC_COUNT */
/*******************************************************************************
* API
******************************************************************************/
#if defined(__cplusplus)
extern "C" {
#endif
/*!
* @name Control for cortex-m7 L1 cache
*@{
*/
/*!
* @brief Enables cortex-m7 L1 instruction cache.
*
*/
static inline void L1CACHE_EnableICache(void)
{
SCB_EnableICache();
}
/*!
* @brief Disables cortex-m7 L1 instruction cache.
*
*/
static inline void L1CACHE_DisableICache(void)
{
if (SCB_CCR_IC_Msk == (SCB_CCR_IC_Msk & SCB->CCR))
{
SCB_DisableICache();
}
}
/*!
* @brief Invalidate cortex-m7 L1 instruction cache.
*
*/
static inline void L1CACHE_InvalidateICache(void)
{
SCB_InvalidateICache();
}
/*!
* @brief Invalidate cortex-m7 L1 instruction cache by range.
*
* @param address The start address of the memory to be invalidated.
* @param size_byte The memory size.
* @note The start address and size_byte should be 32-byte(FSL_FEATURE_L1ICACHE_LINESIZE_BYTE) aligned.
* The startAddr here will be forced to align to L1 I-cache line size if
* startAddr is not aligned. For the size_byte, application should make sure the
* alignment or make sure the right operation order if the size_byte is not aligned.
*/
void L1CACHE_InvalidateICacheByRange(uint32_t address, uint32_t size_byte);
/*!
* @brief Enables cortex-m7 L1 data cache.
*
*/
static inline void L1CACHE_EnableDCache(void)
{
SCB_EnableDCache();
}
/*!
* @brief Disables cortex-m7 L1 data cache.
*
*/
static inline void L1CACHE_DisableDCache(void)
{
if (SCB_CCR_DC_Msk == (SCB_CCR_DC_Msk & SCB->CCR))
{
SCB_DisableDCache();
}
}
/*!
* @brief Invalidates cortex-m7 L1 data cache.
*
*/
static inline void L1CACHE_InvalidateDCache(void)
{
SCB_InvalidateDCache();
}
/*!
* @brief Cleans cortex-m7 L1 data cache.
*
*/
static inline void L1CACHE_CleanDCache(void)
{
SCB_CleanDCache();
}
/*!
* @brief Cleans and Invalidates cortex-m7 L1 data cache.
*
*/
static inline void L1CACHE_CleanInvalidateDCache(void)
{
SCB_CleanInvalidateDCache();
}
/*!
* @brief Invalidates cortex-m7 L1 data cache by range.
*
* @param address The start address of the memory to be invalidated.
* @param size_byte The memory size.
* @note The start address and size_byte should be 32-byte(FSL_FEATURE_L1DCACHE_LINESIZE_BYTE) aligned.
* The startAddr here will be forced to align to L1 D-cache line size if
* startAddr is not aligned. For the size_byte, application should make sure the
* alignment or make sure the right operation order if the size_byte is not aligned.
*/
static inline void L1CACHE_InvalidateDCacheByRange(uint32_t address, uint32_t size_byte)
{
SCB_InvalidateDCache_by_Addr((uint32_t *)address, (int32_t)size_byte);
}
/*!
* @brief Cleans cortex-m7 L1 data cache by range.
*
* @param address The start address of the memory to be cleaned.
* @param size_byte The memory size.
* @note The start address and size_byte should be 32-byte(FSL_FEATURE_L1DCACHE_LINESIZE_BYTE) aligned.
* The startAddr here will be forced to align to L1 D-cache line size if
* startAddr is not aligned. For the size_byte, application should make sure the
* alignment or make sure the right operation order if the size_byte is not aligned.
*/
static inline void L1CACHE_CleanDCacheByRange(uint32_t address, uint32_t size_byte)
{
SCB_CleanDCache_by_Addr((uint32_t *)address, (int32_t)size_byte);
}
/*!
* @brief Cleans and Invalidates cortex-m7 L1 data cache by range.
*
* @param address The start address of the memory to be clean and invalidated.
* @param size_byte The memory size.
* @note The start address and size_byte should be 32-byte(FSL_FEATURE_L1DCACHE_LINESIZE_BYTE) aligned.
* The startAddr here will be forced to align to L1 D-cache line size if
* startAddr is not aligned. For the size_byte, application should make sure the
* alignment or make sure the right operation order if the size_byte is not aligned.
*/
static inline void L1CACHE_CleanInvalidateDCacheByRange(uint32_t address, uint32_t size_byte)
{
SCB_CleanInvalidateDCache_by_Addr((uint32_t *)address, (int32_t)size_byte);
}
/*! @} */
#if defined(FSL_FEATURE_SOC_L2CACHEC_COUNT) && FSL_FEATURE_SOC_L2CACHEC_COUNT
/*!
* @name Control for L2 pl310 cache
*@{
*/
/*!
* @brief Initializes the level 2 cache controller module.
*
* @param config Pointer to configuration structure. See "l2cache_config_t".
*/
void L2CACHE_Init(l2cache_config_t *config);
/*!
* @brief Gets an available default settings for the cache controller.
*
* This function initializes the cache controller configuration structure with default settings.
* The default values are:
* @code
* config->waysNum = kL2CACHE_8ways;
* config->waySize = kL2CACHE_32KbSize;
* config->repacePolicy = kL2CACHE_Roundrobin;
* config->lateConfig = NULL;
* config->istrPrefetchEnable = false;
* config->dataPrefetchEnable = false;
* config->nsLockdownEnable = false;
* config->writeAlloc = kL2CACHE_UseAwcache;
* @endcode
* @param config Pointer to the configuration structure.
*/
void L2CACHE_GetDefaultConfig(l2cache_config_t *config);
/*!
* @brief Enables the level 2 cache controller.
* This function enables the cache controller. Must be written using a secure access.
* If write with a Non-secure access will cause a DECERR response.
*
*/
void L2CACHE_Enable(void);
/*!
* @brief Disables the level 2 cache controller.
* This function disables the cache controller. Must be written using a secure access.
* If write with a Non-secure access will cause a DECERR response.
*
*/
void L2CACHE_Disable(void);
/*!
* @brief Invalidates the Level 2 cache.
* This function invalidates all entries in cache.
*
*/
void L2CACHE_Invalidate(void);
/*!
* @brief Invalidates the Level 2 cache lines in the range of two physical addresses.
* This function invalidates all cache lines between two physical addresses.
*
* @param address The start address of the memory to be invalidated.
* @param size_byte The memory size.
* @note The start address and size_byte should be 32-byte(FSL_FEATURE_L2CACHE_LINESIZE_BYTE) aligned.
* The startAddr here will be forced to align to L2 line size if startAddr
* is not aligned. For the size_byte, application should make sure the
* alignment or make sure the right operation order if the size_byte is not aligned.
*/
void L2CACHE_InvalidateByRange(uint32_t address, uint32_t size_byte);
/*!
* @brief Cleans the level 2 cache controller.
* This function cleans all entries in the level 2 cache controller.
*
*/
void L2CACHE_Clean(void);
/*!
* @brief Cleans the Level 2 cache lines in the range of two physical addresses.
* This function cleans all cache lines between two physical addresses.
*
* @param address The start address of the memory to be cleaned.
* @param size_byte The memory size.
* @note The start address and size_byte should be 32-byte(FSL_FEATURE_L2CACHE_LINESIZE_BYTE) aligned.
* The startAddr here will be forced to align to L2 line size if startAddr
* is not aligned. For the size_byte, application should make sure the
* alignment or make sure the right operation order if the size_byte is not aligned.
*/
void L2CACHE_CleanByRange(uint32_t address, uint32_t size_byte);
/*!
* @brief Cleans and invalidates the level 2 cache controller.
* This function cleans and invalidates all entries in the level 2 cache controller.
*
*/
void L2CACHE_CleanInvalidate(void);
/*!
* @brief Cleans and invalidates the Level 2 cache lines in the range of two physical addresses.
* This function cleans and invalidates all cache lines between two physical addresses.
*
* @param address The start address of the memory to be cleaned and invalidated.
* @param size_byte The memory size.
* @note The start address and size_byte should be 32-byte(FSL_FEATURE_L2CACHE_LINESIZE_BYTE) aligned.
* The startAddr here will be forced to align to L2 line size if startAddr
* is not aligned. For the size_byte, application should make sure the
* alignment or make sure the right operation order if the size_byte is not aligned.
*/
void L2CACHE_CleanInvalidateByRange(uint32_t address, uint32_t size_byte);
/*!
* @brief Enables or disables to lock down the data and instruction by way.
* This function locks down the cached instruction/data by way and prevent the adresses from
* being allocated and prevent dara from being evicted out of the level 2 cache.
* But the normal cache maintenance operations that invalidate, clean or clean
* and validate cache contents affect the locked-down cache lines as normal.
*
* @param masterId The master id, range from 0 ~ 7.
* @param mask The ways to be enabled or disabled to lockdown.
* each bit in value is related to each way of the cache. for example:
* value: bit 0 ------ way 0.
* value: bit 1 ------ way 1.
* --------------------------
* value: bit 15 ------ way 15.
* Note: please make sure the value setting is align with your supported ways.
* @param enable True enable the lockdown, false to disable the lockdown.
*/
void L2CACHE_LockdownByWayEnable(uint32_t masterId, uint32_t mask, bool enable);
/*! @} */
#endif /* FSL_FEATURE_SOC_L2CACHEC_COUNT */
/*!
* @name Unified Cache Control for all caches (cortex-m7 L1 cache + l2 pl310)
* Mainly used for many drivers for easy cache operation.
*@{
*/
/*!
* @brief Invalidates all instruction caches by range.
*
* Both cortex-m7 L1 cache line and L2 PL310 cache line length is 32-byte.
*
* @param address The physical address.
* @param size_byte size of the memory to be invalidated.
* @note address and size should be aligned to cache line size
* 32-Byte due to the cache operation unit is one cache line. The startAddr here will be forced
* to align to the cache line size if startAddr is not aligned. For the size_byte, application should
* make sure the alignment or make sure the right operation order if the size_byte is not aligned.
*/
void ICACHE_InvalidateByRange(uint32_t address, uint32_t size_byte);
/*!
* @brief Invalidates all data caches by range.
*
* Both cortex-m7 L1 cache line and L2 PL310 cache line length is 32-byte.
*
* @param address The physical address.
* @param size_byte size of the memory to be invalidated.
* @note address and size should be aligned to cache line size
* 32-Byte due to the cache operation unit is one cache line. The startAddr here will be forced
* to align to the cache line size if startAddr is not aligned. For the size_byte, application should
* make sure the alignment or make sure the right operation order if the size_byte is not aligned.
*/
void DCACHE_InvalidateByRange(uint32_t address, uint32_t size_byte);
/*!
* @brief Cleans all data caches by range.
*
* Both cortex-m7 L1 cache line and L2 PL310 cache line length is 32-byte.
*
* @param address The physical address.
* @param size_byte size of the memory to be cleaned.
* @note address and size should be aligned to cache line size
* 32-Byte due to the cache operation unit is one cache line. The startAddr here will be forced
* to align to the cache line size if startAddr is not aligned. For the size_byte, application should
* make sure the alignment or make sure the right operation order if the size_byte is not aligned.
*/
void DCACHE_CleanByRange(uint32_t address, uint32_t size_byte);
/*!
* @brief Cleans and Invalidates all data caches by range.
*
* Both cortex-m7 L1 cache line and L2 PL310 cache line length is 32-byte.
*
* @param address The physical address.
* @param size_byte size of the memory to be cleaned and invalidated.
* @note address and size should be aligned to cache line size
* 32-Byte due to the cache operation unit is one cache line. The startAddr here will be forced
* to align to the cache line size if startAddr is not aligned. For the size_byte, application should
* make sure the alignment or make sure the right operation order if the size_byte is not aligned.
*/
void DCACHE_CleanInvalidateByRange(uint32_t address, uint32_t size_byte);
/*! @} */
#if defined(__cplusplus)
}
#endif
/*! @}*/
#endif /* FSL_CACHE_H_*/

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,352 @@
/*
* Copyright (c) 2015-2016, Freescale Semiconductor, Inc.
* Copyright 2016-2022,2024 NXP
* All rights reserved.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#ifndef FSL_COMMON_H_
#define FSL_COMMON_H_
#include <assert.h>
#include <stdbool.h>
#include <stdint.h>
#include <string.h>
#include <stdlib.h>
#if defined(__ICCARM__) || (defined(__CC_ARM) || defined(__ARMCC_VERSION)) || defined(__GNUC__)
#include <stddef.h>
#endif
#include "fsl_device_registers.h"
/*!
* @addtogroup ksdk_common
* @{
*/
/*******************************************************************************
* Configurations
******************************************************************************/
/*! @brief Macro to use the default weak IRQ handler in drivers. */
#ifndef FSL_DRIVER_TRANSFER_DOUBLE_WEAK_IRQ
#define FSL_DRIVER_TRANSFER_DOUBLE_WEAK_IRQ 1
#endif
/*******************************************************************************
* Definitions
******************************************************************************/
/*! @brief Construct a status code value from a group and code number. */
#define MAKE_STATUS(group, code) ((((group)*100L) + (code)))
/*! @brief Construct the version number for drivers.
*
* The driver version is a 32-bit number, for both 32-bit platforms(such as Cortex M)
* and 16-bit platforms(such as DSC).
*
* @verbatim
| Unused || Major Version || Minor Version || Bug Fix |
31 25 24 17 16 9 8 0
@endverbatim
*/
#define MAKE_VERSION(major, minor, bugfix) (((major)*65536L) + ((minor)*256L) + (bugfix))
/*! @name Driver version */
/*! @{ */
/*! @brief common driver version. */
#define FSL_COMMON_DRIVER_VERSION (MAKE_VERSION(2, 5, 0))
/*! @} */
/*! @name Debug console type definition. */
/*! @{ */
#define DEBUG_CONSOLE_DEVICE_TYPE_NONE 0U /*!< No debug console. */
#define DEBUG_CONSOLE_DEVICE_TYPE_UART 1U /*!< Debug console based on UART. */
#define DEBUG_CONSOLE_DEVICE_TYPE_LPUART 2U /*!< Debug console based on LPUART. */
#define DEBUG_CONSOLE_DEVICE_TYPE_LPSCI 3U /*!< Debug console based on LPSCI. */
#define DEBUG_CONSOLE_DEVICE_TYPE_USBCDC 4U /*!< Debug console based on USBCDC. */
#define DEBUG_CONSOLE_DEVICE_TYPE_FLEXCOMM 5U /*!< Debug console based on FLEXCOMM. */
#define DEBUG_CONSOLE_DEVICE_TYPE_IUART 6U /*!< Debug console based on i.MX UART. */
#define DEBUG_CONSOLE_DEVICE_TYPE_VUSART 7U /*!< Debug console based on LPC_VUSART. */
#define DEBUG_CONSOLE_DEVICE_TYPE_MINI_USART 8U /*!< Debug console based on LPC_USART. */
#define DEBUG_CONSOLE_DEVICE_TYPE_SWO 9U /*!< Debug console based on SWO. */
#define DEBUG_CONSOLE_DEVICE_TYPE_QSCI 10U /*!< Debug console based on QSCI. */
/*! @} */
/*! @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_PDM = 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_HASHCRYPT = 77, /*!< Group number for Hashcrypt status codes */
kStatusGroup_LPC_SPI_SSP = 78, /*!< Group number for LPC_SPI_SSP status codes. */
kStatusGroup_I3C = 79, /*!< Group number for I3C status codes */
kStatusGroup_LPC_I2C_1 = 97, /*!< Group number for LPC_I2C_1 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. */
kStatusGroup_IAP = 102, /*!< Group number for IAP status codes */
kStatusGroup_SFA = 103, /*!< Group number for SFA status codes*/
kStatusGroup_SPC = 104, /*!< Group number for SPC status codes. */
kStatusGroup_PUF = 105, /*!< Group number for PUF status codes. */
kStatusGroup_TOUCH_PANEL = 106, /*!< Group number for touch panel status codes */
kStatusGroup_VBAT = 107, /*!< Group number for VBAT status codes */
kStatusGroup_XSPI = 108, /*!< Group number for XSPI status codes */
kStatusGroup_PNGDEC = 109, /*!< Group number for PNGDEC status codes */
kStatusGroup_JPEGDEC = 110, /*!< Group number for JPEGDEC status codes */
kStatusGroup_HAL_GPIO = 121, /*!< Group number for HAL GPIO status codes. */
kStatusGroup_HAL_UART = 122, /*!< Group number for HAL UART status codes. */
kStatusGroup_HAL_TIMER = 123, /*!< Group number for HAL TIMER status codes. */
kStatusGroup_HAL_SPI = 124, /*!< Group number for HAL SPI status codes. */
kStatusGroup_HAL_I2C = 125, /*!< Group number for HAL I2C status codes. */
kStatusGroup_HAL_FLASH = 126, /*!< Group number for HAL FLASH status codes. */
kStatusGroup_HAL_PWM = 127, /*!< Group number for HAL PWM status codes. */
kStatusGroup_HAL_RNG = 128, /*!< Group number for HAL RNG status codes. */
kStatusGroup_HAL_I2S = 129, /*!< Group number for HAL I2S status codes. */
kStatusGroup_HAL_ADC_SENSOR = 130, /*!< Group number for HAL ADC SENSOR status codes. */
kStatusGroup_TIMERMANAGER = 135, /*!< Group number for TiMER MANAGER status codes. */
kStatusGroup_SERIALMANAGER = 136, /*!< Group number for SERIAL MANAGER status codes. */
kStatusGroup_LED = 137, /*!< Group number for LED status codes. */
kStatusGroup_BUTTON = 138, /*!< Group number for BUTTON status codes. */
kStatusGroup_EXTERN_EEPROM = 139, /*!< Group number for EXTERN EEPROM status codes. */
kStatusGroup_SHELL = 140, /*!< Group number for SHELL status codes. */
kStatusGroup_MEM_MANAGER = 141, /*!< Group number for MEM MANAGER status codes. */
kStatusGroup_LIST = 142, /*!< Group number for List status codes. */
kStatusGroup_OSA = 143, /*!< Group number for OSA status codes. */
kStatusGroup_COMMON_TASK = 144, /*!< Group number for Common task status codes. */
kStatusGroup_MSG = 145, /*!< Group number for messaging status codes. */
kStatusGroup_SDK_OCOTP = 146, /*!< Group number for OCOTP status codes. */
kStatusGroup_SDK_FLEXSPINOR = 147, /*!< Group number for FLEXSPINOR status codes.*/
kStatusGroup_CODEC = 148, /*!< Group number for codec status codes. */
kStatusGroup_ASRC = 149, /*!< Group number for codec status ASRC. */
kStatusGroup_OTFAD = 150, /*!< Group number for codec status codes. */
kStatusGroup_SDIOSLV = 151, /*!< Group number for SDIOSLV status codes. */
kStatusGroup_MECC = 152, /*!< Group number for MECC status codes. */
kStatusGroup_ENET_QOS = 153, /*!< Group number for ENET_QOS status codes. */
kStatusGroup_LOG = 154, /*!< Group number for LOG status codes. */
kStatusGroup_I3CBUS = 155, /*!< Group number for I3CBUS status codes. */
kStatusGroup_QSCI = 156, /*!< Group number for QSCI status codes. */
kStatusGroup_ELEMU = 157, /*!< Group number for ELEMU status codes. */
kStatusGroup_QUEUEDSPI = 158, /*!< Group number for QSPI status codes. */
kStatusGroup_POWER_MANAGER = 159, /*!< Group number for POWER_MANAGER status codes. */
kStatusGroup_IPED = 160, /*!< Group number for IPED status codes. */
kStatusGroup_ELS_PKC = 161, /*!< Group number for ELS PKC status codes. */
kStatusGroup_CSS_PKC = 162, /*!< Group number for CSS PKC status codes. */
kStatusGroup_HOSTIF = 163, /*!< Group number for HOSTIF status codes. */
kStatusGroup_CLIF = 164, /*!< Group number for CLIF status codes. */
kStatusGroup_BMA = 165, /*!< Group number for BMA status codes. */
kStatusGroup_NETC = 166, /*!< Group number for NETC status codes. */
kStatusGroup_ELE = 167, /*!< Group number for ELE status codes. */
kStatusGroup_GLIKEY = 168, /*!< Group number for GLIKEY status codes. */
kStatusGroup_AON_POWER = 169, /*!< Group number for AON_POWER status codes. */
kStatusGroup_AON_COMMON = 170, /*!< Group number for AON_COMMON status codes. */
kStatusGroup_ENDAT3 = 171, /*!< Group number for ENDAT3 status codes. */
kStatusGroup_HIPERFACE = 172, /*!< Group number for HIPERFACE status codes. */
kStatusGroup_NPX = 173, /*!< Group number for NPX status codes. */
};
/*! \public
* @brief Generic status return codes.
*/
enum
{
kStatus_Success = MAKE_STATUS(kStatusGroup_Generic, 0), /*!< Generic status for Success. */
kStatus_Fail = MAKE_STATUS(kStatusGroup_Generic, 1), /*!< Generic status for Fail. */
kStatus_ReadOnly = MAKE_STATUS(kStatusGroup_Generic, 2), /*!< Generic status for read only failure. */
kStatus_OutOfRange = MAKE_STATUS(kStatusGroup_Generic, 3), /*!< Generic status for out of range access. */
kStatus_InvalidArgument = MAKE_STATUS(kStatusGroup_Generic, 4), /*!< Generic status for invalid argument check. */
kStatus_Timeout = MAKE_STATUS(kStatusGroup_Generic, 5), /*!< Generic status for timeout. */
kStatus_NoTransferInProgress =
MAKE_STATUS(kStatusGroup_Generic, 6), /*!< Generic status for no transfer in progress. */
kStatus_Busy = MAKE_STATUS(kStatusGroup_Generic, 7), /*!< Generic status for module is busy. */
kStatus_NoData =
MAKE_STATUS(kStatusGroup_Generic, 8), /*!< Generic status for no data is found for the operation. */
};
/*! @brief Type used for all status and error return values. */
typedef int32_t status_t;
#ifdef __ZEPHYR__
#include <zephyr/sys/util.h>
#else
/*!
* @name Min/max macros
* @{
*/
#if !defined(MIN)
/*! Computes the minimum of \a a and \a b. */
#define MIN(a, b) (((a) < (b)) ? (a) : (b))
#endif
#if !defined(MAX)
/*! Computes the maximum of \a a and \a b. */
#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
#endif /* __ZEPHYR__ */
/*! @name UINT16_MAX/UINT32_MAX value */
/*! @{ */
#if !defined(UINT16_MAX)
/*! Max value of uint16_t type. */
#define UINT16_MAX ((uint16_t)-1)
#endif
#if !defined(UINT32_MAX)
/*! Max value of uint32_t type. */
#define UINT32_MAX ((uint32_t)-1)
#endif
/*! @} */
/*! Macro to get upper 32 bits of a 64-bit value */
#if !defined(UINT64_H)
#define UINT64_H(X) ((uint32_t)((((uint64_t) (X)) >> 32U) & 0x0FFFFFFFFULL))
#endif
/*! Macro to get lower 32 bits of a 64-bit value */
#if !defined(UINT64_L)
#define UINT64_L(X) ((uint32_t)(((uint64_t) (X)) & 0x0FFFFFFFFULL))
#endif
/*!
* @def SUPPRESS_FALL_THROUGH_WARNING()
*
* For switch case code block, if case section ends without "break;" statement, there wil be
* fallthrough warning with compiler flag -Wextra or -Wimplicit-fallthrough=n when using armgcc.
* To suppress this warning, "SUPPRESS_FALL_THROUGH_WARNING();" need to be added at the end of each
* case section which misses "break;"statement.
*/
#if defined(__GNUC__) && !defined(__ARMCC_VERSION)
#define SUPPRESS_FALL_THROUGH_WARNING() __attribute__((fallthrough))
#else
#define SUPPRESS_FALL_THROUGH_WARNING()
#endif
/*******************************************************************************
* API
******************************************************************************/
#if defined(__cplusplus)
extern "C" {
#endif
#if !((defined(__DSC__) && defined(__CW__)))
/*!
* @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);
#endif
/*!
* @brief Delay at least for some time.
* Please note that, this API uses while loop for delay, different run-time environments make the time not precise,
* if precise delay count was needed, please implement a new delay function with hardware timer.
*
* @param delayTime_us Delay time in unit of microsecond.
* @param coreClock_Hz Core clock frequency with Hz.
*/
void SDK_DelayAtLeastUs(uint32_t delayTime_us, uint32_t coreClock_Hz);
#if defined(__cplusplus)
}
#endif
/*! @} */
#if (defined(__DSC__) && defined(__CW__))
#include "fsl_common_dsc.h"
#elif defined(__XTENSA__)
#include "fsl_common_dsp.h"
#elif defined(__riscv)
#include "fsl_common_riscv.h"
#else
#include "fsl_common_arm.h"
#endif
#endif /* FSL_COMMON_H_ */

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,735 @@
/*
* Copyright 2017-2021, NXP
* All rights reserved.
*
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#ifndef FSL_DCDC_H__
#define FSL_DCDC_H__
#include "fsl_common.h"
/*!
* @addtogroup dcdc
* @{
*/
/*******************************************************************************
* Definitions
******************************************************************************/
/*! @brief DCDC driver version. */
#define FSL_DCDC_DRIVER_VERSION (MAKE_VERSION(2, 3, 0)) /*!< Version 2.3.0. */
/*!
* @brief DCDC status flags.
*/
enum _dcdc_status_flags_t
{
kDCDC_LockedOKStatus = (1U << 0U), /*!< Indicate DCDC status. 1'b1: DCDC already settled 1'b0: DCDC is settling. */
};
/*!
* @brief The current bias of low power comparator.
*/
typedef enum _dcdc_comparator_current_bias
{
kDCDC_ComparatorCurrentBias50nA = 0U, /*!< The current bias of low power comparator is 50nA. */
kDCDC_ComparatorCurrentBias100nA = 1U, /*!< The current bias of low power comparator is 100nA. */
kDCDC_ComparatorCurrentBias200nA = 2U, /*!< The current bias of low power comparator is 200nA. */
kDCDC_ComparatorCurrentBias400nA = 3U, /*!< The current bias of low power comparator is 400nA. */
} dcdc_comparator_current_bias_t;
/*!
* @brief The threshold of over current detection.
*/
typedef enum _dcdc_over_current_threshold
{
kDCDC_OverCurrentThresholdAlt0 = 0U, /*!< 1A in the run mode, 0.25A in the power save mode. */
kDCDC_OverCurrentThresholdAlt1 = 1U, /*!< 2A in the run mode, 0.25A in the power save mode. */
kDCDC_OverCurrentThresholdAlt2 = 2U, /*!< 1A in the run mode, 0.2A in the power save mode. */
kDCDC_OverCurrentThresholdAlt3 = 3U, /*!< 2A in the run mode, 0.2A in the power save mode. */
} dcdc_over_current_threshold_t;
/*!
* @brief The threshold if peak current detection.
*/
typedef enum _dcdc_peak_current_threshold
{
kDCDC_PeakCurrentThresholdAlt0 = 0U, /*!< 150mA peak current threshold. */
kDCDC_PeakCurrentThresholdAlt1 = 1U, /*!< 250mA peak current threshold. */
kDCDC_PeakCurrentThresholdAlt2 = 2U, /*!< 350mA peak current threshold. */
kDCDC_PeakCurrentThresholdAlt3 = 3U, /*!< 450mA peak current threshold. */
kDCDC_PeakCurrentThresholdAlt4 = 4U, /*!< 550mA peak current threshold. */
kDCDC_PeakCurrentThresholdAlt5 = 5U, /*!< 650mA peak current threshold. */
} dcdc_peak_current_threshold_t;
/*!
* @brief The period of counting the charging times in power save mode.
*/
typedef enum _dcdc_count_charging_time_period
{
kDCDC_CountChargingTimePeriod8Cycle = 0U, /*!< Eight 32k cycle. */
kDCDC_CountChargingTimePeriod16Cycle = 1U, /*!< Sixteen 32k cycle. */
} dcdc_count_charging_time_period_t;
/*!
* @brief The threshold of the counting number of charging times
*/
typedef enum _dcdc_count_charging_time_threshold
{
kDCDC_CountChargingTimeThreshold32 = 0U, /*!< 0x0: 32. */
kDCDC_CountChargingTimeThreshold64 = 1U, /*!< 0x1: 64. */
kDCDC_CountChargingTimeThreshold16 = 2U, /*!< 0x2: 16. */
kDCDC_CountChargingTimeThreshold8 = 3U, /*!< 0x3: 8. */
} dcdc_count_charging_time_threshold_t;
/*!
* @brief Oscillator clock option.
*/
typedef enum _dcdc_clock_source
{
kDCDC_ClockAutoSwitch = 0U, /*!< Automatic clock switch from internal oscillator to external clock. */
kDCDC_ClockInternalOsc = 1U, /*!< Use internal oscillator. */
kDCDC_ClockExternalOsc = 2U, /*!< Use external 24M crystal oscillator. */
} dcdc_clock_source_t;
#if (defined(FSL_FEATURE_DCDC_VDD_OUTPUT_COUNT) && (FSL_FEATURE_DCDC_VDD_OUTPUT_COUNT == 2))
/*!
* @brief Voltage output option.
*/
typedef enum _dcdc_voltage_output_sel
{
kDCDC_VoltageOutput1P8 = 0U, /*!< 1.8V output. */
kDCDC_VoltageOutput1P0 = 1U, /*!< 1.0V output. */
} dcdc_voltage_output_sel_t;
#endif /* FSL_FEATURE_DCDC_VDD_OUTPUT_COUNT */
#if defined(FSL_FEATURE_DCDC_HAS_CTRL_REG) && FSL_FEATURE_DCDC_HAS_CTRL_REG
/*!
* @brief DCDC low power modes.
*/
typedef enum _dcdc_low_power_mode
{
kDCDC_StandbyMode = 0U, /*!< Standby mode. */
kDCDC_LowPowerMode = 1U, /*!< Low power mode. */
kDCDC_GpcStandbyLowPowerMode = 2U, /*!< low power mode for GPC standby request. */
} dcdc_low_power_mode_t;
/*!
* @brief DCDC control mode.
*/
typedef enum _dcdc_control_mode
{
kDCDC_StaticControl = 0U, /*!< Static control. */
kDCDC_SetPointControl = 1U, /*!< Controlled by GPC set points. */
} dcdc_control_mode_t;
/*!
* @brief DCDC trim input mode.
*/
typedef enum _dcdc_trim_input_mode
{
kDCDC_SampleTrimInput = 0U, /*!< Sample trim input. */
kDCDC_HoldTrimInput = 1U, /*!< Hold trim input. */
} dcdc_trim_input_mode_t;
#if defined(DCDC_REG4_ENABLE_SP_MASK) && DCDC_REG4_ENABLE_SP_MASK
/*!
* @brief System setpoints enumeration.
*/
enum _dcdc_setpoint_map
{
kDCDC_SetPoint0 = 1UL << 0UL, /*!< Set point 0. */
kDCDC_SetPoint1 = 1UL << 1UL, /*!< Set point 1. */
kDCDC_SetPoint2 = 1UL << 2UL, /*!< Set point 2. */
kDCDC_SetPoint3 = 1UL << 3UL, /*!< Set point 3. */
kDCDC_SetPoint4 = 1UL << 4UL, /*!< Set point 4. */
kDCDC_SetPoint5 = 1UL << 5UL, /*!< Set point 5. */
kDCDC_SetPoint6 = 1UL << 6UL, /*!< Set point 6. */
kDCDC_SetPoint7 = 1UL << 7UL, /*!< Set point 7. */
kDCDC_SetPoint8 = 1UL << 8UL, /*!< Set point 8. */
kDCDC_SetPoint9 = 1UL << 9UL, /*!< Set point 9. */
kDCDC_SetPoint10 = 1UL << 10UL, /*!< Set point 10. */
kDCDC_SetPoint11 = 1UL << 11UL, /*!< Set point 11. */
kDCDC_SetPoint12 = 1UL << 12UL, /*!< Set point 12. */
kDCDC_SetPoint13 = 1UL << 13UL, /*!< Set point 13. */
kDCDC_SetPoint14 = 1UL << 14UL, /*!< Set point 14. */
kDCDC_SetPoint15 = 1UL << 15UL /*!< Set point 15. */
};
#endif /* DCDC_REG4_ENABLE_SP_MASK */
/*!
* @brief Configuration for DCDC.
*/
typedef struct _dcdc_config
{
dcdc_control_mode_t controlMode; /*!< DCDC control mode. */
dcdc_trim_input_mode_t trimInputMode; /*!< Hold trim input. */
bool enableDcdcTimeout; /*!< Enable internal count for DCDC_OK timeout. */
bool enableSwitchingConverterOutput; /*!< Enable the VDDIO switching converter output.*/
} dcdc_config_t;
#endif /* FSL_FEATURE_DCDC_HAS_CTRL_REGp */
/*!
* @brief Configuration for DCDC detection.
*/
typedef struct _dcdc_detection_config
{
bool enableXtalokDetection; /*!< Enable xtalok detection circuit. */
#if (defined(FSL_FEATURE_DCDC_VDD_OUTPUT_COUNT) && (FSL_FEATURE_DCDC_VDD_OUTPUT_COUNT == 2))
bool powerDownOverVoltageVdd1P8Detection; /*!< Power down over-voltage detection comparator for VDD1P8. */
bool powerDownOverVoltageVdd1P0Detection; /*!< Power down over-voltage detection comparator for VDD1P0. */
#else
bool powerDownOverVoltageDetection; /*!< Power down over-voltage detection comparator. */
#endif /* FSL_FEATURE_DCDC_VDD_OUTPUT_COUNT */
bool powerDownLowVlotageDetection; /*!< Power down low-voltage detection comparator. */
bool powerDownOverCurrentDetection; /*!< Power down over-current detection. */
bool powerDownPeakCurrentDetection; /*!< Power down peak-current detection. */
bool powerDownZeroCrossDetection; /*!< Power down the zero cross detection function for discontinuous conductor
mode. */
dcdc_over_current_threshold_t OverCurrentThreshold; /*!< The threshold of over current detection. */
dcdc_peak_current_threshold_t PeakCurrentThreshold; /*!< The threshold of peak current detection. */
} dcdc_detection_config_t;
/*!
* @brief Configuration for the loop control.
*/
typedef struct _dcdc_loop_control_config
{
bool enableCommonHysteresis; /*!< Enable hysteresis in switching converter common mode analog comparators.
This feature will improve transient supply ripple and efficiency. */
bool enableCommonThresholdDetection; /*!< Increase the threshold detection for common mode analog comparator. */
#if defined(FSL_FEATURE_DCDC_HAS_SWITCHING_CONVERTER_DIFFERENTIAL_MODE) && \
FSL_FEATURE_DCDC_HAS_SWITCHING_CONVERTER_DIFFERENTIAL_MODE
bool enableDifferentialHysteresis; /*!< Enable hysteresis in switching converter differential mode analog
comparators. This feature will improve transient supply ripple and
efficiency. */
bool enableDifferentialThresholdDetection; /*!< Increase the threshold detection for differential mode analog
comparators. */
#endif /* FSL_FEATURE_DCDC_HAS_SWITCHING_CONVERTER_DIFFERENTIAL_MODE */
bool enableInvertHysteresisSign; /*!< Invert the sign of the hysteresis in DC-DC analog comparators. */
bool enableRCThresholdDetection; /*!< Increase the threshold detection for RC scale circuit. */
uint32_t enableRCScaleCircuit; /*!< Available range is 0~7. Enable analog circuit of DC-DC converter to respond
faster under transient load conditions. */
uint32_t complementFeedForwardStep; /*!< Available range is 0~7. Two's complement feed forward step in duty cycle in
the switching DC-DC converter. Each time this field makes a transition from
0x0, the loop filter of the DC-DC converter is stepped once by a value
proportional to the change. This can be used to force a certain control loop
behavior, such as improving response under known heavy load transients. */
} dcdc_loop_control_config_t;
/*!
* @brief Configuration for DCDC low power.
*/
typedef struct _dcdc_low_power_config
{
#if !(defined(FSL_FEATURE_DCDC_HAS_NO_REG0_EN_LP_OVERLOAD_SNS) && FSL_FEATURE_DCDC_HAS_NO_REG0_EN_LP_OVERLOAD_SNS)
bool enableOverloadDetection; /*!< Enable the overload detection in power save mode, if current is larger than the
overloading threshold (typical value is 50 mA), DCDC will switch to the run mode
automatically. */
#endif /* FSL_FEATURE_DCDC_HAS_NO_REG0_EN_LP_OVERLOAD_SNS */
bool enableAdjustHystereticValue; /*!< Adjust hysteretic value in low power from 12.5mV to 25mV. */
dcdc_count_charging_time_period_t
countChargingTimePeriod; /*!< The period of counting the charging times in power save mode. */
dcdc_count_charging_time_threshold_t
countChargingTimeThreshold; /*!< the threshold of the counting number of charging times during
the period that lp_overload_freq_sel sets in power save mode. */
} dcdc_low_power_config_t;
/*!
* @brief Configuration for DCDC internal regulator.
*/
typedef struct _dcdc_internal_regulator_config
{
bool enableLoadResistor; /*!< control the load resistor of the internal regulator of DCDC, the load resistor is
connected as default "true", and need set to "false" to disconnect the load
resistor. */
uint32_t feedbackPoint; /*!< Available range is 0~3. Select the feedback point of the internal regulator. */
} dcdc_internal_regulator_config_t;
/*!
* @brief Configuration for min power setting.
*/
typedef struct _dcdc_min_power_config
{
bool enableUseHalfFreqForContinuous; /*!< Set DCDC clock to half frequency for the continuous mode. */
} dcdc_min_power_config_t;
#if defined(DCDC_REG4_ENABLE_SP_MASK) && DCDC_REG4_ENABLE_SP_MASK
/*!
* @brief DCDC configuration in set point mode.
*/
typedef struct _dcdc_setpoint_config
{
uint32_t enableDCDCMap; /*!< The setpoint map that enable the DCDC module. Should be the OR'ed value of @ref
_dcdc_setpoint_map. */
uint32_t enableDigLogicMap; /*!< The setpoint map that enable the DCDC dig logic. Should be the OR'ed value of @ref
_dcdc_setpoint_map. */
uint32_t lowpowerMap; /*!< The setpoint map that enable the DCDC Low powermode. Should be the OR'ed value of @ref
_dcdc_setpoint_map. */
uint32_t standbyMap; /*!< The setpoint map that enable the DCDC standby mode. Should be the OR'ed value of @ref
_dcdc_setpoint_map. */
uint32_t standbyLowpowerMap; /*!< The setpoint map that enable the DCDC low power mode, when the related setpoint is
in standby mode.
@ref _dcdc_setpoint_map. */
uint8_t *buckVDD1P8TargetVoltage; /*!< Point to the array that store the target voltage level of VDD1P8 in buck
mode. Note that the pointed array must have 16 elements. */
uint8_t *buckVDD1P0TargetVoltage; /*!< Point to the array that store the target voltage level of VDD1P0 in buck
mode. Note that the pointed array must have 16 elements. */
uint8_t *standbyVDD1P8TargetVoltage; /*!< Point to the array that store the target voltage level of VDD1P8 in
standby mode. Note that the pointed array must have 16 elements. */
uint8_t *standbyVDD1P0TargetVoltage; /*!< Point to the array that store the target voltage level of VDD1P0 in
standby mode. Note that the pointed array must have 16 elements. */
} dcdc_setpoint_config_t;
#endif /* DCDC_REG4_ENABLE_SP_MASK */
#if defined(__cplusplus)
extern "C" {
#endif
/*******************************************************************************
* API
******************************************************************************/
/*!
* @name Initialization and deinitialization
* @{
*/
#if defined(FSL_FEATURE_DCDC_HAS_CTRL_REG) && FSL_FEATURE_DCDC_HAS_CTRL_REG
/*!
* @brief Enable the access to DCDC registers.
*
* @param base DCDC peripheral base address.
* @param config Pointer to the configuration structure.
*/
void DCDC_Init(DCDC_Type *base, dcdc_config_t *config);
#else
/*!
* @brief Enable the access to DCDC registers.
*
* @param base DCDC peripheral base address.
*/
void DCDC_Init(DCDC_Type *base);
#endif /* FSL_FEATURE_DCDC_HAS_CTRL_REG */
/*!
* @brief Disable the access to DCDC registers.
*
* @param base DCDC peripheral base address.
*/
void DCDC_Deinit(DCDC_Type *base);
#if defined(FSL_FEATURE_DCDC_HAS_CTRL_REG) && FSL_FEATURE_DCDC_HAS_CTRL_REG
/*!
* brief Get the default setting for DCDC user configuration structure.
*
* This function initializes the user configuration structure to a default value. The default values are:
* code
* config->controlMode = kDCDC_StaticControl;
* config->trimInputMode = kDCDC_SampleTrimInput;
* config->enableDcdcTimeout = false;
* config->enableSwitchingConverterOutput = false;
* endcode
*
* param config Pointer to configuration structure. See to "dcdc_config_t"
*/
void DCDC_GetDefaultConfig(DCDC_Type *base, dcdc_config_t *config);
#endif /* FSL_FEATURE_DCDC_HAS_CTRL_REGp */
/*! @} */
/*!
* @name Status
* @{
*/
/*!
* @brief Get DCDC status flags.
*
* @param base peripheral base address.
* @return Mask of asserted status flags. See to "_dcdc_status_flags_t".
*/
uint32_t DCDC_GetstatusFlags(DCDC_Type *base);
/*! @} */
/*!
* @name Misc control
* @{
*/
#if defined(FSL_FEATURE_DCDC_HAS_CTRL_REG) && FSL_FEATURE_DCDC_HAS_CTRL_REG
/*!
* @brief Make DCDC enter into low power modes.
*
* @param base DCDC peripheral base address.
* @param mode DCDC low power mode selection. See to "_dcdc_low_power_mode"
*/
void DCDC_EnterLowPowerMode(DCDC_Type *base, dcdc_low_power_mode_t mode);
#endif /* FSL_FEATURE_DCDC_HAS_CTRL_REG */
/*!
* @brief Enable the output range comparator.
*
* The output range comparator is disabled by default.
*
* @param base DCDC peripheral base address.
* @param enable Enable the feature or not.
*/
static inline void DCDC_EnableOutputRangeComparator(DCDC_Type *base, bool enable)
{
if (enable)
{
base->REG0 &= ~DCDC_REG0_PWD_CMP_OFFSET_MASK;
}
else
{
base->REG0 |= DCDC_REG0_PWD_CMP_OFFSET_MASK;
}
}
/*!
* @brief Configure the DCDC clock source.
*
* @param base DCDC peripheral base address.
* @param clockSource Clock source for DCDC. See to "dcdc_clock_source_t".
*/
void DCDC_SetClockSource(DCDC_Type *base, dcdc_clock_source_t clockSource);
/*!
* @brief Get the default setting for detection configuration.
*
* The default configuration are set according to responding registers' setting when powered on.
* They are:
* @code
* config->enableXtalokDetection = false;
* config->powerDownOverVoltageDetection = true;
* config->powerDownLowVlotageDetection = false;
* config->powerDownOverCurrentDetection = true;
* config->powerDownPeakCurrentDetection = true;
* config->powerDownZeroCrossDetection = true;
* config->OverCurrentThreshold = kDCDC_OverCurrentThresholdAlt0;
* config->PeakCurrentThreshold = kDCDC_PeakCurrentThresholdAlt0;
* @endcode
*
* @param config Pointer to configuration structure. See to "dcdc_detection_config_t"
*/
void DCDC_GetDefaultDetectionConfig(dcdc_detection_config_t *config);
/*!
* @brief Configure the DCDC detection.
*
* @param base DCDC peripheral base address.
* @param config Pointer to configuration structure. See to "dcdc_detection_config_t"
*/
void DCDC_SetDetectionConfig(DCDC_Type *base, const dcdc_detection_config_t *config);
/*!
* @brief Get the default setting for low power configuration.
*
* The default configuration are set according to responding registers' setting when powered on.
* They are:
* @code
* config->enableOverloadDetection = true;
* config->enableAdjustHystereticValue = false;
* config->countChargingTimePeriod = kDCDC_CountChargingTimePeriod8Cycle;
* config->countChargingTimeThreshold = kDCDC_CountChargingTimeThreshold32;
* @endcode
*
* @param config Pointer to configuration structure. See to "dcdc_low_power_config_t"
*/
void DCDC_GetDefaultLowPowerConfig(dcdc_low_power_config_t *config);
/*!
* @brief Configure the DCDC low power.
*
* @param base DCDC peripheral base address.
* @param config Pointer to configuration structure. See to "dcdc_low_power_config_t".
*/
void DCDC_SetLowPowerConfig(DCDC_Type *base, const dcdc_low_power_config_t *config);
/*!
* @brief Reset current alert signal. Alert signal is generate by peak current detection.
*
* @param base DCDC peripheral base address.
* @param enable Switcher to reset signal. True means reset signal. False means don't reset signal.
*/
void DCDC_ResetCurrentAlertSignal(DCDC_Type *base, bool enable);
/*!
* @brief Set the bangap trim value to trim bandgap voltage.
*
* @param base DCDC peripheral base address.
* @param trimValue The bangap trim value. Available range is 0U-31U.
*/
static inline void DCDC_SetBandgapVoltageTrimValue(DCDC_Type *base, uint32_t trimValue)
{
base->REG1 &= ~DCDC_REG1_VBG_TRIM_MASK;
base->REG1 |= DCDC_REG1_VBG_TRIM(trimValue);
}
/*!
* @brief Get the default setting for loop control configuration.
*
* The default configuration are set according to responding registers' setting when powered on.
* They are:
* @code
* config->enableCommonHysteresis = false;
* config->enableCommonThresholdDetection = false;
* config->enableInvertHysteresisSign = false;
* config->enableRCThresholdDetection = false;
* config->enableRCScaleCircuit = 0U;
* config->complementFeedForwardStep = 0U;
* @endcode
*
* @param config Pointer to configuration structure. See to "dcdc_loop_control_config_t"
*/
void DCDC_GetDefaultLoopControlConfig(dcdc_loop_control_config_t *config);
/*!
* @brief Configure the DCDC loop control.
*
* @param base DCDC peripheral base address.
* @param config Pointer to configuration structure. See to "dcdc_loop_control_config_t".
*/
void DCDC_SetLoopControlConfig(DCDC_Type *base, const dcdc_loop_control_config_t *config);
/*!
* @brief Configure for the min power.
*
* @param base DCDC peripheral base address.
* @param config Pointer to configuration structure. See to "dcdc_min_power_config_t".
*/
void DCDC_SetMinPowerConfig(DCDC_Type *base, const dcdc_min_power_config_t *config);
/*!
* @brief Set the current bias of low power comparator.
*
* @param base DCDC peripheral base address.
* @param biasVaule The current bias of low power comparator. Refer to "dcdc_comparator_current_bias_t".
*/
static inline void DCDC_SetLPComparatorBiasValue(DCDC_Type *base, dcdc_comparator_current_bias_t biasVaule)
{
base->REG1 &= ~DCDC_REG1_LP_CMP_ISRC_SEL_MASK;
base->REG1 |= DCDC_REG1_LP_CMP_ISRC_SEL(biasVaule);
}
#if (defined(FSL_FEATURE_DCDC_VDD_OUTPUT_COUNT) && (FSL_FEATURE_DCDC_VDD_OUTPUT_COUNT == 2))
/*!
* @brief Lock VDD 1P0 target voltage.
*
* @param base DCDC peripheral base address.
*/
static inline void DCDC_LockVdd1p0TargetVoltage(DCDC_Type *base)
{
base->REG3 |= DCDC_REG3_VDD1P0CTRL_DISABLE_STEP_MASK;
}
/*!
* @brief Lock VDD 1P8 target voltage.
*
* @param base DCDC peripheral base address.
*/
static inline void DCDC_LockVdd1p8TargetVoltage(DCDC_Type *base)
{
base->REG3 |= DCDC_REG3_VDD1P8CTRL_DISABLE_STEP_MASK;
}
/*!
* @brief Adjust the target voltage of VDD_SOC in run mode and low power mode.
* @deprecated Do not use this function. It has been superceded by @ref DCDC_AdjustRunTargetVoltage
* and @ref DCDC_AdjustLowPowerTargetVoltage
*
* This function is to adjust the target voltage of DCDC output. Change them and finally wait until the output is
* stabled.
* Set the target value of run mode the same as low power mode before entering power save mode, because DCDC will switch
* back to run mode if it detects the current loading is larger than about 50 mA(typical value).
*
* @param base DCDC peripheral base address.
* @param VDDRun Target value in run mode. 25 mV each step from 0x00 to 0x1F. 00 is for 0.8V, 0x1F is for 1.575V.
* @param VDDStandby Target value in low power mode. 25 mV each step from 0x00 to 0x4. 00 is for 0.9V, 0x4 is for 1.0V.
* @param sel sel DCDC target voltage output selection. See to "_dcdc_voltage_output_sel".
*/
void DCDC_AdjustTargetVoltage(DCDC_Type *base, uint32_t VDDRun, uint32_t VDDStandby, dcdc_voltage_output_sel_t sel);
/*!
* @brief Adjust the target voltage of VDD_SOC in run mode.
*
* This function is to adjust the target voltage of DCDC output. Change them and finally wait until the output is
* stabled.
* Set the target value of run mode the same as low power mode before entering power save mode, because DCDC will switch
* back to run mode if it detects the current loading is larger than about 50 mA(typical value).
*
* @param base DCDC peripheral base address.
* @param VDDRun Target value in run mode. 25 mV each step from 0x00 to 0x1F. 00 is for 0.8V, 0x1F is for 1.575V.
* @param sel sel DCDC target voltage output selection. See to "_dcdc_voltage_output_sel".
*/
void DCDC_AdjustRunTargetVoltage(DCDC_Type *base, uint32_t VDDRun, dcdc_voltage_output_sel_t sel);
/*!
* @brief Adjust the target voltage of VDD_SOC in low power mode.
*
* This function is to adjust the target voltage of DCDC output. Change them and finally wait until the output is
* stabled.
* Set the target value of run mode the same as low power mode before entering power save mode, because DCDC will switch
* back to run mode if it detects the current loading is larger than about 50 mA(typical value).
*
* @param base DCDC peripheral base address.
* @param VDDStandby Target value in low power mode. 25 mV each step from 0x00 to 0x4. 00 is for 0.9V, 0x4 is for 1.0V.
* @param sel sel DCDC target voltage output selection. See to "_dcdc_voltage_output_sel".
*/
void DCDC_AdjustLowPowerTargetVoltage(DCDC_Type *base, uint32_t VDDStandby, dcdc_voltage_output_sel_t sel);
#else
/*!
* @brief Lock target voltage.
*
* @param base DCDC peripheral base address.
*/
static inline void DCDC_LockTargetVoltage(DCDC_Type *base)
{
base->REG3 |= DCDC_REG3_DISABLE_STEP_MASK;
}
/*!
* @brief Adjust the target voltage of VDD_SOC in run mode and low power mode.
* @deprecated Do not use this function. It has been superceded by @ref DCDC_AdjustRunTargetVoltage
* and @ref DCDC_AdjustLowPowerTargetVoltage
*
* This function is to adjust the target voltage of DCDC output. Change them and finally wait until the output is
* stabled.
* Set the target value of run mode the same as low power mode before entering power save mode, because DCDC will switch
* back to run mode if it detects the current loading is larger than about 50 mA(typical value).
*
* @param base DCDC peripheral base address.
* @param VDDRun Target value in run mode. 25 mV each step from 0x00 to 0x1F. 00 is for 0.8V, 0x1F is for 1.575V.
* @param VDDStandby Target value in low power mode. 25 mV each step from 0x00 to 0x4. 00 is for 0.9V, 0x4 is for 1.0V.
*/
void DCDC_AdjustTargetVoltage(DCDC_Type *base, uint32_t VDDRun, uint32_t VDDStandby);
/*!
* @brief Adjust the target voltage of VDD_SOC in run mode.
*
* This function is to adjust the target voltage of DCDC output. Change them and finally wait until the output is
* stabled.
* Set the target value of run mode the same as low power mode before entering power save mode, because DCDC will switch
* back to run mode if it detects the current loading is larger than about 50 mA(typical value).
*
* @param base DCDC peripheral base address.
* @param VDDRun Target value in run mode. 25 mV each step from 0x00 to 0x1F. 00 is for 0.8V, 0x1F is for 1.575V.
*/
void DCDC_AdjustRunTargetVoltage(DCDC_Type *base, uint32_t VDDRun);
/*!
* @brief Adjust the target voltage of VDD_SOC in low power mode.
*
* This function is to adjust the target voltage of DCDC output. Change them and finally wait until the output is
* stabled.
* Set the target value of run mode the same as low power mode before entering power save mode, because DCDC will switch
* back to run mode if it detects the current loading is larger than about 50 mA(typical value).
*
* @param base DCDC peripheral base address.
* @param VDDStandby Target value in low power mode. 25 mV each step from 0x00 to 0x4. 00 is for 0.9V, 0x4 is for 1.0V.
*/
void DCDC_AdjustLowPowerTargetVoltage(DCDC_Type *base, uint32_t VDDStandby);
#endif /* FSL_FEATURE_DCDC_VDD_OUTPUT_COUNT */
/*!
* @brief Configure the DCDC internal regulator.
*
* @param base DCDC peripheral base address.
* @param config Pointer to configuration structure. See to "dcdc_internal_regulator_config_t".
*/
void DCDC_SetInternalRegulatorConfig(DCDC_Type *base, const dcdc_internal_regulator_config_t *config);
/*!
* @brief Enable/Disable to improve the transition from heavy load to light load. It is valid while zero
* cross detection is enabled. If ouput exceeds the threshold, DCDC would return CCM from DCM.
*
* @param base DCDC peripheral base address.
* @param enable Enable the feature or not.
*/
static inline void DCDC_EnableImproveTransition(DCDC_Type *base, bool enable)
{
if (enable)
{
base->REG2 |= DCDC_REG2_DCM_SET_CTRL_MASK;
}
else
{
base->REG2 &= ~DCDC_REG2_DCM_SET_CTRL_MASK;
}
}
/*! @} */
#if defined(DCDC_REG4_ENABLE_SP_MASK) && DCDC_REG4_ENABLE_SP_MASK
/*!
* @name Setpoint mode APIs
*/
/*!
* @brief Init DCDC module when the control mode selected as setpoint mode.
*
* @note The function should be invoked in the initial step to config the
* DCDC via setpoint control mode.
*
* @param base DCDC peripheral base address.
* @param config The pointer to the structure @ref dcdc_setpoint_config_t.
*/
void DCDC_SetPointInit(DCDC_Type *base, const dcdc_setpoint_config_t *config);
/*!
* @brief Disable DCDC module when the control mode selected as setpoint mode.
*
* @param base DCDC peripheral base address.
* @param setpointMap. The map of the setpoint to disable the DCDC module.
* Should be the OR'ed value of _dcdc_setpoint_map.
*/
static inline void DCDC_SetPointDeinit(DCDC_Type *base, uint32_t setpointMap)
{
base->REG4 &= ~setpointMap;
}
/*! @} */
#endif /* DCDC_REG4_ENABLE_SP_MASK */
/*!
* @name Application guideline
* @{
*/
/*!
* @brief Boot DCDC into DCM(discontinous conduction mode).
*
* pwd_zcd=0x0;
* pwd_cmp_offset=0x0;
* dcdc_loopctrl_en_rcscale= 0x5;
* DCM_set_ctrl=1'b1;
*
* @param base DCDC peripheral base address.
*/
void DCDC_BootIntoDCM(DCDC_Type *base);
/*!
* @brief Boot DCDC into CCM(continous conduction mode).
*
* pwd_zcd=0x1;
* pwd_cmp_offset=0x0;
* dcdc_loopctrl_en_rcscale=0x3;
*
* @param base DCDC peripheral base address.
*/
void DCDC_BootIntoCCM(DCDC_Type *base);
/*! @} */
#if defined(__cplusplus)
}
#endif
/*! @} */
#endif /* FSL_DCDC_H__ */

View File

@ -0,0 +1,26 @@
/*
* Copyright 2014-2016 Freescale Semiconductor, Inc.
* Copyright 2016-2024 NXP
* SPDX-License-Identifier: BSD-3-Clause
*
*/
#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_MIMXRT1062CVJ5A) || defined(CPU_MIMXRT1062CVJ5B) || defined(CPU_MIMXRT1062CVL5A) || defined(CPU_MIMXRT1062CVL5B) || defined(CPU_MIMXRT1062DVJ6A) || defined(CPU_MIMXRT1062DVJ6B) || defined(CPU_MIMXRT1062DVL6A) || defined(CPU_MIMXRT1062DVL6B) || defined(CPU_MIMXRT1062DVN6B) || defined(CPU_MIMXRT1062XVN5B))
#include "MIMXRT1062.h"
#else
#error "No valid CPU defined!"
#endif
#endif /* __FSL_DEVICE_REGISTERS_H__ */
/*******************************************************************************
* EOF
******************************************************************************/

View File

@ -0,0 +1,231 @@
/*
* Copyright (c) 2016, Freescale Semiconductor, Inc.
* Copyright 2016-2019 NXP
* All rights reserved.
*
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#ifndef FSL_GPC_H_
#define FSL_GPC_H_
#include "fsl_common.h"
/*!
* @addtogroup gpc
* @{
*/
/*******************************************************************************
* Definitions
******************************************************************************/
/*! @name Driver version */
/*! @{ */
/*! @brief GPC driver version 2.1.1. */
#define FSL_GPC_DRIVER_VERSION (MAKE_VERSION(2, 1, 1))
/*! @} */
#if defined(__cplusplus)
extern "C" {
#endif
/*******************************************************************************
* API
******************************************************************************/
#if (defined(FSL_FEATURE_GPC_HAS_CNTR_GPCIRQM) && FSL_FEATURE_GPC_HAS_CNTR_GPCIRQM)
/*!
* @brief Allow all the IRQ/Events within the charge of GPC.
*
* @param base GPC peripheral base address.
*/
static inline void GPC_AllowIRQs(GPC_Type *base)
{
base->CNTR &= ~GPC_CNTR_GPCIRQM_MASK; /* Events would not be masked. */
}
/*!
* @brief Disallow all the IRQ/Events within the charge of GPC.
*
* @param base GPC peripheral base address.
*/
static inline void GPC_DisallowIRQs(GPC_Type *base)
{
base->CNTR |= GPC_CNTR_GPCIRQM_MASK; /* Mask all the events. */
}
#endif /* FSL_FEATURE_GPC_HAS_CNTR_GPCIRQM */
/*!
* @brief Enable the IRQ.
*
* @param base GPC peripheral base address.
* @param irqId ID number of IRQ to be enabled, available range is 32-159. 0-31 is available in some platforms.
*/
void GPC_EnableIRQ(GPC_Type *base, uint32_t irqId);
/*!
* @brief Disable the IRQ.
*
* @param base GPC peripheral base address.
* @param irqId ID number of IRQ to be disabled, available range is 32-159. 0-31 is available in some platforms.
*/
void GPC_DisableIRQ(GPC_Type *base, uint32_t irqId);
/*!
* @brief Get the IRQ/Event flag.
*
* @param base GPC peripheral base address.
* @param irqId ID number of IRQ to be enabled, available range is 32-159. 0-31 is available in some platforms.
* @return Indicated IRQ/Event is asserted or not.
*/
bool GPC_GetIRQStatusFlag(GPC_Type *base, uint32_t irqId);
#if (defined(FSL_FEATURE_GPC_HAS_CNTR_L2PGE) && FSL_FEATURE_GPC_HAS_CNTR_L2PGE)
/*!
* @brief L2 Cache Power Gate Enable
*
* This function configures the L2 cache if it will keep power when in low power mode.
* When the L2 cache power is OFF, L2 cache will be power down once when CPU core is power down
* and will be hardware invalidated automatically when CPU core is re-power up.
* When the L2 cache power is ON, L2 cache will keep power on even if CPU core is power down and
* will not be hardware invalidated.
* When CPU core is re-power up, the default setting is OFF.
*
* @param base GPC peripheral base address.
* @param enable Enable the request or not.
*/
static inline void GPC_RequestL2CachePowerDown(GPC_Type *base, bool enable)
{
if (enable)
{
base->CNTR |= GPC_CNTR_L2_PGE_MASK; /* OFF. */
}
else
{
base->CNTR &= ~GPC_CNTR_L2_PGE_MASK; /* ON. */
}
}
#endif /* FSL_FEATURE_GPC_HAS_CNTR_L2PGE */
#if (defined(FSL_FEATURE_GPC_HAS_CNTR_PDRAM0PGE) && FSL_FEATURE_GPC_HAS_CNTR_PDRAM0PGE)
/*!
* @brief FLEXRAM PDRAM0 Power Gate Enable
*
* This function configures the FLEXRAM PDRAM0 if it will keep power when cpu core is power down.
* When the PDRAM0 Power is 1, PDRAM0 will be power down once when CPU core is power down.
* When the PDRAM0 Power is 0, PDRAM0 will keep power on even if CPU core is power down.
* When CPU core is re-power up, the default setting is 1.
*
* @param base GPC peripheral base address.
* @param enable Enable the request or not.
*/
static inline void GPC_RequestPdram0PowerDown(GPC_Type *base, bool enable)
{
if (enable)
{
base->CNTR |= GPC_CNTR_PDRAM0_PGE_MASK; /* OFF. */
}
else
{
base->CNTR &= ~GPC_CNTR_PDRAM0_PGE_MASK; /* ON. */
}
}
#endif /* FSL_FEATURE_GPC_HAS_CNTR_PDRAM0PGE */
#if (defined(FSL_FEATURE_GPC_HAS_CNTR_VADC) && FSL_FEATURE_GPC_HAS_CNTR_VADC)
/*!
* @brief VADC power down.
*
* This function requests the VADC power down.
*
* @param base GPC peripheral base address.
* @param enable Enable the request or not.
*/
static inline void GPC_RequestVADCPowerDown(GPC_Type *base, bool enable)
{
if (enable)
{
base->CNTR &= ~GPC_CNTR_VADC_EXT_PWD_N_MASK; /* VADC power down. */
}
else
{
base->CNTR |= GPC_CNTR_VADC_EXT_PWD_N_MASK; /* VADC not power down. */
}
}
/*!
* @brief Checks if the VADC is power off.
*
* @param base GPC peripheral base address.
* @return Whether the VADC is power off or not.
*/
static inline bool GPC_GetVADCPowerDownFlag(GPC_Type *base)
{
return (GPC_CNTR_VADC_ANALOG_OFF_MASK == (GPC_CNTR_VADC_ANALOG_OFF_MASK & base->CNTR));
}
#endif /* FSL_FEATURE_GPC_HAS_CNTR_VADC */
#if (defined(FSL_FEATURE_GPC_HAS_CNTR_DVFS0CR) && FSL_FEATURE_GPC_HAS_CNTR_DVFS0CR)
/*!
* @brief Checks if the DVFS0 is requesting for frequency/voltage update.
*
* @param base GPC peripheral base address.
* @return Whether the DVFS0 is requesting for frequency/voltage update.
*/
static inline bool GPC_HasDVFS0ChangeRequest(GPC_Type *base)
{
return (GPC_CNTR_DVFS0CR_MASK == (GPC_CNTR_DVFS0CR_MASK & base->CNTR));
}
#endif /* FSL_FEATURE_GPC_HAS_CNTR_DVFS0CR */
#if (defined(FSL_FEATURE_GPC_HAS_CNTR_DISPLAY) && FSL_FEATURE_GPC_HAS_CNTR_DISPLAY)
/*!
* @brief Requests the display power switch sequence.
*
* @param base GPC peripheral base address.
* @param enable Enable the power on sequence, or the power down sequence.
*/
static inline void GPC_RequestDisplayPowerOn(GPC_Type *base, bool enable)
{
if (enable)
{
base->CNTR |= GPC_CNTR_DISPLAY_PUP_REQ_MASK; /* Power on sequence. */
}
else
{
base->CNTR |= GPC_CNTR_DISPLAY_PDN_REQ_MASK; /* Power down sequence. */
}
}
#endif /* FSL_FEATURE_GPC_HAS_CNTR_DISPLAY */
/*!
* @brief Requests the MEGA power switch sequence.
*
* @param base GPC peripheral base address.
* @param enable Enable the power on sequence, or the power down sequence.
*/
static inline void GPC_RequestMEGAPowerOn(GPC_Type *base, bool enable)
{
if (enable)
{
base->CNTR |= GPC_CNTR_MEGA_PUP_REQ_MASK; /* Power on sequence. */
}
else
{
base->CNTR |= GPC_CNTR_MEGA_PDN_REQ_MASK; /* Power down sequence. */
}
}
/*!
* @}
*/
#if defined(__cplusplus)
}
#endif
/*!
* @}
*/
#endif /* FSL_GPC_H_ */

View File

@ -0,0 +1,344 @@
/*
* Copyright (c) 2016, Freescale Semiconductor, Inc.
* Copyright 2016-2020 NXP
* All rights reserved.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#ifndef FSL_GPIO_H_
#define FSL_GPIO_H_
#include "fsl_common.h"
/*!
* @addtogroup gpio_driver
* @{
*/
/*******************************************************************************
* Definitions
******************************************************************************/
/*! @name Driver version */
/*! @{ */
/*! @brief GPIO driver version. */
#define FSL_GPIO_DRIVER_VERSION (MAKE_VERSION(2, 0, 6))
/*! @} */
/*! @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;
/*! @brief GPIO interrupt mode definition. */
typedef enum _gpio_interrupt_mode
{
kGPIO_NoIntmode = 0U, /*!< Set current pin general IO functionality.*/
kGPIO_IntLowLevel = 1U, /*!< Set current pin interrupt is low-level sensitive.*/
kGPIO_IntHighLevel = 2U, /*!< Set current pin interrupt is high-level sensitive.*/
kGPIO_IntRisingEdge = 3U, /*!< Set current pin interrupt is rising-edge sensitive.*/
kGPIO_IntFallingEdge = 4U, /*!< Set current pin interrupt is falling-edge sensitive.*/
kGPIO_IntRisingOrFallingEdge = 5U, /*!< Enable the edge select bit to override the ICR register's configuration.*/
} gpio_interrupt_mode_t;
/*! @brief GPIO Init structure definition. */
typedef struct _gpio_pin_config
{
gpio_pin_direction_t direction; /*!< Specifies the pin direction. */
uint8_t outputLogic; /*!< Set a default output logic, which has no use in input */
gpio_interrupt_mode_t
interruptMode; /*!< Specifies the pin interrupt mode, a value of @ref gpio_interrupt_mode_t. */
} gpio_pin_config_t;
/*******************************************************************************
* API
******************************************************************************/
#if defined(__cplusplus)
extern "C" {
#endif
/*!
* @name GPIO Initialization and Configuration functions
* @{
*/
/*!
* @brief Initializes the GPIO peripheral according to the specified
* parameters in the initConfig.
*
* @param base GPIO base pointer.
* @param pin Specifies the pin number
* @param Config pointer to a @ref gpio_pin_config_t structure that
* contains the configuration information.
*/
void GPIO_PinInit(GPIO_Type *base, uint32_t pin, const gpio_pin_config_t *Config);
/*! @} */
/*!
* @name GPIO Reads and Write Functions
* @{
*/
/*!
* @brief Sets the output level of the individual GPIO pin to logic 1 or 0.
*
* @param base GPIO base pointer.
* @param pin GPIO port pin number.
* @param output GPIOpin output logic level.
* - 0: corresponding pin output low-logic level.
* - 1: corresponding pin output high-logic level.
*/
void GPIO_PinWrite(GPIO_Type *base, uint32_t pin, uint8_t output);
/*!
* @brief Sets the output level of the individual GPIO pin to 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 (GPIO1, GPIO2, GPIO3, and so on.)
* @param mask GPIO pin number macro
*/
static inline void GPIO_PortSet(GPIO_Type *base, uint32_t mask)
{
#if (defined(FSL_FEATURE_IGPIO_HAS_DR_SET) && (FSL_FEATURE_IGPIO_HAS_DR_SET == 1))
base->DR_SET = mask;
#else
base->DR |= mask;
#endif /* FSL_FEATURE_IGPIO_HAS_DR_SET */
}
/*!
* @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 (GPIO1, GPIO2, GPIO3, and so on.)
* @param mask GPIO pin number macro
*/
static inline void GPIO_PortClear(GPIO_Type *base, uint32_t mask)
{
#if (defined(FSL_FEATURE_IGPIO_HAS_DR_CLEAR) && (FSL_FEATURE_IGPIO_HAS_DR_CLEAR == 1))
base->DR_CLEAR = mask;
#else
base->DR &= ~mask;
#endif /* FSL_FEATURE_IGPIO_HAS_DR_CLEAR */
}
/*!
* @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.
*/
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 (GPIO1, GPIO2, GPIO3, and so on.)
* @param mask GPIO pin number macro
*/
static inline void GPIO_PortToggle(GPIO_Type *base, uint32_t mask)
{
#if (defined(FSL_FEATURE_IGPIO_HAS_DR_TOGGLE) && (FSL_FEATURE_IGPIO_HAS_DR_TOGGLE == 1))
base->DR_TOGGLE = mask;
#else
base->DR ^= mask;
#endif /* FSL_FEATURE_IGPIO_HAS_DR_TOGGLE */
}
/*!
* @brief Reads the current input value of the GPIO port.
*
* @param base GPIO base pointer.
* @param pin GPIO port pin number.
* @retval GPIO port input value.
*/
static inline uint32_t GPIO_PinRead(GPIO_Type *base, uint32_t pin)
{
assert(pin < 32U);
return (((base->DR) >> pin) & 0x1U);
}
/*!
* @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 Reads Pad Status Functions
* @{
*/
/*!
* @brief Reads the current GPIO pin pad status.
*
* @param base GPIO base pointer.
* @param pin GPIO port pin number.
* @retval GPIO pin pad status value.
*/
static inline uint8_t GPIO_PinReadPadStatus(GPIO_Type *base, uint32_t pin)
{
assert(pin < 32U);
return (uint8_t)(((base->PSR) >> pin) & 0x1U);
}
/*!
* @brief Reads the current GPIO pin pad status.
* @deprecated Do not use this function. It has been superceded by @ref GPIO_PinReadPadStatus.
*/
static inline uint8_t GPIO_ReadPadStatus(GPIO_Type *base, uint32_t pin)
{
return GPIO_PinReadPadStatus(base, pin);
}
/*! @} */
/*!
* @name Interrupts and flags management functions
* @{
*/
/*!
* @brief Sets the current pin interrupt mode.
*
* @param base GPIO base pointer.
* @param pin GPIO port pin number.
* @param pinInterruptMode pointer to a @ref gpio_interrupt_mode_t structure
* that contains the interrupt mode information.
*/
void GPIO_PinSetInterruptConfig(GPIO_Type *base, uint32_t pin, gpio_interrupt_mode_t pinInterruptMode);
/*!
* @brief Sets the current pin interrupt mode.
* @deprecated Do not use this function. It has been superceded by @ref GPIO_PinSetInterruptConfig.
*/
static inline void GPIO_SetPinInterruptConfig(GPIO_Type *base, uint32_t pin, gpio_interrupt_mode_t pinInterruptMode)
{
GPIO_PinSetInterruptConfig(base, pin, pinInterruptMode);
}
/*!
* @brief Enables the specific pin interrupt.
*
* @param base GPIO base pointer.
* @param mask GPIO pin number macro.
*/
static inline void GPIO_PortEnableInterrupts(GPIO_Type *base, uint32_t mask)
{
base->IMR |= mask;
}
/*!
* @brief Enables the specific pin interrupt.
*
* @param base GPIO base pointer.
* @param mask GPIO pin number macro.
*/
static inline void GPIO_EnableInterrupts(GPIO_Type *base, uint32_t mask)
{
GPIO_PortEnableInterrupts(base, mask);
}
/*!
* @brief Disables the specific pin interrupt.
*
* @param base GPIO base pointer.
* @param mask GPIO pin number macro.
*/
static inline void GPIO_PortDisableInterrupts(GPIO_Type *base, uint32_t mask)
{
base->IMR &= ~mask;
}
/*!
* @brief Disables the specific pin interrupt.
* @deprecated Do not use this function. It has been superceded by @ref GPIO_PortDisableInterrupts.
*/
static inline void GPIO_DisableInterrupts(GPIO_Type *base, uint32_t mask)
{
GPIO_PortDisableInterrupts(base, mask);
}
/*!
* @brief Reads individual pin interrupt status.
*
* @param base GPIO base pointer.
* @retval current pin interrupt status flag.
*/
static inline uint32_t GPIO_PortGetInterruptFlags(GPIO_Type *base)
{
return base->ISR;
}
/*!
* @brief Reads individual pin interrupt status.
*
* @param base GPIO base pointer.
* @retval current pin interrupt status flag.
*/
static inline uint32_t GPIO_GetPinsInterruptFlags(GPIO_Type *base)
{
return GPIO_PortGetInterruptFlags(base);
}
/*!
* @brief Clears pin interrupt flag. Status flags are cleared by
* writing a 1 to the corresponding bit position.
*
* @param base GPIO base pointer.
* @param mask GPIO pin number macro.
*/
static inline void GPIO_PortClearInterruptFlags(GPIO_Type *base, uint32_t mask)
{
base->ISR = mask;
}
/*!
* @brief Clears pin interrupt flag. Status flags are cleared by
* writing a 1 to the corresponding bit position.
*
* @param base GPIO base pointer.
* @param mask GPIO pin number macro.
*/
static inline void GPIO_ClearPinsInterruptFlags(GPIO_Type *base, uint32_t mask)
{
GPIO_PortClearInterruptFlags(base, mask);
}
/*! @} */
#if defined(__cplusplus)
}
#endif
/*!
* @}
*/
#endif /* FSL_GPIO_H_*/

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,671 @@
/*
* Copyright (c) 2016, Freescale Semiconductor, Inc.
* Copyright 2016-2019 NXP
* All rights reserved.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#ifndef FSL_PMU_H_
#define FSL_PMU_H_
#include "fsl_common.h"
/*! @addtogroup pmu */
/*! @{ */
/*******************************************************************************
* Definitions
******************************************************************************/
/*! @name Driver version */
/*! @{ */
/*! @brief PMU driver version */
#define FSL_PMU_DRIVER_VERSION (MAKE_VERSION(2, 1, 1)) /*!< Version 2.1.1. */
/*! @} */
/*!
* @brief PMU Status flags.
*/
enum
{
kPMU_1P1RegulatorOutputOK = (1U << 0U), /*!< Status bit that signals when the 1p1 regulator output
is ok. 1 = regulator output > brownout target. */
kPMU_1P1BrownoutOnOutput = (1U << 1U), /*!< Status bit that signals when a 1p1 brownout is detected
on the regulator output. */
kPMU_3P0RegulatorOutputOK = (1U << 2U), /*!< Status bit that signals when the 3p0 regulator output
is ok. 1 = regulator output > brownout target. */
kPMU_3P0BrownoutOnOutput = (1U << 3U), /*!< Status bit that signals when a 3p0 brownout is detected
on the regulator output. */
kPMU_2P5RegulatorOutputOK = (1U << 4U), /*!< Status bit that signals when the 2p5 regulator output
is ok. 1 = regulator output > brownout target. */
kPMU_2P5BrownoutOnOutput = (1U << 5U), /*!< Status bit that signals when a 2p5 brownout is detected
on the regulator output. */
};
/*!
* @brief The source for the reference voltage of the weak 1P1 regulator.
*/
typedef enum _pmu_1p1_weak_reference_source
{
kPMU_1P1WeakReferenceSourceAlt0 = 0U, /*!< Weak-linreg output tracks low-power-bandgap voltage. */
kPMU_1P1WeakReferenceSourceAlt1 = 1U, /*!< Weak-linreg output tracks VDD_SOC_CAP voltage. */
} pmu_1p1_weak_reference_source_t;
/*!
* @brief Input voltage source for LDO_3P0 from USB VBus.
*/
typedef enum _pmu_3p0_vbus_voltage_source
{
kPMU_3P0VBusVoltageSourceAlt0 = 0U, /*!< USB_OTG1_VBUS - Utilize VBUS OTG1 for power. */
kPMU_3P0VBusVoltageSourceAlt1 = 1U, /*!< USB_OTG2_VBUS - Utilize VBUS OTG2 for power. */
} pmu_3p0_vbus_voltage_source_t;
/*!
* @brief Regulator voltage ramp rate.
*/
typedef enum _pmu_core_reg_voltage_ramp_rate
{
kPMU_CoreRegVoltageRampRateFast = 0U, /*!< Fast. */
kPMU_CoreRegVoltageRampRateMediumFast = 1U, /*!< Medium Fast. */
kPMU_CoreRegVoltageRampRateMediumSlow = 2U, /*!< Medium Slow. */
kPMU_CoreRegVoltageRampRateSlow = 0U, /*!< Slow. */
} pmu_core_reg_voltage_ramp_rate_t;
#if defined(FSL_FEATURE_PMU_HAS_LOWPWR_CTRL) && FSL_FEATURE_PMU_HAS_LOWPWR_CTRL
/*!
* @brief Mask values of power gate.
*/
enum _pmu_power_gate
{
kPMU_PowerGateDisplay = PMU_LOWPWR_CTRL_MIX_PWRGATE_MASK, /*!< Display power gate control. */
kPMU_PowerGateDisplayLogic = PMU_LOWPWR_CTRL_DISPLAY_PWRGATE_MASK, /*!< Display logic power gate control. */
kPMU_PowerGateL2 = PMU_LOWPWR_CTRL_L2_PWRGATE_MASK, /*!< L2 power gate control. */
kPMU_PowerGateL1 = PMU_LOWPWR_CTRL_L1_PWRGATE_MASK, /*!< L1 power gate control. */
kPMU_PowerGateRefTopIBias = PMU_LOWPWR_CTRL_REFTOP_IBIAS_OFF_MASK, /*!< Low power reftop ibias disable. */
};
#endif /* FSL_FEATURE_PMU_HAS_LOWPWR_CTRL. */
/*!
* @brief Bandgap select.
*/
typedef enum _pmu_power_bandgap
{
kPMU_NormalPowerBandgap = 0U, /*!< Normal power bandgap. */
kPMU_LowPowerBandgap = 1U, /*!< Low power bandgap. */
} pmu_power_bandgap_t;
/*******************************************************************************
* API
******************************************************************************/
#if defined(__cplusplus)
extern "C" {
#endif /* __cplusplus*/
/*!
* @name Status.
* @{
*/
/*!
* @brief Get PMU status flags.
*
* @param base PMU peripheral base address.
* @return PMU status flags.It indicate if regulator output of 1P1,3P0 and 2P5 is ok
* and brownout output of 1P1,3P0 and 2P5 is detected.
*/
uint32_t PMU_GetStatusFlags(PMU_Type *base);
/*! @} */
/*!
* @name 1P1 Regular
* @{
*/
/*!
* @brief Selects the source for the reference voltage of the weak 1P1 regulator.
*
* @param base PMU peripheral base address.
* @param option The option for reference voltage source, see to #pmu_1p1_weak_reference_source_t.
*/
static inline void PMU_1P1SetWeakReferenceSource(PMU_Type *base, pmu_1p1_weak_reference_source_t option)
{
base->REG_1P1 = (base->REG_1P1 & ~PMU_REG_1P1_SELREF_WEAK_LINREG_MASK) | PMU_REG_1P1_SELREF_WEAK_LINREG(option);
}
/*!
* @brief Enables the weak 1P1 regulator.
*
* This regulator can be used when the main 1P1 regulator is disabled, under low-power conditions.
*
* @param base PMU peripheral base address.
* @param enable Enable the feature or not.
*/
static inline void PMU_1P1EnableWeakRegulator(PMU_Type *base, bool enable)
{
if (enable)
{
base->REG_1P1 |= PMU_REG_1P1_ENABLE_WEAK_LINREG_MASK;
}
else
{
base->REG_1P1 &= ~PMU_REG_1P1_ENABLE_WEAK_LINREG_MASK;
}
}
/*!
* @brief Adjust the 1P1 regulator output voltage.
*
* Each LSB is worth 25mV. Programming examples are detailed below. Other output target voltages
* may be interpolated from these examples. Choices must be in this range:
* - 0x1b(1.375V) >= output_trg >= 0x04(0.8V)
* - 0x04 : 0.8V
* - 0x10 : 1.1V (typical)
* - 0x1b : 1.375V
* NOTE: There may be reduced chip functionality or reliability at the extremes of the programming range.
*
* @param base PMU peripheral base address.
* @param value Setting value for the output.
*/
static inline void PMU_1P1SetRegulatorOutputVoltage(PMU_Type *base, uint32_t value)
{
base->REG_1P1 = (base->REG_1P1 & ~PMU_REG_1P1_OUTPUT_TRG_MASK) | PMU_REG_1P1_OUTPUT_TRG(value);
}
/*!
* @brief Adjust the 1P1 regulator brownout offset voltage.
*
* Control bits to adjust the regulator brownout offset voltage in 25mV steps. The reset
* brown-offset is 175mV below the programmed target code.
* Brownout target = OUTPUT_TRG - BO_OFFSET.
* Some steps may be irrelevant because of input supply limitations or load operation.
*
* @param base PMU peripheral base address.
* @param value Setting value for the brownout offset. The available range is in 3-bit.
*/
static inline void PMU_1P1SetBrownoutOffsetVoltage(PMU_Type *base, uint32_t value)
{
base->REG_1P1 = (base->REG_1P1 & ~PMU_REG_1P1_BO_OFFSET_MASK) | PMU_REG_1P1_BO_OFFSET(value);
}
/*!
* @brief Enable the pull-down circuitry in the regulator.
*
* @param base PMU peripheral base address.
* @param enable Enable the feature or not.
*/
static inline void PMU_1P1EnablePullDown(PMU_Type *base, bool enable)
{
if (enable)
{
base->REG_1P1 |= PMU_REG_1P1_ENABLE_PULLDOWN_MASK;
}
else
{
base->REG_1P1 &= ~PMU_REG_1P1_ENABLE_PULLDOWN_MASK;
}
}
/*!
* @brief Enable the current-limit circuitry in the regulator.
*
* @param base PMU peripheral base address.
* @param enable Enable the feature or not.
*/
static inline void PMU_1P1EnableCurrentLimit(PMU_Type *base, bool enable)
{
if (enable)
{
base->REG_1P1 |= PMU_REG_1P1_ENABLE_ILIMIT_MASK;
}
else
{
base->REG_1P1 &= ~PMU_REG_1P1_ENABLE_ILIMIT_MASK;
}
}
/*!
* @brief Enable the brownout circuitry in the regulator.
*
* @param base PMU peripheral base address.
* @param enable Enable the feature or not.
*/
static inline void PMU_1P1EnableBrownout(PMU_Type *base, bool enable)
{
if (enable)
{
base->REG_1P1 |= PMU_REG_1P1_ENABLE_BO_MASK;
}
else
{
base->REG_1P1 &= ~PMU_REG_1P1_ENABLE_BO_MASK;
}
}
/*!
* @brief Enable the regulator output.
*
* @param base PMU peripheral base address.
* @param enable Enable the feature or not.
*/
static inline void PMU_1P1EnableOutput(PMU_Type *base, bool enable)
{
if (enable)
{
base->REG_1P1 |= PMU_REG_1P1_ENABLE_LINREG_MASK;
}
else
{
base->REG_1P1 &= ~PMU_REG_1P1_ENABLE_LINREG_MASK;
}
}
/*! @} */
/*!
* @name 3P0 Regular
* @{
*/
/*!
* @brief Adjust the 3P0 regulator output voltage.
*
* Each LSB is worth 25mV. Programming examples are detailed below. Other output target voltages
* may be interpolated from these examples. Choices must be in this range:
* - 0x00(2.625V) >= output_trg >= 0x1f(3.4V)
* - 0x00 : 2.625V
* - 0x0f : 3.0V (typical)
* - 0x1f : 3.4V
*
* @param base PMU peripheral base address.
* @param value Setting value for the output.
*/
static inline void PMU_3P0SetRegulatorOutputVoltage(PMU_Type *base, uint32_t value)
{
base->REG_3P0 = (base->REG_3P0 & ~PMU_REG_3P0_OUTPUT_TRG_MASK) | PMU_REG_3P0_OUTPUT_TRG(value);
}
/*!
* @brief Select input voltage source for LDO_3P0.
*
* Select input voltage source for LDO_3P0 from either USB_OTG1_VBUS or USB_OTG2_VBUS. If only
* one of the two VBUS voltages is present, it is automatically selected.
*
* @param base PMU peripheral base address.
* @param option User-defined input voltage source for LDO_3P0.
*/
static inline void PMU_3P0SetVBusVoltageSource(PMU_Type *base, pmu_3p0_vbus_voltage_source_t option)
{
base->REG_3P0 = (base->REG_3P0 & ~PMU_REG_3P0_VBUS_SEL_MASK) | PMU_REG_3P0_VBUS_SEL(option);
}
/*!
* @brief Adjust the 3P0 regulator brownout offset voltage.
*
* Control bits to adjust the 3P0 regulator brownout offset voltage in 25mV steps. The reset
* brown-offset is 175mV below the programmed target code.
* Brownout target = OUTPUT_TRG - BO_OFFSET.
* Some steps may be irrelevant because of input supply limitations or load operation.
*
* @param base PMU peripheral base address.
* @param value Setting value for the brownout offset. The available range is in 3-bit.
*/
static inline void PMU_3P0SetBrownoutOffsetVoltage(PMU_Type *base, uint32_t value)
{
base->REG_3P0 = (base->REG_3P0 & ~PMU_REG_3P0_BO_OFFSET_MASK) | PMU_REG_3P0_BO_OFFSET(value);
}
/*!
* @brief Enable the current-limit circuitry in the 3P0 regulator.
*
* @param base PMU peripheral base address.
* @param enable Enable the feature or not.
*/
static inline void PMU_3P0EnableCurrentLimit(PMU_Type *base, bool enable)
{
if (enable)
{
base->REG_3P0 |= PMU_REG_3P0_ENABLE_ILIMIT_MASK;
}
else
{
base->REG_3P0 &= ~PMU_REG_3P0_ENABLE_ILIMIT_MASK;
}
}
/*!
* @brief Enable the brownout circuitry in the 3P0 regulator.
*
* @param base PMU peripheral base address.
* @param enable Enable the feature or not.
*/
static inline void PMU_3P0EnableBrownout(PMU_Type *base, bool enable)
{
if (enable)
{
base->REG_3P0 |= PMU_REG_3P0_ENABLE_BO_MASK;
}
else
{
base->REG_3P0 &= ~PMU_REG_3P0_ENABLE_BO_MASK;
}
}
/*!
* @brief Enable the 3P0 regulator output.
*
* @param base PMU peripheral base address.
* @param enable Enable the feature or not.
*/
static inline void PMU_3P0EnableOutput(PMU_Type *base, bool enable)
{
if (enable)
{
base->REG_3P0 |= PMU_REG_3P0_ENABLE_LINREG_MASK;
}
else
{
base->REG_3P0 &= ~PMU_REG_3P0_ENABLE_LINREG_MASK;
}
}
/*! @} */
/*!
* @name 2P5 Regulator
* @{
*/
/*!
* @brief Enables the weak 2P5 regulator.
*
* This low power regulator is used when the main 2P5 regulator is disabled
* to keep the 2.5V output roughly at 2.5V. Scales directly with the value of VDDHIGH_IN.
*
* @param base PMU peripheral base address.
* @param enable Enable the feature or not.
*/
static inline void PMU_2P5EnableWeakRegulator(PMU_Type *base, bool enable)
{
if (enable)
{
base->REG_2P5 |= PMU_REG_2P5_ENABLE_WEAK_LINREG_MASK;
}
else
{
base->REG_2P5 &= ~PMU_REG_2P5_ENABLE_WEAK_LINREG_MASK;
}
}
/*!
* @brief Adjust the 1P1 regulator output voltage.
*
* Each LSB is worth 25mV. Programming examples are detailed below. Other output target voltages
* may be interpolated from these examples. Choices must be in this range:
* - 0x00(2.1V) >= output_trg >= 0x1f(2.875V)
* - 0x00 : 2.1V
* - 0x10 : 2.5V (typical)
* - 0x1f : 2.875V
* NOTE: There may be reduced chip functionality or reliability at the extremes of the programming range.
*
* @param base PMU peripheral base address.
* @param value Setting value for the output.
*/
static inline void PMU_2P5SetRegulatorOutputVoltage(PMU_Type *base, uint32_t value)
{
base->REG_2P5 = (base->REG_2P5 & ~PMU_REG_2P5_OUTPUT_TRG_MASK) | PMU_REG_2P5_OUTPUT_TRG(value);
}
/*!
* @brief Adjust the 2P5 regulator brownout offset voltage.
*
* Adjust the regulator brownout offset voltage in 25mV steps. The reset
* brown-offset is 175mV below the programmed target code.
* Brownout target = OUTPUT_TRG - BO_OFFSET.
* Some steps may be irrelevant because of input supply limitations or load operation.
*
* @param base PMU peripheral base address.
* @param value Setting value for the brownout offset. The available range is in 3-bit.
*/
static inline void PMU_2P5SetBrownoutOffsetVoltage(PMU_Type *base, uint32_t value)
{
base->REG_2P5 = (base->REG_2P5 & ~PMU_REG_2P5_BO_OFFSET_MASK) | PMU_REG_2P5_BO_OFFSET(value);
}
/*!
* @brief Enable the pull-down circuitry in the 2P5 regulator.
*
* @param base PMU peripheral base address.
* @param enable Enable the feature or not.
*/
static inline void PMU_2P5EnablePullDown(PMU_Type *base, bool enable)
{
if (enable)
{
base->REG_2P5 |= PMU_REG_2P5_ENABLE_PULLDOWN_MASK;
}
else
{
base->REG_2P5 &= ~PMU_REG_2P5_ENABLE_PULLDOWN_MASK;
}
}
/*!
* @brief Enable the pull-down circuitry in the 2P5 regulator.
* @deprecated Do not use this function. It has been superceded by @ref PMU_2P5EnablePullDown.
*/
static inline void PMU_2P1EnablePullDown(PMU_Type *base, bool enable)
{
if (enable)
{
base->REG_2P5 |= PMU_REG_2P5_ENABLE_PULLDOWN_MASK;
}
else
{
base->REG_2P5 &= ~PMU_REG_2P5_ENABLE_PULLDOWN_MASK;
}
}
/*!
* @brief Enable the current-limit circuitry in the 2P5 regulator.
*
* @param base PMU peripheral base address.
* @param enable Enable the feature or not.
*/
static inline void PMU_2P5EnableCurrentLimit(PMU_Type *base, bool enable)
{
if (enable)
{
base->REG_2P5 |= PMU_REG_2P5_ENABLE_ILIMIT_MASK;
}
else
{
base->REG_2P5 &= ~PMU_REG_2P5_ENABLE_ILIMIT_MASK;
}
}
/*!
* @brief Enable the brownout circuitry in the 2P5 regulator.
*
* @param base PMU peripheral base address.
* @param enable Enable the feature or not.
*/
static inline void PMU_2P5nableBrownout(PMU_Type *base, bool enable)
{
if (enable)
{
base->REG_2P5 |= PMU_REG_2P5_ENABLE_BO_MASK;
}
else
{
base->REG_2P5 &= ~PMU_REG_2P5_ENABLE_BO_MASK;
}
}
/*!
* @brief Enable the 2P5 regulator output.
*
* @param base PMU peripheral base address.
* @param enable Enable the feature or not.
*/
static inline void PMU_2P5EnableOutput(PMU_Type *base, bool enable)
{
if (enable)
{
base->REG_2P5 |= PMU_REG_2P5_ENABLE_LINREG_MASK;
}
else
{
base->REG_2P5 &= ~PMU_REG_2P5_ENABLE_LINREG_MASK;
}
}
/*! @} */
/*!
* @name Core Regulator
* @{
*/
/*!
* @brief Increase the gate drive on power gating FETs.
*
* If set, increases the gate drive on power gating FETs to reduce leakage in the off state.
* Care must be taken to apply this bit only when the input supply voltage to the power FET
* is less than 1.1V.
* NOTE: This bit should only be used in low-power modes where the external input supply voltage
* is nominally 0.9V.
*
* @param base PMU peripheral base address.
* @param enable Enable the feature or not.
*/
static inline void PMU_CoreEnableIncreaseGateDrive(PMU_Type *base, bool enable)
{
if (enable)
{
base->REG_CORE |= PMU_REG_CORE_FET_ODRIVE_MASK;
}
else
{
base->REG_CORE &= ~PMU_REG_CORE_FET_ODRIVE_MASK;
}
}
/*!
* @brief Set the CORE regulator voltage ramp rate.
*
* @param base PMU peripheral base address.
* @param option User-defined option for voltage ramp rate, see to #pmu_core_reg_voltage_ramp_rate_t.
*/
static inline void PMU_CoreSetRegulatorVoltageRampRate(PMU_Type *base, pmu_core_reg_voltage_ramp_rate_t option)
{
base->REG_CORE = (base->REG_CORE & ~PMU_REG_CORE_RAMP_RATE_MASK) | PMU_REG_CORE_RAMP_RATE(option);
}
/*!
* @brief Define the target voltage for the SOC power domain.
*
* Define the target voltage for the SOC power domain. Single-bit increments reflect 25mV core
* voltage steps. Some steps may not be relevant because of input supply limitations or load operation.
* - 0x00 : Power gated off.
* - 0x01 : Target core voltage = 0.725V
* - 0x02 : Target core voltage = 0.750V
* - ...
* - 0x10 : Target core voltage = 1.100V
* - ...
* - 0x1e : Target core voltage = 1.450V
* - 0x1F : Power FET switched full on. No regulation.
* NOTE: This register is capable of programming an over-voltage condition on the device. Consult the
* datasheet Operating Ranges table for the allowed voltages.
*
* @param base PMU peripheral base address.
* @param value Setting value for target voltage. 5-bit available
*/
static inline void PMU_CoreSetSOCDomainVoltage(PMU_Type *base, uint32_t value)
{
base->REG_CORE = (base->REG_CORE & ~PMU_REG_CORE_REG2_TARG_MASK) | PMU_REG_CORE_REG2_TARG(value);
}
/*!
* @brief Define the target voltage for the ARM Core power domain.
*
* Define the target voltage for the ARM Core power domain. Single-bit increments reflect 25mV core
* voltage steps. Some steps may not be relevant because of input supply limitations or load operation.
* - 0x00 : Power gated off.
* - 0x01 : Target core voltage = 0.725V
* - 0x02 : Target core voltage = 0.750V
* - ...
* - 0x10 : Target core voltage = 1.100V
* - ...
* - 0x1e : Target core voltage = 1.450V
* - 0x1F : Power FET switched full on. No regulation.
* NOTE: This register is capable of programming an over-voltage condition on the device. Consult the
* datasheet Operating Ranges table for the allowed voltages.
*
* @param base PMU peripheral base address.
* @param value Setting value for target voltage. 5-bit available
*/
static inline void PMU_CoreSetARMCoreDomainVoltage(PMU_Type *base, uint32_t value)
{
base->REG_CORE = (base->REG_CORE & ~PMU_REG_CORE_REG0_TARG_MASK) | PMU_REG_CORE_REG0_TARG(value);
}
/*! @} */
#if defined(FSL_FEATURE_PMU_HAS_LOWPWR_CTRL) && FSL_FEATURE_PMU_HAS_LOWPWR_CTRL
/*!
* @name Power Gate Controller & other
* @{
*/
/*!
* @brief Gate the power to modules.
*
* @param base PMU peripheral base address.
* @param gates Mask value for the module to be gated. See to #_pmu_power_gate.
*/
static inline void PMU_GatePower(PMU_Type *base, uint32_t gates)
{
base->LOWPWR_CTRL_SET = gates;
}
/*!
* @brief Ungate the power to modules.
*
* @param base PMU peripheral base address.
* @param gates Mask value for the module to be gated. See to #_pmu_power_gate.
*/
static inline void PMU_UngatePower(PMU_Type *base, uint32_t gates)
{
base->LOWPWR_CTRL_CLR = gates;
}
/*!
* @brief Enable the low power bandgap.
*
* @param base PMU peripheral base address.
* @param enable Enable the low power bandgap or use the normal power bandgap.
* @
*/
static inline void PMU_EnableLowPowerBandgap(PMU_Type *base, bool enable)
{
if (enable)
{
base->LOWPWR_CTRL_SET = PMU_LOWPWR_CTRL_LPBG_SEL_MASK; /* Use the low power bandgap. */
}
else
{
base->LOWPWR_CTRL_CLR = PMU_LOWPWR_CTRL_LPBG_SEL_MASK; /* Use the normal power bandgap. */
}
}
#endif /* FSL_FEATURE_PMU_HAS_LOWPWR_CTRL. */
/*! @} */
#if defined(__cplusplus)
}
#endif /* __cplusplus*/
/*! @}*/
#endif /* FSL_PMU_H_*/

View File

@ -0,0 +1,602 @@
/*
* Copyright (c) 2016, Freescale Semiconductor, Inc.
* Copyright 2016-2020 NXP
* All rights reserved.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#ifndef FSL_SRC_H_
#define FSL_SRC_H_
#include "fsl_common.h"
/*!
* @addtogroup src
* @{
*/
/*******************************************************************************
* Definitions
******************************************************************************/
/*! @name Driver version */
/*! @{ */
/*! @brief SRC driver version 2.0.1. */
#define FSL_SRC_DRIVER_VERSION (MAKE_VERSION(2, 0, 1))
/*! @} */
/*!
* @brief SRC reset status flags.
*/
enum _src_reset_status_flags
{
#if (defined(FSL_FEATURE_SRC_HAS_SRSR_RESET_OUT) && FSL_FEATURE_SRC_HAS_SRSR_RESET_OUT)
kSRC_ResetOutputEnableFlag = SRC_SRSR_RESET_OUT_MASK, /*!< This bit indicates if RESET status is
driven out on PTE0 pin. */
#endif /* FSL_FEATURE_SRC_HAS_SRSR_RESET_OUT */
#if !(defined(FSL_FEATURE_SRC_HAS_NO_SRSR_WBI) && FSL_FEATURE_SRC_HAS_NO_SRSR_WBI)
kSRC_WarmBootIndicationFlag = SRC_SRSR_WBI_MASK, /*!< WARM boot indication shows that WARM boot
was initiated by software. */
#endif /* FSL_FEATURE_SRC_HAS_NO_SRSR_WBI */
kSRC_TemperatureSensorResetFlag = SRC_SRSR_TSR_MASK, /*!< Indicates whether the reset was the
result of software reset from on-chip
Temperature Sensor. Temperature Sensor
Interrupt needs to be served before this
bit can be cleaned.*/
#if (defined(FSL_FEATURE_SRC_HAS_SRSR_WDOG3_RST_B) && FSL_FEATURE_SRC_HAS_SRSR_WDOG3_RST_B)
kSRC_Wdog3ResetFlag = SRC_SRSR_WDOG3_RST_B_MASK, /*!< IC Watchdog3 Time-out reset. Indicates
whether the reset was the result of the
watchdog3 time-out event. */
#endif /* FSL_FEATURE_SRC_HAS_SRSR_WDOG3_RST_B */
#if (defined(FSL_FEATURE_SRC_HAS_SRSR_SW) && FSL_FEATURE_SRC_HAS_SRSR_SW)
kSRC_SoftwareResetFlag = SRC_SRSR_SW_MASK, /*!< Indicates a reset has been caused by software
setting of SYSRESETREQ bit in Application
Interrupt and Reset Control Register in the
ARM core. */
#endif /* FSL_FEATURE_SRC_HAS_SRSR_SW */
#if (defined(FSL_FEATURE_SRC_HAS_SRSR_JTAG_SW_RST) && FSL_FEATURE_SRC_HAS_SRSR_JTAG_SW_RST)
kSRC_JTAGSystemResetFlag =
SRC_SRSR_JTAG_SW_RST_MASK, /*!< Indicates whether the reset was the result of software reset form JTAG */
#endif /* FSL_FEATURE_SRC_HAS_SRSR_JTAG_SW_RST */
kSRC_JTAGSoftwareResetFlag = SRC_SRSR_SJC_MASK, /*!< Indicates whether the reset was the result of
setting SJC_GPCCR bit 31. */
kSRC_JTAGGeneratedResetFlag = SRC_SRSR_JTAG_MASK, /*!< Indicates a reset has been caused by JTAG
selection of certain IR codes: EXTEST or
HIGHZ. */
kSRC_WatchdogResetFlag = SRC_SRSR_WDOG_MASK, /*!< Indicates a reset has been caused by the
watchdog timer timing out. This reset source
can be blocked by disabling the watchdog. */
#if (defined(FSL_FEATURE_SRC_HAS_SRSR_IPP_USER_RESET_B) && FSL_FEATURE_SRC_HAS_SRSR_IPP_USER_RESET_B)
kSRC_IppUserResetFlag = SRC_SRSR_IPP_USER_RESET_B_MASK, /*!< Indicates whether the reset was the
result of the ipp_user_reset_b
qualified reset. */
#endif /* FSL_FEATURE_SRC_HAS_SRSR_IPP_USER_RESET_B */
#if (defined(FSL_FEATURE_SRC_HAS_SRSR_SNVS) && FSL_FEATURE_SRC_HAS_SRSR_SNVS)
kSRC_SNVSFailResetFlag = SRC_SRSR_SNVS_MASK, /*!< SNVS hardware failure will always cause a cold
reset. This flag indicates whether the reset
is a result of SNVS hardware failure. */
#endif /* FSL_FEATURE_SRC_HAS_SRSR_SNVS */
#if (defined(FSL_FEATURE_SRC_HAS_SRSR_CSU_RESET_B) && FSL_FEATURE_SRC_HAS_SRSR_CSU_RESET_B)
kSRC_CsuResetFlag = SRC_SRSR_CSU_RESET_B_MASK, /*!< Indicates whether the reset was the result
of the csu_reset_b input. */
#endif /* FSL_FEATURE_SRC_HAS_SRSR_CSU_RESET_B */
#if (defined(FSL_FEATURE_SRC_HAS_SRSR_LOCKUP) && FSL_FEATURE_SRC_HAS_SRSR_LOCKUP)
kSRC_CoreLockupResetFlag = SRC_SRSR_LOCKUP_MASK, /*!< Indicates a reset has been caused by the
ARM core indication of a LOCKUP event. */
#endif /* FSL_FEATURE_SRC_HAS_SRSR_LOCKUP */
#if (defined(FSL_FEATURE_SRC_HAS_SRSR_POR) && FSL_FEATURE_SRC_HAS_SRSR_POR)
kSRC_PowerOnResetFlag = SRC_SRSR_POR_MASK, /*!< Indicates a reset has been caused by the
power-on detection logic. */
#endif /* FSL_FEATURE_SRC_HAS_SRSR_POR */
#if (defined(FSL_FEATURE_SRC_HAS_SRSR_LOCKUP_SYSRESETREQ) && FSL_FEATURE_SRC_HAS_SRSR_LOCKUP_SYSRESETREQ)
kSRC_LockupSysResetFlag =
SRC_SRSR_LOCKUP_SYSRESETREQ_MASK, /*!< Indicates a reset has been caused by CPU lockup or software
setting of SYSRESETREQ bit in Application Interrupt and
Reset Control Register of the ARM core. */
#endif /* FSL_FEATURE_SRC_HAS_SRSR_LOCKUP_SYSRESETREQ */
#if (defined(FSL_FEATURE_SRC_HAS_SRSR_IPP_RESET_B) && FSL_FEATURE_SRC_HAS_SRSR_IPP_RESET_B)
kSRC_IppResetPinFlag = SRC_SRSR_IPP_RESET_B_MASK, /*!< Indicates whether reset was the result of
ipp_reset_b pin (Power-up sequence). */
#endif /* FSL_FEATURE_SRC_HAS_SRSR_IPP_RESET_B */
};
#if (defined(FSL_FEATURE_SRC_HAS_SISR) && FSL_FEATURE_SRC_HAS_SISR)
/*!
* @brief SRC interrupt status flag.
*/
enum _src_status_flags
{
kSRC_Core0WdogResetReqFlag =
SRC_SISR_CORE0_WDOG_RST_REQ_MASK, /*!< WDOG reset request from core0. Read-only status bit. */
};
#endif /* FSL_FEATURE_SRC_HAS_SISR */
#if (defined(FSL_FEATURE_SRC_HAS_SCR_MIX_RST_STRCH) && FSL_FEATURE_SRC_HAS_SCR_MIX_RST_STRCH)
/*!
* @brief Selection of SoC mix power reset stretch.
*
* This type defines the SoC mix (Audio, ENET, uSDHC, EIM, QSPI, OCRAM, MMDC, etc) power up reset
* stretch mix reset width with the optional count of cycles
*/
typedef enum _src_mix_reset_stretch_cycles
{
kSRC_MixResetStretchCycleAlt0 = 0U, /*!< mix reset width is 1 x 88 ipg_cycle cycles. */
kSRC_MixResetStretchCycleAlt1 = 1U, /*!< mix reset width is 2 x 88 ipg_cycle cycles. */
kSRC_MixResetStretchCycleAlt2 = 2U, /*!< mix reset width is 3 x 88 ipg_cycle cycles. */
kSRC_MixResetStretchCycleAlt3 = 3U, /*!< mix reset width is 4 x 88 ipg_cycle cycles. */
} src_mix_reset_stretch_cycles_t;
#endif /* FSL_FEATURE_SRC_HAS_SCR_MIX_RST_STRCH */
#if (defined(FSL_FEATURE_SRC_HAS_SCR_WDOG3_RST_OPTN) && FSL_FEATURE_SRC_HAS_SCR_WDOG3_RST_OPTN)
/*!
* @brief Selection of WDOG3 reset option.
*/
typedef enum _src_wdog3_reset_option
{
kSRC_Wdog3ResetOptionAlt0 = 0U, /*!< Wdog3_rst_b asserts M4 reset (default). */
kSRC_Wdog3ResetOptionAlt1 = 1U, /*!< Wdog3_rst_b asserts global reset. */
} src_wdog3_reset_option_t;
#endif /* FSL_FEATURE_SRC_HAS_SCR_WDOG3_RST_OPTN */
/*!
* @brief Selection of WARM reset bypass count.
*
* This type defines the 32KHz clock cycles to count before bypassing the MMDC acknowledge for WARM
* reset. If the MMDC acknowledge is not asserted before this counter is elapsed, a COLD reset will
* be initiated.
*/
typedef enum _src_warm_reset_bypass_count
{
kSRC_WarmResetWaitAlways = 0U, /*!< System will wait until MMDC acknowledge is asserted. */
kSRC_WarmResetWaitClk16 = 1U, /*!< Wait 16 32KHz clock cycles before switching the reset. */
kSRC_WarmResetWaitClk32 = 2U, /*!< Wait 32 32KHz clock cycles before switching the reset. */
kSRC_WarmResetWaitClk64 = 3U, /*!< Wait 64 32KHz clock cycles before switching the reset. */
} src_warm_reset_bypass_count_t;
#if defined(__cplusplus)
extern "C" {
#endif
/*******************************************************************************
* API
******************************************************************************/
#if (defined(FSL_FEATURE_SRC_HAS_SCR_MASK_WDOG3_RST) && FSL_FEATURE_SRC_HAS_SCR_MASK_WDOG3_RST)
/*!
* @brief Enable the WDOG3 reset.
*
* The WDOG3 reset is enabled by default.
*
* @param base SRC peripheral base address.
* @param enable Enable the reset or not.
*/
static inline void SRC_EnableWDOG3Reset(SRC_Type *base, bool enable)
{
if (enable)
{
base->SCR = (base->SCR & ~SRC_SCR_MASK_WDOG3_RST_MASK) | SRC_SCR_MASK_WDOG3_RST(0xA);
}
else
{
base->SCR = (base->SCR & ~SRC_SCR_MASK_WDOG3_RST_MASK) | SRC_SCR_MASK_WDOG3_RST(0x5);
}
}
#endif /* FSL_FEATURE_SRC_HAS_SCR_MASK_WDOG3_RST */
#if (defined(FSL_FEATURE_SRC_HAS_SCR_MIX_RST_STRCH) && FSL_FEATURE_SRC_HAS_SCR_MIX_RST_STRCH)
/*!
* @brief Set the mix power up reset stretch mix reset width.
*
* @param base SRC peripheral base address.
* @param option Setting option, see to #src_mix_reset_stretch_cycles_t.
*/
static inline void SRC_SetMixResetStretchCycles(SRC_Type *base, src_mix_reset_stretch_cycles_t option)
{
base->SCR = (base->SCR & ~SRC_SCR_MIX_RST_STRCH_MASK) | SRC_SCR_MIX_RST_STRCH(option);
}
#endif /* FSL_FEATURE_SRC_HAS_SCR_MIX_RST_STRCH */
#if (defined(FSL_FEATURE_SRC_HAS_SCR_DBG_RST_MSK_PG) && FSL_FEATURE_SRC_HAS_SCR_DBG_RST_MSK_PG)
/*!
* @brief Debug reset would be asserted after power gating event.
*
* @param base SRC peripheral base address.
* @param enable Enable the reset or not.
*/
static inline void SRC_EnableCoreDebugResetAfterPowerGate(SRC_Type *base, bool enable)
{
if (enable)
{
base->SCR &= ~SRC_SCR_DBG_RST_MSK_PG_MASK;
}
else
{
base->SCR |= SRC_SCR_DBG_RST_MSK_PG_MASK;
}
}
#endif /* FSL_FEATURE_SRC_HAS_SCR_DBG_RST_MSK_PG */
#if (defined(FSL_FEATURE_SRC_HAS_SCR_WDOG3_RST_OPTN) && FSL_FEATURE_SRC_HAS_SCR_WDOG3_RST_OPTN)
/*!
* @brief Set the Wdog3_rst_b option.
*
* @param base SRC peripheral base address.
* @param option Setting option, see to #src_wdog3_reset_option_t.
*/
static inline void SRC_SetWdog3ResetOption(SRC_Type *base, src_wdog3_reset_option_t option)
{
base->SCR = (base->SCR & ~SRC_SCR_WDOG3_RST_OPTN_MASK) | SRC_SCR_WDOG3_RST_OPTN(option);
}
#endif /* FSL_FEATURE_SRC_HAS_SCR_WDOG3_RST_OPTN */
#if (defined(FSL_FEATURE_SRC_HAS_SCR_CORES_DBG_RST) && FSL_FEATURE_SRC_HAS_SCR_CORES_DBG_RST)
/*!
* @brief Software reset for debug of arm platform only.
*
* @param base SRC peripheral base address.
*/
static inline void SRC_DoSoftwareResetARMCoreDebug(SRC_Type *base)
{
base->SCR |= SRC_SCR_CORES_DBG_RST_MASK;
}
/*!
* @brief Check if the software reset for debug of arm platform only is done.
*
* @param base SRC peripheral base address.
*/
static inline bool SRC_GetSoftwareResetARMCoreDebugDone(SRC_Type *base)
{
return (0U == (base->SCR & SRC_SCR_CORES_DBG_RST_MASK));
}
#endif /* FSL_FEATURE_SRC_HAS_SCR_CORES_DBG_RST */
#if (defined(FSL_FEATURE_SRC_HAS_SCR_MTSR) && FSL_FEATURE_SRC_HAS_SCR_MTSR)
/*!
* @brief Enable the temperature sensor reset.
*
* The temperature sersor reset is enabled by default. When the sensor reset happens, an flag bit
* would be asserted. This flag bit can be cleared only by the hardware reset.
*
* @param base SRC peripheral base address.
* @param enable Enable the reset or not.
*/
static inline void SRC_EnableTemperatureSensorReset(SRC_Type *base, bool enable)
{
if (enable) /* Temperature sensor reset is not masked. (default) */
{
base->SCR = (base->SCR & ~SRC_SCR_MTSR_MASK) | SRC_SCR_MTSR(0x2);
}
else /* The on-chip temperature sensor interrupt will not create a reset to the chip. */
{
base->SCR = (base->SCR & ~SRC_SCR_MTSR_MASK) | SRC_SCR_MTSR(0x5);
}
}
#endif /* FSL_FEATURE_SRC_HAS_SCR_MTSR */
#if (defined(FSL_FEATURE_SCR_HAS_SCR_CORE0_DBG_RST) && FSL_FEATURE_SCR_HAS_SCR_CORE0_DBG_RST)
/*!
* @brief Do assert the core0 debug reset.
*
* @param base SRC peripheral base address.
*/
static inline void SRC_DoAssertCore0DebugReset(SRC_Type *base)
{
base->SCR |= SRC_SCR_CORE0_DBG_RST_MASK;
}
/*!
* @brief Check if the core0 debug reset is done.
*
* @param base SRC peripheral base address.
*/
static inline bool SRC_GetAssertCore0DebugResetDone(SRC_Type *base)
{
return (0U == (base->SCR & SRC_SCR_CORE0_DBG_RST_MASK));
}
#endif /* FSL_FEATURE_SCR_HAS_SCR_CORE0_DBG_RST */
#if (defined(FSL_FEATURE_SRC_HAS_SCR_CORE0_RST) && FSL_FEATURE_SRC_HAS_SCR_CORE0_RST)
/*!
* @brief Do software reset the ARM core0 only.
*
* @param base SRC peripheral base address.
*/
static inline void SRC_DoSoftwareResetARMCore0(SRC_Type *base)
{
base->SCR |= SRC_SCR_CORE0_RST_MASK;
}
/*!
* @brief Check if the software for ARM core0 is done.
*
* @param base SRC peripheral base address.
* @return If the reset is done.
*/
static inline bool SRC_GetSoftwareResetARMCore0Done(SRC_Type *base)
{
return (0U == (base->SCR & SRC_SCR_CORE0_RST_MASK));
}
#endif /* FSL_FEATURE_SRC_HAS_SCR_CORE0_RST */
#if (defined(FSL_FEATURE_SRC_HAS_SCR_SWRC) && FSL_FEATURE_SRC_HAS_SCR_SWRC)
/*!
* @brief Do software reset for ARM core.
*
* This function can be used to assert the ARM core reset. Once it is called, the reset process will
* begin. After the reset process is finished, the command bit would be self cleared.
*
* @param base SRC peripheral base address.
*/
static inline void SRC_DoSoftwareResetARMCore(SRC_Type *base)
{
base->SCR |= SRC_SCR_SWRC_MASK;
}
/*!
* @brief Check if the software for ARM core is done.
*
* @param base SRC peripheral base address.
* @return If the reset is done.
*/
static inline bool SRC_GetSoftwareResetARMCoreDone(SRC_Type *base)
{
return (0U == (base->SCR & SRC_SCR_SWRC_MASK));
}
#endif /* FSL_FEATURE_SRC_HAS_SCR_SWRC */
#if (defined(FSL_FEATURE_SRC_HAS_SCR_EIM_RST) && FSL_FEATURE_SRC_HAS_SCR_EIM_RST)
/*!
* @brief Assert the EIM reset.
*
* EIM reset is needed in order to reconfigure the EIM chip select.
* The software reset bit must de-asserted since this is not self-refresh.
*
* @param base SRC peripheral base address.
* @param enable Make the assertion or not.
*/
static inline void SRC_AssertEIMReset(SRC_Type *base, bool enable)
{
if (enable)
{
base->SCR |= SRC_SCR_EIM_RST_MASK;
}
else
{
base->SCR &= ~SRC_SCR_EIM_RST_MASK;
}
}
#endif /* FSL_FEATURE_SRC_HAS_SCR_EIM_RST */
/*!
* @brief Enable the WDOG Reset in SRC.
*
* WDOG Reset is enabled in SRC by default. If the WDOG event to SRC is masked, it would not create
* a reset to the chip. During the time the WDOG event is masked, when the WDOG event flag is
* asserted, it would remain asserted regardless of servicing the WDOG module. The only way to clear
* that bit is the hardware reset.
*
* @param base SRC peripheral base address.
* @param enable Enable the reset or not.
*/
static inline void SRC_EnableWDOGReset(SRC_Type *base, bool enable)
{
if (enable) /* WDOG Reset is not masked in SRC (default). */
{
base->SCR = (base->SCR & ~SRC_SCR_MWDR_MASK) | SRC_SCR_MWDR(0xA);
}
else /* WDOG Reset is masked in SRC. */
{
base->SCR = (base->SCR & ~SRC_SCR_MWDR_MASK) | SRC_SCR_MWDR(0x5);
}
}
#if !(defined(FSL_FEATURE_SRC_HAS_NO_SCR_WRBC) && FSL_FEATURE_SRC_HAS_NO_SCR_WRBC)
/*!
* @brief Set the delay count of waiting MMDC's acknowledge.
*
* This function would define the 32KHz clock cycles to count before bypassing the MMDC acknowledge
* for WARM reset. If the MMDC acknowledge is not asserted before this counter is elapsed, a COLD
* reset will be initiated.
*
* @param base SRC peripheral base address.
* @param option The option of setting mode, see to #src_warm_reset_bypass_count_t.
*/
static inline void SRC_SetWarmResetBypassCount(SRC_Type *base, src_warm_reset_bypass_count_t option)
{
base->SCR = (base->SCR & ~SRC_SCR_WRBC_MASK) | SRC_SCR_WRBC(option);
}
#endif /* FSL_FEATURE_SRC_HAS_NO_SCR_WRBC */
#if (defined(FSL_FEATURE_SRC_HAS_SCR_LOCKUP_RST) && FSL_FEATURE_SRC_HAS_SCR_LOCKUP_RST)
/*!
* @brief Enable the lockup reset.
*
* @param base SRC peripheral base address.
* @param enable Enable the reset or not.
*/
static inline void SRC_EnableLockupReset(SRC_Type *base, bool enable)
{
if (enable) /* Enable lockup reset. */
{
base->SCR |= SRC_SCR_LOCKUP_RST_MASK;
}
else /* Disable lockup reset. */
{
base->SCR &= ~SRC_SCR_LOCKUP_RST_MASK;
}
}
#endif /* FSL_FEATURE_SRC_HAS_SCR_LOCKUP_RST */
#if (defined(FSL_FEATURE_SRC_HAS_SCR_LUEN) && FSL_FEATURE_SRC_HAS_SCR_LUEN)
/*!
* @brief Enable the core lockup reset.
*
* When enable the core luckup reset, the system would be reset when core luckup event happens.
*
* @param base SRC peripheral base address.
* @param enable Enable the reset or not.
*/
static inline void SRC_EnableCoreLockupReset(SRC_Type *base, bool enable)
{
if (enable) /* Core lockup will cause system reset. */
{
base->SCR |= SRC_SCR_LUEN_MASK;
}
else /* Core lockup will not cause system reset. */
{
base->SCR &= ~SRC_SCR_LUEN_MASK;
}
}
#endif /* FSL_FEATURE_SRC_HAS_SCR_LUEN */
#if !(defined(FSL_FEATURE_SRC_HAS_NO_SCR_WRE) && FSL_FEATURE_SRC_HAS_NO_SCR_WRE)
/*!
* @brief Enable the WARM reset.
*
* Only when the WARM reset is enabled, the WARM reset requests would be served by WARM reset.
* Otherwise, all the WARM reset sources would generate COLD reset.
*
* @param base SRC peripheral base address.
* @param enable Enable the WARM reset or not.
*/
static inline void SRC_EnableWarmReset(SRC_Type *base, bool enable)
{
if (enable)
{
base->SCR |= SRC_SCR_WRE_MASK;
}
else
{
base->SCR &= ~SRC_SCR_WRE_MASK;
}
}
#endif /* FSL_FEATURE_SRC_HAS_NO_SCR_WRE */
#if (defined(FSL_FEATURE_SRC_HAS_SISR) && FSL_FEATURE_SRC_HAS_SISR)
/*!
* @brief Get interrupt status flags.
*
* @param base SRC peripheral base address.
* @return Mask value of status flags. See to $_src_status_flags.
*/
static inline uint32_t SRC_GetStatusFlags(SRC_Type *base)
{
return base->SISR;
}
#endif /* FSL_FEATURE_SRC_HAS_SISR */
/*!
* @brief Get the boot mode register 1 value.
*
* The Boot Mode register contains bits that reflect the status of BOOT_CFGx pins of the chip.
* See to chip-specific document for detail information about value.
*
* @param base SRC peripheral base address.
* @return status of BOOT_CFGx pins of the chip.
*/
static inline uint32_t SRC_GetBootModeWord1(SRC_Type *base)
{
return base->SBMR1;
}
/*!
* @brief Get the boot mode register 2 value.
*
* The Boot Mode register contains bits that reflect the status of BOOT_MODEx Pins and fuse values
* that controls boot of the chip. See to chip-specific document for detail information about value.
*
* @param base SRC peripheral base address.
* @return status of BOOT_MODEx Pins and fuse values that controls boot of the chip.
*/
static inline uint32_t SRC_GetBootModeWord2(SRC_Type *base)
{
return base->SBMR2;
}
#if !(defined(FSL_FEATURE_SRC_HAS_NO_SRSR_WBI) && FSL_FEATURE_SRC_HAS_NO_SRSR_WBI)
/*!
* @brief Set the warm boot indication flag.
*
* WARM boot indication shows that WARM boot was initiated by software. This indicates to the
* software that it saved the needed information in the memory before initiating the WARM reset.
* In this case, software will set this bit to '1', before initiating the WARM reset. The warm_boot
* bit should be used as indication only after a warm_reset sequence. Software should clear this bit
* after warm_reset to indicate that the next warm_reset is not performed with warm_boot.
*
* @param base SRC peripheral base address.
* @param enable Assert the flag or not.
*/
static inline void SRC_SetWarmBootIndication(SRC_Type *base, bool enable)
{
if (enable)
{
base->SRSR = (base->SRSR & ~SRC_SRSR_W1C_BITS_MASK) | SRC_SRSR_WBI_MASK;
}
else
{
base->SRSR = (base->SRSR & ~SRC_SRSR_W1C_BITS_MASK) & ~SRC_SRSR_WBI_MASK;
}
}
#endif /* FSL_FEATURE_SRC_HAS_NO_SRSR_WBI */
/*!
* @brief Get the status flags of SRC.
*
* @param base SRC peripheral base address.
* @return Mask value of status flags, see to #_src_reset_status_flags.
*/
static inline uint32_t SRC_GetResetStatusFlags(SRC_Type *base)
{
return base->SRSR;
}
/*!
* @brief Clear the status flags of SRC.
*
* @param base SRC peripheral base address.
* @param flags value of status flags to be cleared, see to #_src_reset_status_flags.
*/
void SRC_ClearResetStatusFlags(SRC_Type *base, uint32_t flags);
/*!
* @brief Set value to general purpose registers.
*
* General purpose registers (GPRx) would hold the value during reset process. Wakeup function could
* be kept in these register. For example, the GPR1 holds the entry function for waking-up from
* Partial SLEEP mode while the GPR2 holds the argument. Other GPRx register would store the
* arbitray values.
*
* @param base SRC peripheral base address.
* @param index The index of GPRx register array. Note index 0 reponses the GPR1 register.
* @param value Setting value for GPRx register.
*/
static inline void SRC_SetGeneralPurposeRegister(SRC_Type *base, uint32_t index, uint32_t value)
{
assert(index < SRC_GPR_COUNT);
base->GPR[index] = value;
}
/*!
* @brief Get the value from general purpose registers.
*
* @param base SRC peripheral base address.
* @param index The index of GPRx register array. Note index 0 reponses the GPR1 register.
* @return The setting value for GPRx register.
*/
static inline uint32_t SRC_GetGeneralPurposeRegister(SRC_Type *base, uint32_t index)
{
assert(index < SRC_GPR_COUNT);
return base->GPR[index];
}
#if defined(__cplusplus)
}
#endif
/*!
* @}
*/
#endif /* FSL_SRC_H_ */

View File

@ -0,0 +1,505 @@
/*
** ###################################################################
** Processors: MIMXRT1061CVJ5A
** MIMXRT1061CVJ5B
** MIMXRT1061CVL5A
** MIMXRT1061CVL5B
** MIMXRT1061DVJ6A
** MIMXRT1061DVJ6B
** MIMXRT1061DVL6A
** MIMXRT1061DVL6B
** MIMXRT1061XVN5B
** MIMXRT1062CVJ5A
** MIMXRT1062CVJ5B
** MIMXRT1062CVL5A
** MIMXRT1062CVL5B
** MIMXRT1062DVJ6A
** MIMXRT1062DVJ6B
** MIMXRT1062DVL6A
** MIMXRT1062DVL6B
** MIMXRT1062DVN6B
** MIMXRT1062XVN5B
** MIMXRT106ADVL6A
** MIMXRT106CDVL6A
** MIMXRT106FDVL6A
** MIMXRT106LDVL6A
** MIMXRT106SDVL6A
**
** Version: rev. 1.4, 2022-03-25
** Build: b240705
**
** Abstract:
** CMSIS Peripheral Access Layer for ADC
**
** Copyright 1997-2016 Freescale Semiconductor, Inc.
** Copyright 2016-2024 NXP
** SPDX-License-Identifier: BSD-3-Clause
**
** http: www.nxp.com
** mail: support@nxp.com
**
** Revisions:
** - rev. 0.1 (2017-01-10)
** Initial version.
** - rev. 1.0 (2018-11-16)
** Update header files to align with IMXRT1060RM Rev.0.
** - rev. 1.1 (2018-11-27)
** Update header files to align with IMXRT1060RM Rev.1.
** - rev. 1.2 (2019-04-29)
** Add SET/CLR/TOG register group to register CTRL, STAT, CHANNELCTRL, CH0STAT, CH0OPTS, CH1STAT, CH1OPTS, CH2STAT, CH2OPTS, CH3STAT, CH3OPTS of DCP module.
** - rev. 1.3 (2021-08-10)
** Update header files to align with IMXRT1060RM Rev.3.
** - rev. 1.4 (2022-03-25)
** Add RT1060X device
**
** ###################################################################
*/
/*!
* @file ADC.h
* @version 1.4
* @date 2022-03-25
* @brief CMSIS Peripheral Access Layer for ADC
*
* CMSIS Peripheral Access Layer for ADC
*/
#if !defined(ADC_H_)
#define ADC_H_ /**< Symbol preventing repeated inclusion */
#if (defined(CPU_MIMXRT1061CVJ5A) || defined(CPU_MIMXRT1061CVJ5B) || defined(CPU_MIMXRT1061CVL5A) || defined(CPU_MIMXRT1061CVL5B) || defined(CPU_MIMXRT1061DVJ6A) || defined(CPU_MIMXRT1061DVJ6B) || defined(CPU_MIMXRT1061DVL6A) || defined(CPU_MIMXRT1061DVL6B) || defined(CPU_MIMXRT1061XVN5B))
#include "MIMXRT1061_COMMON.h"
#elif (defined(CPU_MIMXRT1062CVJ5A) || defined(CPU_MIMXRT1062CVJ5B) || defined(CPU_MIMXRT1062CVL5A) || defined(CPU_MIMXRT1062CVL5B) || defined(CPU_MIMXRT1062DVJ6A) || defined(CPU_MIMXRT1062DVJ6B) || defined(CPU_MIMXRT1062DVL6A) || defined(CPU_MIMXRT1062DVL6B) || defined(CPU_MIMXRT1062DVN6B) || defined(CPU_MIMXRT1062XVN5B))
#include "MIMXRT1062_COMMON.h"
#elif (defined(CPU_MIMXRT106ADVL6A))
#include "MIMXRT106A_COMMON.h"
#elif (defined(CPU_MIMXRT106CDVL6A))
#include "MIMXRT106C_COMMON.h"
#elif (defined(CPU_MIMXRT106FDVL6A))
#include "MIMXRT106F_COMMON.h"
#elif (defined(CPU_MIMXRT106LDVL6A))
#include "MIMXRT106L_COMMON.h"
#elif (defined(CPU_MIMXRT106SDVL6A))
#include "MIMXRT106S_COMMON.h"
#else
#error "No valid CPU defined!"
#endif
/* ----------------------------------------------------------------------------
-- 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 - Size of Registers Arrays */
#define ADC_HC_COUNT 8u
#define ADC_R_COUNT 8u
/** ADC - Register Layout Typedef */
typedef struct {
__IO uint32_t HC[ADC_HC_COUNT]; /**< Control register for hardware triggers, array offset: 0x0, array step: 0x4 */
__I uint32_t HS; /**< Status register for HW triggers, offset: 0x20 */
__I uint32_t R[ADC_R_COUNT]; /**< Data result register for HW triggers, array offset: 0x24, array step: 0x4 */
__IO uint32_t CFG; /**< Configuration register, offset: 0x44 */
__IO uint32_t GC; /**< General control register, offset: 0x48 */
__IO uint32_t GS; /**< General status register, offset: 0x4C */
__IO uint32_t CV; /**< Compare value register, offset: 0x50 */
__IO uint32_t OFS; /**< Offset correction value register, offset: 0x54 */
__IO uint32_t CAL; /**< Calibration value register, offset: 0x58 */
} ADC_Type;
/* ----------------------------------------------------------------------------
-- ADC Register Masks
---------------------------------------------------------------------------- */
/*!
* @addtogroup ADC_Register_Masks ADC Register Masks
* @{
*/
/*! @name HC - Control register for hardware triggers */
/*! @{ */
#define ADC_HC_ADCH_MASK (0x1FU)
#define ADC_HC_ADCH_SHIFT (0U)
/*! ADCH - Input Channel Select
* 0b00000-0b01111..External channels 0 to 15 See External Signals for more information
* 0b10000..External channel selection from ADC_ETC
* 0b10001-0b10111..Reserved
* 0b11000..Reserved.
* 0b11001..VREFSH = internal channel, for ADC self-test, hard connected to VRH internally
* 0b11010..Reserved.
* 0b11011..Reserved.
* 0b11100-0b11110..Reserved.
* 0b11111..Conversion Disabled. Hardware Triggers will not initiate any conversion.
*/
#define ADC_HC_ADCH(x) (((uint32_t)(((uint32_t)(x)) << ADC_HC_ADCH_SHIFT)) & ADC_HC_ADCH_MASK)
#define ADC_HC_AIEN_MASK (0x80U)
#define ADC_HC_AIEN_SHIFT (7U)
/*! AIEN - Conversion Complete Interrupt Enable/Disable Control
* 0b1..Conversion complete interrupt enabled
* 0b0..Conversion complete interrupt disabled
*/
#define ADC_HC_AIEN(x) (((uint32_t)(((uint32_t)(x)) << ADC_HC_AIEN_SHIFT)) & ADC_HC_AIEN_MASK)
/*! @} */
/*! @name HS - Status register for HW triggers */
/*! @{ */
#define ADC_HS_COCO0_MASK (0x1U)
#define ADC_HS_COCO0_SHIFT (0U)
/*! COCO0 - Conversion Complete Flag */
#define ADC_HS_COCO0(x) (((uint32_t)(((uint32_t)(x)) << ADC_HS_COCO0_SHIFT)) & ADC_HS_COCO0_MASK)
#define ADC_HS_COCO1_MASK (0x2U)
#define ADC_HS_COCO1_SHIFT (1U)
/*! COCO1 - Conversion Complete Flag */
#define ADC_HS_COCO1(x) (((uint32_t)(((uint32_t)(x)) << ADC_HS_COCO1_SHIFT)) & ADC_HS_COCO1_MASK)
#define ADC_HS_COCO2_MASK (0x4U)
#define ADC_HS_COCO2_SHIFT (2U)
#define ADC_HS_COCO2(x) (((uint32_t)(((uint32_t)(x)) << ADC_HS_COCO2_SHIFT)) & ADC_HS_COCO2_MASK)
#define ADC_HS_COCO3_MASK (0x8U)
#define ADC_HS_COCO3_SHIFT (3U)
#define ADC_HS_COCO3(x) (((uint32_t)(((uint32_t)(x)) << ADC_HS_COCO3_SHIFT)) & ADC_HS_COCO3_MASK)
#define ADC_HS_COCO4_MASK (0x10U)
#define ADC_HS_COCO4_SHIFT (4U)
#define ADC_HS_COCO4(x) (((uint32_t)(((uint32_t)(x)) << ADC_HS_COCO4_SHIFT)) & ADC_HS_COCO4_MASK)
#define ADC_HS_COCO5_MASK (0x20U)
#define ADC_HS_COCO5_SHIFT (5U)
#define ADC_HS_COCO5(x) (((uint32_t)(((uint32_t)(x)) << ADC_HS_COCO5_SHIFT)) & ADC_HS_COCO5_MASK)
#define ADC_HS_COCO6_MASK (0x40U)
#define ADC_HS_COCO6_SHIFT (6U)
#define ADC_HS_COCO6(x) (((uint32_t)(((uint32_t)(x)) << ADC_HS_COCO6_SHIFT)) & ADC_HS_COCO6_MASK)
#define ADC_HS_COCO7_MASK (0x80U)
#define ADC_HS_COCO7_SHIFT (7U)
#define ADC_HS_COCO7(x) (((uint32_t)(((uint32_t)(x)) << ADC_HS_COCO7_SHIFT)) & ADC_HS_COCO7_MASK)
/*! @} */
/*! @name R - Data result register for HW triggers */
/*! @{ */
#define ADC_R_CDATA_MASK (0xFFFU)
#define ADC_R_CDATA_SHIFT (0U)
/*! CDATA - Data (result of an ADC conversion) */
#define ADC_R_CDATA(x) (((uint32_t)(((uint32_t)(x)) << ADC_R_CDATA_SHIFT)) & ADC_R_CDATA_MASK)
/*! @} */
/*! @name CFG - Configuration register */
/*! @{ */
#define ADC_CFG_ADICLK_MASK (0x3U)
#define ADC_CFG_ADICLK_SHIFT (0U)
/*! ADICLK - Input Clock Select
* 0b00..IPG clock
* 0b01..IPG clock divided by 2
* 0b10..Reserved
* 0b11..Asynchronous clock (ADACK)
*/
#define ADC_CFG_ADICLK(x) (((uint32_t)(((uint32_t)(x)) << ADC_CFG_ADICLK_SHIFT)) & ADC_CFG_ADICLK_MASK)
#define ADC_CFG_MODE_MASK (0xCU)
#define ADC_CFG_MODE_SHIFT (2U)
/*! MODE - Conversion Mode Selection
* 0b00..8-bit conversion
* 0b01..10-bit conversion
* 0b10..12-bit conversion
* 0b11..Reserved
*/
#define ADC_CFG_MODE(x) (((uint32_t)(((uint32_t)(x)) << ADC_CFG_MODE_SHIFT)) & ADC_CFG_MODE_MASK)
#define ADC_CFG_ADLSMP_MASK (0x10U)
#define ADC_CFG_ADLSMP_SHIFT (4U)
/*! ADLSMP - Long Sample Time Configuration
* 0b0..Short sample mode.
* 0b1..Long sample mode.
*/
#define ADC_CFG_ADLSMP(x) (((uint32_t)(((uint32_t)(x)) << ADC_CFG_ADLSMP_SHIFT)) & ADC_CFG_ADLSMP_MASK)
#define ADC_CFG_ADIV_MASK (0x60U)
#define ADC_CFG_ADIV_SHIFT (5U)
/*! ADIV - Clock Divide Select
* 0b00..Input clock
* 0b01..Input clock / 2
* 0b10..Input clock / 4
* 0b11..Input clock / 8
*/
#define ADC_CFG_ADIV(x) (((uint32_t)(((uint32_t)(x)) << ADC_CFG_ADIV_SHIFT)) & ADC_CFG_ADIV_MASK)
#define ADC_CFG_ADLPC_MASK (0x80U)
#define ADC_CFG_ADLPC_SHIFT (7U)
/*! ADLPC - Low-Power Configuration
* 0b0..ADC hard block not in low power mode.
* 0b1..ADC hard block in low power mode.
*/
#define ADC_CFG_ADLPC(x) (((uint32_t)(((uint32_t)(x)) << ADC_CFG_ADLPC_SHIFT)) & ADC_CFG_ADLPC_MASK)
#define ADC_CFG_ADSTS_MASK (0x300U)
#define ADC_CFG_ADSTS_SHIFT (8U)
/*! ADSTS
* 0b00..Sample period (ADC clocks) = 3 if ADLSMP=0b Sample period (ADC clocks) = 13 if ADLSMP=1b
* 0b01..Sample period (ADC clocks) = 5 if ADLSMP=0b Sample period (ADC clocks) = 17 if ADLSMP=1b
* 0b10..Sample period (ADC clocks) = 7 if ADLSMP=0b Sample period (ADC clocks) = 21 if ADLSMP=1b
* 0b11..Sample period (ADC clocks) = 9 if ADLSMP=0b Sample period (ADC clocks) = 25 if ADLSMP=1b
*/
#define ADC_CFG_ADSTS(x) (((uint32_t)(((uint32_t)(x)) << ADC_CFG_ADSTS_SHIFT)) & ADC_CFG_ADSTS_MASK)
#define ADC_CFG_ADHSC_MASK (0x400U)
#define ADC_CFG_ADHSC_SHIFT (10U)
/*! ADHSC - High Speed Configuration
* 0b0..Normal conversion selected.
* 0b1..High speed conversion selected.
*/
#define ADC_CFG_ADHSC(x) (((uint32_t)(((uint32_t)(x)) << ADC_CFG_ADHSC_SHIFT)) & ADC_CFG_ADHSC_MASK)
#define ADC_CFG_REFSEL_MASK (0x1800U)
#define ADC_CFG_REFSEL_SHIFT (11U)
/*! REFSEL - Voltage Reference Selection
* 0b00..Selects VREFH/VREFL as reference voltage.
* 0b01..Reserved
* 0b10..Reserved
* 0b11..Reserved
*/
#define ADC_CFG_REFSEL(x) (((uint32_t)(((uint32_t)(x)) << ADC_CFG_REFSEL_SHIFT)) & ADC_CFG_REFSEL_MASK)
#define ADC_CFG_ADTRG_MASK (0x2000U)
#define ADC_CFG_ADTRG_SHIFT (13U)
/*! ADTRG - Conversion Trigger Select
* 0b0..Software trigger selected
* 0b1..Hardware trigger selected
*/
#define ADC_CFG_ADTRG(x) (((uint32_t)(((uint32_t)(x)) << ADC_CFG_ADTRG_SHIFT)) & ADC_CFG_ADTRG_MASK)
#define ADC_CFG_AVGS_MASK (0xC000U)
#define ADC_CFG_AVGS_SHIFT (14U)
/*! AVGS - Hardware Average select
* 0b00..4 samples averaged
* 0b01..8 samples averaged
* 0b10..16 samples averaged
* 0b11..32 samples averaged
*/
#define ADC_CFG_AVGS(x) (((uint32_t)(((uint32_t)(x)) << ADC_CFG_AVGS_SHIFT)) & ADC_CFG_AVGS_MASK)
#define ADC_CFG_OVWREN_MASK (0x10000U)
#define ADC_CFG_OVWREN_SHIFT (16U)
/*! OVWREN - Data Overwrite Enable
* 0b1..Enable the overwriting.
* 0b0..Disable the overwriting. Existing Data in Data result register will not be overwritten by subsequent converted data.
*/
#define ADC_CFG_OVWREN(x) (((uint32_t)(((uint32_t)(x)) << ADC_CFG_OVWREN_SHIFT)) & ADC_CFG_OVWREN_MASK)
/*! @} */
/*! @name GC - General control register */
/*! @{ */
#define ADC_GC_ADACKEN_MASK (0x1U)
#define ADC_GC_ADACKEN_SHIFT (0U)
/*! ADACKEN - Asynchronous clock output enable
* 0b0..Asynchronous clock output disabled; Asynchronous clock only enabled if selected by ADICLK and a conversion is active.
* 0b1..Asynchronous clock and clock output enabled regardless of the state of the ADC
*/
#define ADC_GC_ADACKEN(x) (((uint32_t)(((uint32_t)(x)) << ADC_GC_ADACKEN_SHIFT)) & ADC_GC_ADACKEN_MASK)
#define ADC_GC_DMAEN_MASK (0x2U)
#define ADC_GC_DMAEN_SHIFT (1U)
/*! DMAEN - DMA Enable
* 0b0..DMA disabled (default)
* 0b1..DMA enabled
*/
#define ADC_GC_DMAEN(x) (((uint32_t)(((uint32_t)(x)) << ADC_GC_DMAEN_SHIFT)) & ADC_GC_DMAEN_MASK)
#define ADC_GC_ACREN_MASK (0x4U)
#define ADC_GC_ACREN_SHIFT (2U)
/*! ACREN - Compare Function Range Enable
* 0b0..Range function disabled. Only the compare value 1 of ADC_CV register (CV1) is compared.
* 0b1..Range function enabled. Both compare values of ADC_CV registers (CV1 and CV2) are compared.
*/
#define ADC_GC_ACREN(x) (((uint32_t)(((uint32_t)(x)) << ADC_GC_ACREN_SHIFT)) & ADC_GC_ACREN_MASK)
#define ADC_GC_ACFGT_MASK (0x8U)
#define ADC_GC_ACFGT_SHIFT (3U)
/*! ACFGT - Compare Function Greater Than Enable
* 0b0..Configures "Less Than Threshold, Outside Range Not Inclusive and Inside Range Not Inclusive"
* functionality based on the values placed in the ADC_CV register.
* 0b1..Configures "Greater Than Or Equal To Threshold, Outside Range Inclusive and Inside Range Inclusive"
* functionality based on the values placed in the ADC_CV registers.
*/
#define ADC_GC_ACFGT(x) (((uint32_t)(((uint32_t)(x)) << ADC_GC_ACFGT_SHIFT)) & ADC_GC_ACFGT_MASK)
#define ADC_GC_ACFE_MASK (0x10U)
#define ADC_GC_ACFE_SHIFT (4U)
/*! ACFE - Compare Function Enable
* 0b0..Compare function disabled
* 0b1..Compare function enabled
*/
#define ADC_GC_ACFE(x) (((uint32_t)(((uint32_t)(x)) << ADC_GC_ACFE_SHIFT)) & ADC_GC_ACFE_MASK)
#define ADC_GC_AVGE_MASK (0x20U)
#define ADC_GC_AVGE_SHIFT (5U)
/*! AVGE - Hardware average enable
* 0b0..Hardware average function disabled
* 0b1..Hardware average function enabled
*/
#define ADC_GC_AVGE(x) (((uint32_t)(((uint32_t)(x)) << ADC_GC_AVGE_SHIFT)) & ADC_GC_AVGE_MASK)
#define ADC_GC_ADCO_MASK (0x40U)
#define ADC_GC_ADCO_SHIFT (6U)
/*! ADCO - Continuous Conversion Enable
* 0b0..One conversion or one set of conversions if the hardware average function is enabled (AVGE=1) after initiating a conversion.
* 0b1..Continuous conversions or sets of conversions if the hardware average function is enabled (AVGE=1) after initiating a conversion.
*/
#define ADC_GC_ADCO(x) (((uint32_t)(((uint32_t)(x)) << ADC_GC_ADCO_SHIFT)) & ADC_GC_ADCO_MASK)
#define ADC_GC_CAL_MASK (0x80U)
#define ADC_GC_CAL_SHIFT (7U)
/*! CAL - Calibration */
#define ADC_GC_CAL(x) (((uint32_t)(((uint32_t)(x)) << ADC_GC_CAL_SHIFT)) & ADC_GC_CAL_MASK)
/*! @} */
/*! @name GS - General status register */
/*! @{ */
#define ADC_GS_ADACT_MASK (0x1U)
#define ADC_GS_ADACT_SHIFT (0U)
/*! ADACT - Conversion Active
* 0b0..Conversion not in progress.
* 0b1..Conversion in progress.
*/
#define ADC_GS_ADACT(x) (((uint32_t)(((uint32_t)(x)) << ADC_GS_ADACT_SHIFT)) & ADC_GS_ADACT_MASK)
#define ADC_GS_CALF_MASK (0x2U)
#define ADC_GS_CALF_SHIFT (1U)
/*! CALF - Calibration Failed Flag
* 0b0..Calibration completed normally.
* 0b1..Calibration failed. ADC accuracy specifications are not guaranteed.
*/
#define ADC_GS_CALF(x) (((uint32_t)(((uint32_t)(x)) << ADC_GS_CALF_SHIFT)) & ADC_GS_CALF_MASK)
#define ADC_GS_AWKST_MASK (0x4U)
#define ADC_GS_AWKST_SHIFT (2U)
/*! AWKST - Asynchronous wakeup interrupt status
* 0b1..Asynchronous wake up interrupt occurred in stop mode.
* 0b0..No asynchronous interrupt.
*/
#define ADC_GS_AWKST(x) (((uint32_t)(((uint32_t)(x)) << ADC_GS_AWKST_SHIFT)) & ADC_GS_AWKST_MASK)
/*! @} */
/*! @name CV - Compare value register */
/*! @{ */
#define ADC_CV_CV1_MASK (0xFFFU)
#define ADC_CV_CV1_SHIFT (0U)
/*! CV1 - Compare Value 1 */
#define ADC_CV_CV1(x) (((uint32_t)(((uint32_t)(x)) << ADC_CV_CV1_SHIFT)) & ADC_CV_CV1_MASK)
#define ADC_CV_CV2_MASK (0xFFF0000U)
#define ADC_CV_CV2_SHIFT (16U)
/*! CV2 - Compare Value 2 */
#define ADC_CV_CV2(x) (((uint32_t)(((uint32_t)(x)) << ADC_CV_CV2_SHIFT)) & ADC_CV_CV2_MASK)
/*! @} */
/*! @name OFS - Offset correction value register */
/*! @{ */
#define ADC_OFS_OFS_MASK (0xFFFU)
#define ADC_OFS_OFS_SHIFT (0U)
/*! OFS - Offset value */
#define ADC_OFS_OFS(x) (((uint32_t)(((uint32_t)(x)) << ADC_OFS_OFS_SHIFT)) & ADC_OFS_OFS_MASK)
#define ADC_OFS_SIGN_MASK (0x1000U)
#define ADC_OFS_SIGN_SHIFT (12U)
/*! SIGN - Sign bit
* 0b0..The offset value is added with the raw result
* 0b1..The offset value is subtracted from the raw converted value
*/
#define ADC_OFS_SIGN(x) (((uint32_t)(((uint32_t)(x)) << ADC_OFS_SIGN_SHIFT)) & ADC_OFS_SIGN_MASK)
/*! @} */
/*! @name CAL - Calibration value register */
/*! @{ */
#define ADC_CAL_CAL_CODE_MASK (0xFU)
#define ADC_CAL_CAL_CODE_SHIFT (0U)
/*! CAL_CODE - Calibration Result Value */
#define ADC_CAL_CAL_CODE(x) (((uint32_t)(((uint32_t)(x)) << ADC_CAL_CAL_CODE_SHIFT)) & ADC_CAL_CAL_CODE_MASK)
/*! @} */
/*!
* @}
*/ /* end of group ADC_Register_Masks */
/*!
* @}
*/ /* end of group ADC_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 */
#endif /* ADC_H_ */

View File

@ -0,0 +1,874 @@
/*
** ###################################################################
** Processors: MIMXRT1061CVJ5A
** MIMXRT1061CVJ5B
** MIMXRT1061CVL5A
** MIMXRT1061CVL5B
** MIMXRT1061DVJ6A
** MIMXRT1061DVJ6B
** MIMXRT1061DVL6A
** MIMXRT1061DVL6B
** MIMXRT1061XVN5B
** MIMXRT1062CVJ5A
** MIMXRT1062CVJ5B
** MIMXRT1062CVL5A
** MIMXRT1062CVL5B
** MIMXRT1062DVJ6A
** MIMXRT1062DVJ6B
** MIMXRT1062DVL6A
** MIMXRT1062DVL6B
** MIMXRT1062DVN6B
** MIMXRT1062XVN5B
** MIMXRT106ADVL6A
** MIMXRT106CDVL6A
** MIMXRT106FDVL6A
** MIMXRT106LDVL6A
** MIMXRT106SDVL6A
**
** Version: rev. 1.4, 2022-03-25
** Build: b240705
**
** Abstract:
** CMSIS Peripheral Access Layer for AIPSTZ
**
** Copyright 1997-2016 Freescale Semiconductor, Inc.
** Copyright 2016-2024 NXP
** SPDX-License-Identifier: BSD-3-Clause
**
** http: www.nxp.com
** mail: support@nxp.com
**
** Revisions:
** - rev. 0.1 (2017-01-10)
** Initial version.
** - rev. 1.0 (2018-11-16)
** Update header files to align with IMXRT1060RM Rev.0.
** - rev. 1.1 (2018-11-27)
** Update header files to align with IMXRT1060RM Rev.1.
** - rev. 1.2 (2019-04-29)
** Add SET/CLR/TOG register group to register CTRL, STAT, CHANNELCTRL, CH0STAT, CH0OPTS, CH1STAT, CH1OPTS, CH2STAT, CH2OPTS, CH3STAT, CH3OPTS of DCP module.
** - rev. 1.3 (2021-08-10)
** Update header files to align with IMXRT1060RM Rev.3.
** - rev. 1.4 (2022-03-25)
** Add RT1060X device
**
** ###################################################################
*/
/*!
* @file AIPSTZ.h
* @version 1.4
* @date 2022-03-25
* @brief CMSIS Peripheral Access Layer for AIPSTZ
*
* CMSIS Peripheral Access Layer for AIPSTZ
*/
#if !defined(AIPSTZ_H_)
#define AIPSTZ_H_ /**< Symbol preventing repeated inclusion */
#if (defined(CPU_MIMXRT1061CVJ5A) || defined(CPU_MIMXRT1061CVJ5B) || defined(CPU_MIMXRT1061CVL5A) || defined(CPU_MIMXRT1061CVL5B) || defined(CPU_MIMXRT1061DVJ6A) || defined(CPU_MIMXRT1061DVJ6B) || defined(CPU_MIMXRT1061DVL6A) || defined(CPU_MIMXRT1061DVL6B) || defined(CPU_MIMXRT1061XVN5B))
#include "MIMXRT1061_COMMON.h"
#elif (defined(CPU_MIMXRT1062CVJ5A) || defined(CPU_MIMXRT1062CVJ5B) || defined(CPU_MIMXRT1062CVL5A) || defined(CPU_MIMXRT1062CVL5B) || defined(CPU_MIMXRT1062DVJ6A) || defined(CPU_MIMXRT1062DVJ6B) || defined(CPU_MIMXRT1062DVL6A) || defined(CPU_MIMXRT1062DVL6B) || defined(CPU_MIMXRT1062DVN6B) || defined(CPU_MIMXRT1062XVN5B))
#include "MIMXRT1062_COMMON.h"
#elif (defined(CPU_MIMXRT106ADVL6A))
#include "MIMXRT106A_COMMON.h"
#elif (defined(CPU_MIMXRT106CDVL6A))
#include "MIMXRT106C_COMMON.h"
#elif (defined(CPU_MIMXRT106FDVL6A))
#include "MIMXRT106F_COMMON.h"
#elif (defined(CPU_MIMXRT106LDVL6A))
#include "MIMXRT106L_COMMON.h"
#elif (defined(CPU_MIMXRT106SDVL6A))
#include "MIMXRT106S_COMMON.h"
#else
#error "No valid CPU defined!"
#endif
/* ----------------------------------------------------------------------------
-- 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
/* ----------------------------------------------------------------------------
-- AIPSTZ Peripheral Access Layer
---------------------------------------------------------------------------- */
/*!
* @addtogroup AIPSTZ_Peripheral_Access_Layer AIPSTZ Peripheral Access Layer
* @{
*/
/** AIPSTZ - Register Layout Typedef */
typedef struct {
__IO uint32_t MPR; /**< Master Priviledge Registers, offset: 0x0 */
uint8_t RESERVED_0[60];
__IO uint32_t OPACR; /**< Off-Platform Peripheral Access Control Registers, offset: 0x40 */
__IO uint32_t OPACR1; /**< Off-Platform Peripheral Access Control Registers, offset: 0x44 */
__IO uint32_t OPACR2; /**< Off-Platform Peripheral Access Control Registers, offset: 0x48 */
__IO uint32_t OPACR3; /**< Off-Platform Peripheral Access Control Registers, offset: 0x4C */
__IO uint32_t OPACR4; /**< Off-Platform Peripheral Access Control Registers, offset: 0x50 */
} AIPSTZ_Type;
/* ----------------------------------------------------------------------------
-- AIPSTZ Register Masks
---------------------------------------------------------------------------- */
/*!
* @addtogroup AIPSTZ_Register_Masks AIPSTZ Register Masks
* @{
*/
/*! @name MPR - Master Priviledge Registers */
/*! @{ */
#define AIPSTZ_MPR_MPROT3_MASK (0xF0000U)
#define AIPSTZ_MPR_MPROT3_SHIFT (16U)
/*! MPROT3
* 0bxxx0..Accesses from this master are forced to user-mode (ips_supervisor_access is forced to zero) regardless of the hprot[1] access attribute.
* 0bxxx1..Accesses from this master are not forced to user-mode. The hprot[1] access attribute is used directly to determine ips_supervisor_access.
* 0bxx0x..This master is not trusted for write accesses.
* 0bxx1x..This master is trusted for write accesses.
* 0bx0xx..This master is not trusted for read accesses.
* 0bx1xx..This master is trusted for read accesses.
* 0b1xxx..Write accesses from this master are allowed to be buffered
*/
#define AIPSTZ_MPR_MPROT3(x) (((uint32_t)(((uint32_t)(x)) << AIPSTZ_MPR_MPROT3_SHIFT)) & AIPSTZ_MPR_MPROT3_MASK)
#define AIPSTZ_MPR_MPROT2_MASK (0xF00000U)
#define AIPSTZ_MPR_MPROT2_SHIFT (20U)
/*! MPROT2
* 0bxxx0..Accesses from this master are forced to user-mode (ips_supervisor_access is forced to zero) regardless of the hprot[1] access attribute.
* 0bxxx1..Accesses from this master are not forced to user-mode. The hprot[1] access attribute is used directly to determine ips_supervisor_access.
* 0bxx0x..This master is not trusted for write accesses.
* 0bxx1x..This master is trusted for write accesses.
* 0bx0xx..This master is not trusted for read accesses.
* 0bx1xx..This master is trusted for read accesses.
* 0b1xxx..Write accesses from this master are allowed to be buffered
*/
#define AIPSTZ_MPR_MPROT2(x) (((uint32_t)(((uint32_t)(x)) << AIPSTZ_MPR_MPROT2_SHIFT)) & AIPSTZ_MPR_MPROT2_MASK)
#define AIPSTZ_MPR_MPROT1_MASK (0xF000000U)
#define AIPSTZ_MPR_MPROT1_SHIFT (24U)
/*! MPROT1
* 0bxxx0..Accesses from this master are forced to user-mode (ips_supervisor_access is forced to zero) regardless of the hprot[1] access attribute.
* 0bxxx1..Accesses from this master are not forced to user-mode. The hprot[1] access attribute is used directly to determine ips_supervisor_access.
* 0bxx0x..This master is not trusted for write accesses.
* 0bxx1x..This master is trusted for write accesses.
* 0bx0xx..This master is not trusted for read accesses.
* 0bx1xx..This master is trusted for read accesses.
* 0b1xxx..Write accesses from this master are allowed to be buffered
*/
#define AIPSTZ_MPR_MPROT1(x) (((uint32_t)(((uint32_t)(x)) << AIPSTZ_MPR_MPROT1_SHIFT)) & AIPSTZ_MPR_MPROT1_MASK)
#define AIPSTZ_MPR_MPROT0_MASK (0xF0000000U)
#define AIPSTZ_MPR_MPROT0_SHIFT (28U)
/*! MPROT0
* 0bxxx0..Accesses from this master are forced to user-mode (ips_supervisor_access is forced to zero) regardless of the hprot[1] access attribute.
* 0bxxx1..Accesses from this master are not forced to user-mode. The hprot[1] access attribute is used directly to determine ips_supervisor_access.
* 0bxx0x..This master is not trusted for write accesses.
* 0bxx1x..This master is trusted for write accesses.
* 0bx0xx..This master is not trusted for read accesses.
* 0bx1xx..This master is trusted for read accesses.
* 0b1xxx..Write accesses from this master are allowed to be buffered
*/
#define AIPSTZ_MPR_MPROT0(x) (((uint32_t)(((uint32_t)(x)) << AIPSTZ_MPR_MPROT0_SHIFT)) & AIPSTZ_MPR_MPROT0_MASK)
/*! @} */
/*! @name OPACR - Off-Platform Peripheral Access Control Registers */
/*! @{ */
#define AIPSTZ_OPACR_OPAC7_MASK (0xFU)
#define AIPSTZ_OPACR_OPAC7_SHIFT (0U)
/*! OPAC7
* 0bxxx0..Accesses from an untrusted master are allowed.
* 0bxxx1..Accesses from an untrusted master are not allowed. If an access is attempted by an untrusted master,
* the access is terminated with an error response and no peripheral access is initiated on the IPS bus.
* 0bxx0x..This peripheral allows write accesses.
* 0bxx1x..This peripheral is write protected. If a write access is attempted, the access is terminated with an
* error response and no peripheral access is initiated on the IPS bus.
* 0bx0xx..This peripheral does not require supervisor privilege level for accesses.
* 0bx1xx..This peripheral requires supervisor privilege level for accesses. The master privilege level must
* indicate supervisor via the hprot[1] access attribute, and the MPROTx[MPL] control bit for the master must
* be set. If not, the access is terminated with an error response and no peripheral access is initiated
* on the IPS bus.
* 0b1xxx..Write accesses to this peripheral are allowed to be buffered by the AIPSTZ.
*/
#define AIPSTZ_OPACR_OPAC7(x) (((uint32_t)(((uint32_t)(x)) << AIPSTZ_OPACR_OPAC7_SHIFT)) & AIPSTZ_OPACR_OPAC7_MASK)
#define AIPSTZ_OPACR_OPAC6_MASK (0xF0U)
#define AIPSTZ_OPACR_OPAC6_SHIFT (4U)
/*! OPAC6
* 0bxxx0..Accesses from an untrusted master are allowed.
* 0bxxx1..Accesses from an untrusted master are not allowed. If an access is attempted by an untrusted master,
* the access is terminated with an error response and no peripheral access is initiated on the IPS bus.
* 0bxx0x..This peripheral allows write accesses.
* 0bxx1x..This peripheral is write protected. If a write access is attempted, the access is terminated with an
* error response and no peripheral access is initiated on the IPS bus.
* 0bx0xx..This peripheral does not require supervisor privilege level for accesses.
* 0bx1xx..This peripheral requires supervisor privilege level for accesses. The master privilege level must
* indicate supervisor via the hprot[1] access attribute, and the MPROTx[MPL] control bit for the master must
* be set. If not, the access is terminated with an error response and no peripheral access is initiated
* on the IPS bus.
* 0b1xxx..Write accesses to this peripheral are allowed to be buffered by the AIPSTZ.
*/
#define AIPSTZ_OPACR_OPAC6(x) (((uint32_t)(((uint32_t)(x)) << AIPSTZ_OPACR_OPAC6_SHIFT)) & AIPSTZ_OPACR_OPAC6_MASK)
#define AIPSTZ_OPACR_OPAC5_MASK (0xF00U)
#define AIPSTZ_OPACR_OPAC5_SHIFT (8U)
/*! OPAC5
* 0bxxx0..Accesses from an untrusted master are allowed.
* 0bxxx1..Accesses from an untrusted master are not allowed. If an access is attempted by an untrusted master,
* the access is terminated with an error response and no peripheral access is initiated on the IPS bus.
* 0bxx0x..This peripheral allows write accesses.
* 0bxx1x..This peripheral is write protected. If a write access is attempted, the access is terminated with an
* error response and no peripheral access is initiated on the IPS bus.
* 0bx0xx..This peripheral does not require supervisor privilege level for accesses.
* 0bx1xx..This peripheral requires supervisor privilege level for accesses. The master privilege level must
* indicate supervisor via the hprot[1] access attribute, and the MPROTx[MPL] control bit for the master must
* be set. If not, the access is terminated with an error response and no peripheral access is initiated
* on the IPS bus.
* 0b1xxx..Write accesses to this peripheral are allowed to be buffered by the AIPSTZ.
*/
#define AIPSTZ_OPACR_OPAC5(x) (((uint32_t)(((uint32_t)(x)) << AIPSTZ_OPACR_OPAC5_SHIFT)) & AIPSTZ_OPACR_OPAC5_MASK)
#define AIPSTZ_OPACR_OPAC4_MASK (0xF000U)
#define AIPSTZ_OPACR_OPAC4_SHIFT (12U)
/*! OPAC4
* 0bxxx0..Accesses from an untrusted master are allowed.
* 0bxxx1..Accesses from an untrusted master are not allowed. If an access is attempted by an untrusted master,
* the access is terminated with an error response and no peripheral access is initiated on the IPS bus.
* 0bxx0x..This peripheral allows write accesses.
* 0bxx1x..This peripheral is write protected. If a write access is attempted, the access is terminated with an
* error response and no peripheral access is initiated on the IPS bus.
* 0bx0xx..This peripheral does not require supervisor privilege level for accesses.
* 0bx1xx..This peripheral requires supervisor privilege level for accesses. The master privilege level must
* indicate supervisor via the hprot[1] access attribute, and the MPROTx[MPL] control bit for the master must
* be set. If not, the access is terminated with an error response and no peripheral access is initiated
* on the IPS bus.
* 0b1xxx..Write accesses to this peripheral are allowed to be buffered by the AIPSTZ.
*/
#define AIPSTZ_OPACR_OPAC4(x) (((uint32_t)(((uint32_t)(x)) << AIPSTZ_OPACR_OPAC4_SHIFT)) & AIPSTZ_OPACR_OPAC4_MASK)
#define AIPSTZ_OPACR_OPAC3_MASK (0xF0000U)
#define AIPSTZ_OPACR_OPAC3_SHIFT (16U)
/*! OPAC3
* 0bxxx0..Accesses from an untrusted master are allowed.
* 0bxxx1..Accesses from an untrusted master are not allowed. If an access is attempted by an untrusted master,
* the access is terminated with an error response and no peripheral access is initiated on the IPS bus.
* 0bxx0x..This peripheral allows write accesses.
* 0bxx1x..This peripheral is write protected. If a write access is attempted, the access is terminated with an
* error response and no peripheral access is initiated on the IPS bus.
* 0bx0xx..This peripheral does not require supervisor privilege level for accesses.
* 0bx1xx..This peripheral requires supervisor privilege level for accesses. The master privilege level must
* indicate supervisor via the hprot[1] access attribute, and the MPROTx[MPL] control bit for the master must
* be set. If not, the access is terminated with an error response and no peripheral access is initiated
* on the IPS bus.
* 0b1xxx..Write accesses to this peripheral are allowed to be buffered by the AIPSTZ.
*/
#define AIPSTZ_OPACR_OPAC3(x) (((uint32_t)(((uint32_t)(x)) << AIPSTZ_OPACR_OPAC3_SHIFT)) & AIPSTZ_OPACR_OPAC3_MASK)
#define AIPSTZ_OPACR_OPAC2_MASK (0xF00000U)
#define AIPSTZ_OPACR_OPAC2_SHIFT (20U)
/*! OPAC2
* 0bxxx0..Accesses from an untrusted master are allowed.
* 0bxxx1..Accesses from an untrusted master are not allowed. If an access is attempted by an untrusted master,
* the access is terminated with an error response and no peripheral access is initiated on the IPS bus.
* 0bxx0x..This peripheral allows write accesses.
* 0bxx1x..This peripheral is write protected. If a write access is attempted, the access is terminated with an
* error response and no peripheral access is initiated on the IPS bus.
* 0bx0xx..This peripheral does not require supervisor privilege level for accesses.
* 0bx1xx..This peripheral requires supervisor privilege level for accesses. The master privilege level must
* indicate supervisor via the hprot[1] access attribute, and the MPROTx[MPL] control bit for the master must
* be set. If not, the access is terminated with an error response and no peripheral access is initiated
* on the IPS bus.
* 0b1xxx..Write accesses to this peripheral are allowed to be buffered by the AIPSTZ.
*/
#define AIPSTZ_OPACR_OPAC2(x) (((uint32_t)(((uint32_t)(x)) << AIPSTZ_OPACR_OPAC2_SHIFT)) & AIPSTZ_OPACR_OPAC2_MASK)
#define AIPSTZ_OPACR_OPAC1_MASK (0xF000000U)
#define AIPSTZ_OPACR_OPAC1_SHIFT (24U)
/*! OPAC1
* 0bxxx0..Accesses from an untrusted master are allowed.
* 0bxxx1..Accesses from an untrusted master are not allowed. If an access is attempted by an untrusted master,
* the access is terminated with an error response and no peripheral access is initiated on the IPS bus.
* 0bxx0x..This peripheral allows write accesses.
* 0bxx1x..This peripheral is write protected. If a write access is attempted, the access is terminated with an
* error response and no peripheral access is initiated on the IPS bus.
* 0bx0xx..This peripheral does not require supervisor privilege level for accesses.
* 0bx1xx..This peripheral requires supervisor privilege level for accesses. The master privilege level must
* indicate supervisor via the hprot[1] access attribute, and the MPROTx[MPL] control bit for the master must
* be set. If not, the access is terminated with an error response and no peripheral access is initiated
* on the IPS bus.
* 0b1xxx..Write accesses to this peripheral are allowed to be buffered by the AIPSTZ.
*/
#define AIPSTZ_OPACR_OPAC1(x) (((uint32_t)(((uint32_t)(x)) << AIPSTZ_OPACR_OPAC1_SHIFT)) & AIPSTZ_OPACR_OPAC1_MASK)
#define AIPSTZ_OPACR_OPAC0_MASK (0xF0000000U)
#define AIPSTZ_OPACR_OPAC0_SHIFT (28U)
/*! OPAC0
* 0bxxx0..Accesses from an untrusted master are allowed.
* 0bxxx1..Accesses from an untrusted master are not allowed. If an access is attempted by an untrusted master,
* the access is terminated with an error response and no peripheral access is initiated on the IPS bus.
* 0bxx0x..This peripheral allows write accesses.
* 0bxx1x..This peripheral is write protected. If a write access is attempted, the access is terminated with an
* error response and no peripheral access is initiated on the IPS bus.
* 0bx0xx..This peripheral does not require supervisor privilege level for accesses.
* 0bx1xx..This peripheral requires supervisor privilege level for accesses. The master privilege level must
* indicate supervisor via the hprot[1] access attribute, and the MPROTx[MPL] control bit for the master must
* be set. If not, the access is terminated with an error response and no peripheral access is initiated
* on the IPS bus.
* 0b1xxx..Write accesses to this peripheral are allowed to be buffered by the AIPSTZ.
*/
#define AIPSTZ_OPACR_OPAC0(x) (((uint32_t)(((uint32_t)(x)) << AIPSTZ_OPACR_OPAC0_SHIFT)) & AIPSTZ_OPACR_OPAC0_MASK)
/*! @} */
/*! @name OPACR1 - Off-Platform Peripheral Access Control Registers */
/*! @{ */
#define AIPSTZ_OPACR1_OPAC15_MASK (0xFU)
#define AIPSTZ_OPACR1_OPAC15_SHIFT (0U)
/*! OPAC15
* 0bxxx0..Accesses from an untrusted master are allowed.
* 0bxxx1..Accesses from an untrusted master are not allowed. If an access is attempted by an untrusted master,
* the access is terminated with an error response and no peripheral access is initiated on the IPS bus.
* 0bxx0x..This peripheral allows write accesses.
* 0bxx1x..This peripheral is write protected. If a write access is attempted, the access is terminated with an
* error response and no peripheral access is initiated on the IPS bus.
* 0bx0xx..This peripheral does not require supervisor privilege level for accesses.
* 0bx1xx..This peripheral requires supervisor privilege level for accesses. The master privilege level must
* indicate supervisor via the hprot[1] access attribute, and the MPROTx[MPL] control bit for the master must
* be set. If not, the access is terminated with an error response and no peripheral access is initiated
* on the IPS bus.
* 0b1xxx..Write accesses to this peripheral are allowed to be buffered by the AIPSTZ.
*/
#define AIPSTZ_OPACR1_OPAC15(x) (((uint32_t)(((uint32_t)(x)) << AIPSTZ_OPACR1_OPAC15_SHIFT)) & AIPSTZ_OPACR1_OPAC15_MASK)
#define AIPSTZ_OPACR1_OPAC14_MASK (0xF0U)
#define AIPSTZ_OPACR1_OPAC14_SHIFT (4U)
/*! OPAC14
* 0bxxx0..Accesses from an untrusted master are allowed.
* 0bxxx1..Accesses from an untrusted master are not allowed. If an access is attempted by an untrusted master,
* the access is terminated with an error response and no peripheral access is initiated on the IPS bus.
* 0bxx0x..This peripheral allows write accesses.
* 0bxx1x..This peripheral is write protected. If a write access is attempted, the access is terminated with an
* error response and no peripheral access is initiated on the IPS bus.
* 0bx0xx..This peripheral does not require supervisor privilege level for accesses.
* 0bx1xx..This peripheral requires supervisor privilege level for accesses. The master privilege level must
* indicate supervisor via the hprot[1] access attribute, and the MPROTx[MPL] control bit for the master must
* be set. If not, the access is terminated with an error response and no peripheral access is initiated
* on the IPS bus.
* 0b1xxx..Write accesses to this peripheral are allowed to be buffered by the AIPSTZ.
*/
#define AIPSTZ_OPACR1_OPAC14(x) (((uint32_t)(((uint32_t)(x)) << AIPSTZ_OPACR1_OPAC14_SHIFT)) & AIPSTZ_OPACR1_OPAC14_MASK)
#define AIPSTZ_OPACR1_OPAC13_MASK (0xF00U)
#define AIPSTZ_OPACR1_OPAC13_SHIFT (8U)
/*! OPAC13
* 0bxxx0..Accesses from an untrusted master are allowed.
* 0bxxx1..Accesses from an untrusted master are not allowed. If an access is attempted by an untrusted master,
* the access is terminated with an error response and no peripheral access is initiated on the IPS bus.
* 0bxx0x..This peripheral allows write accesses.
* 0bxx1x..This peripheral is write protected. If a write access is attempted, the access is terminated with an
* error response and no peripheral access is initiated on the IPS bus.
* 0bx0xx..This peripheral does not require supervisor privilege level for accesses.
* 0bx1xx..This peripheral requires supervisor privilege level for accesses. The master privilege level must
* indicate supervisor via the hprot[1] access attribute, and the MPROTx[MPL] control bit for the master must
* be set. If not, the access is terminated with an error response and no peripheral access is initiated
* on the IPS bus.
* 0b1xxx..Write accesses to this peripheral are allowed to be buffered by the AIPSTZ.
*/
#define AIPSTZ_OPACR1_OPAC13(x) (((uint32_t)(((uint32_t)(x)) << AIPSTZ_OPACR1_OPAC13_SHIFT)) & AIPSTZ_OPACR1_OPAC13_MASK)
#define AIPSTZ_OPACR1_OPAC12_MASK (0xF000U)
#define AIPSTZ_OPACR1_OPAC12_SHIFT (12U)
/*! OPAC12
* 0bxxx0..Accesses from an untrusted master are allowed.
* 0bxxx1..Accesses from an untrusted master are not allowed. If an access is attempted by an untrusted master,
* the access is terminated with an error response and no peripheral access is initiated on the IPS bus.
* 0bxx0x..This peripheral allows write accesses.
* 0bxx1x..This peripheral is write protected. If a write access is attempted, the access is terminated with an
* error response and no peripheral access is initiated on the IPS bus.
* 0bx0xx..This peripheral does not require supervisor privilege level for accesses.
* 0bx1xx..This peripheral requires supervisor privilege level for accesses. The master privilege level must
* indicate supervisor via the hprot[1] access attribute, and the MPROTx[MPL] control bit for the master must
* be set. If not, the access is terminated with an error response and no peripheral access is initiated
* on the IPS bus.
* 0b1xxx..Write accesses to this peripheral are allowed to be buffered by the AIPSTZ.
*/
#define AIPSTZ_OPACR1_OPAC12(x) (((uint32_t)(((uint32_t)(x)) << AIPSTZ_OPACR1_OPAC12_SHIFT)) & AIPSTZ_OPACR1_OPAC12_MASK)
#define AIPSTZ_OPACR1_OPAC11_MASK (0xF0000U)
#define AIPSTZ_OPACR1_OPAC11_SHIFT (16U)
/*! OPAC11
* 0bxxx0..Accesses from an untrusted master are allowed.
* 0bxxx1..Accesses from an untrusted master are not allowed. If an access is attempted by an untrusted master,
* the access is terminated with an error response and no peripheral access is initiated on the IPS bus.
* 0bxx0x..This peripheral allows write accesses.
* 0bxx1x..This peripheral is write protected. If a write access is attempted, the access is terminated with an
* error response and no peripheral access is initiated on the IPS bus.
* 0bx0xx..This peripheral does not require supervisor privilege level for accesses.
* 0bx1xx..This peripheral requires supervisor privilege level for accesses. The master privilege level must
* indicate supervisor via the hprot[1] access attribute, and the MPROTx[MPL] control bit for the master must
* be set. If not, the access is terminated with an error response and no peripheral access is initiated
* on the IPS bus.
* 0b1xxx..Write accesses to this peripheral are allowed to be buffered by the AIPSTZ.
*/
#define AIPSTZ_OPACR1_OPAC11(x) (((uint32_t)(((uint32_t)(x)) << AIPSTZ_OPACR1_OPAC11_SHIFT)) & AIPSTZ_OPACR1_OPAC11_MASK)
#define AIPSTZ_OPACR1_OPAC10_MASK (0xF00000U)
#define AIPSTZ_OPACR1_OPAC10_SHIFT (20U)
/*! OPAC10
* 0bxxx0..Accesses from an untrusted master are allowed.
* 0bxxx1..Accesses from an untrusted master are not allowed. If an access is attempted by an untrusted master,
* the access is terminated with an error response and no peripheral access is initiated on the IPS bus.
* 0bxx0x..This peripheral allows write accesses.
* 0bxx1x..This peripheral is write protected. If a write access is attempted, the access is terminated with an
* error response and no peripheral access is initiated on the IPS bus.
* 0bx0xx..This peripheral does not require supervisor privilege level for accesses.
* 0bx1xx..This peripheral requires supervisor privilege level for accesses. The master privilege level must
* indicate supervisor via the hprot[1] access attribute, and the MPROTx[MPL] control bit for the master must
* be set. If not, the access is terminated with an error response and no peripheral access is initiated
* on the IPS bus.
* 0b1xxx..Write accesses to this peripheral are allowed to be buffered by the AIPSTZ.
*/
#define AIPSTZ_OPACR1_OPAC10(x) (((uint32_t)(((uint32_t)(x)) << AIPSTZ_OPACR1_OPAC10_SHIFT)) & AIPSTZ_OPACR1_OPAC10_MASK)
#define AIPSTZ_OPACR1_OPAC9_MASK (0xF000000U)
#define AIPSTZ_OPACR1_OPAC9_SHIFT (24U)
/*! OPAC9
* 0bxxx0..Accesses from an untrusted master are allowed.
* 0bxxx1..Accesses from an untrusted master are not allowed. If an access is attempted by an untrusted master,
* the access is terminated with an error response and no peripheral access is initiated on the IPS bus.
* 0bxx0x..This peripheral allows write accesses.
* 0bxx1x..This peripheral is write protected. If a write access is attempted, the access is terminated with an
* error response and no peripheral access is initiated on the IPS bus.
* 0bx0xx..This peripheral does not require supervisor privilege level for accesses.
* 0bx1xx..This peripheral requires supervisor privilege level for accesses. The master privilege level must
* indicate supervisor via the hprot[1] access attribute, and the MPROTx[MPL] control bit for the master must
* be set. If not, the access is terminated with an error response and no peripheral access is initiated
* on the IPS bus.
* 0b1xxx..Write accesses to this peripheral are allowed to be buffered by the AIPSTZ.
*/
#define AIPSTZ_OPACR1_OPAC9(x) (((uint32_t)(((uint32_t)(x)) << AIPSTZ_OPACR1_OPAC9_SHIFT)) & AIPSTZ_OPACR1_OPAC9_MASK)
#define AIPSTZ_OPACR1_OPAC8_MASK (0xF0000000U)
#define AIPSTZ_OPACR1_OPAC8_SHIFT (28U)
/*! OPAC8
* 0bxxx0..Accesses from an untrusted master are allowed.
* 0bxxx1..Accesses from an untrusted master are not allowed. If an access is attempted by an untrusted master,
* the access is terminated with an error response and no peripheral access is initiated on the IPS bus.
* 0bxx0x..This peripheral allows write accesses.
* 0bxx1x..This peripheral is write protected. If a write access is attempted, the access is terminated with an
* error response and no peripheral access is initiated on the IPS bus.
* 0bx0xx..This peripheral does not require supervisor privilege level for accesses.
* 0bx1xx..This peripheral requires supervisor privilege level for accesses. The master privilege level must
* indicate supervisor via the hprot[1] access attribute, and the MPROTx[MPL] control bit for the master must
* be set. If not, the access is terminated with an error response and no peripheral access is initiated
* on the IPS bus.
* 0b1xxx..Write accesses to this peripheral are allowed to be buffered by the AIPSTZ.
*/
#define AIPSTZ_OPACR1_OPAC8(x) (((uint32_t)(((uint32_t)(x)) << AIPSTZ_OPACR1_OPAC8_SHIFT)) & AIPSTZ_OPACR1_OPAC8_MASK)
/*! @} */
/*! @name OPACR2 - Off-Platform Peripheral Access Control Registers */
/*! @{ */
#define AIPSTZ_OPACR2_OPAC23_MASK (0xFU)
#define AIPSTZ_OPACR2_OPAC23_SHIFT (0U)
/*! OPAC23
* 0bxxx0..Accesses from an untrusted master are allowed.
* 0bxxx1..Accesses from an untrusted master are not allowed. If an access is attempted by an untrusted master,
* the access is terminated with an error response and no peripheral access is initiated on the IPS bus.
* 0bxx0x..This peripheral allows write accesses.
* 0bxx1x..This peripheral is write protected. If a write access is attempted, the access is terminated with an
* error response and no peripheral access is initiated on the IPS bus.
* 0bx0xx..This peripheral does not require supervisor privilege level for accesses.
* 0bx1xx..This peripheral requires supervisor privilege level for accesses. The master privilege level must
* indicate supervisor via the hprot[1] access attribute, and the MPROTx[MPL] control bit for the master must
* be set. If not, the access is terminated with an error response and no peripheral access is initiated
* on the IPS bus.
* 0b1xxx..Write accesses to this peripheral are allowed to be buffered by the AIPSTZ.
*/
#define AIPSTZ_OPACR2_OPAC23(x) (((uint32_t)(((uint32_t)(x)) << AIPSTZ_OPACR2_OPAC23_SHIFT)) & AIPSTZ_OPACR2_OPAC23_MASK)
#define AIPSTZ_OPACR2_OPAC22_MASK (0xF0U)
#define AIPSTZ_OPACR2_OPAC22_SHIFT (4U)
/*! OPAC22
* 0bxxx0..Accesses from an untrusted master are allowed.
* 0bxxx1..Accesses from an untrusted master are not allowed. If an access is attempted by an untrusted master,
* the access is terminated with an error response and no peripheral access is initiated on the IPS bus.
* 0bxx0x..This peripheral allows write accesses.
* 0bxx1x..This peripheral is write protected. If a write access is attempted, the access is terminated with an
* error response and no peripheral access is initiated on the IPS bus.
* 0bx0xx..This peripheral does not require supervisor privilege level for accesses.
* 0bx1xx..This peripheral requires supervisor privilege level for accesses. The master privilege level must
* indicate supervisor via the hprot[1] access attribute, and the MPROTx[MPL] control bit for the master must
* be set. If not, the access is terminated with an error response and no peripheral access is initiated
* on the IPS bus.
* 0b1xxx..Write accesses to this peripheral are allowed to be buffered by the AIPSTZ.
*/
#define AIPSTZ_OPACR2_OPAC22(x) (((uint32_t)(((uint32_t)(x)) << AIPSTZ_OPACR2_OPAC22_SHIFT)) & AIPSTZ_OPACR2_OPAC22_MASK)
#define AIPSTZ_OPACR2_OPAC21_MASK (0xF00U)
#define AIPSTZ_OPACR2_OPAC21_SHIFT (8U)
/*! OPAC21
* 0bxxx0..Accesses from an untrusted master are allowed.
* 0bxxx1..Accesses from an untrusted master are not allowed. If an access is attempted by an untrusted master,
* the access is terminated with an error response and no peripheral access is initiated on the IPS bus.
* 0bxx0x..This peripheral allows write accesses.
* 0bxx1x..This peripheral is write protected. If a write access is attempted, the access is terminated with an
* error response and no peripheral access is initiated on the IPS bus.
* 0bx0xx..This peripheral does not require supervisor privilege level for accesses.
* 0bx1xx..This peripheral requires supervisor privilege level for accesses. The master privilege level must
* indicate supervisor via the hprot[1] access attribute, and the MPROTx[MPL] control bit for the master must
* be set. If not, the access is terminated with an error response and no peripheral access is initiated
* on the IPS bus.
* 0b1xxx..Write accesses to this peripheral are allowed to be buffered by the AIPSTZ.
*/
#define AIPSTZ_OPACR2_OPAC21(x) (((uint32_t)(((uint32_t)(x)) << AIPSTZ_OPACR2_OPAC21_SHIFT)) & AIPSTZ_OPACR2_OPAC21_MASK)
#define AIPSTZ_OPACR2_OPAC20_MASK (0xF000U)
#define AIPSTZ_OPACR2_OPAC20_SHIFT (12U)
/*! OPAC20
* 0bxxx0..Accesses from an untrusted master are allowed.
* 0bxxx1..Accesses from an untrusted master are not allowed. If an access is attempted by an untrusted master,
* the access is terminated with an error response and no peripheral access is initiated on the IPS bus.
* 0bxx0x..This peripheral allows write accesses.
* 0bxx1x..This peripheral is write protected. If a write access is attempted, the access is terminated with an
* error response and no peripheral access is initiated on the IPS bus.
* 0bx0xx..This peripheral does not require supervisor privilege level for accesses.
* 0bx1xx..This peripheral requires supervisor privilege level for accesses. The master privilege level must
* indicate supervisor via the hprot[1] access attribute, and the MPROTx[MPL] control bit for the master must
* be set. If not, the access is terminated with an error response and no peripheral access is initiated
* on the IPS bus.
* 0b1xxx..Write accesses to this peripheral are allowed to be buffered by the AIPSTZ.
*/
#define AIPSTZ_OPACR2_OPAC20(x) (((uint32_t)(((uint32_t)(x)) << AIPSTZ_OPACR2_OPAC20_SHIFT)) & AIPSTZ_OPACR2_OPAC20_MASK)
#define AIPSTZ_OPACR2_OPAC19_MASK (0xF0000U)
#define AIPSTZ_OPACR2_OPAC19_SHIFT (16U)
/*! OPAC19
* 0bxxx0..Accesses from an untrusted master are allowed.
* 0bxxx1..Accesses from an untrusted master are not allowed. If an access is attempted by an untrusted master,
* the access is terminated with an error response and no peripheral access is initiated on the IPS bus.
* 0bxx0x..This peripheral allows write accesses.
* 0bxx1x..This peripheral is write protected. If a write access is attempted, the access is terminated with an
* error response and no peripheral access is initiated on the IPS bus.
* 0bx0xx..This peripheral does not require supervisor privilege level for accesses.
* 0bx1xx..This peripheral requires supervisor privilege level for accesses. The master privilege level must
* indicate supervisor via the hprot[1] access attribute, and the MPROTx[MPL] control bit for the master must
* be set. If not, the access is terminated with an error response and no peripheral access is initiated
* on the IPS bus.
* 0b1xxx..Write accesses to this peripheral are allowed to be buffered by the AIPSTZ.
*/
#define AIPSTZ_OPACR2_OPAC19(x) (((uint32_t)(((uint32_t)(x)) << AIPSTZ_OPACR2_OPAC19_SHIFT)) & AIPSTZ_OPACR2_OPAC19_MASK)
#define AIPSTZ_OPACR2_OPAC18_MASK (0xF00000U)
#define AIPSTZ_OPACR2_OPAC18_SHIFT (20U)
/*! OPAC18
* 0bxxx0..Accesses from an untrusted master are allowed.
* 0bxxx1..Accesses from an untrusted master are not allowed. If an access is attempted by an untrusted master,
* the access is terminated with an error response and no peripheral access is initiated on the IPS bus.
* 0bxx0x..This peripheral allows write accesses.
* 0bxx1x..This peripheral is write protected. If a write access is attempted, the access is terminated with an
* error response and no peripheral access is initiated on the IPS bus.
* 0bx0xx..This peripheral does not require supervisor privilege level for accesses.
* 0bx1xx..This peripheral requires supervisor privilege level for accesses. The master privilege level must
* indicate supervisor via the hprot[1] access attribute, and the MPROTx[MPL] control bit for the master must
* be set. If not, the access is terminated with an error response and no peripheral access is initiated
* on the IPS bus.
* 0b1xxx..Write accesses to this peripheral are allowed to be buffered by the AIPSTZ.
*/
#define AIPSTZ_OPACR2_OPAC18(x) (((uint32_t)(((uint32_t)(x)) << AIPSTZ_OPACR2_OPAC18_SHIFT)) & AIPSTZ_OPACR2_OPAC18_MASK)
#define AIPSTZ_OPACR2_OPAC17_MASK (0xF000000U)
#define AIPSTZ_OPACR2_OPAC17_SHIFT (24U)
/*! OPAC17
* 0bxxx0..Accesses from an untrusted master are allowed.
* 0bxxx1..Accesses from an untrusted master are not allowed. If an access is attempted by an untrusted master,
* the access is terminated with an error response and no peripheral access is initiated on the IPS bus.
* 0bxx0x..This peripheral allows write accesses.
* 0bxx1x..This peripheral is write protected. If a write access is attempted, the access is terminated with an
* error response and no peripheral access is initiated on the IPS bus.
* 0bx0xx..This peripheral does not require supervisor privilege level for accesses.
* 0bx1xx..This peripheral requires supervisor privilege level for accesses. The master privilege level must
* indicate supervisor via the hprot[1] access attribute, and the MPROTx[MPL] control bit for the master must
* be set. If not, the access is terminated with an error response and no peripheral access is initiated
* on the IPS bus.
* 0b1xxx..Write accesses to this peripheral are allowed to be buffered by the AIPSTZ.
*/
#define AIPSTZ_OPACR2_OPAC17(x) (((uint32_t)(((uint32_t)(x)) << AIPSTZ_OPACR2_OPAC17_SHIFT)) & AIPSTZ_OPACR2_OPAC17_MASK)
#define AIPSTZ_OPACR2_OPAC16_MASK (0xF0000000U)
#define AIPSTZ_OPACR2_OPAC16_SHIFT (28U)
/*! OPAC16
* 0bxxx0..Accesses from an untrusted master are allowed.
* 0bxxx1..Accesses from an untrusted master are not allowed. If an access is attempted by an untrusted master,
* the access is terminated with an error response and no peripheral access is initiated on the IPS bus.
* 0bxx0x..This peripheral allows write accesses.
* 0bxx1x..This peripheral is write protected. If a write access is attempted, the access is terminated with an
* error response and no peripheral access is initiated on the IPS bus.
* 0bx0xx..This peripheral does not require supervisor privilege level for accesses.
* 0bx1xx..This peripheral requires supervisor privilege level for accesses. The master privilege level must
* indicate supervisor via the hprot[1] access attribute, and the MPROTx[MPL] control bit for the master must
* be set. If not, the access is terminated with an error response and no peripheral access is initiated
* on the IPS bus.
* 0b1xxx..Write accesses to this peripheral are allowed to be buffered by the AIPSTZ.
*/
#define AIPSTZ_OPACR2_OPAC16(x) (((uint32_t)(((uint32_t)(x)) << AIPSTZ_OPACR2_OPAC16_SHIFT)) & AIPSTZ_OPACR2_OPAC16_MASK)
/*! @} */
/*! @name OPACR3 - Off-Platform Peripheral Access Control Registers */
/*! @{ */
#define AIPSTZ_OPACR3_OPAC31_MASK (0xFU)
#define AIPSTZ_OPACR3_OPAC31_SHIFT (0U)
/*! OPAC31
* 0bxxx0..Accesses from an untrusted master are allowed.
* 0bxxx1..Accesses from an untrusted master are not allowed. If an access is attempted by an untrusted master,
* the access is terminated with an error response and no peripheral access is initiated on the IPS bus.
* 0bxx0x..This peripheral allows write accesses.
* 0bxx1x..This peripheral is write protected. If a write access is attempted, the access is terminated with an
* error response and no peripheral access is initiated on the IPS bus.
* 0bx0xx..This peripheral does not require supervisor privilege level for accesses.
* 0bx1xx..This peripheral requires supervisor privilege level for accesses. The master privilege level must
* indicate supervisor via the hprot[1] access attribute, and the MPROTx[MPL] control bit for the master must
* be set. If not, the access is terminated with an error response and no peripheral access is initiated
* on the IPS bus.
* 0b1xxx..Write accesses to this peripheral are allowed to be buffered by the AIPSTZ.
*/
#define AIPSTZ_OPACR3_OPAC31(x) (((uint32_t)(((uint32_t)(x)) << AIPSTZ_OPACR3_OPAC31_SHIFT)) & AIPSTZ_OPACR3_OPAC31_MASK)
#define AIPSTZ_OPACR3_OPAC30_MASK (0xF0U)
#define AIPSTZ_OPACR3_OPAC30_SHIFT (4U)
/*! OPAC30
* 0bxxx0..Accesses from an untrusted master are allowed.
* 0bxxx1..Accesses from an untrusted master are not allowed. If an access is attempted by an untrusted master,
* the access is terminated with an error response and no peripheral access is initiated on the IPS bus.
* 0bxx0x..This peripheral allows write accesses.
* 0bxx1x..This peripheral is write protected. If a write access is attempted, the access is terminated with an
* error response and no peripheral access is initiated on the IPS bus.
* 0bx0xx..This peripheral does not require supervisor privilege level for accesses.
* 0bx1xx..This peripheral requires supervisor privilege level for accesses. The master privilege level must
* indicate supervisor via the hprot[1] access attribute, and the MPROTx[MPL] control bit for the master must
* be set. If not, the access is terminated with an error response and no peripheral access is initiated
* on the IPS bus.
* 0b1xxx..Write accesses to this peripheral are allowed to be buffered by the AIPSTZ.
*/
#define AIPSTZ_OPACR3_OPAC30(x) (((uint32_t)(((uint32_t)(x)) << AIPSTZ_OPACR3_OPAC30_SHIFT)) & AIPSTZ_OPACR3_OPAC30_MASK)
#define AIPSTZ_OPACR3_OPAC29_MASK (0xF00U)
#define AIPSTZ_OPACR3_OPAC29_SHIFT (8U)
/*! OPAC29
* 0bxxx0..Accesses from an untrusted master are allowed.
* 0bxxx1..Accesses from an untrusted master are not allowed. If an access is attempted by an untrusted master,
* the access is terminated with an error response and no peripheral access is initiated on the IPS bus.
* 0bxx0x..This peripheral allows write accesses.
* 0bxx1x..This peripheral is write protected. If a write access is attempted, the access is terminated with an
* error response and no peripheral access is initiated on the IPS bus.
* 0bx0xx..This peripheral does not require supervisor privilege level for accesses.
* 0bx1xx..This peripheral requires supervisor privilege level for accesses. The master privilege level must
* indicate supervisor via the hprot[1] access attribute, and the MPROTx[MPL] control bit for the master must
* be set. If not, the access is terminated with an error response and no peripheral access is initiated
* on the IPS bus.
* 0b1xxx..Write accesses to this peripheral are allowed to be buffered by the AIPSTZ.
*/
#define AIPSTZ_OPACR3_OPAC29(x) (((uint32_t)(((uint32_t)(x)) << AIPSTZ_OPACR3_OPAC29_SHIFT)) & AIPSTZ_OPACR3_OPAC29_MASK)
#define AIPSTZ_OPACR3_OPAC28_MASK (0xF000U)
#define AIPSTZ_OPACR3_OPAC28_SHIFT (12U)
/*! OPAC28
* 0bxxx0..Accesses from an untrusted master are allowed.
* 0bxxx1..Accesses from an untrusted master are not allowed. If an access is attempted by an untrusted master,
* the access is terminated with an error response and no peripheral access is initiated on the IPS bus.
* 0bxx0x..This peripheral allows write accesses.
* 0bxx1x..This peripheral is write protected. If a write access is attempted, the access is terminated with an
* error response and no peripheral access is initiated on the IPS bus.
* 0bx0xx..This peripheral does not require supervisor privilege level for accesses.
* 0bx1xx..This peripheral requires supervisor privilege level for accesses. The master privilege level must
* indicate supervisor via the hprot[1] access attribute, and the MPROTx[MPL] control bit for the master must
* be set. If not, the access is terminated with an error response and no peripheral access is initiated
* on the IPS bus.
* 0b1xxx..Write accesses to this peripheral are allowed to be buffered by the AIPSTZ.
*/
#define AIPSTZ_OPACR3_OPAC28(x) (((uint32_t)(((uint32_t)(x)) << AIPSTZ_OPACR3_OPAC28_SHIFT)) & AIPSTZ_OPACR3_OPAC28_MASK)
#define AIPSTZ_OPACR3_OPAC27_MASK (0xF0000U)
#define AIPSTZ_OPACR3_OPAC27_SHIFT (16U)
/*! OPAC27
* 0bxxx0..Accesses from an untrusted master are allowed.
* 0bxxx1..Accesses from an untrusted master are not allowed. If an access is attempted by an untrusted master,
* the access is terminated with an error response and no peripheral access is initiated on the IPS bus.
* 0bxx0x..This peripheral allows write accesses.
* 0bxx1x..This peripheral is write protected. If a write access is attempted, the access is terminated with an
* error response and no peripheral access is initiated on the IPS bus.
* 0bx0xx..This peripheral does not require supervisor privilege level for accesses.
* 0bx1xx..This peripheral requires supervisor privilege level for accesses. The master privilege level must
* indicate supervisor via the hprot[1] access attribute, and the MPROTx[MPL] control bit for the master must
* be set. If not, the access is terminated with an error response and no peripheral access is initiated
* on the IPS bus.
* 0b1xxx..Write accesses to this peripheral are allowed to be buffered by the AIPSTZ.
*/
#define AIPSTZ_OPACR3_OPAC27(x) (((uint32_t)(((uint32_t)(x)) << AIPSTZ_OPACR3_OPAC27_SHIFT)) & AIPSTZ_OPACR3_OPAC27_MASK)
#define AIPSTZ_OPACR3_OPAC26_MASK (0xF00000U)
#define AIPSTZ_OPACR3_OPAC26_SHIFT (20U)
/*! OPAC26
* 0bxxx0..Accesses from an untrusted master are allowed.
* 0bxxx1..Accesses from an untrusted master are not allowed. If an access is attempted by an untrusted master,
* the access is terminated with an error response and no peripheral access is initiated on the IPS bus.
* 0bxx0x..This peripheral allows write accesses.
* 0bxx1x..This peripheral is write protected. If a write access is attempted, the access is terminated with an
* error response and no peripheral access is initiated on the IPS bus.
* 0bx0xx..This peripheral does not require supervisor privilege level for accesses.
* 0bx1xx..This peripheral requires supervisor privilege level for accesses. The master privilege level must
* indicate supervisor via the hprot[1] access attribute, and the MPROTx[MPL] control bit for the master must
* be set. If not, the access is terminated with an error response and no peripheral access is initiated
* on the IPS bus.
* 0b1xxx..Write accesses to this peripheral are allowed to be buffered by the AIPSTZ.
*/
#define AIPSTZ_OPACR3_OPAC26(x) (((uint32_t)(((uint32_t)(x)) << AIPSTZ_OPACR3_OPAC26_SHIFT)) & AIPSTZ_OPACR3_OPAC26_MASK)
#define AIPSTZ_OPACR3_OPAC25_MASK (0xF000000U)
#define AIPSTZ_OPACR3_OPAC25_SHIFT (24U)
/*! OPAC25
* 0bxxx0..Accesses from an untrusted master are allowed.
* 0bxxx1..Accesses from an untrusted master are not allowed. If an access is attempted by an untrusted master,
* the access is terminated with an error response and no peripheral access is initiated on the IPS bus.
* 0bxx0x..This peripheral allows write accesses.
* 0bxx1x..This peripheral is write protected. If a write access is attempted, the access is terminated with an
* error response and no peripheral access is initiated on the IPS bus.
* 0bx0xx..This peripheral does not require supervisor privilege level for accesses.
* 0bx1xx..This peripheral requires supervisor privilege level for accesses. The master privilege level must
* indicate supervisor via the hprot[1] access attribute, and the MPROTx[MPL] control bit for the master must
* be set. If not, the access is terminated with an error response and no peripheral access is initiated
* on the IPS bus.
* 0b1xxx..Write accesses to this peripheral are allowed to be buffered by the AIPSTZ.
*/
#define AIPSTZ_OPACR3_OPAC25(x) (((uint32_t)(((uint32_t)(x)) << AIPSTZ_OPACR3_OPAC25_SHIFT)) & AIPSTZ_OPACR3_OPAC25_MASK)
#define AIPSTZ_OPACR3_OPAC24_MASK (0xF0000000U)
#define AIPSTZ_OPACR3_OPAC24_SHIFT (28U)
/*! OPAC24
* 0bxxx0..Accesses from an untrusted master are allowed.
* 0bxxx1..Accesses from an untrusted master are not allowed. If an access is attempted by an untrusted master,
* the access is terminated with an error response and no peripheral access is initiated on the IPS bus.
* 0bxx0x..This peripheral allows write accesses.
* 0bxx1x..This peripheral is write protected. If a write access is attempted, the access is terminated with an
* error response and no peripheral access is initiated on the IPS bus.
* 0bx0xx..This peripheral does not require supervisor privilege level for accesses.
* 0bx1xx..This peripheral requires supervisor privilege level for accesses. The master privilege level must
* indicate supervisor via the hprot[1] access attribute, and the MPROTx[MPL] control bit for the master must
* be set. If not, the access is terminated with an error response and no peripheral access is initiated
* on the IPS bus.
* 0b1xxx..Write accesses to this peripheral are allowed to be buffered by the AIPSTZ.
*/
#define AIPSTZ_OPACR3_OPAC24(x) (((uint32_t)(((uint32_t)(x)) << AIPSTZ_OPACR3_OPAC24_SHIFT)) & AIPSTZ_OPACR3_OPAC24_MASK)
/*! @} */
/*! @name OPACR4 - Off-Platform Peripheral Access Control Registers */
/*! @{ */
#define AIPSTZ_OPACR4_OPAC33_MASK (0xF000000U)
#define AIPSTZ_OPACR4_OPAC33_SHIFT (24U)
/*! OPAC33
* 0bxxx0..Accesses from an untrusted master are allowed.
* 0bxxx1..Accesses from an untrusted master are not allowed. If an access is attempted by an untrusted master,
* the access is terminated with an error response and no peripheral access is initiated on the IPS bus.
* 0bxx0x..This peripheral allows write accesses.
* 0bxx1x..This peripheral is write protected. If a write access is attempted, the access is terminated with an
* error response and no peripheral access is initiated on the IPS bus.
* 0bx0xx..This peripheral does not require supervisor privilege level for accesses.
* 0bx1xx..This peripheral requires supervisor privilege level for accesses. The master privilege level must
* indicate supervisor via the hprot[1] access attribute, and the MPROTx[MPL] control bit for the master must
* be set. If not, the access is terminated with an error response and no peripheral access is initiated
* on the IPS bus.
* 0b1xxx..Write accesses to this peripheral are allowed to be buffered by the AIPSTZ.
*/
#define AIPSTZ_OPACR4_OPAC33(x) (((uint32_t)(((uint32_t)(x)) << AIPSTZ_OPACR4_OPAC33_SHIFT)) & AIPSTZ_OPACR4_OPAC33_MASK)
#define AIPSTZ_OPACR4_OPAC32_MASK (0xF0000000U)
#define AIPSTZ_OPACR4_OPAC32_SHIFT (28U)
/*! OPAC32
* 0bxxx0..Accesses from an untrusted master are allowed.
* 0bxxx1..Accesses from an untrusted master are not allowed. If an access is attempted by an untrusted master,
* the access is terminated with an error response and no peripheral access is initiated on the IPS bus.
* 0bxx0x..This peripheral allows write accesses.
* 0bxx1x..This peripheral is write protected. If a write access is attempted, the access is terminated with an
* error response and no peripheral access is initiated on the IPS bus.
* 0bx0xx..This peripheral does not require supervisor privilege level for accesses.
* 0bx1xx..This peripheral requires supervisor privilege level for accesses. The master privilege level must
* indicate supervisor via the hprot[1] access attribute, and the MPROTx[MPL] control bit for the master must
* be set. If not, the access is terminated with an error response and no peripheral access is initiated
* on the IPS bus.
* 0b1xxx..Write accesses to this peripheral are allowed to be buffered by the AIPSTZ.
*/
#define AIPSTZ_OPACR4_OPAC32(x) (((uint32_t)(((uint32_t)(x)) << AIPSTZ_OPACR4_OPAC32_SHIFT)) & AIPSTZ_OPACR4_OPAC32_MASK)
/*! @} */
/*!
* @}
*/ /* end of group AIPSTZ_Register_Masks */
/*!
* @}
*/ /* end of group AIPSTZ_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 */
#endif /* AIPSTZ_H_ */

View File

@ -0,0 +1,360 @@
/*
** ###################################################################
** Processors: MIMXRT1061CVJ5A
** MIMXRT1061CVJ5B
** MIMXRT1061CVL5A
** MIMXRT1061CVL5B
** MIMXRT1061DVJ6A
** MIMXRT1061DVJ6B
** MIMXRT1061DVL6A
** MIMXRT1061DVL6B
** MIMXRT1061XVN5B
** MIMXRT1062CVJ5A
** MIMXRT1062CVJ5B
** MIMXRT1062CVL5A
** MIMXRT1062CVL5B
** MIMXRT1062DVJ6A
** MIMXRT1062DVJ6B
** MIMXRT1062DVL6A
** MIMXRT1062DVL6B
** MIMXRT1062DVN6B
** MIMXRT1062XVN5B
** MIMXRT106ADVL6A
** MIMXRT106CDVL6A
** MIMXRT106FDVL6A
** MIMXRT106LDVL6A
** MIMXRT106SDVL6A
**
** Version: rev. 1.4, 2022-03-25
** Build: b240705
**
** Abstract:
** CMSIS Peripheral Access Layer for AOI
**
** Copyright 1997-2016 Freescale Semiconductor, Inc.
** Copyright 2016-2024 NXP
** SPDX-License-Identifier: BSD-3-Clause
**
** http: www.nxp.com
** mail: support@nxp.com
**
** Revisions:
** - rev. 0.1 (2017-01-10)
** Initial version.
** - rev. 1.0 (2018-11-16)
** Update header files to align with IMXRT1060RM Rev.0.
** - rev. 1.1 (2018-11-27)
** Update header files to align with IMXRT1060RM Rev.1.
** - rev. 1.2 (2019-04-29)
** Add SET/CLR/TOG register group to register CTRL, STAT, CHANNELCTRL, CH0STAT, CH0OPTS, CH1STAT, CH1OPTS, CH2STAT, CH2OPTS, CH3STAT, CH3OPTS of DCP module.
** - rev. 1.3 (2021-08-10)
** Update header files to align with IMXRT1060RM Rev.3.
** - rev. 1.4 (2022-03-25)
** Add RT1060X device
**
** ###################################################################
*/
/*!
* @file AOI.h
* @version 1.4
* @date 2022-03-25
* @brief CMSIS Peripheral Access Layer for AOI
*
* CMSIS Peripheral Access Layer for AOI
*/
#if !defined(AOI_H_)
#define AOI_H_ /**< Symbol preventing repeated inclusion */
#if (defined(CPU_MIMXRT1061CVJ5A) || defined(CPU_MIMXRT1061CVJ5B) || defined(CPU_MIMXRT1061CVL5A) || defined(CPU_MIMXRT1061CVL5B) || defined(CPU_MIMXRT1061DVJ6A) || defined(CPU_MIMXRT1061DVJ6B) || defined(CPU_MIMXRT1061DVL6A) || defined(CPU_MIMXRT1061DVL6B) || defined(CPU_MIMXRT1061XVN5B))
#include "MIMXRT1061_COMMON.h"
#elif (defined(CPU_MIMXRT1062CVJ5A) || defined(CPU_MIMXRT1062CVJ5B) || defined(CPU_MIMXRT1062CVL5A) || defined(CPU_MIMXRT1062CVL5B) || defined(CPU_MIMXRT1062DVJ6A) || defined(CPU_MIMXRT1062DVJ6B) || defined(CPU_MIMXRT1062DVL6A) || defined(CPU_MIMXRT1062DVL6B) || defined(CPU_MIMXRT1062DVN6B) || defined(CPU_MIMXRT1062XVN5B))
#include "MIMXRT1062_COMMON.h"
#elif (defined(CPU_MIMXRT106ADVL6A))
#include "MIMXRT106A_COMMON.h"
#elif (defined(CPU_MIMXRT106CDVL6A))
#include "MIMXRT106C_COMMON.h"
#elif (defined(CPU_MIMXRT106FDVL6A))
#include "MIMXRT106F_COMMON.h"
#elif (defined(CPU_MIMXRT106LDVL6A))
#include "MIMXRT106L_COMMON.h"
#elif (defined(CPU_MIMXRT106SDVL6A))
#include "MIMXRT106S_COMMON.h"
#else
#error "No valid CPU defined!"
#endif
/* ----------------------------------------------------------------------------
-- 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
/* ----------------------------------------------------------------------------
-- AOI Peripheral Access Layer
---------------------------------------------------------------------------- */
/*!
* @addtogroup AOI_Peripheral_Access_Layer AOI Peripheral Access Layer
* @{
*/
/** AOI - Size of Registers Arrays */
#define AOI_BFCRT_COUNT 4u
/** AOI - Register Layout Typedef */
typedef struct {
struct { /* offset: 0x0, array step: 0x4 */
__IO uint16_t BFCRT01; /**< Boolean Function Term 0 and 1 Configuration Register for EVENTn, array offset: 0x0, array step: 0x4 */
__IO uint16_t BFCRT23; /**< Boolean Function Term 2 and 3 Configuration Register for EVENTn, array offset: 0x2, array step: 0x4 */
} BFCRT[AOI_BFCRT_COUNT];
} AOI_Type;
/* ----------------------------------------------------------------------------
-- AOI Register Masks
---------------------------------------------------------------------------- */
/*!
* @addtogroup AOI_Register_Masks AOI Register Masks
* @{
*/
/*! @name BFCRT01 - Boolean Function Term 0 and 1 Configuration Register for EVENTn */
/*! @{ */
#define AOI_BFCRT01_PT1_DC_MASK (0x3U)
#define AOI_BFCRT01_PT1_DC_SHIFT (0U)
/*! PT1_DC - Product term 1, D input configuration
* 0b00..Force the D input in this product term to a logical zero
* 0b01..Pass the D input in this product term
* 0b10..Complement the D input in this product term
* 0b11..Force the D input in this product term to a logical one
*/
#define AOI_BFCRT01_PT1_DC(x) (((uint16_t)(((uint16_t)(x)) << AOI_BFCRT01_PT1_DC_SHIFT)) & AOI_BFCRT01_PT1_DC_MASK)
#define AOI_BFCRT01_PT1_CC_MASK (0xCU)
#define AOI_BFCRT01_PT1_CC_SHIFT (2U)
/*! PT1_CC - Product term 1, C input configuration
* 0b00..Force the C input in this product term to a logical zero
* 0b01..Pass the C input in this product term
* 0b10..Complement the C input in this product term
* 0b11..Force the C input in this product term to a logical one
*/
#define AOI_BFCRT01_PT1_CC(x) (((uint16_t)(((uint16_t)(x)) << AOI_BFCRT01_PT1_CC_SHIFT)) & AOI_BFCRT01_PT1_CC_MASK)
#define AOI_BFCRT01_PT1_BC_MASK (0x30U)
#define AOI_BFCRT01_PT1_BC_SHIFT (4U)
/*! PT1_BC - Product term 1, B input configuration
* 0b00..Force the B input in this product term to a logical zero
* 0b01..Pass the B input in this product term
* 0b10..Complement the B input in this product term
* 0b11..Force the B input in this product term to a logical one
*/
#define AOI_BFCRT01_PT1_BC(x) (((uint16_t)(((uint16_t)(x)) << AOI_BFCRT01_PT1_BC_SHIFT)) & AOI_BFCRT01_PT1_BC_MASK)
#define AOI_BFCRT01_PT1_AC_MASK (0xC0U)
#define AOI_BFCRT01_PT1_AC_SHIFT (6U)
/*! PT1_AC - Product term 1, A input configuration
* 0b00..Force the A input in this product term to a logical zero
* 0b01..Pass the A input in this product term
* 0b10..Complement the A input in this product term
* 0b11..Force the A input in this product term to a logical one
*/
#define AOI_BFCRT01_PT1_AC(x) (((uint16_t)(((uint16_t)(x)) << AOI_BFCRT01_PT1_AC_SHIFT)) & AOI_BFCRT01_PT1_AC_MASK)
#define AOI_BFCRT01_PT0_DC_MASK (0x300U)
#define AOI_BFCRT01_PT0_DC_SHIFT (8U)
/*! PT0_DC - Product term 0, D input configuration
* 0b00..Force the D input in this product term to a logical zero
* 0b01..Pass the D input in this product term
* 0b10..Complement the D input in this product term
* 0b11..Force the D input in this product term to a logical one
*/
#define AOI_BFCRT01_PT0_DC(x) (((uint16_t)(((uint16_t)(x)) << AOI_BFCRT01_PT0_DC_SHIFT)) & AOI_BFCRT01_PT0_DC_MASK)
#define AOI_BFCRT01_PT0_CC_MASK (0xC00U)
#define AOI_BFCRT01_PT0_CC_SHIFT (10U)
/*! PT0_CC - Product term 0, C input configuration
* 0b00..Force the C input in this product term to a logical zero
* 0b01..Pass the C input in this product term
* 0b10..Complement the C input in this product term
* 0b11..Force the C input in this product term to a logical one
*/
#define AOI_BFCRT01_PT0_CC(x) (((uint16_t)(((uint16_t)(x)) << AOI_BFCRT01_PT0_CC_SHIFT)) & AOI_BFCRT01_PT0_CC_MASK)
#define AOI_BFCRT01_PT0_BC_MASK (0x3000U)
#define AOI_BFCRT01_PT0_BC_SHIFT (12U)
/*! PT0_BC - Product term 0, B input configuration
* 0b00..Force the B input in this product term to a logical zero
* 0b01..Pass the B input in this product term
* 0b10..Complement the B input in this product term
* 0b11..Force the B input in this product term to a logical one
*/
#define AOI_BFCRT01_PT0_BC(x) (((uint16_t)(((uint16_t)(x)) << AOI_BFCRT01_PT0_BC_SHIFT)) & AOI_BFCRT01_PT0_BC_MASK)
#define AOI_BFCRT01_PT0_AC_MASK (0xC000U)
#define AOI_BFCRT01_PT0_AC_SHIFT (14U)
/*! PT0_AC - Product term 0, A input configuration
* 0b00..Force the A input in this product term to a logical zero
* 0b01..Pass the A input in this product term
* 0b10..Complement the A input in this product term
* 0b11..Force the A input in this product term to a logical one
*/
#define AOI_BFCRT01_PT0_AC(x) (((uint16_t)(((uint16_t)(x)) << AOI_BFCRT01_PT0_AC_SHIFT)) & AOI_BFCRT01_PT0_AC_MASK)
/*! @} */
/* The count of AOI_BFCRT01 */
#define AOI_BFCRT01_COUNT (4U)
/*! @name BFCRT23 - Boolean Function Term 2 and 3 Configuration Register for EVENTn */
/*! @{ */
#define AOI_BFCRT23_PT3_DC_MASK (0x3U)
#define AOI_BFCRT23_PT3_DC_SHIFT (0U)
/*! PT3_DC - Product term 3, D input configuration
* 0b00..Force the D input in this product term to a logical zero
* 0b01..Pass the D input in this product term
* 0b10..Complement the D input in this product term
* 0b11..Force the D input in this product term to a logical one
*/
#define AOI_BFCRT23_PT3_DC(x) (((uint16_t)(((uint16_t)(x)) << AOI_BFCRT23_PT3_DC_SHIFT)) & AOI_BFCRT23_PT3_DC_MASK)
#define AOI_BFCRT23_PT3_CC_MASK (0xCU)
#define AOI_BFCRT23_PT3_CC_SHIFT (2U)
/*! PT3_CC - Product term 3, C input configuration
* 0b00..Force the C input in this product term to a logical zero
* 0b01..Pass the C input in this product term
* 0b10..Complement the C input in this product term
* 0b11..Force the C input in this product term to a logical one
*/
#define AOI_BFCRT23_PT3_CC(x) (((uint16_t)(((uint16_t)(x)) << AOI_BFCRT23_PT3_CC_SHIFT)) & AOI_BFCRT23_PT3_CC_MASK)
#define AOI_BFCRT23_PT3_BC_MASK (0x30U)
#define AOI_BFCRT23_PT3_BC_SHIFT (4U)
/*! PT3_BC - Product term 3, B input configuration
* 0b00..Force the B input in this product term to a logical zero
* 0b01..Pass the B input in this product term
* 0b10..Complement the B input in this product term
* 0b11..Force the B input in this product term to a logical one
*/
#define AOI_BFCRT23_PT3_BC(x) (((uint16_t)(((uint16_t)(x)) << AOI_BFCRT23_PT3_BC_SHIFT)) & AOI_BFCRT23_PT3_BC_MASK)
#define AOI_BFCRT23_PT3_AC_MASK (0xC0U)
#define AOI_BFCRT23_PT3_AC_SHIFT (6U)
/*! PT3_AC - Product term 3, A input configuration
* 0b00..Force the A input in this product term to a logical zero
* 0b01..Pass the A input in this product term
* 0b10..Complement the A input in this product term
* 0b11..Force the A input in this product term to a logical one
*/
#define AOI_BFCRT23_PT3_AC(x) (((uint16_t)(((uint16_t)(x)) << AOI_BFCRT23_PT3_AC_SHIFT)) & AOI_BFCRT23_PT3_AC_MASK)
#define AOI_BFCRT23_PT2_DC_MASK (0x300U)
#define AOI_BFCRT23_PT2_DC_SHIFT (8U)
/*! PT2_DC - Product term 2, D input configuration
* 0b00..Force the D input in this product term to a logical zero
* 0b01..Pass the D input in this product term
* 0b10..Complement the D input in this product term
* 0b11..Force the D input in this product term to a logical one
*/
#define AOI_BFCRT23_PT2_DC(x) (((uint16_t)(((uint16_t)(x)) << AOI_BFCRT23_PT2_DC_SHIFT)) & AOI_BFCRT23_PT2_DC_MASK)
#define AOI_BFCRT23_PT2_CC_MASK (0xC00U)
#define AOI_BFCRT23_PT2_CC_SHIFT (10U)
/*! PT2_CC - Product term 2, C input configuration
* 0b00..Force the C input in this product term to a logical zero
* 0b01..Pass the C input in this product term
* 0b10..Complement the C input in this product term
* 0b11..Force the C input in this product term to a logical one
*/
#define AOI_BFCRT23_PT2_CC(x) (((uint16_t)(((uint16_t)(x)) << AOI_BFCRT23_PT2_CC_SHIFT)) & AOI_BFCRT23_PT2_CC_MASK)
#define AOI_BFCRT23_PT2_BC_MASK (0x3000U)
#define AOI_BFCRT23_PT2_BC_SHIFT (12U)
/*! PT2_BC - Product term 2, B input configuration
* 0b00..Force the B input in this product term to a logical zero
* 0b01..Pass the B input in this product term
* 0b10..Complement the B input in this product term
* 0b11..Force the B input in this product term to a logical one
*/
#define AOI_BFCRT23_PT2_BC(x) (((uint16_t)(((uint16_t)(x)) << AOI_BFCRT23_PT2_BC_SHIFT)) & AOI_BFCRT23_PT2_BC_MASK)
#define AOI_BFCRT23_PT2_AC_MASK (0xC000U)
#define AOI_BFCRT23_PT2_AC_SHIFT (14U)
/*! PT2_AC - Product term 2, A input configuration
* 0b00..Force the A input in this product term to a logical zero
* 0b01..Pass the A input in this product term
* 0b10..Complement the A input in this product term
* 0b11..Force the A input in this product term to a logical one
*/
#define AOI_BFCRT23_PT2_AC(x) (((uint16_t)(((uint16_t)(x)) << AOI_BFCRT23_PT2_AC_SHIFT)) & AOI_BFCRT23_PT2_AC_MASK)
/*! @} */
/* The count of AOI_BFCRT23 */
#define AOI_BFCRT23_COUNT (4U)
/*!
* @}
*/ /* end of group AOI_Register_Masks */
/*!
* @}
*/ /* end of group AOI_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 */
#endif /* AOI_H_ */

View File

@ -0,0 +1,477 @@
/*
** ###################################################################
** Processors: MIMXRT1061CVJ5A
** MIMXRT1061CVJ5B
** MIMXRT1061CVL5A
** MIMXRT1061CVL5B
** MIMXRT1061DVJ6A
** MIMXRT1061DVJ6B
** MIMXRT1061DVL6A
** MIMXRT1061DVL6B
** MIMXRT1061XVN5B
** MIMXRT1062CVJ5A
** MIMXRT1062CVJ5B
** MIMXRT1062CVL5A
** MIMXRT1062CVL5B
** MIMXRT1062DVJ6A
** MIMXRT1062DVJ6B
** MIMXRT1062DVL6A
** MIMXRT1062DVL6B
** MIMXRT1062DVN6B
** MIMXRT1062XVN5B
** MIMXRT106ADVL6A
** MIMXRT106CDVL6A
** MIMXRT106FDVL6A
** MIMXRT106LDVL6A
** MIMXRT106SDVL6A
**
** Version: rev. 1.4, 2022-03-25
** Build: b240705
**
** Abstract:
** CMSIS Peripheral Access Layer for BEE
**
** Copyright 1997-2016 Freescale Semiconductor, Inc.
** Copyright 2016-2024 NXP
** SPDX-License-Identifier: BSD-3-Clause
**
** http: www.nxp.com
** mail: support@nxp.com
**
** Revisions:
** - rev. 0.1 (2017-01-10)
** Initial version.
** - rev. 1.0 (2018-11-16)
** Update header files to align with IMXRT1060RM Rev.0.
** - rev. 1.1 (2018-11-27)
** Update header files to align with IMXRT1060RM Rev.1.
** - rev. 1.2 (2019-04-29)
** Add SET/CLR/TOG register group to register CTRL, STAT, CHANNELCTRL, CH0STAT, CH0OPTS, CH1STAT, CH1OPTS, CH2STAT, CH2OPTS, CH3STAT, CH3OPTS of DCP module.
** - rev. 1.3 (2021-08-10)
** Update header files to align with IMXRT1060RM Rev.3.
** - rev. 1.4 (2022-03-25)
** Add RT1060X device
**
** ###################################################################
*/
/*!
* @file BEE.h
* @version 1.4
* @date 2022-03-25
* @brief CMSIS Peripheral Access Layer for BEE
*
* CMSIS Peripheral Access Layer for BEE
*/
#if !defined(BEE_H_)
#define BEE_H_ /**< Symbol preventing repeated inclusion */
#if (defined(CPU_MIMXRT1061CVJ5A) || defined(CPU_MIMXRT1061CVJ5B) || defined(CPU_MIMXRT1061CVL5A) || defined(CPU_MIMXRT1061CVL5B) || defined(CPU_MIMXRT1061DVJ6A) || defined(CPU_MIMXRT1061DVJ6B) || defined(CPU_MIMXRT1061DVL6A) || defined(CPU_MIMXRT1061DVL6B) || defined(CPU_MIMXRT1061XVN5B))
#include "MIMXRT1061_COMMON.h"
#elif (defined(CPU_MIMXRT1062CVJ5A) || defined(CPU_MIMXRT1062CVJ5B) || defined(CPU_MIMXRT1062CVL5A) || defined(CPU_MIMXRT1062CVL5B) || defined(CPU_MIMXRT1062DVJ6A) || defined(CPU_MIMXRT1062DVJ6B) || defined(CPU_MIMXRT1062DVL6A) || defined(CPU_MIMXRT1062DVL6B) || defined(CPU_MIMXRT1062DVN6B) || defined(CPU_MIMXRT1062XVN5B))
#include "MIMXRT1062_COMMON.h"
#elif (defined(CPU_MIMXRT106ADVL6A))
#include "MIMXRT106A_COMMON.h"
#elif (defined(CPU_MIMXRT106CDVL6A))
#include "MIMXRT106C_COMMON.h"
#elif (defined(CPU_MIMXRT106FDVL6A))
#include "MIMXRT106F_COMMON.h"
#elif (defined(CPU_MIMXRT106LDVL6A))
#include "MIMXRT106L_COMMON.h"
#elif (defined(CPU_MIMXRT106SDVL6A))
#include "MIMXRT106S_COMMON.h"
#else
#error "No valid CPU defined!"
#endif
/* ----------------------------------------------------------------------------
-- 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
/* ----------------------------------------------------------------------------
-- BEE Peripheral Access Layer
---------------------------------------------------------------------------- */
/*!
* @addtogroup BEE_Peripheral_Access_Layer BEE Peripheral Access Layer
* @{
*/
/** BEE - Register Layout Typedef */
typedef struct {
__IO uint32_t CTRL; /**< Control Register, offset: 0x0 */
__IO uint32_t ADDR_OFFSET0; /**< Offset region 0 Register, offset: 0x4 */
__IO uint32_t ADDR_OFFSET1; /**< Offset region 1 Register, offset: 0x8 */
__O uint32_t AES_KEY0_W0; /**< AES Key 0 Register, offset: 0xC */
__O uint32_t AES_KEY0_W1; /**< AES Key 1 Register, offset: 0x10 */
__O uint32_t AES_KEY0_W2; /**< AES Key 2 Register, offset: 0x14 */
__O uint32_t AES_KEY0_W3; /**< AES Key 3 Register, offset: 0x18 */
__IO uint32_t STATUS; /**< Status Register, offset: 0x1C */
__O uint32_t CTR_NONCE0_W0; /**< NONCE00 Register, offset: 0x20 */
__O uint32_t CTR_NONCE0_W1; /**< NONCE01 Register, offset: 0x24 */
__O uint32_t CTR_NONCE0_W2; /**< NONCE02 Register, offset: 0x28 */
__O uint32_t CTR_NONCE0_W3; /**< NONCE03 Register, offset: 0x2C */
__O uint32_t CTR_NONCE1_W0; /**< NONCE10 Register, offset: 0x30 */
__O uint32_t CTR_NONCE1_W1; /**< NONCE11 Register, offset: 0x34 */
__O uint32_t CTR_NONCE1_W2; /**< NONCE12 Register, offset: 0x38 */
__O uint32_t CTR_NONCE1_W3; /**< NONCE13 Register, offset: 0x3C */
__IO uint32_t REGION1_TOP; /**< Region1 Top Address Register, offset: 0x40 */
__IO uint32_t REGION1_BOT; /**< Region1 Bottom Address Register, offset: 0x44 */
} BEE_Type;
/* ----------------------------------------------------------------------------
-- BEE Register Masks
---------------------------------------------------------------------------- */
/*!
* @addtogroup BEE_Register_Masks BEE Register Masks
* @{
*/
/*! @name CTRL - Control Register */
/*! @{ */
#define BEE_CTRL_BEE_ENABLE_MASK (0x1U)
#define BEE_CTRL_BEE_ENABLE_SHIFT (0U)
/*! BEE_ENABLE
* 0b0..Disable BEE
* 0b1..Enable BEE
*/
#define BEE_CTRL_BEE_ENABLE(x) (((uint32_t)(((uint32_t)(x)) << BEE_CTRL_BEE_ENABLE_SHIFT)) & BEE_CTRL_BEE_ENABLE_MASK)
#define BEE_CTRL_CTRL_CLK_EN_MASK (0x2U)
#define BEE_CTRL_CTRL_CLK_EN_SHIFT (1U)
#define BEE_CTRL_CTRL_CLK_EN(x) (((uint32_t)(((uint32_t)(x)) << BEE_CTRL_CTRL_CLK_EN_SHIFT)) & BEE_CTRL_CTRL_CLK_EN_MASK)
#define BEE_CTRL_CTRL_SFTRST_N_MASK (0x4U)
#define BEE_CTRL_CTRL_SFTRST_N_SHIFT (2U)
#define BEE_CTRL_CTRL_SFTRST_N(x) (((uint32_t)(((uint32_t)(x)) << BEE_CTRL_CTRL_SFTRST_N_SHIFT)) & BEE_CTRL_CTRL_SFTRST_N_MASK)
#define BEE_CTRL_KEY_VALID_MASK (0x10U)
#define BEE_CTRL_KEY_VALID_SHIFT (4U)
#define BEE_CTRL_KEY_VALID(x) (((uint32_t)(((uint32_t)(x)) << BEE_CTRL_KEY_VALID_SHIFT)) & BEE_CTRL_KEY_VALID_MASK)
#define BEE_CTRL_KEY_REGION_SEL_MASK (0x20U)
#define BEE_CTRL_KEY_REGION_SEL_SHIFT (5U)
/*! KEY_REGION_SEL
* 0b0..Load AES key for region0
* 0b1..Load AES key for region1
*/
#define BEE_CTRL_KEY_REGION_SEL(x) (((uint32_t)(((uint32_t)(x)) << BEE_CTRL_KEY_REGION_SEL_SHIFT)) & BEE_CTRL_KEY_REGION_SEL_MASK)
#define BEE_CTRL_AC_PROT_EN_MASK (0x40U)
#define BEE_CTRL_AC_PROT_EN_SHIFT (6U)
#define BEE_CTRL_AC_PROT_EN(x) (((uint32_t)(((uint32_t)(x)) << BEE_CTRL_AC_PROT_EN_SHIFT)) & BEE_CTRL_AC_PROT_EN_MASK)
#define BEE_CTRL_LITTLE_ENDIAN_MASK (0x80U)
#define BEE_CTRL_LITTLE_ENDIAN_SHIFT (7U)
/*! LITTLE_ENDIAN
* 0b0..The input and output data of the AES core is swapped as below: {B15,B14,B13,B12,B11,B10,B9,B8,
* B7,B6,B5,B4,B3,B2,B1,B0} swap to {B0,B1,B2,B3,B4,B5,B6,B7, B8,B9,B10,B11,B12,B13,B14,B15}, where B0~B15 refers to
* Byte0 to Byte15.
* 0b1..The input and output data of AES core is not swapped.
*/
#define BEE_CTRL_LITTLE_ENDIAN(x) (((uint32_t)(((uint32_t)(x)) << BEE_CTRL_LITTLE_ENDIAN_SHIFT)) & BEE_CTRL_LITTLE_ENDIAN_MASK)
#define BEE_CTRL_SECURITY_LEVEL_R0_MASK (0x300U)
#define BEE_CTRL_SECURITY_LEVEL_R0_SHIFT (8U)
#define BEE_CTRL_SECURITY_LEVEL_R0(x) (((uint32_t)(((uint32_t)(x)) << BEE_CTRL_SECURITY_LEVEL_R0_SHIFT)) & BEE_CTRL_SECURITY_LEVEL_R0_MASK)
#define BEE_CTRL_CTRL_AES_MODE_R0_MASK (0x400U)
#define BEE_CTRL_CTRL_AES_MODE_R0_SHIFT (10U)
/*! CTRL_AES_MODE_R0
* 0b0..ECB
* 0b1..CTR
*/
#define BEE_CTRL_CTRL_AES_MODE_R0(x) (((uint32_t)(((uint32_t)(x)) << BEE_CTRL_CTRL_AES_MODE_R0_SHIFT)) & BEE_CTRL_CTRL_AES_MODE_R0_MASK)
#define BEE_CTRL_SECURITY_LEVEL_R1_MASK (0x3000U)
#define BEE_CTRL_SECURITY_LEVEL_R1_SHIFT (12U)
#define BEE_CTRL_SECURITY_LEVEL_R1(x) (((uint32_t)(((uint32_t)(x)) << BEE_CTRL_SECURITY_LEVEL_R1_SHIFT)) & BEE_CTRL_SECURITY_LEVEL_R1_MASK)
#define BEE_CTRL_CTRL_AES_MODE_R1_MASK (0x4000U)
#define BEE_CTRL_CTRL_AES_MODE_R1_SHIFT (14U)
/*! CTRL_AES_MODE_R1
* 0b0..ECB
* 0b1..CTR
*/
#define BEE_CTRL_CTRL_AES_MODE_R1(x) (((uint32_t)(((uint32_t)(x)) << BEE_CTRL_CTRL_AES_MODE_R1_SHIFT)) & BEE_CTRL_CTRL_AES_MODE_R1_MASK)
#define BEE_CTRL_BEE_ENABLE_LOCK_MASK (0x10000U)
#define BEE_CTRL_BEE_ENABLE_LOCK_SHIFT (16U)
#define BEE_CTRL_BEE_ENABLE_LOCK(x) (((uint32_t)(((uint32_t)(x)) << BEE_CTRL_BEE_ENABLE_LOCK_SHIFT)) & BEE_CTRL_BEE_ENABLE_LOCK_MASK)
#define BEE_CTRL_CTRL_CLK_EN_LOCK_MASK (0x20000U)
#define BEE_CTRL_CTRL_CLK_EN_LOCK_SHIFT (17U)
#define BEE_CTRL_CTRL_CLK_EN_LOCK(x) (((uint32_t)(((uint32_t)(x)) << BEE_CTRL_CTRL_CLK_EN_LOCK_SHIFT)) & BEE_CTRL_CTRL_CLK_EN_LOCK_MASK)
#define BEE_CTRL_CTRL_SFTRST_N_LOCK_MASK (0x40000U)
#define BEE_CTRL_CTRL_SFTRST_N_LOCK_SHIFT (18U)
#define BEE_CTRL_CTRL_SFTRST_N_LOCK(x) (((uint32_t)(((uint32_t)(x)) << BEE_CTRL_CTRL_SFTRST_N_LOCK_SHIFT)) & BEE_CTRL_CTRL_SFTRST_N_LOCK_MASK)
#define BEE_CTRL_REGION1_ADDR_LOCK_MASK (0x80000U)
#define BEE_CTRL_REGION1_ADDR_LOCK_SHIFT (19U)
#define BEE_CTRL_REGION1_ADDR_LOCK(x) (((uint32_t)(((uint32_t)(x)) << BEE_CTRL_REGION1_ADDR_LOCK_SHIFT)) & BEE_CTRL_REGION1_ADDR_LOCK_MASK)
#define BEE_CTRL_KEY_VALID_LOCK_MASK (0x100000U)
#define BEE_CTRL_KEY_VALID_LOCK_SHIFT (20U)
#define BEE_CTRL_KEY_VALID_LOCK(x) (((uint32_t)(((uint32_t)(x)) << BEE_CTRL_KEY_VALID_LOCK_SHIFT)) & BEE_CTRL_KEY_VALID_LOCK_MASK)
#define BEE_CTRL_KEY_REGION_SEL_LOCK_MASK (0x200000U)
#define BEE_CTRL_KEY_REGION_SEL_LOCK_SHIFT (21U)
#define BEE_CTRL_KEY_REGION_SEL_LOCK(x) (((uint32_t)(((uint32_t)(x)) << BEE_CTRL_KEY_REGION_SEL_LOCK_SHIFT)) & BEE_CTRL_KEY_REGION_SEL_LOCK_MASK)
#define BEE_CTRL_AC_PROT_EN_LOCK_MASK (0x400000U)
#define BEE_CTRL_AC_PROT_EN_LOCK_SHIFT (22U)
#define BEE_CTRL_AC_PROT_EN_LOCK(x) (((uint32_t)(((uint32_t)(x)) << BEE_CTRL_AC_PROT_EN_LOCK_SHIFT)) & BEE_CTRL_AC_PROT_EN_LOCK_MASK)
#define BEE_CTRL_LITTLE_ENDIAN_LOCK_MASK (0x800000U)
#define BEE_CTRL_LITTLE_ENDIAN_LOCK_SHIFT (23U)
#define BEE_CTRL_LITTLE_ENDIAN_LOCK(x) (((uint32_t)(((uint32_t)(x)) << BEE_CTRL_LITTLE_ENDIAN_LOCK_SHIFT)) & BEE_CTRL_LITTLE_ENDIAN_LOCK_MASK)
#define BEE_CTRL_SECURITY_LEVEL_R0_LOCK_MASK (0x3000000U)
#define BEE_CTRL_SECURITY_LEVEL_R0_LOCK_SHIFT (24U)
#define BEE_CTRL_SECURITY_LEVEL_R0_LOCK(x) (((uint32_t)(((uint32_t)(x)) << BEE_CTRL_SECURITY_LEVEL_R0_LOCK_SHIFT)) & BEE_CTRL_SECURITY_LEVEL_R0_LOCK_MASK)
#define BEE_CTRL_CTRL_AES_MODE_R0_LOCK_MASK (0x4000000U)
#define BEE_CTRL_CTRL_AES_MODE_R0_LOCK_SHIFT (26U)
#define BEE_CTRL_CTRL_AES_MODE_R0_LOCK(x) (((uint32_t)(((uint32_t)(x)) << BEE_CTRL_CTRL_AES_MODE_R0_LOCK_SHIFT)) & BEE_CTRL_CTRL_AES_MODE_R0_LOCK_MASK)
#define BEE_CTRL_REGION0_KEY_LOCK_MASK (0x8000000U)
#define BEE_CTRL_REGION0_KEY_LOCK_SHIFT (27U)
#define BEE_CTRL_REGION0_KEY_LOCK(x) (((uint32_t)(((uint32_t)(x)) << BEE_CTRL_REGION0_KEY_LOCK_SHIFT)) & BEE_CTRL_REGION0_KEY_LOCK_MASK)
#define BEE_CTRL_SECURITY_LEVEL_R1_LOCK_MASK (0x30000000U)
#define BEE_CTRL_SECURITY_LEVEL_R1_LOCK_SHIFT (28U)
#define BEE_CTRL_SECURITY_LEVEL_R1_LOCK(x) (((uint32_t)(((uint32_t)(x)) << BEE_CTRL_SECURITY_LEVEL_R1_LOCK_SHIFT)) & BEE_CTRL_SECURITY_LEVEL_R1_LOCK_MASK)
#define BEE_CTRL_CTRL_AES_MODE_R1_LOCK_MASK (0x40000000U)
#define BEE_CTRL_CTRL_AES_MODE_R1_LOCK_SHIFT (30U)
#define BEE_CTRL_CTRL_AES_MODE_R1_LOCK(x) (((uint32_t)(((uint32_t)(x)) << BEE_CTRL_CTRL_AES_MODE_R1_LOCK_SHIFT)) & BEE_CTRL_CTRL_AES_MODE_R1_LOCK_MASK)
#define BEE_CTRL_REGION1_KEY_LOCK_MASK (0x80000000U)
#define BEE_CTRL_REGION1_KEY_LOCK_SHIFT (31U)
#define BEE_CTRL_REGION1_KEY_LOCK(x) (((uint32_t)(((uint32_t)(x)) << BEE_CTRL_REGION1_KEY_LOCK_SHIFT)) & BEE_CTRL_REGION1_KEY_LOCK_MASK)
/*! @} */
/*! @name ADDR_OFFSET0 - Offset region 0 Register */
/*! @{ */
#define BEE_ADDR_OFFSET0_ADDR_OFFSET0_MASK (0xFFFFU)
#define BEE_ADDR_OFFSET0_ADDR_OFFSET0_SHIFT (0U)
#define BEE_ADDR_OFFSET0_ADDR_OFFSET0(x) (((uint32_t)(((uint32_t)(x)) << BEE_ADDR_OFFSET0_ADDR_OFFSET0_SHIFT)) & BEE_ADDR_OFFSET0_ADDR_OFFSET0_MASK)
#define BEE_ADDR_OFFSET0_ADDR_OFFSET0_LOCK_MASK (0xFFFF0000U)
#define BEE_ADDR_OFFSET0_ADDR_OFFSET0_LOCK_SHIFT (16U)
#define BEE_ADDR_OFFSET0_ADDR_OFFSET0_LOCK(x) (((uint32_t)(((uint32_t)(x)) << BEE_ADDR_OFFSET0_ADDR_OFFSET0_LOCK_SHIFT)) & BEE_ADDR_OFFSET0_ADDR_OFFSET0_LOCK_MASK)
/*! @} */
/*! @name ADDR_OFFSET1 - Offset region 1 Register */
/*! @{ */
#define BEE_ADDR_OFFSET1_ADDR_OFFSET1_MASK (0xFFFFU)
#define BEE_ADDR_OFFSET1_ADDR_OFFSET1_SHIFT (0U)
#define BEE_ADDR_OFFSET1_ADDR_OFFSET1(x) (((uint32_t)(((uint32_t)(x)) << BEE_ADDR_OFFSET1_ADDR_OFFSET1_SHIFT)) & BEE_ADDR_OFFSET1_ADDR_OFFSET1_MASK)
#define BEE_ADDR_OFFSET1_ADDR_OFFSET1_LOCK_MASK (0xFFFF0000U)
#define BEE_ADDR_OFFSET1_ADDR_OFFSET1_LOCK_SHIFT (16U)
#define BEE_ADDR_OFFSET1_ADDR_OFFSET1_LOCK(x) (((uint32_t)(((uint32_t)(x)) << BEE_ADDR_OFFSET1_ADDR_OFFSET1_LOCK_SHIFT)) & BEE_ADDR_OFFSET1_ADDR_OFFSET1_LOCK_MASK)
/*! @} */
/*! @name AES_KEY0_W0 - AES Key 0 Register */
/*! @{ */
#define BEE_AES_KEY0_W0_KEY0_MASK (0xFFFFFFFFU)
#define BEE_AES_KEY0_W0_KEY0_SHIFT (0U)
/*! KEY0 - AES 128 key from software */
#define BEE_AES_KEY0_W0_KEY0(x) (((uint32_t)(((uint32_t)(x)) << BEE_AES_KEY0_W0_KEY0_SHIFT)) & BEE_AES_KEY0_W0_KEY0_MASK)
/*! @} */
/*! @name AES_KEY0_W1 - AES Key 1 Register */
/*! @{ */
#define BEE_AES_KEY0_W1_KEY1_MASK (0xFFFFFFFFU)
#define BEE_AES_KEY0_W1_KEY1_SHIFT (0U)
/*! KEY1 - AES 128 key from software */
#define BEE_AES_KEY0_W1_KEY1(x) (((uint32_t)(((uint32_t)(x)) << BEE_AES_KEY0_W1_KEY1_SHIFT)) & BEE_AES_KEY0_W1_KEY1_MASK)
/*! @} */
/*! @name AES_KEY0_W2 - AES Key 2 Register */
/*! @{ */
#define BEE_AES_KEY0_W2_KEY2_MASK (0xFFFFFFFFU)
#define BEE_AES_KEY0_W2_KEY2_SHIFT (0U)
/*! KEY2 - AES 128 key from software */
#define BEE_AES_KEY0_W2_KEY2(x) (((uint32_t)(((uint32_t)(x)) << BEE_AES_KEY0_W2_KEY2_SHIFT)) & BEE_AES_KEY0_W2_KEY2_MASK)
/*! @} */
/*! @name AES_KEY0_W3 - AES Key 3 Register */
/*! @{ */
#define BEE_AES_KEY0_W3_KEY3_MASK (0xFFFFFFFFU)
#define BEE_AES_KEY0_W3_KEY3_SHIFT (0U)
/*! KEY3 - AES 128 key from software */
#define BEE_AES_KEY0_W3_KEY3(x) (((uint32_t)(((uint32_t)(x)) << BEE_AES_KEY0_W3_KEY3_SHIFT)) & BEE_AES_KEY0_W3_KEY3_MASK)
/*! @} */
/*! @name STATUS - Status Register */
/*! @{ */
#define BEE_STATUS_IRQ_VEC_MASK (0xFFU)
#define BEE_STATUS_IRQ_VEC_SHIFT (0U)
#define BEE_STATUS_IRQ_VEC(x) (((uint32_t)(((uint32_t)(x)) << BEE_STATUS_IRQ_VEC_SHIFT)) & BEE_STATUS_IRQ_VEC_MASK)
#define BEE_STATUS_BEE_IDLE_MASK (0x100U)
#define BEE_STATUS_BEE_IDLE_SHIFT (8U)
#define BEE_STATUS_BEE_IDLE(x) (((uint32_t)(((uint32_t)(x)) << BEE_STATUS_BEE_IDLE_SHIFT)) & BEE_STATUS_BEE_IDLE_MASK)
/*! @} */
/*! @name CTR_NONCE0_W0 - NONCE00 Register */
/*! @{ */
#define BEE_CTR_NONCE0_W0_NONCE00_MASK (0xFFFFFFFFU)
#define BEE_CTR_NONCE0_W0_NONCE00_SHIFT (0U)
#define BEE_CTR_NONCE0_W0_NONCE00(x) (((uint32_t)(((uint32_t)(x)) << BEE_CTR_NONCE0_W0_NONCE00_SHIFT)) & BEE_CTR_NONCE0_W0_NONCE00_MASK)
/*! @} */
/*! @name CTR_NONCE0_W1 - NONCE01 Register */
/*! @{ */
#define BEE_CTR_NONCE0_W1_NONCE01_MASK (0xFFFFFFFFU)
#define BEE_CTR_NONCE0_W1_NONCE01_SHIFT (0U)
#define BEE_CTR_NONCE0_W1_NONCE01(x) (((uint32_t)(((uint32_t)(x)) << BEE_CTR_NONCE0_W1_NONCE01_SHIFT)) & BEE_CTR_NONCE0_W1_NONCE01_MASK)
/*! @} */
/*! @name CTR_NONCE0_W2 - NONCE02 Register */
/*! @{ */
#define BEE_CTR_NONCE0_W2_NONCE02_MASK (0xFFFFFFFFU)
#define BEE_CTR_NONCE0_W2_NONCE02_SHIFT (0U)
#define BEE_CTR_NONCE0_W2_NONCE02(x) (((uint32_t)(((uint32_t)(x)) << BEE_CTR_NONCE0_W2_NONCE02_SHIFT)) & BEE_CTR_NONCE0_W2_NONCE02_MASK)
/*! @} */
/*! @name CTR_NONCE0_W3 - NONCE03 Register */
/*! @{ */
#define BEE_CTR_NONCE0_W3_NONCE03_MASK (0xFFFFFFFFU)
#define BEE_CTR_NONCE0_W3_NONCE03_SHIFT (0U)
#define BEE_CTR_NONCE0_W3_NONCE03(x) (((uint32_t)(((uint32_t)(x)) << BEE_CTR_NONCE0_W3_NONCE03_SHIFT)) & BEE_CTR_NONCE0_W3_NONCE03_MASK)
/*! @} */
/*! @name CTR_NONCE1_W0 - NONCE10 Register */
/*! @{ */
#define BEE_CTR_NONCE1_W0_NONCE10_MASK (0xFFFFFFFFU)
#define BEE_CTR_NONCE1_W0_NONCE10_SHIFT (0U)
#define BEE_CTR_NONCE1_W0_NONCE10(x) (((uint32_t)(((uint32_t)(x)) << BEE_CTR_NONCE1_W0_NONCE10_SHIFT)) & BEE_CTR_NONCE1_W0_NONCE10_MASK)
/*! @} */
/*! @name CTR_NONCE1_W1 - NONCE11 Register */
/*! @{ */
#define BEE_CTR_NONCE1_W1_NONCE11_MASK (0xFFFFFFFFU)
#define BEE_CTR_NONCE1_W1_NONCE11_SHIFT (0U)
#define BEE_CTR_NONCE1_W1_NONCE11(x) (((uint32_t)(((uint32_t)(x)) << BEE_CTR_NONCE1_W1_NONCE11_SHIFT)) & BEE_CTR_NONCE1_W1_NONCE11_MASK)
/*! @} */
/*! @name CTR_NONCE1_W2 - NONCE12 Register */
/*! @{ */
#define BEE_CTR_NONCE1_W2_NONCE12_MASK (0xFFFFFFFFU)
#define BEE_CTR_NONCE1_W2_NONCE12_SHIFT (0U)
#define BEE_CTR_NONCE1_W2_NONCE12(x) (((uint32_t)(((uint32_t)(x)) << BEE_CTR_NONCE1_W2_NONCE12_SHIFT)) & BEE_CTR_NONCE1_W2_NONCE12_MASK)
/*! @} */
/*! @name CTR_NONCE1_W3 - NONCE13 Register */
/*! @{ */
#define BEE_CTR_NONCE1_W3_NONCE13_MASK (0xFFFFFFFFU)
#define BEE_CTR_NONCE1_W3_NONCE13_SHIFT (0U)
#define BEE_CTR_NONCE1_W3_NONCE13(x) (((uint32_t)(((uint32_t)(x)) << BEE_CTR_NONCE1_W3_NONCE13_SHIFT)) & BEE_CTR_NONCE1_W3_NONCE13_MASK)
/*! @} */
/*! @name REGION1_TOP - Region1 Top Address Register */
/*! @{ */
#define BEE_REGION1_TOP_REGION1_TOP_MASK (0xFFFFFFFFU)
#define BEE_REGION1_TOP_REGION1_TOP_SHIFT (0U)
/*! REGION1_TOP - Address upper limit of region1 */
#define BEE_REGION1_TOP_REGION1_TOP(x) (((uint32_t)(((uint32_t)(x)) << BEE_REGION1_TOP_REGION1_TOP_SHIFT)) & BEE_REGION1_TOP_REGION1_TOP_MASK)
/*! @} */
/*! @name REGION1_BOT - Region1 Bottom Address Register */
/*! @{ */
#define BEE_REGION1_BOT_REGION1_BOT_MASK (0xFFFFFFFFU)
#define BEE_REGION1_BOT_REGION1_BOT_SHIFT (0U)
/*! REGION1_BOT - Address lower limit of region1 */
#define BEE_REGION1_BOT_REGION1_BOT(x) (((uint32_t)(((uint32_t)(x)) << BEE_REGION1_BOT_REGION1_BOT_SHIFT)) & BEE_REGION1_BOT_REGION1_BOT_MASK)
/*! @} */
/*!
* @}
*/ /* end of group BEE_Register_Masks */
/*!
* @}
*/ /* end of group BEE_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 */
#endif /* BEE_H_ */

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,305 @@
/*
** ###################################################################
** Processors: MIMXRT1061CVJ5A
** MIMXRT1061CVJ5B
** MIMXRT1061CVL5A
** MIMXRT1061CVL5B
** MIMXRT1061DVJ6A
** MIMXRT1061DVJ6B
** MIMXRT1061DVL6A
** MIMXRT1061DVL6B
** MIMXRT1061XVN5B
** MIMXRT1062CVJ5A
** MIMXRT1062CVJ5B
** MIMXRT1062CVL5A
** MIMXRT1062CVL5B
** MIMXRT1062DVJ6A
** MIMXRT1062DVJ6B
** MIMXRT1062DVL6A
** MIMXRT1062DVL6B
** MIMXRT1062DVN6B
** MIMXRT1062XVN5B
** MIMXRT106ADVL6A
** MIMXRT106CDVL6A
** MIMXRT106FDVL6A
** MIMXRT106LDVL6A
** MIMXRT106SDVL6A
**
** Version: rev. 1.4, 2022-03-25
** Build: b240705
**
** Abstract:
** CMSIS Peripheral Access Layer for CM7_MCM
**
** Copyright 1997-2016 Freescale Semiconductor, Inc.
** Copyright 2016-2024 NXP
** SPDX-License-Identifier: BSD-3-Clause
**
** http: www.nxp.com
** mail: support@nxp.com
**
** Revisions:
** - rev. 0.1 (2017-01-10)
** Initial version.
** - rev. 1.0 (2018-11-16)
** Update header files to align with IMXRT1060RM Rev.0.
** - rev. 1.1 (2018-11-27)
** Update header files to align with IMXRT1060RM Rev.1.
** - rev. 1.2 (2019-04-29)
** Add SET/CLR/TOG register group to register CTRL, STAT, CHANNELCTRL, CH0STAT, CH0OPTS, CH1STAT, CH1OPTS, CH2STAT, CH2OPTS, CH3STAT, CH3OPTS of DCP module.
** - rev. 1.3 (2021-08-10)
** Update header files to align with IMXRT1060RM Rev.3.
** - rev. 1.4 (2022-03-25)
** Add RT1060X device
**
** ###################################################################
*/
/*!
* @file CM7_MCM.h
* @version 1.4
* @date 2022-03-25
* @brief CMSIS Peripheral Access Layer for CM7_MCM
*
* CMSIS Peripheral Access Layer for CM7_MCM
*/
#if !defined(CM7_MCM_H_)
#define CM7_MCM_H_ /**< Symbol preventing repeated inclusion */
#if (defined(CPU_MIMXRT1061CVJ5A) || defined(CPU_MIMXRT1061CVJ5B) || defined(CPU_MIMXRT1061CVL5A) || defined(CPU_MIMXRT1061CVL5B) || defined(CPU_MIMXRT1061DVJ6A) || defined(CPU_MIMXRT1061DVJ6B) || defined(CPU_MIMXRT1061DVL6A) || defined(CPU_MIMXRT1061DVL6B) || defined(CPU_MIMXRT1061XVN5B))
#include "MIMXRT1061_COMMON.h"
#elif (defined(CPU_MIMXRT1062CVJ5A) || defined(CPU_MIMXRT1062CVJ5B) || defined(CPU_MIMXRT1062CVL5A) || defined(CPU_MIMXRT1062CVL5B) || defined(CPU_MIMXRT1062DVJ6A) || defined(CPU_MIMXRT1062DVJ6B) || defined(CPU_MIMXRT1062DVL6A) || defined(CPU_MIMXRT1062DVL6B) || defined(CPU_MIMXRT1062DVN6B) || defined(CPU_MIMXRT1062XVN5B))
#include "MIMXRT1062_COMMON.h"
#elif (defined(CPU_MIMXRT106ADVL6A))
#include "MIMXRT106A_COMMON.h"
#elif (defined(CPU_MIMXRT106CDVL6A))
#include "MIMXRT106C_COMMON.h"
#elif (defined(CPU_MIMXRT106FDVL6A))
#include "MIMXRT106F_COMMON.h"
#elif (defined(CPU_MIMXRT106LDVL6A))
#include "MIMXRT106L_COMMON.h"
#elif (defined(CPU_MIMXRT106SDVL6A))
#include "MIMXRT106S_COMMON.h"
#else
#error "No valid CPU defined!"
#endif
/* ----------------------------------------------------------------------------
-- 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
/* ----------------------------------------------------------------------------
-- CM7_MCM Peripheral Access Layer
---------------------------------------------------------------------------- */
/*!
* @addtogroup CM7_MCM_Peripheral_Access_Layer CM7_MCM Peripheral Access Layer
* @{
*/
/** CM7_MCM - Register Layout Typedef */
typedef struct {
uint8_t RESERVED_0[16];
__IO uint32_t ISCR; /**< Interrupt Status and Control Register, offset: 0x10 */
} CM7_MCM_Type;
/* ----------------------------------------------------------------------------
-- CM7_MCM Register Masks
---------------------------------------------------------------------------- */
/*!
* @addtogroup CM7_MCM_Register_Masks CM7_MCM Register Masks
* @{
*/
/*! @name ISCR - Interrupt Status and Control Register */
/*! @{ */
#define CM7_MCM_ISCR_WABS_MASK (0x20U)
#define CM7_MCM_ISCR_WABS_SHIFT (5U)
/*! WABS - Write Abort on Slave
* 0b0..No abort
* 0b1..Abort
*/
#define CM7_MCM_ISCR_WABS(x) (((uint32_t)(((uint32_t)(x)) << CM7_MCM_ISCR_WABS_SHIFT)) & CM7_MCM_ISCR_WABS_MASK)
#define CM7_MCM_ISCR_WABSO_MASK (0x40U)
#define CM7_MCM_ISCR_WABSO_SHIFT (6U)
/*! WABSO - Write Abort on Slave Overrun
* 0b0..No write abort overrun
* 0b1..Write abort overrun occurred
*/
#define CM7_MCM_ISCR_WABSO(x) (((uint32_t)(((uint32_t)(x)) << CM7_MCM_ISCR_WABSO_SHIFT)) & CM7_MCM_ISCR_WABSO_MASK)
#define CM7_MCM_ISCR_FIOC_MASK (0x100U)
#define CM7_MCM_ISCR_FIOC_SHIFT (8U)
/*! FIOC - FPU Invalid Operation interrupt Status
* 0b0..No interrupt
* 0b1..Interrupt occured
*/
#define CM7_MCM_ISCR_FIOC(x) (((uint32_t)(((uint32_t)(x)) << CM7_MCM_ISCR_FIOC_SHIFT)) & CM7_MCM_ISCR_FIOC_MASK)
#define CM7_MCM_ISCR_FDZC_MASK (0x200U)
#define CM7_MCM_ISCR_FDZC_SHIFT (9U)
/*! FDZC - FPU Divide-by-Zero Interrupt Status
* 0b0..No interrupt
* 0b1..Interrupt occured
*/
#define CM7_MCM_ISCR_FDZC(x) (((uint32_t)(((uint32_t)(x)) << CM7_MCM_ISCR_FDZC_SHIFT)) & CM7_MCM_ISCR_FDZC_MASK)
#define CM7_MCM_ISCR_FOFC_MASK (0x400U)
#define CM7_MCM_ISCR_FOFC_SHIFT (10U)
/*! FOFC - FPU Overflow interrupt status
* 0b0..No interrupt
* 0b1..Interrupt occured
*/
#define CM7_MCM_ISCR_FOFC(x) (((uint32_t)(((uint32_t)(x)) << CM7_MCM_ISCR_FOFC_SHIFT)) & CM7_MCM_ISCR_FOFC_MASK)
#define CM7_MCM_ISCR_FUFC_MASK (0x800U)
#define CM7_MCM_ISCR_FUFC_SHIFT (11U)
/*! FUFC - FPU Underflow Interrupt Status
* 0b0..No interrupt
* 0b1..Interrupt occured
*/
#define CM7_MCM_ISCR_FUFC(x) (((uint32_t)(((uint32_t)(x)) << CM7_MCM_ISCR_FUFC_SHIFT)) & CM7_MCM_ISCR_FUFC_MASK)
#define CM7_MCM_ISCR_FIXC_MASK (0x1000U)
#define CM7_MCM_ISCR_FIXC_SHIFT (12U)
/*! FIXC - FPU Inexact Interrupt Status
* 0b0..No interrupt
* 0b1..Interrupt occured
*/
#define CM7_MCM_ISCR_FIXC(x) (((uint32_t)(((uint32_t)(x)) << CM7_MCM_ISCR_FIXC_SHIFT)) & CM7_MCM_ISCR_FIXC_MASK)
#define CM7_MCM_ISCR_FIDC_MASK (0x8000U)
#define CM7_MCM_ISCR_FIDC_SHIFT (15U)
/*! FIDC - FPU Input Denormal Interrupt Status
* 0b0..No interrupt
* 0b1..Interrupt occured
*/
#define CM7_MCM_ISCR_FIDC(x) (((uint32_t)(((uint32_t)(x)) << CM7_MCM_ISCR_FIDC_SHIFT)) & CM7_MCM_ISCR_FIDC_MASK)
#define CM7_MCM_ISCR_WABE_MASK (0x200000U)
#define CM7_MCM_ISCR_WABE_SHIFT (21U)
/*! WABE - TCM Write Abort Interrupt enable
* 0b0..Disable interrupt
* 0b1..Enable interrupt
*/
#define CM7_MCM_ISCR_WABE(x) (((uint32_t)(((uint32_t)(x)) << CM7_MCM_ISCR_WABE_SHIFT)) & CM7_MCM_ISCR_WABE_MASK)
#define CM7_MCM_ISCR_FIOCE_MASK (0x1000000U)
#define CM7_MCM_ISCR_FIOCE_SHIFT (24U)
/*! FIOCE - FPU Invalid Operation Interrupt Enable
* 0b0..Disable interrupt
* 0b1..Enable interrupt
*/
#define CM7_MCM_ISCR_FIOCE(x) (((uint32_t)(((uint32_t)(x)) << CM7_MCM_ISCR_FIOCE_SHIFT)) & CM7_MCM_ISCR_FIOCE_MASK)
#define CM7_MCM_ISCR_FDZCE_MASK (0x2000000U)
#define CM7_MCM_ISCR_FDZCE_SHIFT (25U)
/*! FDZCE - FPU Divide-by-Zero Interrupt Enable
* 0b0..Disable interrupt
* 0b1..Enable interrupt
*/
#define CM7_MCM_ISCR_FDZCE(x) (((uint32_t)(((uint32_t)(x)) << CM7_MCM_ISCR_FDZCE_SHIFT)) & CM7_MCM_ISCR_FDZCE_MASK)
#define CM7_MCM_ISCR_FOFCE_MASK (0x4000000U)
#define CM7_MCM_ISCR_FOFCE_SHIFT (26U)
/*! FOFCE - FPU Overflow Interrupt Enable
* 0b0..Disable interrupt
* 0b1..Enable interrupt
*/
#define CM7_MCM_ISCR_FOFCE(x) (((uint32_t)(((uint32_t)(x)) << CM7_MCM_ISCR_FOFCE_SHIFT)) & CM7_MCM_ISCR_FOFCE_MASK)
#define CM7_MCM_ISCR_FUFCE_MASK (0x8000000U)
#define CM7_MCM_ISCR_FUFCE_SHIFT (27U)
/*! FUFCE - FPU Underflow Interrupt Enable
* 0b0..Disable interrupt
* 0b1..Enable interrupt
*/
#define CM7_MCM_ISCR_FUFCE(x) (((uint32_t)(((uint32_t)(x)) << CM7_MCM_ISCR_FUFCE_SHIFT)) & CM7_MCM_ISCR_FUFCE_MASK)
#define CM7_MCM_ISCR_FIXCE_MASK (0x10000000U)
#define CM7_MCM_ISCR_FIXCE_SHIFT (28U)
/*! FIXCE - FPU Inexact Interrupt Enable
* 0b0..Disable interrupt
* 0b1..Enable interrupt
*/
#define CM7_MCM_ISCR_FIXCE(x) (((uint32_t)(((uint32_t)(x)) << CM7_MCM_ISCR_FIXCE_SHIFT)) & CM7_MCM_ISCR_FIXCE_MASK)
#define CM7_MCM_ISCR_FIDCE_MASK (0x80000000U)
#define CM7_MCM_ISCR_FIDCE_SHIFT (31U)
/*! FIDCE - FPU Input Denormal Interrupt Enable
* 0b0..Disable interrupt
* 0b1..Enable interrupt
*/
#define CM7_MCM_ISCR_FIDCE(x) (((uint32_t)(((uint32_t)(x)) << CM7_MCM_ISCR_FIDCE_SHIFT)) & CM7_MCM_ISCR_FIDCE_MASK)
/*! @} */
/*!
* @}
*/ /* end of group CM7_MCM_Register_Masks */
/*!
* @}
*/ /* end of group CM7_MCM_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 */
#endif /* CM7_MCM_H_ */

View File

@ -0,0 +1,390 @@
/*
** ###################################################################
** Processors: MIMXRT1061CVJ5A
** MIMXRT1061CVJ5B
** MIMXRT1061CVL5A
** MIMXRT1061CVL5B
** MIMXRT1061DVJ6A
** MIMXRT1061DVJ6B
** MIMXRT1061DVL6A
** MIMXRT1061DVL6B
** MIMXRT1061XVN5B
** MIMXRT1062CVJ5A
** MIMXRT1062CVJ5B
** MIMXRT1062CVL5A
** MIMXRT1062CVL5B
** MIMXRT1062DVJ6A
** MIMXRT1062DVJ6B
** MIMXRT1062DVL6A
** MIMXRT1062DVL6B
** MIMXRT1062DVN6B
** MIMXRT1062XVN5B
** MIMXRT106ADVL6A
** MIMXRT106CDVL6A
** MIMXRT106FDVL6A
** MIMXRT106LDVL6A
** MIMXRT106SDVL6A
**
** Version: rev. 1.4, 2022-03-25
** Build: b240705
**
** Abstract:
** CMSIS Peripheral Access Layer for CMP
**
** Copyright 1997-2016 Freescale Semiconductor, Inc.
** Copyright 2016-2024 NXP
** SPDX-License-Identifier: BSD-3-Clause
**
** http: www.nxp.com
** mail: support@nxp.com
**
** Revisions:
** - rev. 0.1 (2017-01-10)
** Initial version.
** - rev. 1.0 (2018-11-16)
** Update header files to align with IMXRT1060RM Rev.0.
** - rev. 1.1 (2018-11-27)
** Update header files to align with IMXRT1060RM Rev.1.
** - rev. 1.2 (2019-04-29)
** Add SET/CLR/TOG register group to register CTRL, STAT, CHANNELCTRL, CH0STAT, CH0OPTS, CH1STAT, CH1OPTS, CH2STAT, CH2OPTS, CH3STAT, CH3OPTS of DCP module.
** - rev. 1.3 (2021-08-10)
** Update header files to align with IMXRT1060RM Rev.3.
** - rev. 1.4 (2022-03-25)
** Add RT1060X device
**
** ###################################################################
*/
/*!
* @file CMP.h
* @version 1.4
* @date 2022-03-25
* @brief CMSIS Peripheral Access Layer for CMP
*
* CMSIS Peripheral Access Layer for CMP
*/
#if !defined(CMP_H_)
#define CMP_H_ /**< Symbol preventing repeated inclusion */
#if (defined(CPU_MIMXRT1061CVJ5A) || defined(CPU_MIMXRT1061CVJ5B) || defined(CPU_MIMXRT1061CVL5A) || defined(CPU_MIMXRT1061CVL5B) || defined(CPU_MIMXRT1061DVJ6A) || defined(CPU_MIMXRT1061DVJ6B) || defined(CPU_MIMXRT1061DVL6A) || defined(CPU_MIMXRT1061DVL6B) || defined(CPU_MIMXRT1061XVN5B))
#include "MIMXRT1061_COMMON.h"
#elif (defined(CPU_MIMXRT1062CVJ5A) || defined(CPU_MIMXRT1062CVJ5B) || defined(CPU_MIMXRT1062CVL5A) || defined(CPU_MIMXRT1062CVL5B) || defined(CPU_MIMXRT1062DVJ6A) || defined(CPU_MIMXRT1062DVJ6B) || defined(CPU_MIMXRT1062DVL6A) || defined(CPU_MIMXRT1062DVL6B) || defined(CPU_MIMXRT1062DVN6B) || defined(CPU_MIMXRT1062XVN5B))
#include "MIMXRT1062_COMMON.h"
#elif (defined(CPU_MIMXRT106ADVL6A))
#include "MIMXRT106A_COMMON.h"
#elif (defined(CPU_MIMXRT106CDVL6A))
#include "MIMXRT106C_COMMON.h"
#elif (defined(CPU_MIMXRT106FDVL6A))
#include "MIMXRT106F_COMMON.h"
#elif (defined(CPU_MIMXRT106LDVL6A))
#include "MIMXRT106L_COMMON.h"
#elif (defined(CPU_MIMXRT106SDVL6A))
#include "MIMXRT106S_COMMON.h"
#else
#error "No valid CPU defined!"
#endif
/* ----------------------------------------------------------------------------
-- 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
/* ----------------------------------------------------------------------------
-- 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)
/*! HYSTCTR - Comparator hard block hysteresis control
* 0b00..Level 0
* 0b01..Level 1
* 0b10..Level 2
* 0b11..Level 3
*/
#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)
/*! FILTER_CNT - Filter Sample Count
* 0b000..Filter is disabled. If SE = 1, then COUT is a logic 0. This is not a legal state, and is not recommended. If SE = 0, COUT = COUTA.
* 0b001..One sample must agree. The comparator output is simply sampled.
* 0b010..2 consecutive samples must agree.
* 0b011..3 consecutive samples must agree.
* 0b100..4 consecutive samples must agree.
* 0b101..5 consecutive samples must agree.
* 0b110..6 consecutive samples must agree.
* 0b111..7 consecutive samples must agree.
*/
#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)
/*! EN - Comparator Module Enable
* 0b0..Analog Comparator is disabled.
* 0b1..Analog Comparator is enabled.
*/
#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)
/*! OPE - Comparator Output Pin Enable
* 0b0..CMPO is not available on the associated CMPO output pin. If the comparator does not own the pin, this field has no effect.
* 0b1..CMPO is available on the associated CMPO output pin. The comparator output (CMPO) is driven out on the
* associated CMPO output pin if the comparator owns the pin. If the comparator does not own the field, this
* bit has no effect.
*/
#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)
/*! COS - Comparator Output Select
* 0b0..Set the filtered comparator output (CMPO) to equal COUT.
* 0b1..Set the unfiltered comparator output (CMPO) to equal COUTA.
*/
#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)
/*! INV - Comparator INVERT
* 0b0..Does not invert the comparator output.
* 0b1..Inverts the comparator output.
*/
#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)
/*! PMODE - Power Mode Select
* 0b0..Low-Speed (LS) Comparison mode selected. In this mode, CMP has slower output propagation delay and lower current consumption.
* 0b1..High-Speed (HS) Comparison mode selected. In this mode, CMP has faster output propagation delay and higher current consumption.
*/
#define CMP_CR1_PMODE(x) (((uint8_t)(((uint8_t)(x)) << CMP_CR1_PMODE_SHIFT)) & CMP_CR1_PMODE_MASK)
#define CMP_CR1_WE_MASK (0x40U)
#define CMP_CR1_WE_SHIFT (6U)
/*! WE - Windowing Enable
* 0b0..Windowing mode is not selected.
* 0b1..Windowing mode is selected.
*/
#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)
/*! SE - Sample Enable
* 0b0..Sampling mode is not selected.
* 0b1..Sampling mode is selected.
*/
#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)
/*! FILT_PER - Filter Sample Period */
#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)
/*! COUT - Analog Comparator Output */
#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)
/*! CFF - Analog Comparator Flag Falling
* 0b0..Falling-edge on COUT has not been detected.
* 0b1..Falling-edge on COUT has occurred.
*/
#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)
/*! CFR - Analog Comparator Flag Rising
* 0b0..Rising-edge on COUT has not been detected.
* 0b1..Rising-edge on COUT has occurred.
*/
#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)
/*! IEF - Comparator Interrupt Enable Falling
* 0b0..Interrupt is disabled.
* 0b1..Interrupt is enabled.
*/
#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)
/*! IER - Comparator Interrupt Enable Rising
* 0b0..Interrupt is disabled.
* 0b1..Interrupt is enabled.
*/
#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)
/*! DMAEN - DMA Enable Control
* 0b0..DMA is disabled.
* 0b1..DMA is enabled.
*/
#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)
/*! VOSEL - DAC Output Voltage Select */
#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)
/*! VRSEL - Supply Voltage Reference Source Select
* 0b0..Vin1 is selected as resistor ladder network supply reference.
* 0b1..Vin2 is selected as resistor ladder network supply reference.
*/
#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)
/*! DACEN - DAC Enable
* 0b0..DAC is disabled.
* 0b1..DAC is enabled.
*/
#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)
/*! MSEL - Minus Input Mux Control
* 0b000..IN0
* 0b001..IN1
* 0b010..IN2
* 0b011..IN3
* 0b100..IN4
* 0b101..IN5
* 0b110..IN6
* 0b111..IN7
*/
#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)
/*! PSEL - Plus Input Mux Control
* 0b000..IN0
* 0b001..IN1
* 0b010..IN2
* 0b011..IN3
* 0b100..IN4
* 0b101..IN5
* 0b110..IN6
* 0b111..IN7
*/
#define CMP_MUXCR_PSEL(x) (((uint8_t)(((uint8_t)(x)) << CMP_MUXCR_PSEL_SHIFT)) & CMP_MUXCR_PSEL_MASK)
/*! @} */
/*!
* @}
*/ /* end of group CMP_Register_Masks */
/*!
* @}
*/ /* end of group CMP_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 */
#endif /* CMP_H_ */

View File

@ -0,0 +1,916 @@
/*
** ###################################################################
** Processors: MIMXRT1061CVJ5A
** MIMXRT1061CVJ5B
** MIMXRT1061CVL5A
** MIMXRT1061CVL5B
** MIMXRT1061DVJ6A
** MIMXRT1061DVJ6B
** MIMXRT1061DVL6A
** MIMXRT1061DVL6B
** MIMXRT1061XVN5B
** MIMXRT1062CVJ5A
** MIMXRT1062CVJ5B
** MIMXRT1062CVL5A
** MIMXRT1062CVL5B
** MIMXRT1062DVJ6A
** MIMXRT1062DVJ6B
** MIMXRT1062DVL6A
** MIMXRT1062DVL6B
** MIMXRT1062DVN6B
** MIMXRT1062XVN5B
** MIMXRT106ADVL6A
** MIMXRT106CDVL6A
** MIMXRT106FDVL6A
** MIMXRT106LDVL6A
** MIMXRT106SDVL6A
**
** Version: rev. 1.4, 2022-03-25
** Build: b240705
**
** Abstract:
** CMSIS Peripheral Access Layer for CSI
**
** Copyright 1997-2016 Freescale Semiconductor, Inc.
** Copyright 2016-2024 NXP
** SPDX-License-Identifier: BSD-3-Clause
**
** http: www.nxp.com
** mail: support@nxp.com
**
** Revisions:
** - rev. 0.1 (2017-01-10)
** Initial version.
** - rev. 1.0 (2018-11-16)
** Update header files to align with IMXRT1060RM Rev.0.
** - rev. 1.1 (2018-11-27)
** Update header files to align with IMXRT1060RM Rev.1.
** - rev. 1.2 (2019-04-29)
** Add SET/CLR/TOG register group to register CTRL, STAT, CHANNELCTRL, CH0STAT, CH0OPTS, CH1STAT, CH1OPTS, CH2STAT, CH2OPTS, CH3STAT, CH3OPTS of DCP module.
** - rev. 1.3 (2021-08-10)
** Update header files to align with IMXRT1060RM Rev.3.
** - rev. 1.4 (2022-03-25)
** Add RT1060X device
**
** ###################################################################
*/
/*!
* @file CSI.h
* @version 1.4
* @date 2022-03-25
* @brief CMSIS Peripheral Access Layer for CSI
*
* CMSIS Peripheral Access Layer for CSI
*/
#if !defined(CSI_H_)
#define CSI_H_ /**< Symbol preventing repeated inclusion */
#if (defined(CPU_MIMXRT1061CVJ5A) || defined(CPU_MIMXRT1061CVJ5B) || defined(CPU_MIMXRT1061CVL5A) || defined(CPU_MIMXRT1061CVL5B) || defined(CPU_MIMXRT1061DVJ6A) || defined(CPU_MIMXRT1061DVJ6B) || defined(CPU_MIMXRT1061DVL6A) || defined(CPU_MIMXRT1061DVL6B) || defined(CPU_MIMXRT1061XVN5B))
#include "MIMXRT1061_COMMON.h"
#elif (defined(CPU_MIMXRT1062CVJ5A) || defined(CPU_MIMXRT1062CVJ5B) || defined(CPU_MIMXRT1062CVL5A) || defined(CPU_MIMXRT1062CVL5B) || defined(CPU_MIMXRT1062DVJ6A) || defined(CPU_MIMXRT1062DVJ6B) || defined(CPU_MIMXRT1062DVL6A) || defined(CPU_MIMXRT1062DVL6B) || defined(CPU_MIMXRT1062DVN6B) || defined(CPU_MIMXRT1062XVN5B))
#include "MIMXRT1062_COMMON.h"
#elif (defined(CPU_MIMXRT106ADVL6A))
#include "MIMXRT106A_COMMON.h"
#elif (defined(CPU_MIMXRT106CDVL6A))
#include "MIMXRT106C_COMMON.h"
#elif (defined(CPU_MIMXRT106FDVL6A))
#include "MIMXRT106F_COMMON.h"
#elif (defined(CPU_MIMXRT106LDVL6A))
#include "MIMXRT106L_COMMON.h"
#elif (defined(CPU_MIMXRT106SDVL6A))
#include "MIMXRT106S_COMMON.h"
#else
#error "No valid CPU defined!"
#endif
/* ----------------------------------------------------------------------------
-- 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
/* ----------------------------------------------------------------------------
-- CSI Peripheral Access Layer
---------------------------------------------------------------------------- */
/*!
* @addtogroup CSI_Peripheral_Access_Layer CSI Peripheral Access Layer
* @{
*/
/** CSI - Register Layout Typedef */
typedef struct {
__IO uint32_t CR1; /**< CSI Control Register 1, offset: 0x0 */
__IO uint32_t CR2; /**< CSI Control Register 2, offset: 0x4 */
__IO uint32_t CR3; /**< CSI Control Register 3, offset: 0x8 */
__I uint32_t STATFIFO; /**< CSI Statistic FIFO Register, offset: 0xC */
__I uint32_t RFIFO; /**< CSI RX FIFO Register, offset: 0x10 */
__IO uint32_t RXCNT; /**< CSI RX Count Register, offset: 0x14 */
__IO uint32_t SR; /**< CSI Status Register, offset: 0x18 */
uint8_t RESERVED_0[4];
__IO uint32_t DMASA_STATFIFO; /**< CSI DMA Start Address Register - for STATFIFO, offset: 0x20 */
__IO uint32_t DMATS_STATFIFO; /**< CSI DMA Transfer Size Register - for STATFIFO, offset: 0x24 */
__IO uint32_t DMASA_FB1; /**< CSI DMA Start Address Register - for Frame Buffer1, offset: 0x28 */
__IO uint32_t DMASA_FB2; /**< CSI DMA Transfer Size Register - for Frame Buffer2, offset: 0x2C */
__IO uint32_t FBUF_PARA; /**< CSI Frame Buffer Parameter Register, offset: 0x30 */
__IO uint32_t IMAG_PARA; /**< CSI Image Parameter Register, offset: 0x34 */
uint8_t RESERVED_1[16];
__IO uint32_t CR18; /**< CSI Control Register 18, offset: 0x48 */
__IO uint32_t CR19; /**< CSI Control Register 19, offset: 0x4C */
} CSI_Type;
/* ----------------------------------------------------------------------------
-- CSI Register Masks
---------------------------------------------------------------------------- */
/*!
* @addtogroup CSI_Register_Masks CSI Register Masks
* @{
*/
/*! @name CR1 - CSI Control Register 1 */
/*! @{ */
#define CSI_CR1_PIXEL_BIT_MASK (0x1U)
#define CSI_CR1_PIXEL_BIT_SHIFT (0U)
/*! PIXEL_BIT
* 0b0..8-bit data for each pixel
* 0b1..10-bit data for each pixel
*/
#define CSI_CR1_PIXEL_BIT(x) (((uint32_t)(((uint32_t)(x)) << CSI_CR1_PIXEL_BIT_SHIFT)) & CSI_CR1_PIXEL_BIT_MASK)
#define CSI_CR1_REDGE_MASK (0x2U)
#define CSI_CR1_REDGE_SHIFT (1U)
/*! REDGE
* 0b0..Pixel data is latched at the falling edge of CSI_PIXCLK
* 0b1..Pixel data is latched at the rising edge of CSI_PIXCLK
*/
#define CSI_CR1_REDGE(x) (((uint32_t)(((uint32_t)(x)) << CSI_CR1_REDGE_SHIFT)) & CSI_CR1_REDGE_MASK)
#define CSI_CR1_INV_PCLK_MASK (0x4U)
#define CSI_CR1_INV_PCLK_SHIFT (2U)
/*! INV_PCLK
* 0b0..CSI_PIXCLK is directly applied to internal circuitry
* 0b1..CSI_PIXCLK is inverted before applied to internal circuitry
*/
#define CSI_CR1_INV_PCLK(x) (((uint32_t)(((uint32_t)(x)) << CSI_CR1_INV_PCLK_SHIFT)) & CSI_CR1_INV_PCLK_MASK)
#define CSI_CR1_INV_DATA_MASK (0x8U)
#define CSI_CR1_INV_DATA_SHIFT (3U)
/*! INV_DATA
* 0b0..CSI_D[7:0] data lines are directly applied to internal circuitry
* 0b1..CSI_D[7:0] data lines are inverted before applied to internal circuitry
*/
#define CSI_CR1_INV_DATA(x) (((uint32_t)(((uint32_t)(x)) << CSI_CR1_INV_DATA_SHIFT)) & CSI_CR1_INV_DATA_MASK)
#define CSI_CR1_GCLK_MODE_MASK (0x10U)
#define CSI_CR1_GCLK_MODE_SHIFT (4U)
/*! GCLK_MODE
* 0b0..Non-gated clock mode. All incoming pixel clocks are valid. HSYNC is ignored.
* 0b1..Gated clock mode. Pixel clock signal is valid only when HSYNC is active.
*/
#define CSI_CR1_GCLK_MODE(x) (((uint32_t)(((uint32_t)(x)) << CSI_CR1_GCLK_MODE_SHIFT)) & CSI_CR1_GCLK_MODE_MASK)
#define CSI_CR1_CLR_RXFIFO_MASK (0x20U)
#define CSI_CR1_CLR_RXFIFO_SHIFT (5U)
#define CSI_CR1_CLR_RXFIFO(x) (((uint32_t)(((uint32_t)(x)) << CSI_CR1_CLR_RXFIFO_SHIFT)) & CSI_CR1_CLR_RXFIFO_MASK)
#define CSI_CR1_CLR_STATFIFO_MASK (0x40U)
#define CSI_CR1_CLR_STATFIFO_SHIFT (6U)
#define CSI_CR1_CLR_STATFIFO(x) (((uint32_t)(((uint32_t)(x)) << CSI_CR1_CLR_STATFIFO_SHIFT)) & CSI_CR1_CLR_STATFIFO_MASK)
#define CSI_CR1_PACK_DIR_MASK (0x80U)
#define CSI_CR1_PACK_DIR_SHIFT (7U)
/*! PACK_DIR
* 0b0..Pack from LSB first. For image data, 0x11, 0x22, 0x33, 0x44, it will appear as 0x44332211 in RX FIFO. For
* stat data, 0xAAAA, 0xBBBB, it will appear as 0xBBBBAAAA in STAT FIFO.
* 0b1..Pack from MSB first. For image data, 0x11, 0x22, 0x33, 0x44, it will appear as 0x11223344 in RX FIFO. For
* stat data, 0xAAAA, 0xBBBB, it will appear as 0xAAAABBBB in STAT FIFO.
*/
#define CSI_CR1_PACK_DIR(x) (((uint32_t)(((uint32_t)(x)) << CSI_CR1_PACK_DIR_SHIFT)) & CSI_CR1_PACK_DIR_MASK)
#define CSI_CR1_FCC_MASK (0x100U)
#define CSI_CR1_FCC_SHIFT (8U)
/*! FCC
* 0b0..Asynchronous FIFO clear is selected.
* 0b1..Synchronous FIFO clear is selected.
*/
#define CSI_CR1_FCC(x) (((uint32_t)(((uint32_t)(x)) << CSI_CR1_FCC_SHIFT)) & CSI_CR1_FCC_MASK)
#define CSI_CR1_CCIR_EN_MASK (0x400U)
#define CSI_CR1_CCIR_EN_SHIFT (10U)
/*! CCIR_EN
* 0b0..Traditional interface is selected.
* 0b1..BT.656 interface is selected.
*/
#define CSI_CR1_CCIR_EN(x) (((uint32_t)(((uint32_t)(x)) << CSI_CR1_CCIR_EN_SHIFT)) & CSI_CR1_CCIR_EN_MASK)
#define CSI_CR1_HSYNC_POL_MASK (0x800U)
#define CSI_CR1_HSYNC_POL_SHIFT (11U)
/*! HSYNC_POL
* 0b0..HSYNC is active low
* 0b1..HSYNC is active high
*/
#define CSI_CR1_HSYNC_POL(x) (((uint32_t)(((uint32_t)(x)) << CSI_CR1_HSYNC_POL_SHIFT)) & CSI_CR1_HSYNC_POL_MASK)
#define CSI_CR1_SOF_INTEN_MASK (0x10000U)
#define CSI_CR1_SOF_INTEN_SHIFT (16U)
/*! SOF_INTEN
* 0b0..SOF interrupt disable
* 0b1..SOF interrupt enable
*/
#define CSI_CR1_SOF_INTEN(x) (((uint32_t)(((uint32_t)(x)) << CSI_CR1_SOF_INTEN_SHIFT)) & CSI_CR1_SOF_INTEN_MASK)
#define CSI_CR1_SOF_POL_MASK (0x20000U)
#define CSI_CR1_SOF_POL_SHIFT (17U)
/*! SOF_POL
* 0b0..SOF interrupt is generated on SOF falling edge
* 0b1..SOF interrupt is generated on SOF rising edge
*/
#define CSI_CR1_SOF_POL(x) (((uint32_t)(((uint32_t)(x)) << CSI_CR1_SOF_POL_SHIFT)) & CSI_CR1_SOF_POL_MASK)
#define CSI_CR1_RXFF_INTEN_MASK (0x40000U)
#define CSI_CR1_RXFF_INTEN_SHIFT (18U)
/*! RXFF_INTEN
* 0b0..RxFIFO full interrupt disable
* 0b1..RxFIFO full interrupt enable
*/
#define CSI_CR1_RXFF_INTEN(x) (((uint32_t)(((uint32_t)(x)) << CSI_CR1_RXFF_INTEN_SHIFT)) & CSI_CR1_RXFF_INTEN_MASK)
#define CSI_CR1_FB1_DMA_DONE_INTEN_MASK (0x80000U)
#define CSI_CR1_FB1_DMA_DONE_INTEN_SHIFT (19U)
/*! FB1_DMA_DONE_INTEN
* 0b0..Frame Buffer1 DMA Transfer Done interrupt disable
* 0b1..Frame Buffer1 DMA Transfer Done interrupt enable
*/
#define CSI_CR1_FB1_DMA_DONE_INTEN(x) (((uint32_t)(((uint32_t)(x)) << CSI_CR1_FB1_DMA_DONE_INTEN_SHIFT)) & CSI_CR1_FB1_DMA_DONE_INTEN_MASK)
#define CSI_CR1_FB2_DMA_DONE_INTEN_MASK (0x100000U)
#define CSI_CR1_FB2_DMA_DONE_INTEN_SHIFT (20U)
/*! FB2_DMA_DONE_INTEN
* 0b0..Frame Buffer2 DMA Transfer Done interrupt disable
* 0b1..Frame Buffer2 DMA Transfer Done interrupt enable
*/
#define CSI_CR1_FB2_DMA_DONE_INTEN(x) (((uint32_t)(((uint32_t)(x)) << CSI_CR1_FB2_DMA_DONE_INTEN_SHIFT)) & CSI_CR1_FB2_DMA_DONE_INTEN_MASK)
#define CSI_CR1_STATFF_INTEN_MASK (0x200000U)
#define CSI_CR1_STATFF_INTEN_SHIFT (21U)
/*! STATFF_INTEN
* 0b0..STATFIFO full interrupt disable
* 0b1..STATFIFO full interrupt enable
*/
#define CSI_CR1_STATFF_INTEN(x) (((uint32_t)(((uint32_t)(x)) << CSI_CR1_STATFF_INTEN_SHIFT)) & CSI_CR1_STATFF_INTEN_MASK)
#define CSI_CR1_SFF_DMA_DONE_INTEN_MASK (0x400000U)
#define CSI_CR1_SFF_DMA_DONE_INTEN_SHIFT (22U)
/*! SFF_DMA_DONE_INTEN
* 0b0..STATFIFO DMA Transfer Done interrupt disable
* 0b1..STATFIFO DMA Transfer Done interrupt enable
*/
#define CSI_CR1_SFF_DMA_DONE_INTEN(x) (((uint32_t)(((uint32_t)(x)) << CSI_CR1_SFF_DMA_DONE_INTEN_SHIFT)) & CSI_CR1_SFF_DMA_DONE_INTEN_MASK)
#define CSI_CR1_RF_OR_INTEN_MASK (0x1000000U)
#define CSI_CR1_RF_OR_INTEN_SHIFT (24U)
/*! RF_OR_INTEN
* 0b0..RxFIFO overrun interrupt is disabled
* 0b1..RxFIFO overrun interrupt is enabled
*/
#define CSI_CR1_RF_OR_INTEN(x) (((uint32_t)(((uint32_t)(x)) << CSI_CR1_RF_OR_INTEN_SHIFT)) & CSI_CR1_RF_OR_INTEN_MASK)
#define CSI_CR1_SF_OR_INTEN_MASK (0x2000000U)
#define CSI_CR1_SF_OR_INTEN_SHIFT (25U)
/*! SF_OR_INTEN
* 0b0..STATFIFO overrun interrupt is disabled
* 0b1..STATFIFO overrun interrupt is enabled
*/
#define CSI_CR1_SF_OR_INTEN(x) (((uint32_t)(((uint32_t)(x)) << CSI_CR1_SF_OR_INTEN_SHIFT)) & CSI_CR1_SF_OR_INTEN_MASK)
#define CSI_CR1_COF_INT_EN_MASK (0x4000000U)
#define CSI_CR1_COF_INT_EN_SHIFT (26U)
/*! COF_INT_EN
* 0b0..COF interrupt is disabled
* 0b1..COF interrupt is enabled
*/
#define CSI_CR1_COF_INT_EN(x) (((uint32_t)(((uint32_t)(x)) << CSI_CR1_COF_INT_EN_SHIFT)) & CSI_CR1_COF_INT_EN_MASK)
#define CSI_CR1_CCIR_MODE_MASK (0x8000000U)
#define CSI_CR1_CCIR_MODE_SHIFT (27U)
/*! CCIR_MODE
* 0b0..Progressive mode is selected
* 0b1..Interlace mode is selected
*/
#define CSI_CR1_CCIR_MODE(x) (((uint32_t)(((uint32_t)(x)) << CSI_CR1_CCIR_MODE_SHIFT)) & CSI_CR1_CCIR_MODE_MASK)
#define CSI_CR1_PrP_IF_EN_MASK (0x10000000U)
#define CSI_CR1_PrP_IF_EN_SHIFT (28U)
/*! PrP_IF_EN
* 0b0..CSI to PrP bus is disabled
* 0b1..CSI to PrP bus is enabled
*/
#define CSI_CR1_PrP_IF_EN(x) (((uint32_t)(((uint32_t)(x)) << CSI_CR1_PrP_IF_EN_SHIFT)) & CSI_CR1_PrP_IF_EN_MASK)
#define CSI_CR1_EOF_INT_EN_MASK (0x20000000U)
#define CSI_CR1_EOF_INT_EN_SHIFT (29U)
/*! EOF_INT_EN
* 0b0..EOF interrupt is disabled.
* 0b1..EOF interrupt is generated when RX count value is reached.
*/
#define CSI_CR1_EOF_INT_EN(x) (((uint32_t)(((uint32_t)(x)) << CSI_CR1_EOF_INT_EN_SHIFT)) & CSI_CR1_EOF_INT_EN_MASK)
#define CSI_CR1_EXT_VSYNC_MASK (0x40000000U)
#define CSI_CR1_EXT_VSYNC_SHIFT (30U)
/*! EXT_VSYNC
* 0b0..Internal VSYNC mode
* 0b1..External VSYNC mode
*/
#define CSI_CR1_EXT_VSYNC(x) (((uint32_t)(((uint32_t)(x)) << CSI_CR1_EXT_VSYNC_SHIFT)) & CSI_CR1_EXT_VSYNC_MASK)
#define CSI_CR1_SWAP16_EN_MASK (0x80000000U)
#define CSI_CR1_SWAP16_EN_SHIFT (31U)
/*! SWAP16_EN
* 0b0..Disable swapping
* 0b1..Enable swapping
*/
#define CSI_CR1_SWAP16_EN(x) (((uint32_t)(((uint32_t)(x)) << CSI_CR1_SWAP16_EN_SHIFT)) & CSI_CR1_SWAP16_EN_MASK)
/*! @} */
/*! @name CR2 - CSI Control Register 2 */
/*! @{ */
#define CSI_CR2_HSC_MASK (0xFFU)
#define CSI_CR2_HSC_SHIFT (0U)
/*! HSC
* 0b00000000-0b11111111..Number of pixels to skip minus 1
*/
#define CSI_CR2_HSC(x) (((uint32_t)(((uint32_t)(x)) << CSI_CR2_HSC_SHIFT)) & CSI_CR2_HSC_MASK)
#define CSI_CR2_VSC_MASK (0xFF00U)
#define CSI_CR2_VSC_SHIFT (8U)
/*! VSC
* 0b00000000-0b11111111..Number of rows to skip minus 1
*/
#define CSI_CR2_VSC(x) (((uint32_t)(((uint32_t)(x)) << CSI_CR2_VSC_SHIFT)) & CSI_CR2_VSC_MASK)
#define CSI_CR2_LVRM_MASK (0x70000U)
#define CSI_CR2_LVRM_SHIFT (16U)
/*! LVRM
* 0b000..512 x 384
* 0b001..448 x 336
* 0b010..384 x 288
* 0b011..384 x 256
* 0b100..320 x 240
* 0b101..288 x 216
* 0b110..400 x 300
*/
#define CSI_CR2_LVRM(x) (((uint32_t)(((uint32_t)(x)) << CSI_CR2_LVRM_SHIFT)) & CSI_CR2_LVRM_MASK)
#define CSI_CR2_BTS_MASK (0x180000U)
#define CSI_CR2_BTS_SHIFT (19U)
/*! BTS
* 0b00..GR
* 0b01..RG
* 0b10..BG
* 0b11..GB
*/
#define CSI_CR2_BTS(x) (((uint32_t)(((uint32_t)(x)) << CSI_CR2_BTS_SHIFT)) & CSI_CR2_BTS_MASK)
#define CSI_CR2_SCE_MASK (0x800000U)
#define CSI_CR2_SCE_SHIFT (23U)
/*! SCE
* 0b0..Skip count disable
* 0b1..Skip count enable
*/
#define CSI_CR2_SCE(x) (((uint32_t)(((uint32_t)(x)) << CSI_CR2_SCE_SHIFT)) & CSI_CR2_SCE_MASK)
#define CSI_CR2_AFS_MASK (0x3000000U)
#define CSI_CR2_AFS_SHIFT (24U)
/*! AFS
* 0b00..Abs Diff on consecutive green pixels
* 0b01..Abs Diff on every third green pixels
* 0b1x..Abs Diff on every four green pixels
*/
#define CSI_CR2_AFS(x) (((uint32_t)(((uint32_t)(x)) << CSI_CR2_AFS_SHIFT)) & CSI_CR2_AFS_MASK)
#define CSI_CR2_DRM_MASK (0x4000000U)
#define CSI_CR2_DRM_SHIFT (26U)
/*! DRM
* 0b0..Stats grid of 8 x 6
* 0b1..Stats grid of 8 x 12
*/
#define CSI_CR2_DRM(x) (((uint32_t)(((uint32_t)(x)) << CSI_CR2_DRM_SHIFT)) & CSI_CR2_DRM_MASK)
#define CSI_CR2_DMA_BURST_TYPE_SFF_MASK (0x30000000U)
#define CSI_CR2_DMA_BURST_TYPE_SFF_SHIFT (28U)
/*! DMA_BURST_TYPE_SFF
* 0bx0..INCR8
* 0b01..INCR4
* 0b11..INCR16
*/
#define CSI_CR2_DMA_BURST_TYPE_SFF(x) (((uint32_t)(((uint32_t)(x)) << CSI_CR2_DMA_BURST_TYPE_SFF_SHIFT)) & CSI_CR2_DMA_BURST_TYPE_SFF_MASK)
#define CSI_CR2_DMA_BURST_TYPE_RFF_MASK (0xC0000000U)
#define CSI_CR2_DMA_BURST_TYPE_RFF_SHIFT (30U)
/*! DMA_BURST_TYPE_RFF
* 0bx0..INCR8
* 0b01..INCR4
* 0b11..INCR16
*/
#define CSI_CR2_DMA_BURST_TYPE_RFF(x) (((uint32_t)(((uint32_t)(x)) << CSI_CR2_DMA_BURST_TYPE_RFF_SHIFT)) & CSI_CR2_DMA_BURST_TYPE_RFF_MASK)
/*! @} */
/*! @name CR3 - CSI Control Register 3 */
/*! @{ */
#define CSI_CR3_ECC_AUTO_EN_MASK (0x1U)
#define CSI_CR3_ECC_AUTO_EN_SHIFT (0U)
/*! ECC_AUTO_EN
* 0b0..Auto Error correction is disabled.
* 0b1..Auto Error correction is enabled.
*/
#define CSI_CR3_ECC_AUTO_EN(x) (((uint32_t)(((uint32_t)(x)) << CSI_CR3_ECC_AUTO_EN_SHIFT)) & CSI_CR3_ECC_AUTO_EN_MASK)
#define CSI_CR3_ECC_INT_EN_MASK (0x2U)
#define CSI_CR3_ECC_INT_EN_SHIFT (1U)
/*! ECC_INT_EN
* 0b0..No interrupt is generated when error is detected. Only the status bit ECC_INT is set.
* 0b1..Interrupt is generated when error is detected.
*/
#define CSI_CR3_ECC_INT_EN(x) (((uint32_t)(((uint32_t)(x)) << CSI_CR3_ECC_INT_EN_SHIFT)) & CSI_CR3_ECC_INT_EN_MASK)
#define CSI_CR3_ZERO_PACK_EN_MASK (0x4U)
#define CSI_CR3_ZERO_PACK_EN_SHIFT (2U)
/*! ZERO_PACK_EN
* 0b0..Zero packing disabled
* 0b1..Zero packing enabled
*/
#define CSI_CR3_ZERO_PACK_EN(x) (((uint32_t)(((uint32_t)(x)) << CSI_CR3_ZERO_PACK_EN_SHIFT)) & CSI_CR3_ZERO_PACK_EN_MASK)
#define CSI_CR3_SENSOR_16BITS_MASK (0x8U)
#define CSI_CR3_SENSOR_16BITS_SHIFT (3U)
/*! SENSOR_16BITS
* 0b0..Only one 8-bit sensor is connected.
* 0b1..One 16-bit sensor is connected.
*/
#define CSI_CR3_SENSOR_16BITS(x) (((uint32_t)(((uint32_t)(x)) << CSI_CR3_SENSOR_16BITS_SHIFT)) & CSI_CR3_SENSOR_16BITS_MASK)
#define CSI_CR3_RxFF_LEVEL_MASK (0x70U)
#define CSI_CR3_RxFF_LEVEL_SHIFT (4U)
/*! RxFF_LEVEL
* 0b000..4 Double words
* 0b001..8 Double words
* 0b010..16 Double words
* 0b011..24 Double words
* 0b100..32 Double words
* 0b101..48 Double words
* 0b110..64 Double words
* 0b111..96 Double words
*/
#define CSI_CR3_RxFF_LEVEL(x) (((uint32_t)(((uint32_t)(x)) << CSI_CR3_RxFF_LEVEL_SHIFT)) & CSI_CR3_RxFF_LEVEL_MASK)
#define CSI_CR3_HRESP_ERR_EN_MASK (0x80U)
#define CSI_CR3_HRESP_ERR_EN_SHIFT (7U)
/*! HRESP_ERR_EN
* 0b0..Disable hresponse error interrupt
* 0b1..Enable hresponse error interrupt
*/
#define CSI_CR3_HRESP_ERR_EN(x) (((uint32_t)(((uint32_t)(x)) << CSI_CR3_HRESP_ERR_EN_SHIFT)) & CSI_CR3_HRESP_ERR_EN_MASK)
#define CSI_CR3_STATFF_LEVEL_MASK (0x700U)
#define CSI_CR3_STATFF_LEVEL_SHIFT (8U)
/*! STATFF_LEVEL
* 0b000..4 Double words
* 0b001..8 Double words
* 0b010..12 Double words
* 0b011..16 Double words
* 0b100..24 Double words
* 0b101..32 Double words
* 0b110..48 Double words
* 0b111..64 Double words
*/
#define CSI_CR3_STATFF_LEVEL(x) (((uint32_t)(((uint32_t)(x)) << CSI_CR3_STATFF_LEVEL_SHIFT)) & CSI_CR3_STATFF_LEVEL_MASK)
#define CSI_CR3_DMA_REQ_EN_SFF_MASK (0x800U)
#define CSI_CR3_DMA_REQ_EN_SFF_SHIFT (11U)
/*! DMA_REQ_EN_SFF
* 0b0..Disable the dma request
* 0b1..Enable the dma request
*/
#define CSI_CR3_DMA_REQ_EN_SFF(x) (((uint32_t)(((uint32_t)(x)) << CSI_CR3_DMA_REQ_EN_SFF_SHIFT)) & CSI_CR3_DMA_REQ_EN_SFF_MASK)
#define CSI_CR3_DMA_REQ_EN_RFF_MASK (0x1000U)
#define CSI_CR3_DMA_REQ_EN_RFF_SHIFT (12U)
/*! DMA_REQ_EN_RFF
* 0b0..Disable the dma request
* 0b1..Enable the dma request
*/
#define CSI_CR3_DMA_REQ_EN_RFF(x) (((uint32_t)(((uint32_t)(x)) << CSI_CR3_DMA_REQ_EN_RFF_SHIFT)) & CSI_CR3_DMA_REQ_EN_RFF_MASK)
#define CSI_CR3_DMA_REFLASH_SFF_MASK (0x2000U)
#define CSI_CR3_DMA_REFLASH_SFF_SHIFT (13U)
/*! DMA_REFLASH_SFF
* 0b0..No reflashing
* 0b1..Reflash the embedded DMA controller
*/
#define CSI_CR3_DMA_REFLASH_SFF(x) (((uint32_t)(((uint32_t)(x)) << CSI_CR3_DMA_REFLASH_SFF_SHIFT)) & CSI_CR3_DMA_REFLASH_SFF_MASK)
#define CSI_CR3_DMA_REFLASH_RFF_MASK (0x4000U)
#define CSI_CR3_DMA_REFLASH_RFF_SHIFT (14U)
/*! DMA_REFLASH_RFF
* 0b0..No reflashing
* 0b1..Reflash the embedded DMA controller
*/
#define CSI_CR3_DMA_REFLASH_RFF(x) (((uint32_t)(((uint32_t)(x)) << CSI_CR3_DMA_REFLASH_RFF_SHIFT)) & CSI_CR3_DMA_REFLASH_RFF_MASK)
#define CSI_CR3_FRMCNT_RST_MASK (0x8000U)
#define CSI_CR3_FRMCNT_RST_SHIFT (15U)
/*! FRMCNT_RST
* 0b0..Do not reset
* 0b1..Reset frame counter immediately
*/
#define CSI_CR3_FRMCNT_RST(x) (((uint32_t)(((uint32_t)(x)) << CSI_CR3_FRMCNT_RST_SHIFT)) & CSI_CR3_FRMCNT_RST_MASK)
#define CSI_CR3_FRMCNT_MASK (0xFFFF0000U)
#define CSI_CR3_FRMCNT_SHIFT (16U)
#define CSI_CR3_FRMCNT(x) (((uint32_t)(((uint32_t)(x)) << CSI_CR3_FRMCNT_SHIFT)) & CSI_CR3_FRMCNT_MASK)
/*! @} */
/*! @name STATFIFO - CSI Statistic FIFO Register */
/*! @{ */
#define CSI_STATFIFO_STAT_MASK (0xFFFFFFFFU)
#define CSI_STATFIFO_STAT_SHIFT (0U)
#define CSI_STATFIFO_STAT(x) (((uint32_t)(((uint32_t)(x)) << CSI_STATFIFO_STAT_SHIFT)) & CSI_STATFIFO_STAT_MASK)
/*! @} */
/*! @name RFIFO - CSI RX FIFO Register */
/*! @{ */
#define CSI_RFIFO_IMAGE_MASK (0xFFFFFFFFU)
#define CSI_RFIFO_IMAGE_SHIFT (0U)
#define CSI_RFIFO_IMAGE(x) (((uint32_t)(((uint32_t)(x)) << CSI_RFIFO_IMAGE_SHIFT)) & CSI_RFIFO_IMAGE_MASK)
/*! @} */
/*! @name RXCNT - CSI RX Count Register */
/*! @{ */
#define CSI_RXCNT_RXCNT_MASK (0x3FFFFFU)
#define CSI_RXCNT_RXCNT_SHIFT (0U)
#define CSI_RXCNT_RXCNT(x) (((uint32_t)(((uint32_t)(x)) << CSI_RXCNT_RXCNT_SHIFT)) & CSI_RXCNT_RXCNT_MASK)
/*! @} */
/*! @name SR - CSI Status Register */
/*! @{ */
#define CSI_SR_DRDY_MASK (0x1U)
#define CSI_SR_DRDY_SHIFT (0U)
/*! DRDY
* 0b0..No data (word) is ready
* 0b1..At least 1 datum (word) is ready in RXFIFO.
*/
#define CSI_SR_DRDY(x) (((uint32_t)(((uint32_t)(x)) << CSI_SR_DRDY_SHIFT)) & CSI_SR_DRDY_MASK)
#define CSI_SR_ECC_INT_MASK (0x2U)
#define CSI_SR_ECC_INT_SHIFT (1U)
/*! ECC_INT
* 0b0..No error detected
* 0b1..Error is detected in BT.656 coding
*/
#define CSI_SR_ECC_INT(x) (((uint32_t)(((uint32_t)(x)) << CSI_SR_ECC_INT_SHIFT)) & CSI_SR_ECC_INT_MASK)
#define CSI_SR_HRESP_ERR_INT_MASK (0x80U)
#define CSI_SR_HRESP_ERR_INT_SHIFT (7U)
/*! HRESP_ERR_INT
* 0b0..No hresponse error.
* 0b1..Hresponse error is detected.
*/
#define CSI_SR_HRESP_ERR_INT(x) (((uint32_t)(((uint32_t)(x)) << CSI_SR_HRESP_ERR_INT_SHIFT)) & CSI_SR_HRESP_ERR_INT_MASK)
#define CSI_SR_COF_INT_MASK (0x2000U)
#define CSI_SR_COF_INT_SHIFT (13U)
/*! COF_INT
* 0b0..Video field has no change.
* 0b1..Change of video field is detected.
*/
#define CSI_SR_COF_INT(x) (((uint32_t)(((uint32_t)(x)) << CSI_SR_COF_INT_SHIFT)) & CSI_SR_COF_INT_MASK)
#define CSI_SR_F1_INT_MASK (0x4000U)
#define CSI_SR_F1_INT_SHIFT (14U)
/*! F1_INT
* 0b0..Field 1 of video is not detected.
* 0b1..Field 1 of video is about to start.
*/
#define CSI_SR_F1_INT(x) (((uint32_t)(((uint32_t)(x)) << CSI_SR_F1_INT_SHIFT)) & CSI_SR_F1_INT_MASK)
#define CSI_SR_F2_INT_MASK (0x8000U)
#define CSI_SR_F2_INT_SHIFT (15U)
/*! F2_INT
* 0b0..Field 2 of video is not detected
* 0b1..Field 2 of video is about to start
*/
#define CSI_SR_F2_INT(x) (((uint32_t)(((uint32_t)(x)) << CSI_SR_F2_INT_SHIFT)) & CSI_SR_F2_INT_MASK)
#define CSI_SR_SOF_INT_MASK (0x10000U)
#define CSI_SR_SOF_INT_SHIFT (16U)
/*! SOF_INT
* 0b0..SOF is not detected.
* 0b1..SOF is detected.
*/
#define CSI_SR_SOF_INT(x) (((uint32_t)(((uint32_t)(x)) << CSI_SR_SOF_INT_SHIFT)) & CSI_SR_SOF_INT_MASK)
#define CSI_SR_EOF_INT_MASK (0x20000U)
#define CSI_SR_EOF_INT_SHIFT (17U)
/*! EOF_INT
* 0b0..EOF is not detected.
* 0b1..EOF is detected.
*/
#define CSI_SR_EOF_INT(x) (((uint32_t)(((uint32_t)(x)) << CSI_SR_EOF_INT_SHIFT)) & CSI_SR_EOF_INT_MASK)
#define CSI_SR_RxFF_INT_MASK (0x40000U)
#define CSI_SR_RxFF_INT_SHIFT (18U)
/*! RxFF_INT
* 0b0..RxFIFO is not full.
* 0b1..RxFIFO is full.
*/
#define CSI_SR_RxFF_INT(x) (((uint32_t)(((uint32_t)(x)) << CSI_SR_RxFF_INT_SHIFT)) & CSI_SR_RxFF_INT_MASK)
#define CSI_SR_DMA_TSF_DONE_FB1_MASK (0x80000U)
#define CSI_SR_DMA_TSF_DONE_FB1_SHIFT (19U)
/*! DMA_TSF_DONE_FB1
* 0b0..DMA transfer is not completed.
* 0b1..DMA transfer is completed.
*/
#define CSI_SR_DMA_TSF_DONE_FB1(x) (((uint32_t)(((uint32_t)(x)) << CSI_SR_DMA_TSF_DONE_FB1_SHIFT)) & CSI_SR_DMA_TSF_DONE_FB1_MASK)
#define CSI_SR_DMA_TSF_DONE_FB2_MASK (0x100000U)
#define CSI_SR_DMA_TSF_DONE_FB2_SHIFT (20U)
/*! DMA_TSF_DONE_FB2
* 0b0..DMA transfer is not completed.
* 0b1..DMA transfer is completed.
*/
#define CSI_SR_DMA_TSF_DONE_FB2(x) (((uint32_t)(((uint32_t)(x)) << CSI_SR_DMA_TSF_DONE_FB2_SHIFT)) & CSI_SR_DMA_TSF_DONE_FB2_MASK)
#define CSI_SR_STATFF_INT_MASK (0x200000U)
#define CSI_SR_STATFF_INT_SHIFT (21U)
/*! STATFF_INT
* 0b0..STATFIFO is not full.
* 0b1..STATFIFO is full.
*/
#define CSI_SR_STATFF_INT(x) (((uint32_t)(((uint32_t)(x)) << CSI_SR_STATFF_INT_SHIFT)) & CSI_SR_STATFF_INT_MASK)
#define CSI_SR_DMA_TSF_DONE_SFF_MASK (0x400000U)
#define CSI_SR_DMA_TSF_DONE_SFF_SHIFT (22U)
/*! DMA_TSF_DONE_SFF
* 0b0..DMA transfer is not completed.
* 0b1..DMA transfer is completed.
*/
#define CSI_SR_DMA_TSF_DONE_SFF(x) (((uint32_t)(((uint32_t)(x)) << CSI_SR_DMA_TSF_DONE_SFF_SHIFT)) & CSI_SR_DMA_TSF_DONE_SFF_MASK)
#define CSI_SR_RF_OR_INT_MASK (0x1000000U)
#define CSI_SR_RF_OR_INT_SHIFT (24U)
/*! RF_OR_INT
* 0b0..RXFIFO has not overflowed.
* 0b1..RXFIFO has overflowed.
*/
#define CSI_SR_RF_OR_INT(x) (((uint32_t)(((uint32_t)(x)) << CSI_SR_RF_OR_INT_SHIFT)) & CSI_SR_RF_OR_INT_MASK)
#define CSI_SR_SF_OR_INT_MASK (0x2000000U)
#define CSI_SR_SF_OR_INT_SHIFT (25U)
/*! SF_OR_INT
* 0b0..STATFIFO has not overflowed.
* 0b1..STATFIFO has overflowed.
*/
#define CSI_SR_SF_OR_INT(x) (((uint32_t)(((uint32_t)(x)) << CSI_SR_SF_OR_INT_SHIFT)) & CSI_SR_SF_OR_INT_MASK)
#define CSI_SR_DMA_FIELD1_DONE_MASK (0x4000000U)
#define CSI_SR_DMA_FIELD1_DONE_SHIFT (26U)
#define CSI_SR_DMA_FIELD1_DONE(x) (((uint32_t)(((uint32_t)(x)) << CSI_SR_DMA_FIELD1_DONE_SHIFT)) & CSI_SR_DMA_FIELD1_DONE_MASK)
#define CSI_SR_DMA_FIELD0_DONE_MASK (0x8000000U)
#define CSI_SR_DMA_FIELD0_DONE_SHIFT (27U)
#define CSI_SR_DMA_FIELD0_DONE(x) (((uint32_t)(((uint32_t)(x)) << CSI_SR_DMA_FIELD0_DONE_SHIFT)) & CSI_SR_DMA_FIELD0_DONE_MASK)
#define CSI_SR_BASEADDR_CHHANGE_ERROR_MASK (0x10000000U)
#define CSI_SR_BASEADDR_CHHANGE_ERROR_SHIFT (28U)
#define CSI_SR_BASEADDR_CHHANGE_ERROR(x) (((uint32_t)(((uint32_t)(x)) << CSI_SR_BASEADDR_CHHANGE_ERROR_SHIFT)) & CSI_SR_BASEADDR_CHHANGE_ERROR_MASK)
/*! @} */
/*! @name DMASA_STATFIFO - CSI DMA Start Address Register - for STATFIFO */
/*! @{ */
#define CSI_DMASA_STATFIFO_DMA_START_ADDR_SFF_MASK (0xFFFFFFFCU)
#define CSI_DMASA_STATFIFO_DMA_START_ADDR_SFF_SHIFT (2U)
#define CSI_DMASA_STATFIFO_DMA_START_ADDR_SFF(x) (((uint32_t)(((uint32_t)(x)) << CSI_DMASA_STATFIFO_DMA_START_ADDR_SFF_SHIFT)) & CSI_DMASA_STATFIFO_DMA_START_ADDR_SFF_MASK)
/*! @} */
/*! @name DMATS_STATFIFO - CSI DMA Transfer Size Register - for STATFIFO */
/*! @{ */
#define CSI_DMATS_STATFIFO_DMA_TSF_SIZE_SFF_MASK (0xFFFFFFFFU)
#define CSI_DMATS_STATFIFO_DMA_TSF_SIZE_SFF_SHIFT (0U)
#define CSI_DMATS_STATFIFO_DMA_TSF_SIZE_SFF(x) (((uint32_t)(((uint32_t)(x)) << CSI_DMATS_STATFIFO_DMA_TSF_SIZE_SFF_SHIFT)) & CSI_DMATS_STATFIFO_DMA_TSF_SIZE_SFF_MASK)
/*! @} */
/*! @name DMASA_FB1 - CSI DMA Start Address Register - for Frame Buffer1 */
/*! @{ */
#define CSI_DMASA_FB1_DMA_START_ADDR_FB1_MASK (0xFFFFFFFCU)
#define CSI_DMASA_FB1_DMA_START_ADDR_FB1_SHIFT (2U)
#define CSI_DMASA_FB1_DMA_START_ADDR_FB1(x) (((uint32_t)(((uint32_t)(x)) << CSI_DMASA_FB1_DMA_START_ADDR_FB1_SHIFT)) & CSI_DMASA_FB1_DMA_START_ADDR_FB1_MASK)
/*! @} */
/*! @name DMASA_FB2 - CSI DMA Transfer Size Register - for Frame Buffer2 */
/*! @{ */
#define CSI_DMASA_FB2_DMA_START_ADDR_FB2_MASK (0xFFFFFFFCU)
#define CSI_DMASA_FB2_DMA_START_ADDR_FB2_SHIFT (2U)
#define CSI_DMASA_FB2_DMA_START_ADDR_FB2(x) (((uint32_t)(((uint32_t)(x)) << CSI_DMASA_FB2_DMA_START_ADDR_FB2_SHIFT)) & CSI_DMASA_FB2_DMA_START_ADDR_FB2_MASK)
/*! @} */
/*! @name FBUF_PARA - CSI Frame Buffer Parameter Register */
/*! @{ */
#define CSI_FBUF_PARA_FBUF_STRIDE_MASK (0xFFFFU)
#define CSI_FBUF_PARA_FBUF_STRIDE_SHIFT (0U)
#define CSI_FBUF_PARA_FBUF_STRIDE(x) (((uint32_t)(((uint32_t)(x)) << CSI_FBUF_PARA_FBUF_STRIDE_SHIFT)) & CSI_FBUF_PARA_FBUF_STRIDE_MASK)
#define CSI_FBUF_PARA_DEINTERLACE_STRIDE_MASK (0xFFFF0000U)
#define CSI_FBUF_PARA_DEINTERLACE_STRIDE_SHIFT (16U)
#define CSI_FBUF_PARA_DEINTERLACE_STRIDE(x) (((uint32_t)(((uint32_t)(x)) << CSI_FBUF_PARA_DEINTERLACE_STRIDE_SHIFT)) & CSI_FBUF_PARA_DEINTERLACE_STRIDE_MASK)
/*! @} */
/*! @name IMAG_PARA - CSI Image Parameter Register */
/*! @{ */
#define CSI_IMAG_PARA_IMAGE_HEIGHT_MASK (0xFFFFU)
#define CSI_IMAG_PARA_IMAGE_HEIGHT_SHIFT (0U)
#define CSI_IMAG_PARA_IMAGE_HEIGHT(x) (((uint32_t)(((uint32_t)(x)) << CSI_IMAG_PARA_IMAGE_HEIGHT_SHIFT)) & CSI_IMAG_PARA_IMAGE_HEIGHT_MASK)
#define CSI_IMAG_PARA_IMAGE_WIDTH_MASK (0xFFFF0000U)
#define CSI_IMAG_PARA_IMAGE_WIDTH_SHIFT (16U)
#define CSI_IMAG_PARA_IMAGE_WIDTH(x) (((uint32_t)(((uint32_t)(x)) << CSI_IMAG_PARA_IMAGE_WIDTH_SHIFT)) & CSI_IMAG_PARA_IMAGE_WIDTH_MASK)
/*! @} */
/*! @name CR18 - CSI Control Register 18 */
/*! @{ */
#define CSI_CR18_DEINTERLACE_EN_MASK (0x4U)
#define CSI_CR18_DEINTERLACE_EN_SHIFT (2U)
/*! DEINTERLACE_EN
* 0b0..Deinterlace disabled
* 0b1..Deinterlace enabled
*/
#define CSI_CR18_DEINTERLACE_EN(x) (((uint32_t)(((uint32_t)(x)) << CSI_CR18_DEINTERLACE_EN_SHIFT)) & CSI_CR18_DEINTERLACE_EN_MASK)
#define CSI_CR18_PARALLEL24_EN_MASK (0x8U)
#define CSI_CR18_PARALLEL24_EN_SHIFT (3U)
/*! PARALLEL24_EN
* 0b0..Input is disabled
* 0b1..Input is enabled
*/
#define CSI_CR18_PARALLEL24_EN(x) (((uint32_t)(((uint32_t)(x)) << CSI_CR18_PARALLEL24_EN_SHIFT)) & CSI_CR18_PARALLEL24_EN_MASK)
#define CSI_CR18_BASEADDR_SWITCH_EN_MASK (0x10U)
#define CSI_CR18_BASEADDR_SWITCH_EN_SHIFT (4U)
#define CSI_CR18_BASEADDR_SWITCH_EN(x) (((uint32_t)(((uint32_t)(x)) << CSI_CR18_BASEADDR_SWITCH_EN_SHIFT)) & CSI_CR18_BASEADDR_SWITCH_EN_MASK)
#define CSI_CR18_BASEADDR_SWITCH_SEL_MASK (0x20U)
#define CSI_CR18_BASEADDR_SWITCH_SEL_SHIFT (5U)
/*! BASEADDR_SWITCH_SEL
* 0b0..Switching base address at the edge of the vsync
* 0b1..Switching base address at the edge of the first data of each frame
*/
#define CSI_CR18_BASEADDR_SWITCH_SEL(x) (((uint32_t)(((uint32_t)(x)) << CSI_CR18_BASEADDR_SWITCH_SEL_SHIFT)) & CSI_CR18_BASEADDR_SWITCH_SEL_MASK)
#define CSI_CR18_FIELD0_DONE_IE_MASK (0x40U)
#define CSI_CR18_FIELD0_DONE_IE_SHIFT (6U)
/*! FIELD0_DONE_IE
* 0b0..Interrupt disabled
* 0b1..Interrupt enabled
*/
#define CSI_CR18_FIELD0_DONE_IE(x) (((uint32_t)(((uint32_t)(x)) << CSI_CR18_FIELD0_DONE_IE_SHIFT)) & CSI_CR18_FIELD0_DONE_IE_MASK)
#define CSI_CR18_DMA_FIELD1_DONE_IE_MASK (0x80U)
#define CSI_CR18_DMA_FIELD1_DONE_IE_SHIFT (7U)
/*! DMA_FIELD1_DONE_IE
* 0b0..Interrupt disabled
* 0b1..Interrupt enabled
*/
#define CSI_CR18_DMA_FIELD1_DONE_IE(x) (((uint32_t)(((uint32_t)(x)) << CSI_CR18_DMA_FIELD1_DONE_IE_SHIFT)) & CSI_CR18_DMA_FIELD1_DONE_IE_MASK)
#define CSI_CR18_LAST_DMA_REQ_SEL_MASK (0x100U)
#define CSI_CR18_LAST_DMA_REQ_SEL_SHIFT (8U)
/*! LAST_DMA_REQ_SEL
* 0b0..fifo_full_level
* 0b1..hburst_length
*/
#define CSI_CR18_LAST_DMA_REQ_SEL(x) (((uint32_t)(((uint32_t)(x)) << CSI_CR18_LAST_DMA_REQ_SEL_SHIFT)) & CSI_CR18_LAST_DMA_REQ_SEL_MASK)
#define CSI_CR18_BASEADDR_CHANGE_ERROR_IE_MASK (0x200U)
#define CSI_CR18_BASEADDR_CHANGE_ERROR_IE_SHIFT (9U)
/*! BASEADDR_CHANGE_ERROR_IE
* 0b0..Interrupt disabled
* 0b1..Interrupt enabled
*/
#define CSI_CR18_BASEADDR_CHANGE_ERROR_IE(x) (((uint32_t)(((uint32_t)(x)) << CSI_CR18_BASEADDR_CHANGE_ERROR_IE_SHIFT)) & CSI_CR18_BASEADDR_CHANGE_ERROR_IE_MASK)
#define CSI_CR18_RGB888A_FORMAT_SEL_MASK (0x400U)
#define CSI_CR18_RGB888A_FORMAT_SEL_SHIFT (10U)
/*! RGB888A_FORMAT_SEL
* 0b0..{8'h0, data[23:0]}
* 0b1..{data[23:0], 8'h0}
*/
#define CSI_CR18_RGB888A_FORMAT_SEL(x) (((uint32_t)(((uint32_t)(x)) << CSI_CR18_RGB888A_FORMAT_SEL_SHIFT)) & CSI_CR18_RGB888A_FORMAT_SEL_MASK)
#define CSI_CR18_AHB_HPROT_MASK (0xF000U)
#define CSI_CR18_AHB_HPROT_SHIFT (12U)
#define CSI_CR18_AHB_HPROT(x) (((uint32_t)(((uint32_t)(x)) << CSI_CR18_AHB_HPROT_SHIFT)) & CSI_CR18_AHB_HPROT_MASK)
#define CSI_CR18_MASK_OPTION_MASK (0xC0000U)
#define CSI_CR18_MASK_OPTION_SHIFT (18U)
/*! MASK_OPTION
* 0b00..Writing to memory (OCRAM or external DDR) from first completely frame, when using this option, the CSI_ENABLE should be 1.
* 0b01..Writing to memory when CSI_ENABLE is 1.
* 0b10..Writing to memory from second completely frame, when using this option, the CSI_ENABLE should be 1.
* 0b11..Writing to memory when data comes in, not matter the CSI_ENABLE is 1 or 0.
*/
#define CSI_CR18_MASK_OPTION(x) (((uint32_t)(((uint32_t)(x)) << CSI_CR18_MASK_OPTION_SHIFT)) & CSI_CR18_MASK_OPTION_MASK)
#define CSI_CR18_CSI_ENABLE_MASK (0x80000000U)
#define CSI_CR18_CSI_ENABLE_SHIFT (31U)
#define CSI_CR18_CSI_ENABLE(x) (((uint32_t)(((uint32_t)(x)) << CSI_CR18_CSI_ENABLE_SHIFT)) & CSI_CR18_CSI_ENABLE_MASK)
/*! @} */
/*! @name CR19 - CSI Control Register 19 */
/*! @{ */
#define CSI_CR19_DMA_RFIFO_HIGHEST_FIFO_LEVEL_MASK (0xFFU)
#define CSI_CR19_DMA_RFIFO_HIGHEST_FIFO_LEVEL_SHIFT (0U)
#define CSI_CR19_DMA_RFIFO_HIGHEST_FIFO_LEVEL(x) (((uint32_t)(((uint32_t)(x)) << CSI_CR19_DMA_RFIFO_HIGHEST_FIFO_LEVEL_SHIFT)) & CSI_CR19_DMA_RFIFO_HIGHEST_FIFO_LEVEL_MASK)
/*! @} */
/*!
* @}
*/ /* end of group CSI_Register_Masks */
/*!
* @}
*/ /* end of group CSI_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 */
#endif /* CSI_H_ */

View File

@ -0,0 +1,877 @@
/*
** ###################################################################
** Processors: MIMXRT1061CVJ5A
** MIMXRT1061CVJ5B
** MIMXRT1061CVL5A
** MIMXRT1061CVL5B
** MIMXRT1061DVJ6A
** MIMXRT1061DVJ6B
** MIMXRT1061DVL6A
** MIMXRT1061DVL6B
** MIMXRT1061XVN5B
** MIMXRT1062CVJ5A
** MIMXRT1062CVJ5B
** MIMXRT1062CVL5A
** MIMXRT1062CVL5B
** MIMXRT1062DVJ6A
** MIMXRT1062DVJ6B
** MIMXRT1062DVL6A
** MIMXRT1062DVL6B
** MIMXRT1062DVN6B
** MIMXRT1062XVN5B
** MIMXRT106ADVL6A
** MIMXRT106CDVL6A
** MIMXRT106FDVL6A
** MIMXRT106LDVL6A
** MIMXRT106SDVL6A
**
** Version: rev. 1.4, 2022-03-25
** Build: b240705
**
** Abstract:
** CMSIS Peripheral Access Layer for CSU
**
** Copyright 1997-2016 Freescale Semiconductor, Inc.
** Copyright 2016-2024 NXP
** SPDX-License-Identifier: BSD-3-Clause
**
** http: www.nxp.com
** mail: support@nxp.com
**
** Revisions:
** - rev. 0.1 (2017-01-10)
** Initial version.
** - rev. 1.0 (2018-11-16)
** Update header files to align with IMXRT1060RM Rev.0.
** - rev. 1.1 (2018-11-27)
** Update header files to align with IMXRT1060RM Rev.1.
** - rev. 1.2 (2019-04-29)
** Add SET/CLR/TOG register group to register CTRL, STAT, CHANNELCTRL, CH0STAT, CH0OPTS, CH1STAT, CH1OPTS, CH2STAT, CH2OPTS, CH3STAT, CH3OPTS of DCP module.
** - rev. 1.3 (2021-08-10)
** Update header files to align with IMXRT1060RM Rev.3.
** - rev. 1.4 (2022-03-25)
** Add RT1060X device
**
** ###################################################################
*/
/*!
* @file CSU.h
* @version 1.4
* @date 2022-03-25
* @brief CMSIS Peripheral Access Layer for CSU
*
* CMSIS Peripheral Access Layer for CSU
*/
#if !defined(CSU_H_)
#define CSU_H_ /**< Symbol preventing repeated inclusion */
#if (defined(CPU_MIMXRT1061CVJ5A) || defined(CPU_MIMXRT1061CVJ5B) || defined(CPU_MIMXRT1061CVL5A) || defined(CPU_MIMXRT1061CVL5B) || defined(CPU_MIMXRT1061DVJ6A) || defined(CPU_MIMXRT1061DVJ6B) || defined(CPU_MIMXRT1061DVL6A) || defined(CPU_MIMXRT1061DVL6B) || defined(CPU_MIMXRT1061XVN5B))
#include "MIMXRT1061_COMMON.h"
#elif (defined(CPU_MIMXRT1062CVJ5A) || defined(CPU_MIMXRT1062CVJ5B) || defined(CPU_MIMXRT1062CVL5A) || defined(CPU_MIMXRT1062CVL5B) || defined(CPU_MIMXRT1062DVJ6A) || defined(CPU_MIMXRT1062DVJ6B) || defined(CPU_MIMXRT1062DVL6A) || defined(CPU_MIMXRT1062DVL6B) || defined(CPU_MIMXRT1062DVN6B) || defined(CPU_MIMXRT1062XVN5B))
#include "MIMXRT1062_COMMON.h"
#elif (defined(CPU_MIMXRT106ADVL6A))
#include "MIMXRT106A_COMMON.h"
#elif (defined(CPU_MIMXRT106CDVL6A))
#include "MIMXRT106C_COMMON.h"
#elif (defined(CPU_MIMXRT106FDVL6A))
#include "MIMXRT106F_COMMON.h"
#elif (defined(CPU_MIMXRT106LDVL6A))
#include "MIMXRT106L_COMMON.h"
#elif (defined(CPU_MIMXRT106SDVL6A))
#include "MIMXRT106S_COMMON.h"
#else
#error "No valid CPU defined!"
#endif
/* ----------------------------------------------------------------------------
-- 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
/* ----------------------------------------------------------------------------
-- CSU Peripheral Access Layer
---------------------------------------------------------------------------- */
/*!
* @addtogroup CSU_Peripheral_Access_Layer CSU Peripheral Access Layer
* @{
*/
/** CSU - Size of Registers Arrays */
#define CSU_CSL_COUNT 32u
/** CSU - Register Layout Typedef */
typedef struct {
__IO uint32_t CSL[CSU_CSL_COUNT]; /**< Config security level register, array offset: 0x0, array step: 0x4 */
uint8_t RESERVED_0[384];
__IO uint32_t HP0; /**< HP0 register, offset: 0x200 */
uint8_t RESERVED_1[20];
__IO uint32_t SA; /**< Secure access register, offset: 0x218 */
uint8_t RESERVED_2[316];
__IO uint32_t HPCONTROL0; /**< HPCONTROL0 register, offset: 0x358 */
} CSU_Type;
/* ----------------------------------------------------------------------------
-- CSU Register Masks
---------------------------------------------------------------------------- */
/*!
* @addtogroup CSU_Register_Masks CSU Register Masks
* @{
*/
/*! @name CSL - Config security level register */
/*! @{ */
#define CSU_CSL_SUR_S2_MASK (0x1U)
#define CSU_CSL_SUR_S2_SHIFT (0U)
/*! SUR_S2
* 0b0..The secure user read access is disabled for the second slave.
* 0b1..The secure user read access is enabled for the second slave.
*/
#define CSU_CSL_SUR_S2(x) (((uint32_t)(((uint32_t)(x)) << CSU_CSL_SUR_S2_SHIFT)) & CSU_CSL_SUR_S2_MASK)
#define CSU_CSL_SSR_S2_MASK (0x2U)
#define CSU_CSL_SSR_S2_SHIFT (1U)
/*! SSR_S2
* 0b0..The secure supervisor read access is disabled for the second slave.
* 0b1..The secure supervisor read access is enabled for the second slave.
*/
#define CSU_CSL_SSR_S2(x) (((uint32_t)(((uint32_t)(x)) << CSU_CSL_SSR_S2_SHIFT)) & CSU_CSL_SSR_S2_MASK)
#define CSU_CSL_NUR_S2_MASK (0x4U)
#define CSU_CSL_NUR_S2_SHIFT (2U)
/*! NUR_S2
* 0b0..The non-secure user read access is disabled for the second slave.
* 0b1..The non-secure user read access is enabled for the second slave.
*/
#define CSU_CSL_NUR_S2(x) (((uint32_t)(((uint32_t)(x)) << CSU_CSL_NUR_S2_SHIFT)) & CSU_CSL_NUR_S2_MASK)
#define CSU_CSL_NSR_S2_MASK (0x8U)
#define CSU_CSL_NSR_S2_SHIFT (3U)
/*! NSR_S2
* 0b0..The non-secure supervisor read access is disabled for the second slave.
* 0b1..The non-secure supervisor read access is enabled for the second slave.
*/
#define CSU_CSL_NSR_S2(x) (((uint32_t)(((uint32_t)(x)) << CSU_CSL_NSR_S2_SHIFT)) & CSU_CSL_NSR_S2_MASK)
#define CSU_CSL_SUW_S2_MASK (0x10U)
#define CSU_CSL_SUW_S2_SHIFT (4U)
/*! SUW_S2
* 0b0..The secure user write access is disabled for the second slave.
* 0b1..The secure user write access is enabled for the second slave.
*/
#define CSU_CSL_SUW_S2(x) (((uint32_t)(((uint32_t)(x)) << CSU_CSL_SUW_S2_SHIFT)) & CSU_CSL_SUW_S2_MASK)
#define CSU_CSL_SSW_S2_MASK (0x20U)
#define CSU_CSL_SSW_S2_SHIFT (5U)
/*! SSW_S2
* 0b0..The secure supervisor write access is disabled for the second slave.
* 0b1..The secure supervisor write access is enabled for the second slave.
*/
#define CSU_CSL_SSW_S2(x) (((uint32_t)(((uint32_t)(x)) << CSU_CSL_SSW_S2_SHIFT)) & CSU_CSL_SSW_S2_MASK)
#define CSU_CSL_NUW_S2_MASK (0x40U)
#define CSU_CSL_NUW_S2_SHIFT (6U)
/*! NUW_S2
* 0b0..The non-secure user write access is disabled for the second slave.
* 0b1..The non-secure user write access is enabled for the second slave.
*/
#define CSU_CSL_NUW_S2(x) (((uint32_t)(((uint32_t)(x)) << CSU_CSL_NUW_S2_SHIFT)) & CSU_CSL_NUW_S2_MASK)
#define CSU_CSL_NSW_S2_MASK (0x80U)
#define CSU_CSL_NSW_S2_SHIFT (7U)
/*! NSW_S2
* 0b0..The non-secure supervisor write access is disabled for the second slave.
* 0b1..The non-secure supervisor write access is enabled for the second slave.
*/
#define CSU_CSL_NSW_S2(x) (((uint32_t)(((uint32_t)(x)) << CSU_CSL_NSW_S2_SHIFT)) & CSU_CSL_NSW_S2_MASK)
#define CSU_CSL_LOCK_S2_MASK (0x100U)
#define CSU_CSL_LOCK_S2_SHIFT (8U)
/*! LOCK_S2
* 0b0..Not locked. Bits 7-0 can be written by the software.
* 0b1..Bits 7-0 are locked and cannot be written by the software
*/
#define CSU_CSL_LOCK_S2(x) (((uint32_t)(((uint32_t)(x)) << CSU_CSL_LOCK_S2_SHIFT)) & CSU_CSL_LOCK_S2_MASK)
#define CSU_CSL_SUR_S1_MASK (0x10000U)
#define CSU_CSL_SUR_S1_SHIFT (16U)
/*! SUR_S1
* 0b0..The secure user read access is disabled for the first slave.
* 0b1..The secure user read access is enabled for the first slave.
*/
#define CSU_CSL_SUR_S1(x) (((uint32_t)(((uint32_t)(x)) << CSU_CSL_SUR_S1_SHIFT)) & CSU_CSL_SUR_S1_MASK)
#define CSU_CSL_SSR_S1_MASK (0x20000U)
#define CSU_CSL_SSR_S1_SHIFT (17U)
/*! SSR_S1
* 0b0..The secure supervisor read access is disabled for the first slave.
* 0b1..The secure supervisor read access is enabled for the first slave.
*/
#define CSU_CSL_SSR_S1(x) (((uint32_t)(((uint32_t)(x)) << CSU_CSL_SSR_S1_SHIFT)) & CSU_CSL_SSR_S1_MASK)
#define CSU_CSL_NUR_S1_MASK (0x40000U)
#define CSU_CSL_NUR_S1_SHIFT (18U)
/*! NUR_S1
* 0b0..The non-secure user read access is disabled for the first slave.
* 0b1..The non-secure user read access is enabled for the first slave.
*/
#define CSU_CSL_NUR_S1(x) (((uint32_t)(((uint32_t)(x)) << CSU_CSL_NUR_S1_SHIFT)) & CSU_CSL_NUR_S1_MASK)
#define CSU_CSL_NSR_S1_MASK (0x80000U)
#define CSU_CSL_NSR_S1_SHIFT (19U)
/*! NSR_S1
* 0b0..The non-secure supervisor read access is disabled for the first slave.
* 0b1..The non-secure supervisor read access is enabled for the first slave.
*/
#define CSU_CSL_NSR_S1(x) (((uint32_t)(((uint32_t)(x)) << CSU_CSL_NSR_S1_SHIFT)) & CSU_CSL_NSR_S1_MASK)
#define CSU_CSL_SUW_S1_MASK (0x100000U)
#define CSU_CSL_SUW_S1_SHIFT (20U)
/*! SUW_S1
* 0b0..The secure user write access is disabled for the first slave.
* 0b1..The secure user write access is enabled for the first slave.
*/
#define CSU_CSL_SUW_S1(x) (((uint32_t)(((uint32_t)(x)) << CSU_CSL_SUW_S1_SHIFT)) & CSU_CSL_SUW_S1_MASK)
#define CSU_CSL_SSW_S1_MASK (0x200000U)
#define CSU_CSL_SSW_S1_SHIFT (21U)
/*! SSW_S1
* 0b0..The secure supervisor write access is disabled for the first slave.
* 0b1..The secure supervisor write access is enabled for the first slave.
*/
#define CSU_CSL_SSW_S1(x) (((uint32_t)(((uint32_t)(x)) << CSU_CSL_SSW_S1_SHIFT)) & CSU_CSL_SSW_S1_MASK)
#define CSU_CSL_NUW_S1_MASK (0x400000U)
#define CSU_CSL_NUW_S1_SHIFT (22U)
/*! NUW_S1
* 0b0..The non-secure user write access is disabled for the first slave.
* 0b1..The non-secure user write access is enabled for the first slave.
*/
#define CSU_CSL_NUW_S1(x) (((uint32_t)(((uint32_t)(x)) << CSU_CSL_NUW_S1_SHIFT)) & CSU_CSL_NUW_S1_MASK)
#define CSU_CSL_NSW_S1_MASK (0x800000U)
#define CSU_CSL_NSW_S1_SHIFT (23U)
/*! NSW_S1
* 0b0..The non-secure supervisor write access is disabled for the first slave.
* 0b1..The non-secure supervisor write access is enabled for the first slave
*/
#define CSU_CSL_NSW_S1(x) (((uint32_t)(((uint32_t)(x)) << CSU_CSL_NSW_S1_SHIFT)) & CSU_CSL_NSW_S1_MASK)
#define CSU_CSL_LOCK_S1_MASK (0x1000000U)
#define CSU_CSL_LOCK_S1_SHIFT (24U)
/*! LOCK_S1
* 0b0..Not locked. The bits 16-23 can be written by the software.
* 0b1..The bits 16-23 are locked and can't be written by the software.
*/
#define CSU_CSL_LOCK_S1(x) (((uint32_t)(((uint32_t)(x)) << CSU_CSL_LOCK_S1_SHIFT)) & CSU_CSL_LOCK_S1_MASK)
/*! @} */
/*! @name HP0 - HP0 register */
/*! @{ */
#define CSU_HP0_HP_DMA_MASK (0x4U)
#define CSU_HP0_HP_DMA_SHIFT (2U)
/*! HP_DMA
* 0b0..The hprot1 input signal value is routed to the csu_hprot1 output for the corresponding master.
* 0b1..The HP register bit is routed to the csu_hprot1 output for the corresponding master.
*/
#define CSU_HP0_HP_DMA(x) (((uint32_t)(((uint32_t)(x)) << CSU_HP0_HP_DMA_SHIFT)) & CSU_HP0_HP_DMA_MASK)
#define CSU_HP0_L_DMA_MASK (0x8U)
#define CSU_HP0_L_DMA_SHIFT (3U)
/*! L_DMA
* 0b0..No lock-the adjacent (next lower) bit can be written by the software.
* 0b1..Lock-the adjacent (next lower) bit can't be written by the software.
*/
#define CSU_HP0_L_DMA(x) (((uint32_t)(((uint32_t)(x)) << CSU_HP0_L_DMA_SHIFT)) & CSU_HP0_L_DMA_MASK)
#define CSU_HP0_HP_LCDIF_MASK (0x10U)
#define CSU_HP0_HP_LCDIF_SHIFT (4U)
/*! HP_LCDIF
* 0b0..The hprot1 input signal value is routed to the csu_hprot1 output for the corresponding master.
* 0b1..The HP register bit is routed to the csu_hprot1 output for the corresponding master.
*/
#define CSU_HP0_HP_LCDIF(x) (((uint32_t)(((uint32_t)(x)) << CSU_HP0_HP_LCDIF_SHIFT)) & CSU_HP0_HP_LCDIF_MASK)
#define CSU_HP0_L_LCDIF_MASK (0x20U)
#define CSU_HP0_L_LCDIF_SHIFT (5U)
/*! L_LCDIF
* 0b0..No lock-the adjacent (next lower) bit can be written by the software.
* 0b1..Lock-the adjacent (next lower) bit can't be written by the software.
*/
#define CSU_HP0_L_LCDIF(x) (((uint32_t)(((uint32_t)(x)) << CSU_HP0_L_LCDIF_SHIFT)) & CSU_HP0_L_LCDIF_MASK)
#define CSU_HP0_HP_CSI_MASK (0x40U)
#define CSU_HP0_HP_CSI_SHIFT (6U)
/*! HP_CSI
* 0b0..The hprot1 input signal value is routed to the csu_hprot1 output for the corresponding master.
* 0b1..The HP register bit is routed to the csu_hprot1 output for the corresponding master.
*/
#define CSU_HP0_HP_CSI(x) (((uint32_t)(((uint32_t)(x)) << CSU_HP0_HP_CSI_SHIFT)) & CSU_HP0_HP_CSI_MASK)
#define CSU_HP0_L_CSI_MASK (0x80U)
#define CSU_HP0_L_CSI_SHIFT (7U)
/*! L_CSI
* 0b0..No lock-the adjacent (next lower) bit can be written by the software.
* 0b1..Lock-the adjacent (next lower) bit can't be written by the software.
*/
#define CSU_HP0_L_CSI(x) (((uint32_t)(((uint32_t)(x)) << CSU_HP0_L_CSI_SHIFT)) & CSU_HP0_L_CSI_MASK)
#define CSU_HP0_HP_PXP_MASK (0x100U)
#define CSU_HP0_HP_PXP_SHIFT (8U)
/*! HP_PXP
* 0b0..The hprot1 input signal value is routed to the csu_hprot1 output for the corresponding master.
* 0b1..The HP register bit is routed to the csu_hprot1 output for the corresponding master.
*/
#define CSU_HP0_HP_PXP(x) (((uint32_t)(((uint32_t)(x)) << CSU_HP0_HP_PXP_SHIFT)) & CSU_HP0_HP_PXP_MASK)
#define CSU_HP0_L_PXP_MASK (0x200U)
#define CSU_HP0_L_PXP_SHIFT (9U)
/*! L_PXP
* 0b0..No lock-the adjacent (next lower) bit can be written by the software.
* 0b1..Lock-the adjacent (next lower) bit can't be written by the software.
*/
#define CSU_HP0_L_PXP(x) (((uint32_t)(((uint32_t)(x)) << CSU_HP0_L_PXP_SHIFT)) & CSU_HP0_L_PXP_MASK)
#define CSU_HP0_HP_DCP_MASK (0x400U)
#define CSU_HP0_HP_DCP_SHIFT (10U)
/*! HP_DCP
* 0b0..The hprot1 input signal value is routed to the csu_hprot1 output for the corresponding master.
* 0b1..The HP register bit is routed to the csu_hprot1 output for the corresponding master.
*/
#define CSU_HP0_HP_DCP(x) (((uint32_t)(((uint32_t)(x)) << CSU_HP0_HP_DCP_SHIFT)) & CSU_HP0_HP_DCP_MASK)
#define CSU_HP0_L_DCP_MASK (0x800U)
#define CSU_HP0_L_DCP_SHIFT (11U)
/*! L_DCP
* 0b0..No lock-the adjacent (next lower) bit can be written by the software.
* 0b1..Lock-the adjacent (next lower) bit cannot be written by the software.
*/
#define CSU_HP0_L_DCP(x) (((uint32_t)(((uint32_t)(x)) << CSU_HP0_L_DCP_SHIFT)) & CSU_HP0_L_DCP_MASK)
#define CSU_HP0_HP_ENET_MASK (0x4000U)
#define CSU_HP0_HP_ENET_SHIFT (14U)
/*! HP_ENET
* 0b0..The hprot1 input signal value is routed to the csu_hprot1 output for the corresponding master.
* 0b1..The HP register bit is routed to the csu_hprot1 output for the corresponding master.
*/
#define CSU_HP0_HP_ENET(x) (((uint32_t)(((uint32_t)(x)) << CSU_HP0_HP_ENET_SHIFT)) & CSU_HP0_HP_ENET_MASK)
#define CSU_HP0_L_ENET_MASK (0x8000U)
#define CSU_HP0_L_ENET_SHIFT (15U)
/*! L_ENET
* 0b0..No lock-the adjacent (next lower) bit can be written by the software.
* 0b1..Lock-the adjacent (next lower) bit can't be written by the software.
*/
#define CSU_HP0_L_ENET(x) (((uint32_t)(((uint32_t)(x)) << CSU_HP0_L_ENET_SHIFT)) & CSU_HP0_L_ENET_MASK)
#define CSU_HP0_HP_USDHC1_MASK (0x10000U)
#define CSU_HP0_HP_USDHC1_SHIFT (16U)
/*! HP_USDHC1
* 0b0..The hprot1 input signal value is routed to the csu_hprot1 output for the corresponding master.
* 0b1..The HP register bit is routed to the csu_hprot1 output for the corresponding master.
*/
#define CSU_HP0_HP_USDHC1(x) (((uint32_t)(((uint32_t)(x)) << CSU_HP0_HP_USDHC1_SHIFT)) & CSU_HP0_HP_USDHC1_MASK)
#define CSU_HP0_L_USDHC1_MASK (0x20000U)
#define CSU_HP0_L_USDHC1_SHIFT (17U)
/*! L_USDHC1
* 0b0..No lock-the adjacent (next lower) bit can be written by the software.
* 0b1..Lock-the adjacent (next lower) bit can't be written by the software.
*/
#define CSU_HP0_L_USDHC1(x) (((uint32_t)(((uint32_t)(x)) << CSU_HP0_L_USDHC1_SHIFT)) & CSU_HP0_L_USDHC1_MASK)
#define CSU_HP0_HP_USDHC2_MASK (0x40000U)
#define CSU_HP0_HP_USDHC2_SHIFT (18U)
/*! HP_USDHC2
* 0b0..The hprot1 input signal value is routed to the csu_hprot1 output for the corresponding master.
* 0b1..The HP register bit is routed to the csu_hprot1 output for the corresponding master.
*/
#define CSU_HP0_HP_USDHC2(x) (((uint32_t)(((uint32_t)(x)) << CSU_HP0_HP_USDHC2_SHIFT)) & CSU_HP0_HP_USDHC2_MASK)
#define CSU_HP0_L_USDHC2_MASK (0x80000U)
#define CSU_HP0_L_USDHC2_SHIFT (19U)
/*! L_USDHC2
* 0b0..No lock-the adjacent (next lower) bit can be written by the software.
* 0b1..Lock-the adjacent (next lower) bit can't be written by the software.
*/
#define CSU_HP0_L_USDHC2(x) (((uint32_t)(((uint32_t)(x)) << CSU_HP0_L_USDHC2_SHIFT)) & CSU_HP0_L_USDHC2_MASK)
#define CSU_HP0_HP_TPSMP_MASK (0x100000U)
#define CSU_HP0_HP_TPSMP_SHIFT (20U)
/*! HP_TPSMP
* 0b0..The hprot1 input signal value is routed to the csu_hprot1 output for the corresponding master.
* 0b1..The HP register bit is routed to the csu_hprot1 output for the corresponding master.
*/
#define CSU_HP0_HP_TPSMP(x) (((uint32_t)(((uint32_t)(x)) << CSU_HP0_HP_TPSMP_SHIFT)) & CSU_HP0_HP_TPSMP_MASK)
#define CSU_HP0_L_TPSMP_MASK (0x200000U)
#define CSU_HP0_L_TPSMP_SHIFT (21U)
/*! L_TPSMP
* 0b0..No lock-the adjacent (next lower) bit can be written by the software.
* 0b1..Lock-the adjacent (next lower) bit can't be written by the software.
*/
#define CSU_HP0_L_TPSMP(x) (((uint32_t)(((uint32_t)(x)) << CSU_HP0_L_TPSMP_SHIFT)) & CSU_HP0_L_TPSMP_MASK)
#define CSU_HP0_HP_USB_MASK (0x400000U)
#define CSU_HP0_HP_USB_SHIFT (22U)
/*! HP_USB
* 0b0..The hprot1 input signal value is routed to the csu_hprot1 output for the corresponding master.
* 0b1..The HP register bit is routed to the csu_hprot1 output for the corresponding master.
*/
#define CSU_HP0_HP_USB(x) (((uint32_t)(((uint32_t)(x)) << CSU_HP0_HP_USB_SHIFT)) & CSU_HP0_HP_USB_MASK)
#define CSU_HP0_L_USB_MASK (0x800000U)
#define CSU_HP0_L_USB_SHIFT (23U)
/*! L_USB
* 0b0..No lock-the adjacent (next lower) bit can be written by the software.
* 0b1..Lock-the adjacent (next lower) bit can't be written by the software.
*/
#define CSU_HP0_L_USB(x) (((uint32_t)(((uint32_t)(x)) << CSU_HP0_L_USB_SHIFT)) & CSU_HP0_L_USB_MASK)
#define CSU_HP0_HP_ENET2_MASK (0x1000000U)
#define CSU_HP0_HP_ENET2_SHIFT (24U)
/*! HP_ENET2
* 0b0..The hprot1 input signal value is routed to the csu_hprot1 output for the corresponding master.
* 0b1..The HP register bit is routed to the csu_hprot1 output for the corresponding master.
*/
#define CSU_HP0_HP_ENET2(x) (((uint32_t)(((uint32_t)(x)) << CSU_HP0_HP_ENET2_SHIFT)) & CSU_HP0_HP_ENET2_MASK)
#define CSU_HP0_L_ENET2_MASK (0x2000000U)
#define CSU_HP0_L_ENET2_SHIFT (25U)
/*! L_ENET2
* 0b0..No lock-the adjacent (next lower) bit can be written by the software.
* 0b1..Lock-the adjacent (next lower) bit can't be written by the software.
*/
#define CSU_HP0_L_ENET2(x) (((uint32_t)(((uint32_t)(x)) << CSU_HP0_L_ENET2_SHIFT)) & CSU_HP0_L_ENET2_MASK)
/*! @} */
/*! @name SA - Secure access register */
/*! @{ */
#define CSU_SA_NSA_DMA_MASK (0x4U)
#define CSU_SA_NSA_DMA_SHIFT (2U)
/*! NSA_DMA - Non-secure access policy indicator bit
* 0b0..Secure access for the corresponding type-1 master
* 0b1..Non-secure access for the corresponding type-1 master
*/
#define CSU_SA_NSA_DMA(x) (((uint32_t)(((uint32_t)(x)) << CSU_SA_NSA_DMA_SHIFT)) & CSU_SA_NSA_DMA_MASK)
#define CSU_SA_L_DMA_MASK (0x8U)
#define CSU_SA_L_DMA_SHIFT (3U)
/*! L_DMA
* 0b0..No lock-the adjacent (next lower) bit can be written by the software.
* 0b1..Lock-the adjacent (next lower) bit can't be written by the software.
*/
#define CSU_SA_L_DMA(x) (((uint32_t)(((uint32_t)(x)) << CSU_SA_L_DMA_SHIFT)) & CSU_SA_L_DMA_MASK)
#define CSU_SA_NSA_LCDIF_MASK (0x10U)
#define CSU_SA_NSA_LCDIF_SHIFT (4U)
/*! NSA_LCDIF - Non-secure access policy indicator bit
* 0b0..Secure access for the corresponding type-1 master
* 0b1..Non-secure access for the corresponding type-1 master
*/
#define CSU_SA_NSA_LCDIF(x) (((uint32_t)(((uint32_t)(x)) << CSU_SA_NSA_LCDIF_SHIFT)) & CSU_SA_NSA_LCDIF_MASK)
#define CSU_SA_L_LCDIF_MASK (0x20U)
#define CSU_SA_L_LCDIF_SHIFT (5U)
/*! L_LCDIF
* 0b0..No lock-the adjacent (next lower) bit can be written by the software.
* 0b1..Lock-the adjacent (next lower) bit can't be written by the software.
*/
#define CSU_SA_L_LCDIF(x) (((uint32_t)(((uint32_t)(x)) << CSU_SA_L_LCDIF_SHIFT)) & CSU_SA_L_LCDIF_MASK)
#define CSU_SA_NSA_CSI_MASK (0x40U)
#define CSU_SA_NSA_CSI_SHIFT (6U)
/*! NSA_CSI - Non-secure access policy indicator bit
* 0b0..Secure access for the corresponding type-1 master
* 0b1..Non-secure access for the corresponding type-1 master
*/
#define CSU_SA_NSA_CSI(x) (((uint32_t)(((uint32_t)(x)) << CSU_SA_NSA_CSI_SHIFT)) & CSU_SA_NSA_CSI_MASK)
#define CSU_SA_L_CSI_MASK (0x80U)
#define CSU_SA_L_CSI_SHIFT (7U)
/*! L_CSI
* 0b0..No lock-the adjacent (next lower) bit can be written by the software.
* 0b1..Lock-the adjacent (next lower) bit can't be written by the software.
*/
#define CSU_SA_L_CSI(x) (((uint32_t)(((uint32_t)(x)) << CSU_SA_L_CSI_SHIFT)) & CSU_SA_L_CSI_MASK)
#define CSU_SA_NSA_PXP_MASK (0x100U)
#define CSU_SA_NSA_PXP_SHIFT (8U)
/*! NSA_PXP - Non-Secure Access Policy indicator bit
* 0b0..Secure access for the corresponding type-1 master
* 0b1..Non-secure access for the corresponding type-1 master
*/
#define CSU_SA_NSA_PXP(x) (((uint32_t)(((uint32_t)(x)) << CSU_SA_NSA_PXP_SHIFT)) & CSU_SA_NSA_PXP_MASK)
#define CSU_SA_L_PXP_MASK (0x200U)
#define CSU_SA_L_PXP_SHIFT (9U)
/*! L_PXP
* 0b0..No lock-the adjacent (next lower) bit can be written by the software.
* 0b1..Lock-the adjacent (next lower) bit can't be written by the software.
*/
#define CSU_SA_L_PXP(x) (((uint32_t)(((uint32_t)(x)) << CSU_SA_L_PXP_SHIFT)) & CSU_SA_L_PXP_MASK)
#define CSU_SA_NSA_DCP_MASK (0x400U)
#define CSU_SA_NSA_DCP_SHIFT (10U)
/*! NSA_DCP - Non-secure access policy indicator bit
* 0b0..Secure access for the corresponding type-1 master
* 0b1..Non-secure access for the corresponding type-1 master
*/
#define CSU_SA_NSA_DCP(x) (((uint32_t)(((uint32_t)(x)) << CSU_SA_NSA_DCP_SHIFT)) & CSU_SA_NSA_DCP_MASK)
#define CSU_SA_L_DCP_MASK (0x800U)
#define CSU_SA_L_DCP_SHIFT (11U)
/*! L_DCP
* 0b0..No lock-the adjacent (next lower) bit can be written by the software.
* 0b1..Lock-the adjacent (next lower) bit can't be written by the software.
*/
#define CSU_SA_L_DCP(x) (((uint32_t)(((uint32_t)(x)) << CSU_SA_L_DCP_SHIFT)) & CSU_SA_L_DCP_MASK)
#define CSU_SA_NSA_ENET_MASK (0x4000U)
#define CSU_SA_NSA_ENET_SHIFT (14U)
/*! NSA_ENET - Non-secure access policy indicator bit
* 0b0..Secure access for the corresponding type-1 master
* 0b1..Non-secure access for the corresponding type-1 master
*/
#define CSU_SA_NSA_ENET(x) (((uint32_t)(((uint32_t)(x)) << CSU_SA_NSA_ENET_SHIFT)) & CSU_SA_NSA_ENET_MASK)
#define CSU_SA_L_ENET_MASK (0x8000U)
#define CSU_SA_L_ENET_SHIFT (15U)
/*! L_ENET
* 0b0..No lock-the adjacent (next lower) bit can be written by the software.
* 0b1..Lock-the adjacent (next lower) bit can't be written by the software.
*/
#define CSU_SA_L_ENET(x) (((uint32_t)(((uint32_t)(x)) << CSU_SA_L_ENET_SHIFT)) & CSU_SA_L_ENET_MASK)
#define CSU_SA_NSA_USDHC1_MASK (0x10000U)
#define CSU_SA_NSA_USDHC1_SHIFT (16U)
/*! NSA_USDHC1 - Non-secure access policy indicator bit
* 0b0..Secure access for the corresponding type-1 master
* 0b1..Non-secure access for the corresponding type-1 master
*/
#define CSU_SA_NSA_USDHC1(x) (((uint32_t)(((uint32_t)(x)) << CSU_SA_NSA_USDHC1_SHIFT)) & CSU_SA_NSA_USDHC1_MASK)
#define CSU_SA_L_USDHC1_MASK (0x20000U)
#define CSU_SA_L_USDHC1_SHIFT (17U)
/*! L_USDHC1
* 0b0..No lock-the adjacent (next lower) bit can be written by the software.
* 0b1..Lock-the adjacent (next lower) bit can't be written by the software.
*/
#define CSU_SA_L_USDHC1(x) (((uint32_t)(((uint32_t)(x)) << CSU_SA_L_USDHC1_SHIFT)) & CSU_SA_L_USDHC1_MASK)
#define CSU_SA_NSA_USDHC2_MASK (0x40000U)
#define CSU_SA_NSA_USDHC2_SHIFT (18U)
/*! NSA_USDHC2 - Non-secure access policy indicator bit
* 0b0..Secure access for the corresponding type-1 master
* 0b1..Non-secure access for the corresponding type-1 master
*/
#define CSU_SA_NSA_USDHC2(x) (((uint32_t)(((uint32_t)(x)) << CSU_SA_NSA_USDHC2_SHIFT)) & CSU_SA_NSA_USDHC2_MASK)
#define CSU_SA_L_USDHC2_MASK (0x80000U)
#define CSU_SA_L_USDHC2_SHIFT (19U)
/*! L_USDHC2
* 0b0..No lock-the adjacent (next lower) bit can be written by the software.
* 0b1..Lock-the adjacent (next lower) bit can't be written by the software.
*/
#define CSU_SA_L_USDHC2(x) (((uint32_t)(((uint32_t)(x)) << CSU_SA_L_USDHC2_SHIFT)) & CSU_SA_L_USDHC2_MASK)
#define CSU_SA_NSA_TPSMP_MASK (0x100000U)
#define CSU_SA_NSA_TPSMP_SHIFT (20U)
/*! NSA_TPSMP - Non-secure access policy indicator bit
* 0b0..Secure access for the corresponding type-1 master
* 0b1..Non-secure access for the corresponding type-1 master
*/
#define CSU_SA_NSA_TPSMP(x) (((uint32_t)(((uint32_t)(x)) << CSU_SA_NSA_TPSMP_SHIFT)) & CSU_SA_NSA_TPSMP_MASK)
#define CSU_SA_L_TPSMP_MASK (0x200000U)
#define CSU_SA_L_TPSMP_SHIFT (21U)
/*! L_TPSMP
* 0b0..No lock-the adjacent (next lower) bit can be written by the software.
* 0b1..Lock-the adjacent (next lower) bit can't be written by the software.
*/
#define CSU_SA_L_TPSMP(x) (((uint32_t)(((uint32_t)(x)) << CSU_SA_L_TPSMP_SHIFT)) & CSU_SA_L_TPSMP_MASK)
#define CSU_SA_NSA_USB_MASK (0x400000U)
#define CSU_SA_NSA_USB_SHIFT (22U)
/*! NSA_USB - Non-secure access policy indicator bit
* 0b0..Secure access for the corresponding type-1 master
* 0b1..Non-secure access for the corresponding type-1 master
*/
#define CSU_SA_NSA_USB(x) (((uint32_t)(((uint32_t)(x)) << CSU_SA_NSA_USB_SHIFT)) & CSU_SA_NSA_USB_MASK)
#define CSU_SA_L_USB_MASK (0x800000U)
#define CSU_SA_L_USB_SHIFT (23U)
/*! L_USB
* 0b0..No lock-the adjacent (next lower) bit can be written by the software.
* 0b1..Lock-the adjacent (next lower) bit can't be written by the software.
*/
#define CSU_SA_L_USB(x) (((uint32_t)(((uint32_t)(x)) << CSU_SA_L_USB_SHIFT)) & CSU_SA_L_USB_MASK)
#define CSU_SA_NSA_ENET2_MASK (0x1000000U)
#define CSU_SA_NSA_ENET2_SHIFT (24U)
/*! NSA_ENET2 - Non-secure access policy indicator bit
* 0b0..Secure access for the corresponding type-1 master
* 0b1..Non-secure access for the corresponding type-1 master
*/
#define CSU_SA_NSA_ENET2(x) (((uint32_t)(((uint32_t)(x)) << CSU_SA_NSA_ENET2_SHIFT)) & CSU_SA_NSA_ENET2_MASK)
#define CSU_SA_L_ENET2_MASK (0x2000000U)
#define CSU_SA_L_ENET2_SHIFT (25U)
/*! L_ENET2
* 0b0..No lock-the adjacent (next lower) bit can be written by the software.
* 0b1..Lock-the adjacent (next lower) bit can't be written by the software.
*/
#define CSU_SA_L_ENET2(x) (((uint32_t)(((uint32_t)(x)) << CSU_SA_L_ENET2_SHIFT)) & CSU_SA_L_ENET2_MASK)
/*! @} */
/*! @name HPCONTROL0 - HPCONTROL0 register */
/*! @{ */
#define CSU_HPCONTROL0_HPC_DMA_MASK (0x4U)
#define CSU_HPCONTROL0_HPC_DMA_SHIFT (2U)
/*! HPC_DMA
* 0b0..User mode for the corresponding master
* 0b1..Supervisor mode for the corresponding master
*/
#define CSU_HPCONTROL0_HPC_DMA(x) (((uint32_t)(((uint32_t)(x)) << CSU_HPCONTROL0_HPC_DMA_SHIFT)) & CSU_HPCONTROL0_HPC_DMA_MASK)
#define CSU_HPCONTROL0_L_DMA_MASK (0x8U)
#define CSU_HPCONTROL0_L_DMA_SHIFT (3U)
/*! L_DMA
* 0b0..No lock-the adjacent (next lower) bit can be written by the software.
* 0b1..Lock-the adjacent (next lower) bit can't be written by the software.
*/
#define CSU_HPCONTROL0_L_DMA(x) (((uint32_t)(((uint32_t)(x)) << CSU_HPCONTROL0_L_DMA_SHIFT)) & CSU_HPCONTROL0_L_DMA_MASK)
#define CSU_HPCONTROL0_HPC_LCDIF_MASK (0x10U)
#define CSU_HPCONTROL0_HPC_LCDIF_SHIFT (4U)
/*! HPC_LCDIF
* 0b0..User mode for the corresponding master
* 0b1..Supervisor mode for the corresponding master
*/
#define CSU_HPCONTROL0_HPC_LCDIF(x) (((uint32_t)(((uint32_t)(x)) << CSU_HPCONTROL0_HPC_LCDIF_SHIFT)) & CSU_HPCONTROL0_HPC_LCDIF_MASK)
#define CSU_HPCONTROL0_L_LCDIF_MASK (0x20U)
#define CSU_HPCONTROL0_L_LCDIF_SHIFT (5U)
/*! L_LCDIF
* 0b0..No lock-the adjacent (next lower) bit can be written by the software.
* 0b1..Lock-the adjacent (next lower) bit can't be written by the software.
*/
#define CSU_HPCONTROL0_L_LCDIF(x) (((uint32_t)(((uint32_t)(x)) << CSU_HPCONTROL0_L_LCDIF_SHIFT)) & CSU_HPCONTROL0_L_LCDIF_MASK)
#define CSU_HPCONTROL0_HPC_CSI_MASK (0x40U)
#define CSU_HPCONTROL0_HPC_CSI_SHIFT (6U)
/*! HPC_CSI
* 0b0..User mode for the corresponding master
* 0b1..Supervisor mode for the corresponding master
*/
#define CSU_HPCONTROL0_HPC_CSI(x) (((uint32_t)(((uint32_t)(x)) << CSU_HPCONTROL0_HPC_CSI_SHIFT)) & CSU_HPCONTROL0_HPC_CSI_MASK)
#define CSU_HPCONTROL0_L_CSI_MASK (0x80U)
#define CSU_HPCONTROL0_L_CSI_SHIFT (7U)
/*! L_CSI
* 0b0..No lock-the adjacent (next lower) bit can be written by the software.
* 0b1..Lock-the adjacent (next lower) bit can't be written by the software.
*/
#define CSU_HPCONTROL0_L_CSI(x) (((uint32_t)(((uint32_t)(x)) << CSU_HPCONTROL0_L_CSI_SHIFT)) & CSU_HPCONTROL0_L_CSI_MASK)
#define CSU_HPCONTROL0_HPC_PXP_MASK (0x100U)
#define CSU_HPCONTROL0_HPC_PXP_SHIFT (8U)
/*! HPC_PXP
* 0b0..User mode for the corresponding master
* 0b1..Supervisor mode for the corresponding master
*/
#define CSU_HPCONTROL0_HPC_PXP(x) (((uint32_t)(((uint32_t)(x)) << CSU_HPCONTROL0_HPC_PXP_SHIFT)) & CSU_HPCONTROL0_HPC_PXP_MASK)
#define CSU_HPCONTROL0_L_PXP_MASK (0x200U)
#define CSU_HPCONTROL0_L_PXP_SHIFT (9U)
/*! L_PXP
* 0b0..No lock-the adjacent (next lower) bit can be written by the software.
* 0b1..Lock-the adjacent (next lower) bit can't be written by the software.
*/
#define CSU_HPCONTROL0_L_PXP(x) (((uint32_t)(((uint32_t)(x)) << CSU_HPCONTROL0_L_PXP_SHIFT)) & CSU_HPCONTROL0_L_PXP_MASK)
#define CSU_HPCONTROL0_HPC_DCP_MASK (0x400U)
#define CSU_HPCONTROL0_HPC_DCP_SHIFT (10U)
/*! HPC_DCP
* 0b0..User mode for the corresponding master
* 0b1..Supervisor mode for the corresponding master
*/
#define CSU_HPCONTROL0_HPC_DCP(x) (((uint32_t)(((uint32_t)(x)) << CSU_HPCONTROL0_HPC_DCP_SHIFT)) & CSU_HPCONTROL0_HPC_DCP_MASK)
#define CSU_HPCONTROL0_L_DCP_MASK (0x800U)
#define CSU_HPCONTROL0_L_DCP_SHIFT (11U)
/*! L_DCP
* 0b0..No lock-the adjacent (next lower) bit can be written by the software.
* 0b1..Lock-the adjacent (next lower) bit can't be written by the software.
*/
#define CSU_HPCONTROL0_L_DCP(x) (((uint32_t)(((uint32_t)(x)) << CSU_HPCONTROL0_L_DCP_SHIFT)) & CSU_HPCONTROL0_L_DCP_MASK)
#define CSU_HPCONTROL0_HPC_ENET_MASK (0x4000U)
#define CSU_HPCONTROL0_HPC_ENET_SHIFT (14U)
/*! HPC_ENET
* 0b0..User mode for the corresponding master
* 0b1..Supervisor mode for the corresponding master
*/
#define CSU_HPCONTROL0_HPC_ENET(x) (((uint32_t)(((uint32_t)(x)) << CSU_HPCONTROL0_HPC_ENET_SHIFT)) & CSU_HPCONTROL0_HPC_ENET_MASK)
#define CSU_HPCONTROL0_L_ENET_MASK (0x8000U)
#define CSU_HPCONTROL0_L_ENET_SHIFT (15U)
/*! L_ENET
* 0b0..No lock-the adjacent (next lower) bit can be written by the software.
* 0b1..Lock-the adjacent (next lower) bit can't be written by the software.
*/
#define CSU_HPCONTROL0_L_ENET(x) (((uint32_t)(((uint32_t)(x)) << CSU_HPCONTROL0_L_ENET_SHIFT)) & CSU_HPCONTROL0_L_ENET_MASK)
#define CSU_HPCONTROL0_HPC_USDHC1_MASK (0x10000U)
#define CSU_HPCONTROL0_HPC_USDHC1_SHIFT (16U)
/*! HPC_USDHC1
* 0b0..User mode for the corresponding master
* 0b1..Supervisor mode for the corresponding master
*/
#define CSU_HPCONTROL0_HPC_USDHC1(x) (((uint32_t)(((uint32_t)(x)) << CSU_HPCONTROL0_HPC_USDHC1_SHIFT)) & CSU_HPCONTROL0_HPC_USDHC1_MASK)
#define CSU_HPCONTROL0_L_USDHC1_MASK (0x20000U)
#define CSU_HPCONTROL0_L_USDHC1_SHIFT (17U)
/*! L_USDHC1
* 0b0..No lock-the adjacent (next lower) bit can be written by the software.
* 0b1..Lock-the adjacent (next lower) bit can't be written by the software.
*/
#define CSU_HPCONTROL0_L_USDHC1(x) (((uint32_t)(((uint32_t)(x)) << CSU_HPCONTROL0_L_USDHC1_SHIFT)) & CSU_HPCONTROL0_L_USDHC1_MASK)
#define CSU_HPCONTROL0_HPC_USDHC2_MASK (0x40000U)
#define CSU_HPCONTROL0_HPC_USDHC2_SHIFT (18U)
/*! HPC_USDHC2
* 0b0..User mode for the corresponding master
* 0b1..Supervisor mode for the corresponding master
*/
#define CSU_HPCONTROL0_HPC_USDHC2(x) (((uint32_t)(((uint32_t)(x)) << CSU_HPCONTROL0_HPC_USDHC2_SHIFT)) & CSU_HPCONTROL0_HPC_USDHC2_MASK)
#define CSU_HPCONTROL0_L_USDHC2_MASK (0x80000U)
#define CSU_HPCONTROL0_L_USDHC2_SHIFT (19U)
/*! L_USDHC2
* 0b0..No lock-the adjacent (next lower) bit can be written by the software.
* 0b1..Lock-the adjacent (next lower) bit can't be written by the software.
*/
#define CSU_HPCONTROL0_L_USDHC2(x) (((uint32_t)(((uint32_t)(x)) << CSU_HPCONTROL0_L_USDHC2_SHIFT)) & CSU_HPCONTROL0_L_USDHC2_MASK)
#define CSU_HPCONTROL0_HPC_TPSMP_MASK (0x100000U)
#define CSU_HPCONTROL0_HPC_TPSMP_SHIFT (20U)
/*! HPC_TPSMP
* 0b0..User mode for the corresponding master
* 0b1..Supervisor mode for the corresponding master
*/
#define CSU_HPCONTROL0_HPC_TPSMP(x) (((uint32_t)(((uint32_t)(x)) << CSU_HPCONTROL0_HPC_TPSMP_SHIFT)) & CSU_HPCONTROL0_HPC_TPSMP_MASK)
#define CSU_HPCONTROL0_L_TPSMP_MASK (0x200000U)
#define CSU_HPCONTROL0_L_TPSMP_SHIFT (21U)
/*! L_TPSMP
* 0b0..No lock-the adjacent (next lower) bit can be written by the software.
* 0b1..Lock-the adjacent (next lower) bit can't be written by the software.
*/
#define CSU_HPCONTROL0_L_TPSMP(x) (((uint32_t)(((uint32_t)(x)) << CSU_HPCONTROL0_L_TPSMP_SHIFT)) & CSU_HPCONTROL0_L_TPSMP_MASK)
#define CSU_HPCONTROL0_HPC_USB_MASK (0x400000U)
#define CSU_HPCONTROL0_HPC_USB_SHIFT (22U)
/*! HPC_USB
* 0b0..User mode for the corresponding master
* 0b1..Supervisor mode for the corresponding master
*/
#define CSU_HPCONTROL0_HPC_USB(x) (((uint32_t)(((uint32_t)(x)) << CSU_HPCONTROL0_HPC_USB_SHIFT)) & CSU_HPCONTROL0_HPC_USB_MASK)
#define CSU_HPCONTROL0_L_USB_MASK (0x800000U)
#define CSU_HPCONTROL0_L_USB_SHIFT (23U)
/*! L_USB
* 0b0..No lock-the adjacent (next lower) bit can be written by the software.
* 0b1..Lock-the adjacent (next lower) bit can't be written by the software.
*/
#define CSU_HPCONTROL0_L_USB(x) (((uint32_t)(((uint32_t)(x)) << CSU_HPCONTROL0_L_USB_SHIFT)) & CSU_HPCONTROL0_L_USB_MASK)
#define CSU_HPCONTROL0_HPC_ENET2_MASK (0x1000000U)
#define CSU_HPCONTROL0_HPC_ENET2_SHIFT (24U)
/*! HPC_ENET2
* 0b0..User mode for the corresponding master
* 0b1..Supervisor mode for the corresponding master
*/
#define CSU_HPCONTROL0_HPC_ENET2(x) (((uint32_t)(((uint32_t)(x)) << CSU_HPCONTROL0_HPC_ENET2_SHIFT)) & CSU_HPCONTROL0_HPC_ENET2_MASK)
#define CSU_HPCONTROL0_L_ENET2_MASK (0x2000000U)
#define CSU_HPCONTROL0_L_ENET2_SHIFT (25U)
/*! L_ENET2
* 0b0..No lock-the adjacent (next lower) bit can be written by the software.
* 0b1..Lock-the adjacent (next lower) bit can't be written by the software.
*/
#define CSU_HPCONTROL0_L_ENET2(x) (((uint32_t)(((uint32_t)(x)) << CSU_HPCONTROL0_L_ENET2_SHIFT)) & CSU_HPCONTROL0_L_ENET2_MASK)
/*! @} */
/*!
* @}
*/ /* end of group CSU_Register_Masks */
/*!
* @}
*/ /* end of group CSU_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 */
#endif /* CSU_H_ */

View File

@ -0,0 +1,478 @@
/*
** ###################################################################
** Processors: MIMXRT1061CVJ5A
** MIMXRT1061CVJ5B
** MIMXRT1061CVL5A
** MIMXRT1061CVL5B
** MIMXRT1061DVJ6A
** MIMXRT1061DVJ6B
** MIMXRT1061DVL6A
** MIMXRT1061DVL6B
** MIMXRT1061XVN5B
** MIMXRT1062CVJ5A
** MIMXRT1062CVJ5B
** MIMXRT1062CVL5A
** MIMXRT1062CVL5B
** MIMXRT1062DVJ6A
** MIMXRT1062DVJ6B
** MIMXRT1062DVL6A
** MIMXRT1062DVL6B
** MIMXRT1062DVN6B
** MIMXRT1062XVN5B
** MIMXRT106ADVL6A
** MIMXRT106CDVL6A
** MIMXRT106FDVL6A
** MIMXRT106LDVL6A
** MIMXRT106SDVL6A
**
** Version: rev. 1.4, 2022-03-25
** Build: b240705
**
** Abstract:
** CMSIS Peripheral Access Layer for DCDC
**
** Copyright 1997-2016 Freescale Semiconductor, Inc.
** Copyright 2016-2024 NXP
** SPDX-License-Identifier: BSD-3-Clause
**
** http: www.nxp.com
** mail: support@nxp.com
**
** Revisions:
** - rev. 0.1 (2017-01-10)
** Initial version.
** - rev. 1.0 (2018-11-16)
** Update header files to align with IMXRT1060RM Rev.0.
** - rev. 1.1 (2018-11-27)
** Update header files to align with IMXRT1060RM Rev.1.
** - rev. 1.2 (2019-04-29)
** Add SET/CLR/TOG register group to register CTRL, STAT, CHANNELCTRL, CH0STAT, CH0OPTS, CH1STAT, CH1OPTS, CH2STAT, CH2OPTS, CH3STAT, CH3OPTS of DCP module.
** - rev. 1.3 (2021-08-10)
** Update header files to align with IMXRT1060RM Rev.3.
** - rev. 1.4 (2022-03-25)
** Add RT1060X device
**
** ###################################################################
*/
/*!
* @file DCDC.h
* @version 1.4
* @date 2022-03-25
* @brief CMSIS Peripheral Access Layer for DCDC
*
* CMSIS Peripheral Access Layer for DCDC
*/
#if !defined(DCDC_H_)
#define DCDC_H_ /**< Symbol preventing repeated inclusion */
#if (defined(CPU_MIMXRT1061CVJ5A) || defined(CPU_MIMXRT1061CVJ5B) || defined(CPU_MIMXRT1061CVL5A) || defined(CPU_MIMXRT1061CVL5B) || defined(CPU_MIMXRT1061DVJ6A) || defined(CPU_MIMXRT1061DVJ6B) || defined(CPU_MIMXRT1061DVL6A) || defined(CPU_MIMXRT1061DVL6B) || defined(CPU_MIMXRT1061XVN5B))
#include "MIMXRT1061_COMMON.h"
#elif (defined(CPU_MIMXRT1062CVJ5A) || defined(CPU_MIMXRT1062CVJ5B) || defined(CPU_MIMXRT1062CVL5A) || defined(CPU_MIMXRT1062CVL5B) || defined(CPU_MIMXRT1062DVJ6A) || defined(CPU_MIMXRT1062DVJ6B) || defined(CPU_MIMXRT1062DVL6A) || defined(CPU_MIMXRT1062DVL6B) || defined(CPU_MIMXRT1062DVN6B) || defined(CPU_MIMXRT1062XVN5B))
#include "MIMXRT1062_COMMON.h"
#elif (defined(CPU_MIMXRT106ADVL6A))
#include "MIMXRT106A_COMMON.h"
#elif (defined(CPU_MIMXRT106CDVL6A))
#include "MIMXRT106C_COMMON.h"
#elif (defined(CPU_MIMXRT106FDVL6A))
#include "MIMXRT106F_COMMON.h"
#elif (defined(CPU_MIMXRT106LDVL6A))
#include "MIMXRT106L_COMMON.h"
#elif (defined(CPU_MIMXRT106SDVL6A))
#include "MIMXRT106S_COMMON.h"
#else
#error "No valid CPU defined!"
#endif
/* ----------------------------------------------------------------------------
-- 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
/* ----------------------------------------------------------------------------
-- DCDC Peripheral Access Layer
---------------------------------------------------------------------------- */
/*!
* @addtogroup DCDC_Peripheral_Access_Layer DCDC Peripheral Access Layer
* @{
*/
/** DCDC - Register Layout Typedef */
typedef struct {
__IO uint32_t REG0; /**< DCDC Register 0, offset: 0x0 */
__IO uint32_t REG1; /**< DCDC Register 1, offset: 0x4 */
__IO uint32_t REG2; /**< DCDC Register 2, offset: 0x8 */
__IO uint32_t REG3; /**< DCDC Register 3, offset: 0xC */
} DCDC_Type;
/* ----------------------------------------------------------------------------
-- DCDC Register Masks
---------------------------------------------------------------------------- */
/*!
* @addtogroup DCDC_Register_Masks DCDC Register Masks
* @{
*/
/*! @name REG0 - DCDC Register 0 */
/*! @{ */
#define DCDC_REG0_PWD_ZCD_MASK (0x1U)
#define DCDC_REG0_PWD_ZCD_SHIFT (0U)
/*! PWD_ZCD - Power Down Zero Cross Detection
* 0b0..Zero cross detetion function powered up
* 0b1..Zero cross detetion function powered down
*/
#define DCDC_REG0_PWD_ZCD(x) (((uint32_t)(((uint32_t)(x)) << DCDC_REG0_PWD_ZCD_SHIFT)) & DCDC_REG0_PWD_ZCD_MASK)
#define DCDC_REG0_DISABLE_AUTO_CLK_SWITCH_MASK (0x2U)
#define DCDC_REG0_DISABLE_AUTO_CLK_SWITCH_SHIFT (1U)
/*! DISABLE_AUTO_CLK_SWITCH - Disable Auto Clock Switch
* 0b0..If DISABLE_AUTO_CLK_SWITCH is set to 0 and 24M xtal is OK, the clock source will switch from internal ring OSC to 24M xtal automatically
* 0b1..If DISABLE_AUTO_CLK_SWITCH is set to 1, SEL_CLK will determine which clock source the DCDC uses
*/
#define DCDC_REG0_DISABLE_AUTO_CLK_SWITCH(x) (((uint32_t)(((uint32_t)(x)) << DCDC_REG0_DISABLE_AUTO_CLK_SWITCH_SHIFT)) & DCDC_REG0_DISABLE_AUTO_CLK_SWITCH_MASK)
#define DCDC_REG0_SEL_CLK_MASK (0x4U)
#define DCDC_REG0_SEL_CLK_SHIFT (2U)
/*! SEL_CLK - Select Clock
* 0b0..DCDC uses internal ring oscillator
* 0b1..DCDC uses 24M xtal
*/
#define DCDC_REG0_SEL_CLK(x) (((uint32_t)(((uint32_t)(x)) << DCDC_REG0_SEL_CLK_SHIFT)) & DCDC_REG0_SEL_CLK_MASK)
#define DCDC_REG0_PWD_OSC_INT_MASK (0x8U)
#define DCDC_REG0_PWD_OSC_INT_SHIFT (3U)
/*! PWD_OSC_INT - Power down internal osc
* 0b0..Internal oscillator powered up
* 0b1..Internal oscillator powered down
*/
#define DCDC_REG0_PWD_OSC_INT(x) (((uint32_t)(((uint32_t)(x)) << DCDC_REG0_PWD_OSC_INT_SHIFT)) & DCDC_REG0_PWD_OSC_INT_MASK)
#define DCDC_REG0_PWD_CUR_SNS_CMP_MASK (0x10U)
#define DCDC_REG0_PWD_CUR_SNS_CMP_SHIFT (4U)
/*! PWD_CUR_SNS_CMP - Power down signal of the current detector.
* 0b0..Current Detector powered up
* 0b1..Current Detector powered down
*/
#define DCDC_REG0_PWD_CUR_SNS_CMP(x) (((uint32_t)(((uint32_t)(x)) << DCDC_REG0_PWD_CUR_SNS_CMP_SHIFT)) & DCDC_REG0_PWD_CUR_SNS_CMP_MASK)
#define DCDC_REG0_CUR_SNS_THRSH_MASK (0xE0U)
#define DCDC_REG0_CUR_SNS_THRSH_SHIFT (5U)
/*! CUR_SNS_THRSH - Current Sense (detector) Threshold
* 0b000..150 mA
* 0b001..250 mA
* 0b010..350 mA
* 0b011..450 mA
* 0b100..550 mA
* 0b101..650 mA
*/
#define DCDC_REG0_CUR_SNS_THRSH(x) (((uint32_t)(((uint32_t)(x)) << DCDC_REG0_CUR_SNS_THRSH_SHIFT)) & DCDC_REG0_CUR_SNS_THRSH_MASK)
#define DCDC_REG0_PWD_OVERCUR_DET_MASK (0x100U)
#define DCDC_REG0_PWD_OVERCUR_DET_SHIFT (8U)
/*! PWD_OVERCUR_DET - Power down overcurrent detection comparator
* 0b0..Overcurrent detection comparator is enabled
* 0b1..Overcurrent detection comparator is disabled
*/
#define DCDC_REG0_PWD_OVERCUR_DET(x) (((uint32_t)(((uint32_t)(x)) << DCDC_REG0_PWD_OVERCUR_DET_SHIFT)) & DCDC_REG0_PWD_OVERCUR_DET_MASK)
#define DCDC_REG0_OVERCUR_TRIG_ADJ_MASK (0x600U)
#define DCDC_REG0_OVERCUR_TRIG_ADJ_SHIFT (9U)
/*! OVERCUR_TRIG_ADJ - Overcurrent Trigger Adjust
* 0b00..In Run Mode, 1 A. In Power Save Mode, 0.25 A
* 0b01..In Run Mode, 2 A. In Power Save Mode, 0.25 A
* 0b10..In Run Mode, 1 A. In Power Save Mode, 0.2 A
* 0b11..In Run Mode, 2 A. In Power Save Mode, 0.2 A
*/
#define DCDC_REG0_OVERCUR_TRIG_ADJ(x) (((uint32_t)(((uint32_t)(x)) << DCDC_REG0_OVERCUR_TRIG_ADJ_SHIFT)) & DCDC_REG0_OVERCUR_TRIG_ADJ_MASK)
#define DCDC_REG0_PWD_CMP_BATT_DET_MASK (0x800U)
#define DCDC_REG0_PWD_CMP_BATT_DET_SHIFT (11U)
/*! PWD_CMP_BATT_DET - Power Down Battery Detection Comparator
* 0b0..Low voltage detection comparator is enabled
* 0b1..Low voltage detection comparator is disabled
*/
#define DCDC_REG0_PWD_CMP_BATT_DET(x) (((uint32_t)(((uint32_t)(x)) << DCDC_REG0_PWD_CMP_BATT_DET_SHIFT)) & DCDC_REG0_PWD_CMP_BATT_DET_MASK)
#define DCDC_REG0_EN_LP_OVERLOAD_SNS_MASK (0x10000U)
#define DCDC_REG0_EN_LP_OVERLOAD_SNS_SHIFT (16U)
/*! EN_LP_OVERLOAD_SNS - Low Power Overload Sense Enable
* 0b0..Overload Detection in power save mode disabled
* 0b1..Overload Detection in power save mode enabled
*/
#define DCDC_REG0_EN_LP_OVERLOAD_SNS(x) (((uint32_t)(((uint32_t)(x)) << DCDC_REG0_EN_LP_OVERLOAD_SNS_SHIFT)) & DCDC_REG0_EN_LP_OVERLOAD_SNS_MASK)
#define DCDC_REG0_PWD_HIGH_VOLT_DET_MASK (0x20000U)
#define DCDC_REG0_PWD_HIGH_VOLT_DET_SHIFT (17U)
/*! PWD_HIGH_VOLT_DET - Power Down High Voltage Detection
* 0b0..Overvoltage detection comparator is enabled
* 0b1..Overvoltage detection comparator is disabled
*/
#define DCDC_REG0_PWD_HIGH_VOLT_DET(x) (((uint32_t)(((uint32_t)(x)) << DCDC_REG0_PWD_HIGH_VOLT_DET_SHIFT)) & DCDC_REG0_PWD_HIGH_VOLT_DET_MASK)
#define DCDC_REG0_LP_OVERLOAD_THRSH_MASK (0xC0000U)
#define DCDC_REG0_LP_OVERLOAD_THRSH_SHIFT (18U)
/*! LP_OVERLOAD_THRSH - Low Power Overload Threshold
* 0b00..32
* 0b01..64
* 0b10..16
* 0b11..8
*/
#define DCDC_REG0_LP_OVERLOAD_THRSH(x) (((uint32_t)(((uint32_t)(x)) << DCDC_REG0_LP_OVERLOAD_THRSH_SHIFT)) & DCDC_REG0_LP_OVERLOAD_THRSH_MASK)
#define DCDC_REG0_LP_OVERLOAD_FREQ_SEL_MASK (0x100000U)
#define DCDC_REG0_LP_OVERLOAD_FREQ_SEL_SHIFT (20U)
/*! LP_OVERLOAD_FREQ_SEL - Low Power Overload Frequency Select
* 0b0..eight 32k cycle
* 0b1..sixteen 32k cycle
*/
#define DCDC_REG0_LP_OVERLOAD_FREQ_SEL(x) (((uint32_t)(((uint32_t)(x)) << DCDC_REG0_LP_OVERLOAD_FREQ_SEL_SHIFT)) & DCDC_REG0_LP_OVERLOAD_FREQ_SEL_MASK)
#define DCDC_REG0_LP_HIGH_HYS_MASK (0x200000U)
#define DCDC_REG0_LP_HIGH_HYS_SHIFT (21U)
/*! LP_HIGH_HYS - Low Power High Hysteric Value
* 0b0..Adjust hysteretic value in low power to 12.5mV
* 0b1..Adjust hysteretic value in low power to 25mV
*/
#define DCDC_REG0_LP_HIGH_HYS(x) (((uint32_t)(((uint32_t)(x)) << DCDC_REG0_LP_HIGH_HYS_SHIFT)) & DCDC_REG0_LP_HIGH_HYS_MASK)
#define DCDC_REG0_PWD_CMP_OFFSET_MASK (0x4000000U)
#define DCDC_REG0_PWD_CMP_OFFSET_SHIFT (26U)
/*! PWD_CMP_OFFSET - Power down output range comparator
* 0b0..Output range comparator powered up
* 0b1..Output range comparator powered down
*/
#define DCDC_REG0_PWD_CMP_OFFSET(x) (((uint32_t)(((uint32_t)(x)) << DCDC_REG0_PWD_CMP_OFFSET_SHIFT)) & DCDC_REG0_PWD_CMP_OFFSET_MASK)
#define DCDC_REG0_XTALOK_DISABLE_MASK (0x8000000U)
#define DCDC_REG0_XTALOK_DISABLE_SHIFT (27U)
/*! XTALOK_DISABLE - Disable xtalok detection circuit
* 0b0..Enable xtalok detection circuit
* 0b1..Disable xtalok detection circuit and always outputs OK signal "1"
*/
#define DCDC_REG0_XTALOK_DISABLE(x) (((uint32_t)(((uint32_t)(x)) << DCDC_REG0_XTALOK_DISABLE_SHIFT)) & DCDC_REG0_XTALOK_DISABLE_MASK)
#define DCDC_REG0_CURRENT_ALERT_RESET_MASK (0x10000000U)
#define DCDC_REG0_CURRENT_ALERT_RESET_SHIFT (28U)
/*! CURRENT_ALERT_RESET - Reset Current Alert Signal
* 0b0..Current Alert Signal not reset
* 0b1..Current Alert Signal reset
*/
#define DCDC_REG0_CURRENT_ALERT_RESET(x) (((uint32_t)(((uint32_t)(x)) << DCDC_REG0_CURRENT_ALERT_RESET_SHIFT)) & DCDC_REG0_CURRENT_ALERT_RESET_MASK)
#define DCDC_REG0_XTAL_24M_OK_MASK (0x20000000U)
#define DCDC_REG0_XTAL_24M_OK_SHIFT (29U)
/*! XTAL_24M_OK - 24M XTAL OK
* 0b0..DCDC uses internal ring OSC
* 0b1..DCDC uses xtal 24M
*/
#define DCDC_REG0_XTAL_24M_OK(x) (((uint32_t)(((uint32_t)(x)) << DCDC_REG0_XTAL_24M_OK_SHIFT)) & DCDC_REG0_XTAL_24M_OK_MASK)
#define DCDC_REG0_STS_DC_OK_MASK (0x80000000U)
#define DCDC_REG0_STS_DC_OK_SHIFT (31U)
/*! STS_DC_OK - DCDC Output OK
* 0b0..DCDC is settling
* 0b1..DCDC already settled
*/
#define DCDC_REG0_STS_DC_OK(x) (((uint32_t)(((uint32_t)(x)) << DCDC_REG0_STS_DC_OK_SHIFT)) & DCDC_REG0_STS_DC_OK_MASK)
/*! @} */
/*! @name REG1 - DCDC Register 1 */
/*! @{ */
#define DCDC_REG1_REG_FBK_SEL_MASK (0x180U)
#define DCDC_REG1_REG_FBK_SEL_SHIFT (7U)
/*! REG_FBK_SEL
* 0b00..The regulator outputs 1.0V with 1.2V reference voltage
* 0b01..The regulator outputs 1.1V with 1.2V reference voltage
* 0b10..The regulator outputs 1.0V with 1.3V reference voltage
* 0b11..The regulator outputs 1.1V with 1.3V reference voltage
*/
#define DCDC_REG1_REG_FBK_SEL(x) (((uint32_t)(((uint32_t)(x)) << DCDC_REG1_REG_FBK_SEL_SHIFT)) & DCDC_REG1_REG_FBK_SEL_MASK)
#define DCDC_REG1_REG_RLOAD_SW_MASK (0x200U)
#define DCDC_REG1_REG_RLOAD_SW_SHIFT (9U)
/*! REG_RLOAD_SW
* 0b0..Load resistor disconnected
* 0b1..Load resistor connected
*/
#define DCDC_REG1_REG_RLOAD_SW(x) (((uint32_t)(((uint32_t)(x)) << DCDC_REG1_REG_RLOAD_SW_SHIFT)) & DCDC_REG1_REG_RLOAD_SW_MASK)
#define DCDC_REG1_LP_CMP_ISRC_SEL_MASK (0x3000U)
#define DCDC_REG1_LP_CMP_ISRC_SEL_SHIFT (12U)
/*! LP_CMP_ISRC_SEL - Low Power Comparator Current Bias
* 0b00..50 nA
* 0b01..100 nA
* 0b10..200 nA
* 0b11..400 nA
*/
#define DCDC_REG1_LP_CMP_ISRC_SEL(x) (((uint32_t)(((uint32_t)(x)) << DCDC_REG1_LP_CMP_ISRC_SEL_SHIFT)) & DCDC_REG1_LP_CMP_ISRC_SEL_MASK)
#define DCDC_REG1_LOOPCTRL_HST_THRESH_MASK (0x200000U)
#define DCDC_REG1_LOOPCTRL_HST_THRESH_SHIFT (21U)
/*! LOOPCTRL_HST_THRESH - Increase Threshold Detection
* 0b0..Lower hysteresis threshold (about 2.5mV in typical, but this value can vary with PVT corners
* 0b1..Higher hysteresis threshold (about 5mV in typical)
*/
#define DCDC_REG1_LOOPCTRL_HST_THRESH(x) (((uint32_t)(((uint32_t)(x)) << DCDC_REG1_LOOPCTRL_HST_THRESH_SHIFT)) & DCDC_REG1_LOOPCTRL_HST_THRESH_MASK)
#define DCDC_REG1_LOOPCTRL_EN_HYST_MASK (0x800000U)
#define DCDC_REG1_LOOPCTRL_EN_HYST_SHIFT (23U)
/*! LOOPCTRL_EN_HYST - Enable Hysteresis
* 0b0..Disable hysteresis in switching converter common mode analog comparators
* 0b1..Enable hysteresis in switching converter common mode analog comparators
*/
#define DCDC_REG1_LOOPCTRL_EN_HYST(x) (((uint32_t)(((uint32_t)(x)) << DCDC_REG1_LOOPCTRL_EN_HYST_SHIFT)) & DCDC_REG1_LOOPCTRL_EN_HYST_MASK)
#define DCDC_REG1_VBG_TRIM_MASK (0x1F000000U)
#define DCDC_REG1_VBG_TRIM_SHIFT (24U)
/*! VBG_TRIM - Trim Bandgap Voltage */
#define DCDC_REG1_VBG_TRIM(x) (((uint32_t)(((uint32_t)(x)) << DCDC_REG1_VBG_TRIM_SHIFT)) & DCDC_REG1_VBG_TRIM_MASK)
/*! @} */
/*! @name REG2 - DCDC Register 2 */
/*! @{ */
#define DCDC_REG2_LOOPCTRL_DC_FF_MASK (0x1C0U)
#define DCDC_REG2_LOOPCTRL_DC_FF_SHIFT (6U)
#define DCDC_REG2_LOOPCTRL_DC_FF(x) (((uint32_t)(((uint32_t)(x)) << DCDC_REG2_LOOPCTRL_DC_FF_SHIFT)) & DCDC_REG2_LOOPCTRL_DC_FF_MASK)
#define DCDC_REG2_LOOPCTRL_EN_RCSCALE_MASK (0xE00U)
#define DCDC_REG2_LOOPCTRL_EN_RCSCALE_SHIFT (9U)
/*! LOOPCTRL_EN_RCSCALE - Enable RC Scale */
#define DCDC_REG2_LOOPCTRL_EN_RCSCALE(x) (((uint32_t)(((uint32_t)(x)) << DCDC_REG2_LOOPCTRL_EN_RCSCALE_SHIFT)) & DCDC_REG2_LOOPCTRL_EN_RCSCALE_MASK)
#define DCDC_REG2_LOOPCTRL_RCSCALE_THRSH_MASK (0x1000U)
#define DCDC_REG2_LOOPCTRL_RCSCALE_THRSH_SHIFT (12U)
/*! LOOPCTRL_RCSCALE_THRSH
* 0b0..Do not increase the threshold detection for RC scale circuit.
* 0b1..Increase the threshold detection for RC scale circuit.
*/
#define DCDC_REG2_LOOPCTRL_RCSCALE_THRSH(x) (((uint32_t)(((uint32_t)(x)) << DCDC_REG2_LOOPCTRL_RCSCALE_THRSH_SHIFT)) & DCDC_REG2_LOOPCTRL_RCSCALE_THRSH_MASK)
#define DCDC_REG2_LOOPCTRL_HYST_SIGN_MASK (0x2000U)
#define DCDC_REG2_LOOPCTRL_HYST_SIGN_SHIFT (13U)
/*! LOOPCTRL_HYST_SIGN
* 0b0..Do not invert sign of the hysteresis
* 0b1..Invert sign of the hysteresis
*/
#define DCDC_REG2_LOOPCTRL_HYST_SIGN(x) (((uint32_t)(((uint32_t)(x)) << DCDC_REG2_LOOPCTRL_HYST_SIGN_SHIFT)) & DCDC_REG2_LOOPCTRL_HYST_SIGN_MASK)
#define DCDC_REG2_DISABLE_PULSE_SKIP_MASK (0x8000000U)
#define DCDC_REG2_DISABLE_PULSE_SKIP_SHIFT (27U)
/*! DISABLE_PULSE_SKIP - Disable Pulse Skip
* 0b0..DCDC will be idle to save current dissipation when the duty cycle get to the low limit which is set by NEGLIMIT_IN.
* 0b1..DCDC will keep working with the low limited duty cycle NEGLIMIT_IN.
*/
#define DCDC_REG2_DISABLE_PULSE_SKIP(x) (((uint32_t)(((uint32_t)(x)) << DCDC_REG2_DISABLE_PULSE_SKIP_SHIFT)) & DCDC_REG2_DISABLE_PULSE_SKIP_MASK)
#define DCDC_REG2_DCM_SET_CTRL_MASK (0x10000000U)
#define DCDC_REG2_DCM_SET_CTRL_SHIFT (28U)
/*! DCM_SET_CTRL - DCM Set Control */
#define DCDC_REG2_DCM_SET_CTRL(x) (((uint32_t)(((uint32_t)(x)) << DCDC_REG2_DCM_SET_CTRL_SHIFT)) & DCDC_REG2_DCM_SET_CTRL_MASK)
/*! @} */
/*! @name REG3 - DCDC Register 3 */
/*! @{ */
#define DCDC_REG3_TRG_MASK (0x1FU)
#define DCDC_REG3_TRG_SHIFT (0U)
/*! TRG - Target value of VDD_SOC */
#define DCDC_REG3_TRG(x) (((uint32_t)(((uint32_t)(x)) << DCDC_REG3_TRG_SHIFT)) & DCDC_REG3_TRG_MASK)
#define DCDC_REG3_TARGET_LP_MASK (0x700U)
#define DCDC_REG3_TARGET_LP_SHIFT (8U)
/*! TARGET_LP - Low Power Target Value
* 0b000..0.9 V
* 0b001..0.925 V
* 0b010..0.95 V
* 0b011..0.975 V
* 0b100..1.0 V
*/
#define DCDC_REG3_TARGET_LP(x) (((uint32_t)(((uint32_t)(x)) << DCDC_REG3_TARGET_LP_SHIFT)) & DCDC_REG3_TARGET_LP_MASK)
#define DCDC_REG3_MINPWR_DC_HALFCLK_MASK (0x1000000U)
#define DCDC_REG3_MINPWR_DC_HALFCLK_SHIFT (24U)
/*! MINPWR_DC_HALFCLK
* 0b0..DCDC clock remains at full frequency for continuous mode
* 0b1..DCDC clock set to half frequency for continuous mode
*/
#define DCDC_REG3_MINPWR_DC_HALFCLK(x) (((uint32_t)(((uint32_t)(x)) << DCDC_REG3_MINPWR_DC_HALFCLK_SHIFT)) & DCDC_REG3_MINPWR_DC_HALFCLK_MASK)
#define DCDC_REG3_DISABLE_STEP_MASK (0x40000000U)
#define DCDC_REG3_DISABLE_STEP_SHIFT (30U)
/*! DISABLE_STEP - Disable Step
* 0b0..Enable stepping for the output of VDD_SOC of DCDC
* 0b1..Disable stepping for the output of VDD_SOC of DCDC
*/
#define DCDC_REG3_DISABLE_STEP(x) (((uint32_t)(((uint32_t)(x)) << DCDC_REG3_DISABLE_STEP_SHIFT)) & DCDC_REG3_DISABLE_STEP_MASK)
/*! @} */
/*!
* @}
*/ /* end of group DCDC_Register_Masks */
/*!
* @}
*/ /* end of group DCDC_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 */
#endif /* DCDC_H_ */

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,380 @@
/*
** ###################################################################
** Processors: MIMXRT1061CVJ5A
** MIMXRT1061CVJ5B
** MIMXRT1061CVL5A
** MIMXRT1061CVL5B
** MIMXRT1061DVJ6A
** MIMXRT1061DVJ6B
** MIMXRT1061DVL6A
** MIMXRT1061DVL6B
** MIMXRT1061XVN5B
** MIMXRT1062CVJ5A
** MIMXRT1062CVJ5B
** MIMXRT1062CVL5A
** MIMXRT1062CVL5B
** MIMXRT1062DVJ6A
** MIMXRT1062DVJ6B
** MIMXRT1062DVL6A
** MIMXRT1062DVL6B
** MIMXRT1062DVN6B
** MIMXRT1062XVN5B
** MIMXRT106ADVL6A
** MIMXRT106CDVL6A
** MIMXRT106FDVL6A
** MIMXRT106LDVL6A
** MIMXRT106SDVL6A
**
** Version: rev. 1.4, 2022-03-25
** Build: b240705
**
** Abstract:
** CMSIS Peripheral Access Layer for DMAMUX
**
** Copyright 1997-2016 Freescale Semiconductor, Inc.
** Copyright 2016-2024 NXP
** SPDX-License-Identifier: BSD-3-Clause
**
** http: www.nxp.com
** mail: support@nxp.com
**
** Revisions:
** - rev. 0.1 (2017-01-10)
** Initial version.
** - rev. 1.0 (2018-11-16)
** Update header files to align with IMXRT1060RM Rev.0.
** - rev. 1.1 (2018-11-27)
** Update header files to align with IMXRT1060RM Rev.1.
** - rev. 1.2 (2019-04-29)
** Add SET/CLR/TOG register group to register CTRL, STAT, CHANNELCTRL, CH0STAT, CH0OPTS, CH1STAT, CH1OPTS, CH2STAT, CH2OPTS, CH3STAT, CH3OPTS of DCP module.
** - rev. 1.3 (2021-08-10)
** Update header files to align with IMXRT1060RM Rev.3.
** - rev. 1.4 (2022-03-25)
** Add RT1060X device
**
** ###################################################################
*/
/*!
* @file DMAMUX.h
* @version 1.4
* @date 2022-03-25
* @brief CMSIS Peripheral Access Layer for DMAMUX
*
* CMSIS Peripheral Access Layer for DMAMUX
*/
#if !defined(DMAMUX_H_)
#define DMAMUX_H_ /**< Symbol preventing repeated inclusion */
#if (defined(CPU_MIMXRT1061CVJ5A) || defined(CPU_MIMXRT1061CVJ5B) || defined(CPU_MIMXRT1061CVL5A) || defined(CPU_MIMXRT1061CVL5B) || defined(CPU_MIMXRT1061DVJ6A) || defined(CPU_MIMXRT1061DVJ6B) || defined(CPU_MIMXRT1061DVL6A) || defined(CPU_MIMXRT1061DVL6B) || defined(CPU_MIMXRT1061XVN5B))
#include "MIMXRT1061_COMMON.h"
#elif (defined(CPU_MIMXRT1062CVJ5A) || defined(CPU_MIMXRT1062CVJ5B) || defined(CPU_MIMXRT1062CVL5A) || defined(CPU_MIMXRT1062CVL5B) || defined(CPU_MIMXRT1062DVJ6A) || defined(CPU_MIMXRT1062DVJ6B) || defined(CPU_MIMXRT1062DVL6A) || defined(CPU_MIMXRT1062DVL6B) || defined(CPU_MIMXRT1062DVN6B) || defined(CPU_MIMXRT1062XVN5B))
#include "MIMXRT1062_COMMON.h"
#elif (defined(CPU_MIMXRT106ADVL6A))
#include "MIMXRT106A_COMMON.h"
#elif (defined(CPU_MIMXRT106CDVL6A))
#include "MIMXRT106C_COMMON.h"
#elif (defined(CPU_MIMXRT106FDVL6A))
#include "MIMXRT106F_COMMON.h"
#elif (defined(CPU_MIMXRT106LDVL6A))
#include "MIMXRT106L_COMMON.h"
#elif (defined(CPU_MIMXRT106SDVL6A))
#include "MIMXRT106S_COMMON.h"
#else
#error "No valid CPU defined!"
#endif
/* ----------------------------------------------------------------------------
-- Mapping Information
---------------------------------------------------------------------------- */
/*!
* @addtogroup Mapping_Information Mapping Information
* @{
*/
/** Mapping Information */
#if !defined(DMA_REQUEST_SOURCE_T_)
#define DMA_REQUEST_SOURCE_T_
/*!
* @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
{
kDmaRequestMuxFlexIO1Request0Request1 = 0|0x100U, /**< FlexIO1 Request0 and Request1 */
kDmaRequestMuxFlexIO2Request0Request1 = 1|0x100U, /**< FlexIO2 Request0 and Request1 */
kDmaRequestMuxLPUART1Tx = 2|0x100U, /**< LPUART1 Transmit */
kDmaRequestMuxLPUART1Rx = 3|0x100U, /**< LPUART1 Receive */
kDmaRequestMuxLPUART3Tx = 4|0x100U, /**< LPUART3 Transmit */
kDmaRequestMuxLPUART3Rx = 5|0x100U, /**< LPUART3 Receive */
kDmaRequestMuxLPUART5Tx = 6|0x100U, /**< LPUART5 Transmit */
kDmaRequestMuxLPUART5Rx = 7|0x100U, /**< LPUART5 Receive */
kDmaRequestMuxLPUART7Tx = 8|0x100U, /**< LPUART7 Transmit */
kDmaRequestMuxLPUART7Rx = 9|0x100U, /**< LPUART7 Receive */
kDmaRequestMuxCAN3 = 11|0x100U, /**< CAN3 */
kDmaRequestMuxLPSPI1Rx = 13|0x100U, /**< LPSPI1 Receive */
kDmaRequestMuxLPSPI1Tx = 14|0x100U, /**< LPSPI1 Transmit */
kDmaRequestMuxLPSPI3Rx = 15|0x100U, /**< LPSPI3 Receive */
kDmaRequestMuxLPSPI3Tx = 16|0x100U, /**< LPSPI3 Transmit */
kDmaRequestMuxLPI2C1 = 17|0x100U, /**< LPI2C1 */
kDmaRequestMuxLPI2C3 = 18|0x100U, /**< LPI2C3 */
kDmaRequestMuxSai1Rx = 19|0x100U, /**< SAI1 Receive */
kDmaRequestMuxSai1Tx = 20|0x100U, /**< SAI1 Transmit */
kDmaRequestMuxSai2Rx = 21|0x100U, /**< SAI2 Receive */
kDmaRequestMuxSai2Tx = 22|0x100U, /**< SAI2 Transmit */
kDmaRequestMuxADC_ETC = 23|0x100U, /**< ADC_ETC */
kDmaRequestMuxADC1 = 24|0x100U, /**< ADC1 */
kDmaRequestMuxACMP1 = 25|0x100U, /**< ACMP1 */
kDmaRequestMuxACMP3 = 26|0x100U, /**< ACMP3 */
kDmaRequestMuxFlexSPIRx = 28|0x100U, /**< FlexSPI Receive */
kDmaRequestMuxFlexSPITx = 29|0x100U, /**< FlexSPI Transmit */
kDmaRequestMuxXBAR1Request0 = 30|0x100U, /**< XBAR1 Request 0 */
kDmaRequestMuxXBAR1Request1 = 31|0x100U, /**< XBAR1 Request 1 */
kDmaRequestMuxFlexPWM1CaptureSub0 = 32|0x100U, /**< FlexPWM1 Capture sub-module0 */
kDmaRequestMuxFlexPWM1CaptureSub1 = 33|0x100U, /**< FlexPWM1 Capture sub-module1 */
kDmaRequestMuxFlexPWM1CaptureSub2 = 34|0x100U, /**< FlexPWM1 Capture sub-module2 */
kDmaRequestMuxFlexPWM1CaptureSub3 = 35|0x100U, /**< FlexPWM1 Capture sub-module3 */
kDmaRequestMuxFlexPWM1ValueSub0 = 36|0x100U, /**< FlexPWM1 Value sub-module0 */
kDmaRequestMuxFlexPWM1ValueSub1 = 37|0x100U, /**< FlexPWM1 Value sub-module1 */
kDmaRequestMuxFlexPWM1ValueSub2 = 38|0x100U, /**< FlexPWM1 Value sub-module2 */
kDmaRequestMuxFlexPWM1ValueSub3 = 39|0x100U, /**< FlexPWM1 Value sub-module3 */
kDmaRequestMuxFlexPWM3CaptureSub0 = 40|0x100U, /**< FlexPWM3 Capture sub-module0 */
kDmaRequestMuxFlexPWM3CaptureSub1 = 41|0x100U, /**< FlexPWM3 Capture sub-module1 */
kDmaRequestMuxFlexPWM3CaptureSub2 = 42|0x100U, /**< FlexPWM3 Capture sub-module2 */
kDmaRequestMuxFlexPWM3CaptureSub3 = 43|0x100U, /**< FlexPWM3 Capture sub-module3 */
kDmaRequestMuxFlexPWM3ValueSub0 = 44|0x100U, /**< FlexPWM3 Value sub-module0 */
kDmaRequestMuxFlexPWM3ValueSub1 = 45|0x100U, /**< FlexPWM3 Value sub-module1 */
kDmaRequestMuxFlexPWM3ValueSub2 = 46|0x100U, /**< FlexPWM3 Value sub-module2 */
kDmaRequestMuxFlexPWM3ValueSub3 = 47|0x100U, /**< FlexPWM3 Value sub-module3 */
kDmaRequestMuxQTIMER1CaptTimer0 = 48|0x100U, /**< TMR1 Capture timer 0 */
kDmaRequestMuxQTIMER1CaptTimer1 = 49|0x100U, /**< TMR1 Capture timer 1 */
kDmaRequestMuxQTIMER1CaptTimer2 = 50|0x100U, /**< TMR1 Capture timer 2 */
kDmaRequestMuxQTIMER1CaptTimer3 = 51|0x100U, /**< TMR1 Capture timer 3 */
kDmaRequestMuxQTIMER1Cmpld1Timer0Cmpld2Timer1 = 52|0x100U, /**< TMR1 cmpld1 in timer 0 or cmpld2 in timer 1 */
kDmaRequestMuxQTIMER1Cmpld1Timer1Cmpld2Timer0 = 53|0x100U, /**< TMR1 cmpld1 in timer 1 or cmpld2 in timer 0 */
kDmaRequestMuxQTIMER1Cmpld1Timer2Cmpld2Timer3 = 54|0x100U, /**< TMR1 cmpld1 in timer 2 or cmpld2 in timer 3 */
kDmaRequestMuxQTIMER1Cmpld1Timer3Cmpld2Timer2 = 55|0x100U, /**< TMR1 cmpld1 in timer 3 or cmpld2 in timer 2 */
kDmaRequestMuxQTIMER3CaptTimer0Cmpld1Timer0Cmpld2Timer1 = 56|0x100U, /**< TMR3 capture timer 0, cmpld1 in timer 0 or cmpld2 in timer 1 */
kDmaRequestMuxQTIMER3CaptTimer1Cmpld1Timer1Cmpld2Timer0 = 57|0x100U, /**< TMR3 capture timer 1, cmpld1 in timer 1 or cmpld2 in timer 0 */
kDmaRequestMuxQTIMER3CaptTimer2Cmpld1Timer2Cmpld2Timer3 = 58|0x100U, /**< TMR3 capture timer 2, cmpld1 in timer 2 or cmpld2 in timer 3 */
kDmaRequestMuxQTIMER3CaptTimer3Cmpld1Timer3Cmpld2Timer2 = 59|0x100U, /**< TMR3 capture timer 3, cmpld1 in timer 3 or cmpld2 in timer 2 */
kDmaRequestMuxFlexSPI2Rx = 60|0x100U, /**< FlexSPI2 Receive */
kDmaRequestMuxFlexSPI2Tx = 61|0x100U, /**< FlexSPI2 Transmit */
kDmaRequestMuxFlexIO1Request2Request3 = 64|0x100U, /**< FlexIO1 Request2 and Request3 */
kDmaRequestMuxFlexIO2Request2Request3 = 65|0x100U, /**< FlexIO2 Request2 and Request3 */
kDmaRequestMuxLPUART2Tx = 66|0x100U, /**< LPUART2 Transmit */
kDmaRequestMuxLPUART2Rx = 67|0x100U, /**< LPUART2 Receive */
kDmaRequestMuxLPUART4Tx = 68|0x100U, /**< LPUART4 Transmit */
kDmaRequestMuxLPUART4Rx = 69|0x100U, /**< LPUART4 Receive */
kDmaRequestMuxLPUART6Tx = 70|0x100U, /**< LPUART6 Transmit */
kDmaRequestMuxLPUART6Rx = 71|0x100U, /**< LPUART6 Receive */
kDmaRequestMuxLPUART8Tx = 72|0x100U, /**< LPUART8 Transmit */
kDmaRequestMuxLPUART8Rx = 73|0x100U, /**< LPUART8 Receive */
kDmaRequestMuxLPSPI2Rx = 77|0x100U, /**< LPSPI2 Receive */
kDmaRequestMuxLPSPI2Tx = 78|0x100U, /**< LPSPI2 Transmit */
kDmaRequestMuxLPSPI4Rx = 79|0x100U, /**< LPSPI4 Receive */
kDmaRequestMuxLPSPI4Tx = 80|0x100U, /**< LPSPI4 Transmit */
kDmaRequestMuxLPI2C2 = 81|0x100U, /**< LPI2C2 */
kDmaRequestMuxLPI2C4 = 82|0x100U, /**< LPI2C4 */
kDmaRequestMuxSai3Rx = 83|0x100U, /**< SAI3 Receive */
kDmaRequestMuxSai3Tx = 84|0x100U, /**< SAI3 Transmit */
kDmaRequestMuxSpdifRx = 85|0x100U, /**< SPDIF Receive */
kDmaRequestMuxSpdifTx = 86|0x100U, /**< SPDIF Transmit */
kDmaRequestMuxADC2 = 88|0x100U, /**< ADC2 */
kDmaRequestMuxACMP2 = 89|0x100U, /**< ACMP2 */
kDmaRequestMuxACMP4 = 90|0x100U, /**< ACMP4 */
kDmaRequestMuxEnetTimer0 = 92|0x100U, /**< ENET Timer0 */
kDmaRequestMuxEnetTimer1 = 93|0x100U, /**< ENET Timer1 */
kDmaRequestMuxXBAR1Request2 = 94|0x100U, /**< XBAR1 Request 2 */
kDmaRequestMuxXBAR1Request3 = 95|0x100U, /**< XBAR1 Request 3 */
kDmaRequestMuxFlexPWM2CaptureSub0 = 96|0x100U, /**< FlexPWM2 Capture sub-module0 */
kDmaRequestMuxFlexPWM2CaptureSub1 = 97|0x100U, /**< FlexPWM2 Capture sub-module1 */
kDmaRequestMuxFlexPWM2CaptureSub2 = 98|0x100U, /**< FlexPWM2 Capture sub-module2 */
kDmaRequestMuxFlexPWM2CaptureSub3 = 99|0x100U, /**< FlexPWM2 Capture sub-module3 */
kDmaRequestMuxFlexPWM2ValueSub0 = 100|0x100U, /**< FlexPWM2 Value sub-module0 */
kDmaRequestMuxFlexPWM2ValueSub1 = 101|0x100U, /**< FlexPWM2 Value sub-module1 */
kDmaRequestMuxFlexPWM2ValueSub2 = 102|0x100U, /**< FlexPWM2 Value sub-module2 */
kDmaRequestMuxFlexPWM2ValueSub3 = 103|0x100U, /**< FlexPWM2 Value sub-module3 */
kDmaRequestMuxFlexPWM4CaptureSub0 = 104|0x100U, /**< FlexPWM4 Capture sub-module0 */
kDmaRequestMuxFlexPWM4CaptureSub1 = 105|0x100U, /**< FlexPWM4 Capture sub-module1 */
kDmaRequestMuxFlexPWM4CaptureSub2 = 106|0x100U, /**< FlexPWM4 Capture sub-module2 */
kDmaRequestMuxFlexPWM4CaptureSub3 = 107|0x100U, /**< FlexPWM4 Capture sub-module3 */
kDmaRequestMuxFlexPWM4ValueSub0 = 108|0x100U, /**< FlexPWM4 Value sub-module0 */
kDmaRequestMuxFlexPWM4ValueSub1 = 109|0x100U, /**< FlexPWM4 Value sub-module1 */
kDmaRequestMuxFlexPWM4ValueSub2 = 110|0x100U, /**< FlexPWM4 Value sub-module2 */
kDmaRequestMuxFlexPWM4ValueSub3 = 111|0x100U, /**< FlexPWM4 Value sub-module3 */
kDmaRequestMuxQTIMER2CaptTimer0 = 112|0x100U, /**< TMR2 Capture timer 0 */
kDmaRequestMuxQTIMER2CaptTimer1 = 113|0x100U, /**< TMR2 Capture timer 1 */
kDmaRequestMuxQTIMER2CaptTimer2 = 114|0x100U, /**< TMR2 Capture timer 2 */
kDmaRequestMuxQTIMER2CaptTimer3 = 115|0x100U, /**< TMR2 Capture timer 3 */
kDmaRequestMuxQTIMER2Cmpld1Timer0Cmpld2Timer1 = 116|0x100U, /**< TMR2 cmpld1 in timer 0 or cmpld2 in timer 1 */
kDmaRequestMuxQTIMER2Cmpld1Timer1Cmpld2Timer0 = 117|0x100U, /**< TMR2 cmpld1 in timer 1 or cmpld2 in timer 0 */
kDmaRequestMuxQTIMER2Cmpld1Timer2Cmpld2Timer3 = 118|0x100U, /**< TMR2 cmpld1 in timer 2 or cmpld2 in timer 3 */
kDmaRequestMuxQTIMER2Cmpld1Timer3Cmpld2Timer2 = 119|0x100U, /**< TMR2 cmpld1 in timer 3 or cmpld2 in timer 2 */
kDmaRequestMuxQTIMER4CaptTimer0Cmpld1Timer0Cmpld2Timer1 = 120|0x100U, /**< TMR4 capture timer 0, cmpld1 in timer 0 or cmpld2 in timer 1 */
kDmaRequestMuxQTIMER4CaptTimer1Cmpld1Timer1Cmpld2Timer0 = 121|0x100U, /**< TMR4 capture timer 1, cmpld1 in timer 1 or cmpld2 in timer 0 */
kDmaRequestMuxQTIMER4CaptTimer2Cmpld1Timer2Cmpld2Timer3 = 122|0x100U, /**< TMR4 capture timer 2, cmpld1 in timer 2 or cmpld2 in timer 3 */
kDmaRequestMuxQTIMER4CaptTimer3Cmpld1Timer3Cmpld2Timer2 = 123|0x100U, /**< TMR4 capture timer 3, cmpld1 in timer 3 or cmpld2 in timer 2 */
kDmaRequestMuxEnet2Timer0 = 124|0x100U, /**< ENET2 Timer0 */
kDmaRequestMuxEnet2Timer1 = 125|0x100U, /**< ENET2 Timer1 */
kDmaRequestMuxCSI = 12|0x100U, /**< CSI */
kDmaRequestMuxPxp = 75|0x100U, /**< PXP */
kDmaRequestMuxLCDIF = 76|0x100U, /**< LCDIF */
} dma_request_source_t;
/* @} */
#endif /* 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
/* ----------------------------------------------------------------------------
-- DMAMUX Peripheral Access Layer
---------------------------------------------------------------------------- */
/*!
* @addtogroup DMAMUX_Peripheral_Access_Layer DMAMUX Peripheral Access Layer
* @{
*/
/** DMAMUX - Size of Registers Arrays */
#define DMAMUX_CHCFG_REG_ARRAY_COUNT 32u
/** DMAMUX - Register Layout Typedef */
typedef struct {
__IO uint32_t CHCFG[DMAMUX_CHCFG_REG_ARRAY_COUNT]; /**< Channel 0 Configuration Register..Channel 31 Configuration Register, array offset: 0x0, array step: 0x4 */
} DMAMUX_Type;
/* ----------------------------------------------------------------------------
-- DMAMUX Register Masks
---------------------------------------------------------------------------- */
/*!
* @addtogroup DMAMUX_Register_Masks DMAMUX Register Masks
* @{
*/
/*! @name CHCFG - Channel 0 Configuration Register..Channel 31 Configuration Register */
/*! @{ */
#define DMAMUX_CHCFG_SOURCE_MASK (0x7FU)
#define DMAMUX_CHCFG_SOURCE_SHIFT (0U)
/*! SOURCE - DMA Channel Source (Slot Number) */
#define DMAMUX_CHCFG_SOURCE(x) (((uint32_t)(((uint32_t)(x)) << DMAMUX_CHCFG_SOURCE_SHIFT)) & DMAMUX_CHCFG_SOURCE_MASK)
#define DMAMUX_CHCFG_A_ON_MASK (0x20000000U)
#define DMAMUX_CHCFG_A_ON_SHIFT (29U)
/*! A_ON - DMA Channel Always Enable
* 0b0..DMA Channel Always ON function is disabled
* 0b1..DMA Channel Always ON function is enabled
*/
#define DMAMUX_CHCFG_A_ON(x) (((uint32_t)(((uint32_t)(x)) << DMAMUX_CHCFG_A_ON_SHIFT)) & DMAMUX_CHCFG_A_ON_MASK)
#define DMAMUX_CHCFG_TRIG_MASK (0x40000000U)
#define DMAMUX_CHCFG_TRIG_SHIFT (30U)
/*! TRIG - DMA Channel Trigger Enable
* 0b0..Triggering is disabled. If triggering is disabled and ENBL is set, the DMA Channel will simply route the
* specified source to the DMA channel. (Normal mode)
* 0b1..Triggering is enabled. If triggering is enabled and ENBL is set, the DMA_CH_MUX is in Periodic Trigger mode.
*/
#define DMAMUX_CHCFG_TRIG(x) (((uint32_t)(((uint32_t)(x)) << DMAMUX_CHCFG_TRIG_SHIFT)) & DMAMUX_CHCFG_TRIG_MASK)
#define DMAMUX_CHCFG_ENBL_MASK (0x80000000U)
#define DMAMUX_CHCFG_ENBL_SHIFT (31U)
/*! ENBL - DMA Mux Channel Enable
* 0b0..DMA Mux channel is disabled
* 0b1..DMA Mux channel is enabled
*/
#define DMAMUX_CHCFG_ENBL(x) (((uint32_t)(((uint32_t)(x)) << DMAMUX_CHCFG_ENBL_SHIFT)) & DMAMUX_CHCFG_ENBL_MASK)
/*! @} */
/* The count of DMAMUX_CHCFG */
#define DMAMUX_CHCFG_COUNT (32U)
/*!
* @}
*/ /* end of group DMAMUX_Register_Masks */
/*!
* @}
*/ /* end of group DMAMUX_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 */
#endif /* DMAMUX_H_ */

View File

@ -0,0 +1,654 @@
/*
** ###################################################################
** Processors: MIMXRT1061CVJ5A
** MIMXRT1061CVJ5B
** MIMXRT1061CVL5A
** MIMXRT1061CVL5B
** MIMXRT1061DVJ6A
** MIMXRT1061DVJ6B
** MIMXRT1061DVL6A
** MIMXRT1061DVL6B
** MIMXRT1061XVN5B
** MIMXRT1062CVJ5A
** MIMXRT1062CVJ5B
** MIMXRT1062CVL5A
** MIMXRT1062CVL5B
** MIMXRT1062DVJ6A
** MIMXRT1062DVJ6B
** MIMXRT1062DVL6A
** MIMXRT1062DVL6B
** MIMXRT1062DVN6B
** MIMXRT1062XVN5B
** MIMXRT106ADVL6A
** MIMXRT106CDVL6A
** MIMXRT106FDVL6A
** MIMXRT106LDVL6A
** MIMXRT106SDVL6A
**
** Version: rev. 1.4, 2022-03-25
** Build: b240705
**
** Abstract:
** CMSIS Peripheral Access Layer for ENC
**
** Copyright 1997-2016 Freescale Semiconductor, Inc.
** Copyright 2016-2024 NXP
** SPDX-License-Identifier: BSD-3-Clause
**
** http: www.nxp.com
** mail: support@nxp.com
**
** Revisions:
** - rev. 0.1 (2017-01-10)
** Initial version.
** - rev. 1.0 (2018-11-16)
** Update header files to align with IMXRT1060RM Rev.0.
** - rev. 1.1 (2018-11-27)
** Update header files to align with IMXRT1060RM Rev.1.
** - rev. 1.2 (2019-04-29)
** Add SET/CLR/TOG register group to register CTRL, STAT, CHANNELCTRL, CH0STAT, CH0OPTS, CH1STAT, CH1OPTS, CH2STAT, CH2OPTS, CH3STAT, CH3OPTS of DCP module.
** - rev. 1.3 (2021-08-10)
** Update header files to align with IMXRT1060RM Rev.3.
** - rev. 1.4 (2022-03-25)
** Add RT1060X device
**
** ###################################################################
*/
/*!
* @file ENC.h
* @version 1.4
* @date 2022-03-25
* @brief CMSIS Peripheral Access Layer for ENC
*
* CMSIS Peripheral Access Layer for ENC
*/
#if !defined(ENC_H_)
#define ENC_H_ /**< Symbol preventing repeated inclusion */
#if (defined(CPU_MIMXRT1061CVJ5A) || defined(CPU_MIMXRT1061CVJ5B) || defined(CPU_MIMXRT1061CVL5A) || defined(CPU_MIMXRT1061CVL5B) || defined(CPU_MIMXRT1061DVJ6A) || defined(CPU_MIMXRT1061DVJ6B) || defined(CPU_MIMXRT1061DVL6A) || defined(CPU_MIMXRT1061DVL6B) || defined(CPU_MIMXRT1061XVN5B))
#include "MIMXRT1061_COMMON.h"
#elif (defined(CPU_MIMXRT1062CVJ5A) || defined(CPU_MIMXRT1062CVJ5B) || defined(CPU_MIMXRT1062CVL5A) || defined(CPU_MIMXRT1062CVL5B) || defined(CPU_MIMXRT1062DVJ6A) || defined(CPU_MIMXRT1062DVJ6B) || defined(CPU_MIMXRT1062DVL6A) || defined(CPU_MIMXRT1062DVL6B) || defined(CPU_MIMXRT1062DVN6B) || defined(CPU_MIMXRT1062XVN5B))
#include "MIMXRT1062_COMMON.h"
#elif (defined(CPU_MIMXRT106ADVL6A))
#include "MIMXRT106A_COMMON.h"
#elif (defined(CPU_MIMXRT106CDVL6A))
#include "MIMXRT106C_COMMON.h"
#elif (defined(CPU_MIMXRT106FDVL6A))
#include "MIMXRT106F_COMMON.h"
#elif (defined(CPU_MIMXRT106LDVL6A))
#include "MIMXRT106L_COMMON.h"
#elif (defined(CPU_MIMXRT106SDVL6A))
#include "MIMXRT106S_COMMON.h"
#else
#error "No valid CPU defined!"
#endif
/* ----------------------------------------------------------------------------
-- 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
/* ----------------------------------------------------------------------------
-- ENC Peripheral Access Layer
---------------------------------------------------------------------------- */
/*!
* @addtogroup ENC_Peripheral_Access_Layer ENC Peripheral Access Layer
* @{
*/
/** ENC - Register Layout Typedef */
typedef struct {
__IO uint16_t CTRL; /**< Control Register, offset: 0x0 */
__IO uint16_t FILT; /**< Input Filter Register, offset: 0x2 */
__IO uint16_t WTR; /**< Watchdog Timeout Register, offset: 0x4 */
__IO uint16_t POSD; /**< Position Difference Counter Register, offset: 0x6 */
__I uint16_t POSDH; /**< Position Difference Hold Register, offset: 0x8 */
__IO uint16_t REV; /**< Revolution Counter Register, offset: 0xA */
__I uint16_t REVH; /**< Revolution Hold Register, offset: 0xC */
__IO uint16_t UPOS; /**< Upper Position Counter Register, offset: 0xE */
__IO uint16_t LPOS; /**< Lower Position Counter Register, offset: 0x10 */
__I uint16_t UPOSH; /**< Upper Position Hold Register, offset: 0x12 */
__I uint16_t LPOSH; /**< Lower Position Hold Register, offset: 0x14 */
__IO uint16_t UINIT; /**< Upper Initialization Register, offset: 0x16 */
__IO uint16_t LINIT; /**< Lower Initialization Register, offset: 0x18 */
__I uint16_t IMR; /**< Input Monitor Register, offset: 0x1A */
__IO uint16_t TST; /**< Test Register, offset: 0x1C */
__IO uint16_t CTRL2; /**< Control 2 Register, offset: 0x1E */
__IO uint16_t UMOD; /**< Upper Modulus Register, offset: 0x20 */
__IO uint16_t LMOD; /**< Lower Modulus Register, offset: 0x22 */
__IO uint16_t UCOMP; /**< Upper Position Compare Register, offset: 0x24 */
__IO uint16_t LCOMP; /**< Lower Position Compare Register, offset: 0x26 */
} ENC_Type;
/* ----------------------------------------------------------------------------
-- ENC Register Masks
---------------------------------------------------------------------------- */
/*!
* @addtogroup ENC_Register_Masks ENC Register Masks
* @{
*/
/*! @name CTRL - Control Register */
/*! @{ */
#define ENC_CTRL_CMPIE_MASK (0x1U)
#define ENC_CTRL_CMPIE_SHIFT (0U)
/*! CMPIE - Compare Interrupt Enable
* 0b0..Disabled
* 0b1..Enabled
*/
#define ENC_CTRL_CMPIE(x) (((uint16_t)(((uint16_t)(x)) << ENC_CTRL_CMPIE_SHIFT)) & ENC_CTRL_CMPIE_MASK)
#define ENC_CTRL_CMPIRQ_MASK (0x2U)
#define ENC_CTRL_CMPIRQ_SHIFT (1U)
/*! CMPIRQ - Compare Interrupt Request
* 0b0..No match has occurred (the counter does not match the COMP value)
* 0b1..COMP match has occurred (the counter matches the COMP value)
*/
#define ENC_CTRL_CMPIRQ(x) (((uint16_t)(((uint16_t)(x)) << ENC_CTRL_CMPIRQ_SHIFT)) & ENC_CTRL_CMPIRQ_MASK)
#define ENC_CTRL_WDE_MASK (0x4U)
#define ENC_CTRL_WDE_SHIFT (2U)
/*! WDE - Watchdog Enable
* 0b0..Disabled
* 0b1..Enabled
*/
#define ENC_CTRL_WDE(x) (((uint16_t)(((uint16_t)(x)) << ENC_CTRL_WDE_SHIFT)) & ENC_CTRL_WDE_MASK)
#define ENC_CTRL_DIE_MASK (0x8U)
#define ENC_CTRL_DIE_SHIFT (3U)
/*! DIE - Watchdog Timeout Interrupt Enable
* 0b0..Disabled
* 0b1..Enabled
*/
#define ENC_CTRL_DIE(x) (((uint16_t)(((uint16_t)(x)) << ENC_CTRL_DIE_SHIFT)) & ENC_CTRL_DIE_MASK)
#define ENC_CTRL_DIRQ_MASK (0x10U)
#define ENC_CTRL_DIRQ_SHIFT (4U)
/*! DIRQ - Watchdog Timeout Interrupt Request
* 0b0..No Watchdog timeout interrupt has occurred
* 0b1..Watchdog timeout interrupt has occurred
*/
#define ENC_CTRL_DIRQ(x) (((uint16_t)(((uint16_t)(x)) << ENC_CTRL_DIRQ_SHIFT)) & ENC_CTRL_DIRQ_MASK)
#define ENC_CTRL_XNE_MASK (0x20U)
#define ENC_CTRL_XNE_SHIFT (5U)
/*! XNE - Use Negative Edge of INDEX Pulse
* 0b0..Use positive edge of INDEX pulse
* 0b1..Use negative edge of INDEX pulse
*/
#define ENC_CTRL_XNE(x) (((uint16_t)(((uint16_t)(x)) << ENC_CTRL_XNE_SHIFT)) & ENC_CTRL_XNE_MASK)
#define ENC_CTRL_XIP_MASK (0x40U)
#define ENC_CTRL_XIP_SHIFT (6U)
/*! XIP - INDEX Triggered Initialization of Position Counters UPOS and LPOS
* 0b0..INDEX pulse does not initialize the position counter
* 0b1..INDEX pulse initializes the position counter
*/
#define ENC_CTRL_XIP(x) (((uint16_t)(((uint16_t)(x)) << ENC_CTRL_XIP_SHIFT)) & ENC_CTRL_XIP_MASK)
#define ENC_CTRL_XIE_MASK (0x80U)
#define ENC_CTRL_XIE_SHIFT (7U)
/*! XIE - INDEX Pulse Interrupt Enable
* 0b0..Disabled
* 0b1..Enabled
*/
#define ENC_CTRL_XIE(x) (((uint16_t)(((uint16_t)(x)) << ENC_CTRL_XIE_SHIFT)) & ENC_CTRL_XIE_MASK)
#define ENC_CTRL_XIRQ_MASK (0x100U)
#define ENC_CTRL_XIRQ_SHIFT (8U)
/*! XIRQ - INDEX Pulse Interrupt Request
* 0b0..INDEX pulse has not occurred
* 0b1..INDEX pulse has occurred
*/
#define ENC_CTRL_XIRQ(x) (((uint16_t)(((uint16_t)(x)) << ENC_CTRL_XIRQ_SHIFT)) & ENC_CTRL_XIRQ_MASK)
#define ENC_CTRL_PH1_MASK (0x200U)
#define ENC_CTRL_PH1_SHIFT (9U)
/*! PH1 - Enable Signal Phase Count Mode
* 0b0..Use the standard quadrature decoder, where PHASEA and PHASEB represent a two-phase quadrature signal.
* 0b1..Bypass the quadrature decoder. A positive transition of the PHASEA input generates a count signal. The
* PHASEB input and the REV bit control the counter direction: If CTRL[REV] = 0, PHASEB = 0, then count up If
* CTRL[REV] = 1, PHASEB = 1, then count up If CTRL[REV] = 0, PHASEB = 1, then count down If CTRL[REV] = 1,
* PHASEB = 0, then count down
*/
#define ENC_CTRL_PH1(x) (((uint16_t)(((uint16_t)(x)) << ENC_CTRL_PH1_SHIFT)) & ENC_CTRL_PH1_MASK)
#define ENC_CTRL_REV_MASK (0x400U)
#define ENC_CTRL_REV_SHIFT (10U)
/*! REV - Enable Reverse Direction Counting
* 0b0..Count normally
* 0b1..Count in the reverse direction
*/
#define ENC_CTRL_REV(x) (((uint16_t)(((uint16_t)(x)) << ENC_CTRL_REV_SHIFT)) & ENC_CTRL_REV_MASK)
#define ENC_CTRL_SWIP_MASK (0x800U)
#define ENC_CTRL_SWIP_SHIFT (11U)
/*! SWIP - Software-Triggered Initialization of Position Counters UPOS and LPOS
* 0b0..No action
* 0b1..Initialize position counter (using upper and lower initialization registers, UINIT and LINIT)
*/
#define ENC_CTRL_SWIP(x) (((uint16_t)(((uint16_t)(x)) << ENC_CTRL_SWIP_SHIFT)) & ENC_CTRL_SWIP_MASK)
#define ENC_CTRL_HNE_MASK (0x1000U)
#define ENC_CTRL_HNE_SHIFT (12U)
/*! HNE - Use Negative Edge of HOME Input
* 0b0..Use positive-going edge-to-trigger initialization of position counters UPOS and LPOS
* 0b1..Use negative-going edge-to-trigger initialization of position counters UPOS and LPOS
*/
#define ENC_CTRL_HNE(x) (((uint16_t)(((uint16_t)(x)) << ENC_CTRL_HNE_SHIFT)) & ENC_CTRL_HNE_MASK)
#define ENC_CTRL_HIP_MASK (0x2000U)
#define ENC_CTRL_HIP_SHIFT (13U)
/*! HIP - Enable HOME to Initialize Position Counters UPOS and LPOS
* 0b0..No action
* 0b1..HOME signal initializes the position counter
*/
#define ENC_CTRL_HIP(x) (((uint16_t)(((uint16_t)(x)) << ENC_CTRL_HIP_SHIFT)) & ENC_CTRL_HIP_MASK)
#define ENC_CTRL_HIE_MASK (0x4000U)
#define ENC_CTRL_HIE_SHIFT (14U)
/*! HIE - HOME Interrupt Enable
* 0b0..Disabled
* 0b1..Enabled
*/
#define ENC_CTRL_HIE(x) (((uint16_t)(((uint16_t)(x)) << ENC_CTRL_HIE_SHIFT)) & ENC_CTRL_HIE_MASK)
#define ENC_CTRL_HIRQ_MASK (0x8000U)
#define ENC_CTRL_HIRQ_SHIFT (15U)
/*! HIRQ - HOME Signal Transition Interrupt Request
* 0b0..No transition on the HOME signal has occurred
* 0b1..A transition on the HOME signal has occurred
*/
#define ENC_CTRL_HIRQ(x) (((uint16_t)(((uint16_t)(x)) << ENC_CTRL_HIRQ_SHIFT)) & ENC_CTRL_HIRQ_MASK)
/*! @} */
/*! @name FILT - Input Filter Register */
/*! @{ */
#define ENC_FILT_FILT_PER_MASK (0xFFU)
#define ENC_FILT_FILT_PER_SHIFT (0U)
/*! FILT_PER - Input Filter Sample Period */
#define ENC_FILT_FILT_PER(x) (((uint16_t)(((uint16_t)(x)) << ENC_FILT_FILT_PER_SHIFT)) & ENC_FILT_FILT_PER_MASK)
#define ENC_FILT_FILT_CNT_MASK (0x700U)
#define ENC_FILT_FILT_CNT_SHIFT (8U)
/*! FILT_CNT - Input Filter Sample Count */
#define ENC_FILT_FILT_CNT(x) (((uint16_t)(((uint16_t)(x)) << ENC_FILT_FILT_CNT_SHIFT)) & ENC_FILT_FILT_CNT_MASK)
#define ENC_FILT_FILT_PRSC_MASK (0xE000U)
#define ENC_FILT_FILT_PRSC_SHIFT (13U)
/*! FILT_PRSC - prescaler divide IPbus clock to FILT clk */
#define ENC_FILT_FILT_PRSC(x) (((uint16_t)(((uint16_t)(x)) << ENC_FILT_FILT_PRSC_SHIFT)) & ENC_FILT_FILT_PRSC_MASK)
/*! @} */
/*! @name WTR - Watchdog Timeout Register */
/*! @{ */
#define ENC_WTR_WDOG_MASK (0xFFFFU)
#define ENC_WTR_WDOG_SHIFT (0U)
/*! WDOG - WDOG */
#define ENC_WTR_WDOG(x) (((uint16_t)(((uint16_t)(x)) << ENC_WTR_WDOG_SHIFT)) & ENC_WTR_WDOG_MASK)
/*! @} */
/*! @name POSD - Position Difference Counter Register */
/*! @{ */
#define ENC_POSD_POSD_MASK (0xFFFFU)
#define ENC_POSD_POSD_SHIFT (0U)
/*! POSD - POSD */
#define ENC_POSD_POSD(x) (((uint16_t)(((uint16_t)(x)) << ENC_POSD_POSD_SHIFT)) & ENC_POSD_POSD_MASK)
/*! @} */
/*! @name POSDH - Position Difference Hold Register */
/*! @{ */
#define ENC_POSDH_POSDH_MASK (0xFFFFU)
#define ENC_POSDH_POSDH_SHIFT (0U)
/*! POSDH - POSDH */
#define ENC_POSDH_POSDH(x) (((uint16_t)(((uint16_t)(x)) << ENC_POSDH_POSDH_SHIFT)) & ENC_POSDH_POSDH_MASK)
/*! @} */
/*! @name REV - Revolution Counter Register */
/*! @{ */
#define ENC_REV_REV_MASK (0xFFFFU)
#define ENC_REV_REV_SHIFT (0U)
/*! REV - REV */
#define ENC_REV_REV(x) (((uint16_t)(((uint16_t)(x)) << ENC_REV_REV_SHIFT)) & ENC_REV_REV_MASK)
/*! @} */
/*! @name REVH - Revolution Hold Register */
/*! @{ */
#define ENC_REVH_REVH_MASK (0xFFFFU)
#define ENC_REVH_REVH_SHIFT (0U)
/*! REVH - REVH */
#define ENC_REVH_REVH(x) (((uint16_t)(((uint16_t)(x)) << ENC_REVH_REVH_SHIFT)) & ENC_REVH_REVH_MASK)
/*! @} */
/*! @name UPOS - Upper Position Counter Register */
/*! @{ */
#define ENC_UPOS_POS_MASK (0xFFFFU)
#define ENC_UPOS_POS_SHIFT (0U)
/*! POS - POS */
#define ENC_UPOS_POS(x) (((uint16_t)(((uint16_t)(x)) << ENC_UPOS_POS_SHIFT)) & ENC_UPOS_POS_MASK)
/*! @} */
/*! @name LPOS - Lower Position Counter Register */
/*! @{ */
#define ENC_LPOS_POS_MASK (0xFFFFU)
#define ENC_LPOS_POS_SHIFT (0U)
/*! POS - POS */
#define ENC_LPOS_POS(x) (((uint16_t)(((uint16_t)(x)) << ENC_LPOS_POS_SHIFT)) & ENC_LPOS_POS_MASK)
/*! @} */
/*! @name UPOSH - Upper Position Hold Register */
/*! @{ */
#define ENC_UPOSH_POSH_MASK (0xFFFFU)
#define ENC_UPOSH_POSH_SHIFT (0U)
/*! POSH - POSH */
#define ENC_UPOSH_POSH(x) (((uint16_t)(((uint16_t)(x)) << ENC_UPOSH_POSH_SHIFT)) & ENC_UPOSH_POSH_MASK)
/*! @} */
/*! @name LPOSH - Lower Position Hold Register */
/*! @{ */
#define ENC_LPOSH_POSH_MASK (0xFFFFU)
#define ENC_LPOSH_POSH_SHIFT (0U)
/*! POSH - POSH */
#define ENC_LPOSH_POSH(x) (((uint16_t)(((uint16_t)(x)) << ENC_LPOSH_POSH_SHIFT)) & ENC_LPOSH_POSH_MASK)
/*! @} */
/*! @name UINIT - Upper Initialization Register */
/*! @{ */
#define ENC_UINIT_INIT_MASK (0xFFFFU)
#define ENC_UINIT_INIT_SHIFT (0U)
/*! INIT - INIT */
#define ENC_UINIT_INIT(x) (((uint16_t)(((uint16_t)(x)) << ENC_UINIT_INIT_SHIFT)) & ENC_UINIT_INIT_MASK)
/*! @} */
/*! @name LINIT - Lower Initialization Register */
/*! @{ */
#define ENC_LINIT_INIT_MASK (0xFFFFU)
#define ENC_LINIT_INIT_SHIFT (0U)
/*! INIT - INIT */
#define ENC_LINIT_INIT(x) (((uint16_t)(((uint16_t)(x)) << ENC_LINIT_INIT_SHIFT)) & ENC_LINIT_INIT_MASK)
/*! @} */
/*! @name IMR - Input Monitor Register */
/*! @{ */
#define ENC_IMR_HOME_MASK (0x1U)
#define ENC_IMR_HOME_SHIFT (0U)
/*! HOME - HOME */
#define ENC_IMR_HOME(x) (((uint16_t)(((uint16_t)(x)) << ENC_IMR_HOME_SHIFT)) & ENC_IMR_HOME_MASK)
#define ENC_IMR_INDEX_MASK (0x2U)
#define ENC_IMR_INDEX_SHIFT (1U)
/*! INDEX - INDEX */
#define ENC_IMR_INDEX(x) (((uint16_t)(((uint16_t)(x)) << ENC_IMR_INDEX_SHIFT)) & ENC_IMR_INDEX_MASK)
#define ENC_IMR_PHB_MASK (0x4U)
#define ENC_IMR_PHB_SHIFT (2U)
/*! PHB - PHB */
#define ENC_IMR_PHB(x) (((uint16_t)(((uint16_t)(x)) << ENC_IMR_PHB_SHIFT)) & ENC_IMR_PHB_MASK)
#define ENC_IMR_PHA_MASK (0x8U)
#define ENC_IMR_PHA_SHIFT (3U)
/*! PHA - PHA */
#define ENC_IMR_PHA(x) (((uint16_t)(((uint16_t)(x)) << ENC_IMR_PHA_SHIFT)) & ENC_IMR_PHA_MASK)
#define ENC_IMR_FHOM_MASK (0x10U)
#define ENC_IMR_FHOM_SHIFT (4U)
/*! FHOM - FHOM */
#define ENC_IMR_FHOM(x) (((uint16_t)(((uint16_t)(x)) << ENC_IMR_FHOM_SHIFT)) & ENC_IMR_FHOM_MASK)
#define ENC_IMR_FIND_MASK (0x20U)
#define ENC_IMR_FIND_SHIFT (5U)
/*! FIND - FIND */
#define ENC_IMR_FIND(x) (((uint16_t)(((uint16_t)(x)) << ENC_IMR_FIND_SHIFT)) & ENC_IMR_FIND_MASK)
#define ENC_IMR_FPHB_MASK (0x40U)
#define ENC_IMR_FPHB_SHIFT (6U)
/*! FPHB - FPHB */
#define ENC_IMR_FPHB(x) (((uint16_t)(((uint16_t)(x)) << ENC_IMR_FPHB_SHIFT)) & ENC_IMR_FPHB_MASK)
#define ENC_IMR_FPHA_MASK (0x80U)
#define ENC_IMR_FPHA_SHIFT (7U)
/*! FPHA - FPHA */
#define ENC_IMR_FPHA(x) (((uint16_t)(((uint16_t)(x)) << ENC_IMR_FPHA_SHIFT)) & ENC_IMR_FPHA_MASK)
/*! @} */
/*! @name TST - Test Register */
/*! @{ */
#define ENC_TST_TEST_COUNT_MASK (0xFFU)
#define ENC_TST_TEST_COUNT_SHIFT (0U)
/*! TEST_COUNT - TEST_COUNT */
#define ENC_TST_TEST_COUNT(x) (((uint16_t)(((uint16_t)(x)) << ENC_TST_TEST_COUNT_SHIFT)) & ENC_TST_TEST_COUNT_MASK)
#define ENC_TST_TEST_PERIOD_MASK (0x1F00U)
#define ENC_TST_TEST_PERIOD_SHIFT (8U)
/*! TEST_PERIOD - TEST_PERIOD */
#define ENC_TST_TEST_PERIOD(x) (((uint16_t)(((uint16_t)(x)) << ENC_TST_TEST_PERIOD_SHIFT)) & ENC_TST_TEST_PERIOD_MASK)
#define ENC_TST_QDN_MASK (0x2000U)
#define ENC_TST_QDN_SHIFT (13U)
/*! QDN - Quadrature Decoder Negative Signal
* 0b0..Generates a positive quadrature decoder signal
* 0b1..Generates a negative quadrature decoder signal
*/
#define ENC_TST_QDN(x) (((uint16_t)(((uint16_t)(x)) << ENC_TST_QDN_SHIFT)) & ENC_TST_QDN_MASK)
#define ENC_TST_TCE_MASK (0x4000U)
#define ENC_TST_TCE_SHIFT (14U)
/*! TCE - Test Counter Enable
* 0b0..Disabled
* 0b1..Enabled
*/
#define ENC_TST_TCE(x) (((uint16_t)(((uint16_t)(x)) << ENC_TST_TCE_SHIFT)) & ENC_TST_TCE_MASK)
#define ENC_TST_TEN_MASK (0x8000U)
#define ENC_TST_TEN_SHIFT (15U)
/*! TEN - Test Mode Enable
* 0b0..Disabled
* 0b1..Enabled
*/
#define ENC_TST_TEN(x) (((uint16_t)(((uint16_t)(x)) << ENC_TST_TEN_SHIFT)) & ENC_TST_TEN_MASK)
/*! @} */
/*! @name CTRL2 - Control 2 Register */
/*! @{ */
#define ENC_CTRL2_UPDHLD_MASK (0x1U)
#define ENC_CTRL2_UPDHLD_SHIFT (0U)
/*! UPDHLD - Update Hold Registers
* 0b0..Disable updates of hold registers on the rising edge of TRIGGER input signal
* 0b1..Enable updates of hold registers on the rising edge of TRIGGER input signal
*/
#define ENC_CTRL2_UPDHLD(x) (((uint16_t)(((uint16_t)(x)) << ENC_CTRL2_UPDHLD_SHIFT)) & ENC_CTRL2_UPDHLD_MASK)
#define ENC_CTRL2_UPDPOS_MASK (0x2U)
#define ENC_CTRL2_UPDPOS_SHIFT (1U)
/*! UPDPOS - Update Position Registers
* 0b0..No action for POSD, REV, UPOS and LPOS registers on rising edge of TRIGGER
* 0b1..Clear POSD, REV, UPOS and LPOS registers on rising edge of TRIGGER
*/
#define ENC_CTRL2_UPDPOS(x) (((uint16_t)(((uint16_t)(x)) << ENC_CTRL2_UPDPOS_SHIFT)) & ENC_CTRL2_UPDPOS_MASK)
#define ENC_CTRL2_MOD_MASK (0x4U)
#define ENC_CTRL2_MOD_SHIFT (2U)
/*! MOD - Enable Modulo Counting
* 0b0..Disable modulo counting
* 0b1..Enable modulo counting
*/
#define ENC_CTRL2_MOD(x) (((uint16_t)(((uint16_t)(x)) << ENC_CTRL2_MOD_SHIFT)) & ENC_CTRL2_MOD_MASK)
#define ENC_CTRL2_DIR_MASK (0x8U)
#define ENC_CTRL2_DIR_SHIFT (3U)
/*! DIR - Count Direction Flag
* 0b0..Last count was in the down direction
* 0b1..Last count was in the up direction
*/
#define ENC_CTRL2_DIR(x) (((uint16_t)(((uint16_t)(x)) << ENC_CTRL2_DIR_SHIFT)) & ENC_CTRL2_DIR_MASK)
#define ENC_CTRL2_RUIE_MASK (0x10U)
#define ENC_CTRL2_RUIE_SHIFT (4U)
/*! RUIE - Roll-under Interrupt Enable
* 0b0..Disabled
* 0b1..Enabled
*/
#define ENC_CTRL2_RUIE(x) (((uint16_t)(((uint16_t)(x)) << ENC_CTRL2_RUIE_SHIFT)) & ENC_CTRL2_RUIE_MASK)
#define ENC_CTRL2_RUIRQ_MASK (0x20U)
#define ENC_CTRL2_RUIRQ_SHIFT (5U)
/*! RUIRQ - Roll-under Interrupt Request
* 0b0..No roll-under has occurred
* 0b1..Roll-under has occurred
*/
#define ENC_CTRL2_RUIRQ(x) (((uint16_t)(((uint16_t)(x)) << ENC_CTRL2_RUIRQ_SHIFT)) & ENC_CTRL2_RUIRQ_MASK)
#define ENC_CTRL2_ROIE_MASK (0x40U)
#define ENC_CTRL2_ROIE_SHIFT (6U)
/*! ROIE - Roll-over Interrupt Enable
* 0b0..Disabled
* 0b1..Enabled
*/
#define ENC_CTRL2_ROIE(x) (((uint16_t)(((uint16_t)(x)) << ENC_CTRL2_ROIE_SHIFT)) & ENC_CTRL2_ROIE_MASK)
#define ENC_CTRL2_ROIRQ_MASK (0x80U)
#define ENC_CTRL2_ROIRQ_SHIFT (7U)
/*! ROIRQ - Roll-over Interrupt Request
* 0b0..No roll-over has occurred
* 0b1..Roll-over has occurred
*/
#define ENC_CTRL2_ROIRQ(x) (((uint16_t)(((uint16_t)(x)) << ENC_CTRL2_ROIRQ_SHIFT)) & ENC_CTRL2_ROIRQ_MASK)
#define ENC_CTRL2_REVMOD_MASK (0x100U)
#define ENC_CTRL2_REVMOD_SHIFT (8U)
/*! REVMOD - Revolution Counter Modulus Enable
* 0b0..Use INDEX pulse to increment/decrement revolution counter (REV)
* 0b1..Use modulus counting roll-over/under to increment/decrement revolution counter (REV)
*/
#define ENC_CTRL2_REVMOD(x) (((uint16_t)(((uint16_t)(x)) << ENC_CTRL2_REVMOD_SHIFT)) & ENC_CTRL2_REVMOD_MASK)
#define ENC_CTRL2_OUTCTL_MASK (0x200U)
#define ENC_CTRL2_OUTCTL_SHIFT (9U)
/*! OUTCTL - Output Control
* 0b0..POSMATCH pulses when a match occurs between the position counters (POS) and the corresponding compare value (COMP )
* 0b1..POSMATCH pulses when the UPOS, LPOS, REV, or POSD registers are read
*/
#define ENC_CTRL2_OUTCTL(x) (((uint16_t)(((uint16_t)(x)) << ENC_CTRL2_OUTCTL_SHIFT)) & ENC_CTRL2_OUTCTL_MASK)
/*! @} */
/*! @name UMOD - Upper Modulus Register */
/*! @{ */
#define ENC_UMOD_MOD_MASK (0xFFFFU)
#define ENC_UMOD_MOD_SHIFT (0U)
/*! MOD - MOD */
#define ENC_UMOD_MOD(x) (((uint16_t)(((uint16_t)(x)) << ENC_UMOD_MOD_SHIFT)) & ENC_UMOD_MOD_MASK)
/*! @} */
/*! @name LMOD - Lower Modulus Register */
/*! @{ */
#define ENC_LMOD_MOD_MASK (0xFFFFU)
#define ENC_LMOD_MOD_SHIFT (0U)
/*! MOD - MOD */
#define ENC_LMOD_MOD(x) (((uint16_t)(((uint16_t)(x)) << ENC_LMOD_MOD_SHIFT)) & ENC_LMOD_MOD_MASK)
/*! @} */
/*! @name UCOMP - Upper Position Compare Register */
/*! @{ */
#define ENC_UCOMP_COMP_MASK (0xFFFFU)
#define ENC_UCOMP_COMP_SHIFT (0U)
/*! COMP - COMP */
#define ENC_UCOMP_COMP(x) (((uint16_t)(((uint16_t)(x)) << ENC_UCOMP_COMP_SHIFT)) & ENC_UCOMP_COMP_MASK)
/*! @} */
/*! @name LCOMP - Lower Position Compare Register */
/*! @{ */
#define ENC_LCOMP_COMP_MASK (0xFFFFU)
#define ENC_LCOMP_COMP_SHIFT (0U)
/*! COMP - COMP */
#define ENC_LCOMP_COMP(x) (((uint16_t)(((uint16_t)(x)) << ENC_LCOMP_COMP_SHIFT)) & ENC_LCOMP_COMP_MASK)
/*! @} */
/*!
* @}
*/ /* end of group ENC_Register_Masks */
/*!
* @}
*/ /* end of group ENC_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 */
#endif /* ENC_H_ */

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,266 @@
/*
** ###################################################################
** Processors: MIMXRT1061CVJ5A
** MIMXRT1061CVJ5B
** MIMXRT1061CVL5A
** MIMXRT1061CVL5B
** MIMXRT1061DVJ6A
** MIMXRT1061DVJ6B
** MIMXRT1061DVL6A
** MIMXRT1061DVL6B
** MIMXRT1061XVN5B
** MIMXRT1062CVJ5A
** MIMXRT1062CVJ5B
** MIMXRT1062CVL5A
** MIMXRT1062CVL5B
** MIMXRT1062DVJ6A
** MIMXRT1062DVJ6B
** MIMXRT1062DVL6A
** MIMXRT1062DVL6B
** MIMXRT1062DVN6B
** MIMXRT1062XVN5B
** MIMXRT106ADVL6A
** MIMXRT106CDVL6A
** MIMXRT106FDVL6A
** MIMXRT106LDVL6A
** MIMXRT106SDVL6A
**
** Version: rev. 1.4, 2022-03-25
** Build: b240705
**
** Abstract:
** CMSIS Peripheral Access Layer for EWM
**
** Copyright 1997-2016 Freescale Semiconductor, Inc.
** Copyright 2016-2024 NXP
** SPDX-License-Identifier: BSD-3-Clause
**
** http: www.nxp.com
** mail: support@nxp.com
**
** Revisions:
** - rev. 0.1 (2017-01-10)
** Initial version.
** - rev. 1.0 (2018-11-16)
** Update header files to align with IMXRT1060RM Rev.0.
** - rev. 1.1 (2018-11-27)
** Update header files to align with IMXRT1060RM Rev.1.
** - rev. 1.2 (2019-04-29)
** Add SET/CLR/TOG register group to register CTRL, STAT, CHANNELCTRL, CH0STAT, CH0OPTS, CH1STAT, CH1OPTS, CH2STAT, CH2OPTS, CH3STAT, CH3OPTS of DCP module.
** - rev. 1.3 (2021-08-10)
** Update header files to align with IMXRT1060RM Rev.3.
** - rev. 1.4 (2022-03-25)
** Add RT1060X device
**
** ###################################################################
*/
/*!
* @file EWM.h
* @version 1.4
* @date 2022-03-25
* @brief CMSIS Peripheral Access Layer for EWM
*
* CMSIS Peripheral Access Layer for EWM
*/
#if !defined(EWM_H_)
#define EWM_H_ /**< Symbol preventing repeated inclusion */
#if (defined(CPU_MIMXRT1061CVJ5A) || defined(CPU_MIMXRT1061CVJ5B) || defined(CPU_MIMXRT1061CVL5A) || defined(CPU_MIMXRT1061CVL5B) || defined(CPU_MIMXRT1061DVJ6A) || defined(CPU_MIMXRT1061DVJ6B) || defined(CPU_MIMXRT1061DVL6A) || defined(CPU_MIMXRT1061DVL6B) || defined(CPU_MIMXRT1061XVN5B))
#include "MIMXRT1061_COMMON.h"
#elif (defined(CPU_MIMXRT1062CVJ5A) || defined(CPU_MIMXRT1062CVJ5B) || defined(CPU_MIMXRT1062CVL5A) || defined(CPU_MIMXRT1062CVL5B) || defined(CPU_MIMXRT1062DVJ6A) || defined(CPU_MIMXRT1062DVJ6B) || defined(CPU_MIMXRT1062DVL6A) || defined(CPU_MIMXRT1062DVL6B) || defined(CPU_MIMXRT1062DVN6B) || defined(CPU_MIMXRT1062XVN5B))
#include "MIMXRT1062_COMMON.h"
#elif (defined(CPU_MIMXRT106ADVL6A))
#include "MIMXRT106A_COMMON.h"
#elif (defined(CPU_MIMXRT106CDVL6A))
#include "MIMXRT106C_COMMON.h"
#elif (defined(CPU_MIMXRT106FDVL6A))
#include "MIMXRT106F_COMMON.h"
#elif (defined(CPU_MIMXRT106LDVL6A))
#include "MIMXRT106L_COMMON.h"
#elif (defined(CPU_MIMXRT106SDVL6A))
#include "MIMXRT106S_COMMON.h"
#else
#error "No valid CPU defined!"
#endif
/* ----------------------------------------------------------------------------
-- 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
/* ----------------------------------------------------------------------------
-- 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 */
__IO uint8_t CLKCTRL; /**< Clock Control Register, offset: 0x4 */
__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)
/*! EWMEN - EWM enable.
* 0b0..EWM module is disabled.
* 0b1..EWM module is enabled.
*/
#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)
/*! ASSIN - EWM_in's Assertion State Select.
* 0b0..Default assert state of the EWM_in signal.
* 0b1..Inverts the assert state of EWM_in signal.
*/
#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)
/*! INEN - Input Enable.
* 0b0..EWM_in port is disabled.
* 0b1..EWM_in port is enabled.
*/
#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)
/*! INTEN - Interrupt Enable.
* 0b1..Generates an interrupt request, when EWM_OUT_b is asserted.
* 0b0..Deasserts the interrupt request.
*/
#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)
/*! SERVICE - SERVICE */
#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)
/*! COMPAREL - COMPAREL */
#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)
/*! COMPAREH - COMPAREH */
#define EWM_CMPH_COMPAREH(x) (((uint8_t)(((uint8_t)(x)) << EWM_CMPH_COMPAREH_SHIFT)) & EWM_CMPH_COMPAREH_MASK)
/*! @} */
/*! @name CLKCTRL - Clock Control Register */
/*! @{ */
#define EWM_CLKCTRL_CLKSEL_MASK (0x3U)
#define EWM_CLKCTRL_CLKSEL_SHIFT (0U)
/*! CLKSEL - CLKSEL */
#define EWM_CLKCTRL_CLKSEL(x) (((uint8_t)(((uint8_t)(x)) << EWM_CLKCTRL_CLKSEL_SHIFT)) & EWM_CLKCTRL_CLKSEL_MASK)
/*! @} */
/*! @name CLKPRESCALER - Clock Prescaler Register */
/*! @{ */
#define EWM_CLKPRESCALER_CLK_DIV_MASK (0xFFU)
#define EWM_CLKPRESCALER_CLK_DIV_SHIFT (0U)
/*! CLK_DIV - CLK_DIV */
#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 */
/*!
* @}
*/ /* end of group EWM_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 */
#endif /* EWM_H_ */

View File

@ -0,0 +1,713 @@
/*
** ###################################################################
** Processors: MIMXRT1061CVJ5A
** MIMXRT1061CVJ5B
** MIMXRT1061CVL5A
** MIMXRT1061CVL5B
** MIMXRT1061DVJ6A
** MIMXRT1061DVJ6B
** MIMXRT1061DVL6A
** MIMXRT1061DVL6B
** MIMXRT1061XVN5B
** MIMXRT1062CVJ5A
** MIMXRT1062CVJ5B
** MIMXRT1062CVL5A
** MIMXRT1062CVL5B
** MIMXRT1062DVJ6A
** MIMXRT1062DVJ6B
** MIMXRT1062DVL6A
** MIMXRT1062DVL6B
** MIMXRT1062DVN6B
** MIMXRT1062XVN5B
** MIMXRT106ADVL6A
** MIMXRT106CDVL6A
** MIMXRT106FDVL6A
** MIMXRT106LDVL6A
** MIMXRT106SDVL6A
**
** Version: rev. 1.4, 2022-03-25
** Build: b240705
**
** Abstract:
** CMSIS Peripheral Access Layer for FLEXIO
**
** Copyright 1997-2016 Freescale Semiconductor, Inc.
** Copyright 2016-2024 NXP
** SPDX-License-Identifier: BSD-3-Clause
**
** http: www.nxp.com
** mail: support@nxp.com
**
** Revisions:
** - rev. 0.1 (2017-01-10)
** Initial version.
** - rev. 1.0 (2018-11-16)
** Update header files to align with IMXRT1060RM Rev.0.
** - rev. 1.1 (2018-11-27)
** Update header files to align with IMXRT1060RM Rev.1.
** - rev. 1.2 (2019-04-29)
** Add SET/CLR/TOG register group to register CTRL, STAT, CHANNELCTRL, CH0STAT, CH0OPTS, CH1STAT, CH1OPTS, CH2STAT, CH2OPTS, CH3STAT, CH3OPTS of DCP module.
** - rev. 1.3 (2021-08-10)
** Update header files to align with IMXRT1060RM Rev.3.
** - rev. 1.4 (2022-03-25)
** Add RT1060X device
**
** ###################################################################
*/
/*!
* @file FLEXIO.h
* @version 1.4
* @date 2022-03-25
* @brief CMSIS Peripheral Access Layer for FLEXIO
*
* CMSIS Peripheral Access Layer for FLEXIO
*/
#if !defined(FLEXIO_H_)
#define FLEXIO_H_ /**< Symbol preventing repeated inclusion */
#if (defined(CPU_MIMXRT1061CVJ5A) || defined(CPU_MIMXRT1061CVJ5B) || defined(CPU_MIMXRT1061CVL5A) || defined(CPU_MIMXRT1061CVL5B) || defined(CPU_MIMXRT1061DVJ6A) || defined(CPU_MIMXRT1061DVJ6B) || defined(CPU_MIMXRT1061DVL6A) || defined(CPU_MIMXRT1061DVL6B) || defined(CPU_MIMXRT1061XVN5B))
#include "MIMXRT1061_COMMON.h"
#elif (defined(CPU_MIMXRT1062CVJ5A) || defined(CPU_MIMXRT1062CVJ5B) || defined(CPU_MIMXRT1062CVL5A) || defined(CPU_MIMXRT1062CVL5B) || defined(CPU_MIMXRT1062DVJ6A) || defined(CPU_MIMXRT1062DVJ6B) || defined(CPU_MIMXRT1062DVL6A) || defined(CPU_MIMXRT1062DVL6B) || defined(CPU_MIMXRT1062DVN6B) || defined(CPU_MIMXRT1062XVN5B))
#include "MIMXRT1062_COMMON.h"
#elif (defined(CPU_MIMXRT106ADVL6A))
#include "MIMXRT106A_COMMON.h"
#elif (defined(CPU_MIMXRT106CDVL6A))
#include "MIMXRT106C_COMMON.h"
#elif (defined(CPU_MIMXRT106FDVL6A))
#include "MIMXRT106F_COMMON.h"
#elif (defined(CPU_MIMXRT106LDVL6A))
#include "MIMXRT106L_COMMON.h"
#elif (defined(CPU_MIMXRT106SDVL6A))
#include "MIMXRT106S_COMMON.h"
#else
#error "No valid CPU defined!"
#endif
/* ----------------------------------------------------------------------------
-- 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
/* ----------------------------------------------------------------------------
-- FLEXIO Peripheral Access Layer
---------------------------------------------------------------------------- */
/*!
* @addtogroup FLEXIO_Peripheral_Access_Layer FLEXIO Peripheral Access Layer
* @{
*/
/** FLEXIO - Size of Registers Arrays */
#define FLEXIO_SHIFTCTL_COUNT 8u
#define FLEXIO_SHIFTCFG_COUNT 8u
#define FLEXIO_SHIFTBUF_COUNT 8u
#define FLEXIO_SHIFTBUFBIS_COUNT 8u
#define FLEXIO_SHIFTBUFBYS_COUNT 8u
#define FLEXIO_SHIFTBUFBBS_COUNT 8u
#define FLEXIO_TIMCTL_COUNT 8u
#define FLEXIO_TIMCFG_COUNT 8u
#define FLEXIO_TIMCMP_COUNT 8u
#define FLEXIO_SHIFTBUFNBS_COUNT 8u
#define FLEXIO_SHIFTBUFHWS_COUNT 8u
#define FLEXIO_SHIFTBUFNIS_COUNT 8u
/** FLEXIO - Register Layout Typedef */
typedef struct {
__I uint32_t VERID; /**< Version ID Register, offset: 0x0 */
__I uint32_t PARAM; /**< Parameter Register, offset: 0x4 */
__IO uint32_t CTRL; /**< FlexIO Control Register, offset: 0x8 */
__I uint32_t PIN; /**< Pin State Register, offset: 0xC */
__IO uint32_t SHIFTSTAT; /**< Shifter Status Register, offset: 0x10 */
__IO uint32_t SHIFTERR; /**< Shifter Error Register, offset: 0x14 */
__IO uint32_t TIMSTAT; /**< Timer Status Register, offset: 0x18 */
uint8_t RESERVED_0[4];
__IO uint32_t SHIFTSIEN; /**< Shifter Status Interrupt Enable, offset: 0x20 */
__IO uint32_t SHIFTEIEN; /**< Shifter Error Interrupt Enable, offset: 0x24 */
__IO uint32_t TIMIEN; /**< Timer Interrupt Enable Register, offset: 0x28 */
uint8_t RESERVED_1[4];
__IO uint32_t SHIFTSDEN; /**< Shifter Status DMA Enable, offset: 0x30 */
uint8_t RESERVED_2[12];
__IO uint32_t SHIFTSTATE; /**< Shifter State Register, offset: 0x40 */
uint8_t RESERVED_3[60];
__IO uint32_t SHIFTCTL[FLEXIO_SHIFTCTL_COUNT]; /**< Shifter Control N Register, array offset: 0x80, array step: 0x4 */
uint8_t RESERVED_4[96];
__IO uint32_t SHIFTCFG[FLEXIO_SHIFTCFG_COUNT]; /**< Shifter Configuration N Register, array offset: 0x100, array step: 0x4 */
uint8_t RESERVED_5[224];
__IO uint32_t SHIFTBUF[FLEXIO_SHIFTBUF_COUNT]; /**< Shifter Buffer N Register, array offset: 0x200, array step: 0x4 */
uint8_t RESERVED_6[96];
__IO uint32_t SHIFTBUFBIS[FLEXIO_SHIFTBUFBIS_COUNT]; /**< Shifter Buffer N Bit Swapped Register, array offset: 0x280, array step: 0x4 */
uint8_t RESERVED_7[96];
__IO uint32_t SHIFTBUFBYS[FLEXIO_SHIFTBUFBYS_COUNT]; /**< Shifter Buffer N Byte Swapped Register, array offset: 0x300, array step: 0x4 */
uint8_t RESERVED_8[96];
__IO uint32_t SHIFTBUFBBS[FLEXIO_SHIFTBUFBBS_COUNT]; /**< Shifter Buffer N Bit Byte Swapped Register, array offset: 0x380, array step: 0x4 */
uint8_t RESERVED_9[96];
__IO uint32_t TIMCTL[FLEXIO_TIMCTL_COUNT]; /**< Timer Control N Register, array offset: 0x400, array step: 0x4 */
uint8_t RESERVED_10[96];
__IO uint32_t TIMCFG[FLEXIO_TIMCFG_COUNT]; /**< Timer Configuration N Register, array offset: 0x480, array step: 0x4 */
uint8_t RESERVED_11[96];
__IO uint32_t TIMCMP[FLEXIO_TIMCMP_COUNT]; /**< Timer Compare N Register, array offset: 0x500, array step: 0x4 */
uint8_t RESERVED_12[352];
__IO uint32_t SHIFTBUFNBS[FLEXIO_SHIFTBUFNBS_COUNT]; /**< Shifter Buffer N Nibble Byte Swapped Register, array offset: 0x680, array step: 0x4 */
uint8_t RESERVED_13[96];
__IO uint32_t SHIFTBUFHWS[FLEXIO_SHIFTBUFHWS_COUNT]; /**< Shifter Buffer N Half Word Swapped Register, array offset: 0x700, array step: 0x4 */
uint8_t RESERVED_14[96];
__IO uint32_t SHIFTBUFNIS[FLEXIO_SHIFTBUFNIS_COUNT]; /**< Shifter Buffer N Nibble Swapped Register, array offset: 0x780, array step: 0x4 */
} FLEXIO_Type;
/* ----------------------------------------------------------------------------
-- FLEXIO Register Masks
---------------------------------------------------------------------------- */
/*!
* @addtogroup FLEXIO_Register_Masks FLEXIO Register Masks
* @{
*/
/*! @name VERID - Version ID Register */
/*! @{ */
#define FLEXIO_VERID_FEATURE_MASK (0xFFFFU)
#define FLEXIO_VERID_FEATURE_SHIFT (0U)
/*! FEATURE - Feature Specification Number
* 0b0000000000000000..Standard features implemented.
* 0b0000000000000001..Supports state, logic and parallel modes.
*/
#define FLEXIO_VERID_FEATURE(x) (((uint32_t)(((uint32_t)(x)) << FLEXIO_VERID_FEATURE_SHIFT)) & FLEXIO_VERID_FEATURE_MASK)
#define FLEXIO_VERID_MINOR_MASK (0xFF0000U)
#define FLEXIO_VERID_MINOR_SHIFT (16U)
/*! MINOR - Minor Version Number */
#define FLEXIO_VERID_MINOR(x) (((uint32_t)(((uint32_t)(x)) << FLEXIO_VERID_MINOR_SHIFT)) & FLEXIO_VERID_MINOR_MASK)
#define FLEXIO_VERID_MAJOR_MASK (0xFF000000U)
#define FLEXIO_VERID_MAJOR_SHIFT (24U)
/*! MAJOR - Major Version Number */
#define FLEXIO_VERID_MAJOR(x) (((uint32_t)(((uint32_t)(x)) << FLEXIO_VERID_MAJOR_SHIFT)) & FLEXIO_VERID_MAJOR_MASK)
/*! @} */
/*! @name PARAM - Parameter Register */
/*! @{ */
#define FLEXIO_PARAM_SHIFTER_MASK (0xFFU)
#define FLEXIO_PARAM_SHIFTER_SHIFT (0U)
/*! SHIFTER - Shifter Number */
#define FLEXIO_PARAM_SHIFTER(x) (((uint32_t)(((uint32_t)(x)) << FLEXIO_PARAM_SHIFTER_SHIFT)) & FLEXIO_PARAM_SHIFTER_MASK)
#define FLEXIO_PARAM_TIMER_MASK (0xFF00U)
#define FLEXIO_PARAM_TIMER_SHIFT (8U)
/*! TIMER - Timer Number */
#define FLEXIO_PARAM_TIMER(x) (((uint32_t)(((uint32_t)(x)) << FLEXIO_PARAM_TIMER_SHIFT)) & FLEXIO_PARAM_TIMER_MASK)
#define FLEXIO_PARAM_PIN_MASK (0xFF0000U)
#define FLEXIO_PARAM_PIN_SHIFT (16U)
/*! PIN - Pin Number */
#define FLEXIO_PARAM_PIN(x) (((uint32_t)(((uint32_t)(x)) << FLEXIO_PARAM_PIN_SHIFT)) & FLEXIO_PARAM_PIN_MASK)
#define FLEXIO_PARAM_TRIGGER_MASK (0xFF000000U)
#define FLEXIO_PARAM_TRIGGER_SHIFT (24U)
/*! TRIGGER - Trigger Number */
#define FLEXIO_PARAM_TRIGGER(x) (((uint32_t)(((uint32_t)(x)) << FLEXIO_PARAM_TRIGGER_SHIFT)) & FLEXIO_PARAM_TRIGGER_MASK)
/*! @} */
/*! @name CTRL - FlexIO Control Register */
/*! @{ */
#define FLEXIO_CTRL_FLEXEN_MASK (0x1U)
#define FLEXIO_CTRL_FLEXEN_SHIFT (0U)
/*! FLEXEN - FlexIO Enable
* 0b0..FlexIO module is disabled.
* 0b1..FlexIO module is enabled.
*/
#define FLEXIO_CTRL_FLEXEN(x) (((uint32_t)(((uint32_t)(x)) << FLEXIO_CTRL_FLEXEN_SHIFT)) & FLEXIO_CTRL_FLEXEN_MASK)
#define FLEXIO_CTRL_SWRST_MASK (0x2U)
#define FLEXIO_CTRL_SWRST_SHIFT (1U)
/*! SWRST - Software Reset
* 0b0..Software reset is disabled
* 0b1..Software reset is enabled, all FlexIO registers except the Control Register are reset.
*/
#define FLEXIO_CTRL_SWRST(x) (((uint32_t)(((uint32_t)(x)) << FLEXIO_CTRL_SWRST_SHIFT)) & FLEXIO_CTRL_SWRST_MASK)
#define FLEXIO_CTRL_FASTACC_MASK (0x4U)
#define FLEXIO_CTRL_FASTACC_SHIFT (2U)
/*! FASTACC - Fast Access
* 0b0..Configures for normal register accesses to FlexIO
* 0b1..Configures for fast register accesses to FlexIO
*/
#define FLEXIO_CTRL_FASTACC(x) (((uint32_t)(((uint32_t)(x)) << FLEXIO_CTRL_FASTACC_SHIFT)) & FLEXIO_CTRL_FASTACC_MASK)
#define FLEXIO_CTRL_DBGE_MASK (0x40000000U)
#define FLEXIO_CTRL_DBGE_SHIFT (30U)
/*! DBGE - Debug Enable
* 0b0..FlexIO is disabled in debug modes.
* 0b1..FlexIO is enabled in debug modes
*/
#define FLEXIO_CTRL_DBGE(x) (((uint32_t)(((uint32_t)(x)) << FLEXIO_CTRL_DBGE_SHIFT)) & FLEXIO_CTRL_DBGE_MASK)
#define FLEXIO_CTRL_DOZEN_MASK (0x80000000U)
#define FLEXIO_CTRL_DOZEN_SHIFT (31U)
/*! DOZEN - Doze Enable
* 0b0..FlexIO enabled in Doze modes.
* 0b1..FlexIO disabled in Doze modes.
*/
#define FLEXIO_CTRL_DOZEN(x) (((uint32_t)(((uint32_t)(x)) << FLEXIO_CTRL_DOZEN_SHIFT)) & FLEXIO_CTRL_DOZEN_MASK)
/*! @} */
/*! @name PIN - Pin State Register */
/*! @{ */
#define FLEXIO_PIN_PDI_MASK (0xFFFFFFFFU) /* Merged from fields with different position or width, of widths (16, 32), largest definition used */
#define FLEXIO_PIN_PDI_SHIFT (0U)
/*! PDI - Pin Data Input */
#define FLEXIO_PIN_PDI(x) (((uint32_t)(((uint32_t)(x)) << FLEXIO_PIN_PDI_SHIFT)) & FLEXIO_PIN_PDI_MASK) /* Merged from fields with different position or width, of widths (16, 32), largest definition used */
/*! @} */
/*! @name SHIFTSTAT - Shifter Status Register */
/*! @{ */
#define FLEXIO_SHIFTSTAT_SSF_MASK (0xFFU)
#define FLEXIO_SHIFTSTAT_SSF_SHIFT (0U)
/*! SSF - Shifter Status Flag */
#define FLEXIO_SHIFTSTAT_SSF(x) (((uint32_t)(((uint32_t)(x)) << FLEXIO_SHIFTSTAT_SSF_SHIFT)) & FLEXIO_SHIFTSTAT_SSF_MASK)
/*! @} */
/*! @name SHIFTERR - Shifter Error Register */
/*! @{ */
#define FLEXIO_SHIFTERR_SEF_MASK (0xFFU)
#define FLEXIO_SHIFTERR_SEF_SHIFT (0U)
/*! SEF - Shifter Error Flags */
#define FLEXIO_SHIFTERR_SEF(x) (((uint32_t)(((uint32_t)(x)) << FLEXIO_SHIFTERR_SEF_SHIFT)) & FLEXIO_SHIFTERR_SEF_MASK)
/*! @} */
/*! @name TIMSTAT - Timer Status Register */
/*! @{ */
#define FLEXIO_TIMSTAT_TSF_MASK (0xFFU)
#define FLEXIO_TIMSTAT_TSF_SHIFT (0U)
/*! TSF - Timer Status Flags */
#define FLEXIO_TIMSTAT_TSF(x) (((uint32_t)(((uint32_t)(x)) << FLEXIO_TIMSTAT_TSF_SHIFT)) & FLEXIO_TIMSTAT_TSF_MASK)
/*! @} */
/*! @name SHIFTSIEN - Shifter Status Interrupt Enable */
/*! @{ */
#define FLEXIO_SHIFTSIEN_SSIE_MASK (0xFFU)
#define FLEXIO_SHIFTSIEN_SSIE_SHIFT (0U)
/*! SSIE - Shifter Status Interrupt Enable */
#define FLEXIO_SHIFTSIEN_SSIE(x) (((uint32_t)(((uint32_t)(x)) << FLEXIO_SHIFTSIEN_SSIE_SHIFT)) & FLEXIO_SHIFTSIEN_SSIE_MASK)
/*! @} */
/*! @name SHIFTEIEN - Shifter Error Interrupt Enable */
/*! @{ */
#define FLEXIO_SHIFTEIEN_SEIE_MASK (0xFFU)
#define FLEXIO_SHIFTEIEN_SEIE_SHIFT (0U)
/*! SEIE - Shifter Error Interrupt Enable */
#define FLEXIO_SHIFTEIEN_SEIE(x) (((uint32_t)(((uint32_t)(x)) << FLEXIO_SHIFTEIEN_SEIE_SHIFT)) & FLEXIO_SHIFTEIEN_SEIE_MASK)
/*! @} */
/*! @name TIMIEN - Timer Interrupt Enable Register */
/*! @{ */
#define FLEXIO_TIMIEN_TEIE_MASK (0xFFU)
#define FLEXIO_TIMIEN_TEIE_SHIFT (0U)
/*! TEIE - Timer Status Interrupt Enable */
#define FLEXIO_TIMIEN_TEIE(x) (((uint32_t)(((uint32_t)(x)) << FLEXIO_TIMIEN_TEIE_SHIFT)) & FLEXIO_TIMIEN_TEIE_MASK)
/*! @} */
/*! @name SHIFTSDEN - Shifter Status DMA Enable */
/*! @{ */
#define FLEXIO_SHIFTSDEN_SSDE_MASK (0xFFU)
#define FLEXIO_SHIFTSDEN_SSDE_SHIFT (0U)
/*! SSDE - Shifter Status DMA Enable */
#define FLEXIO_SHIFTSDEN_SSDE(x) (((uint32_t)(((uint32_t)(x)) << FLEXIO_SHIFTSDEN_SSDE_SHIFT)) & FLEXIO_SHIFTSDEN_SSDE_MASK)
/*! @} */
/*! @name SHIFTSTATE - Shifter State Register */
/*! @{ */
#define FLEXIO_SHIFTSTATE_STATE_MASK (0x7U)
#define FLEXIO_SHIFTSTATE_STATE_SHIFT (0U)
/*! STATE - Current State Pointer */
#define FLEXIO_SHIFTSTATE_STATE(x) (((uint32_t)(((uint32_t)(x)) << FLEXIO_SHIFTSTATE_STATE_SHIFT)) & FLEXIO_SHIFTSTATE_STATE_MASK)
/*! @} */
/*! @name SHIFTCTL - Shifter Control N Register */
/*! @{ */
#define FLEXIO_SHIFTCTL_SMOD_MASK (0x7U)
#define FLEXIO_SHIFTCTL_SMOD_SHIFT (0U)
/*! SMOD - Shifter Mode
* 0b000..Disabled.
* 0b001..Receive mode. Captures the current Shifter content into the SHIFTBUF on expiration of the Timer.
* 0b010..Transmit mode. Load SHIFTBUF contents into the Shifter on expiration of the Timer.
* 0b011..Reserved.
* 0b100..Match Store mode. Shifter data is compared to SHIFTBUF content on expiration of the Timer.
* 0b101..Match Continuous mode. Shifter data is continuously compared to SHIFTBUF contents.
* 0b110..State mode. SHIFTBUF contents are used for storing programmable state attributes.
* 0b111..Logic mode. SHIFTBUF contents are used for implementing programmable logic look up table.
*/
#define FLEXIO_SHIFTCTL_SMOD(x) (((uint32_t)(((uint32_t)(x)) << FLEXIO_SHIFTCTL_SMOD_SHIFT)) & FLEXIO_SHIFTCTL_SMOD_MASK)
#define FLEXIO_SHIFTCTL_PINPOL_MASK (0x80U)
#define FLEXIO_SHIFTCTL_PINPOL_SHIFT (7U)
/*! PINPOL - Shifter Pin Polarity
* 0b0..Pin is active high
* 0b1..Pin is active low
*/
#define FLEXIO_SHIFTCTL_PINPOL(x) (((uint32_t)(((uint32_t)(x)) << FLEXIO_SHIFTCTL_PINPOL_SHIFT)) & FLEXIO_SHIFTCTL_PINPOL_MASK)
#define FLEXIO_SHIFTCTL_PINSEL_MASK (0x1F00U) /* Merged from fields with different position or width, of widths (4, 5), largest definition used */
#define FLEXIO_SHIFTCTL_PINSEL_SHIFT (8U)
/*! PINSEL - Shifter Pin Select */
#define FLEXIO_SHIFTCTL_PINSEL(x) (((uint32_t)(((uint32_t)(x)) << FLEXIO_SHIFTCTL_PINSEL_SHIFT)) & FLEXIO_SHIFTCTL_PINSEL_MASK) /* Merged from fields with different position or width, of widths (4, 5), largest definition used */
#define FLEXIO_SHIFTCTL_PINCFG_MASK (0x30000U)
#define FLEXIO_SHIFTCTL_PINCFG_SHIFT (16U)
/*! PINCFG - Shifter Pin Configuration
* 0b00..Shifter pin output disabled
* 0b01..Shifter pin open drain or bidirectional output enable
* 0b10..Shifter pin bidirectional output data
* 0b11..Shifter pin output
*/
#define FLEXIO_SHIFTCTL_PINCFG(x) (((uint32_t)(((uint32_t)(x)) << FLEXIO_SHIFTCTL_PINCFG_SHIFT)) & FLEXIO_SHIFTCTL_PINCFG_MASK)
#define FLEXIO_SHIFTCTL_TIMPOL_MASK (0x800000U)
#define FLEXIO_SHIFTCTL_TIMPOL_SHIFT (23U)
/*! TIMPOL - Timer Polarity
* 0b0..Shift on posedge of Shift clock
* 0b1..Shift on negedge of Shift clock
*/
#define FLEXIO_SHIFTCTL_TIMPOL(x) (((uint32_t)(((uint32_t)(x)) << FLEXIO_SHIFTCTL_TIMPOL_SHIFT)) & FLEXIO_SHIFTCTL_TIMPOL_MASK)
#define FLEXIO_SHIFTCTL_TIMSEL_MASK (0x7000000U)
#define FLEXIO_SHIFTCTL_TIMSEL_SHIFT (24U)
/*! TIMSEL - Timer Select */
#define FLEXIO_SHIFTCTL_TIMSEL(x) (((uint32_t)(((uint32_t)(x)) << FLEXIO_SHIFTCTL_TIMSEL_SHIFT)) & FLEXIO_SHIFTCTL_TIMSEL_MASK)
/*! @} */
/*! @name SHIFTCFG - Shifter Configuration N Register */
/*! @{ */
#define FLEXIO_SHIFTCFG_SSTART_MASK (0x3U)
#define FLEXIO_SHIFTCFG_SSTART_SHIFT (0U)
/*! SSTART - Shifter Start bit
* 0b00..Start bit disabled for transmitter/receiver/match store, transmitter loads data on enable
* 0b01..Start bit disabled for transmitter/receiver/match store, transmitter loads data on first shift
* 0b10..Transmitter outputs start bit value 0 before loading data on first shift, receiver/match store sets error flag if start bit is not 0
* 0b11..Transmitter outputs start bit value 1 before loading data on first shift, receiver/match store sets error flag if start bit is not 1
*/
#define FLEXIO_SHIFTCFG_SSTART(x) (((uint32_t)(((uint32_t)(x)) << FLEXIO_SHIFTCFG_SSTART_SHIFT)) & FLEXIO_SHIFTCFG_SSTART_MASK)
#define FLEXIO_SHIFTCFG_SSTOP_MASK (0x30U)
#define FLEXIO_SHIFTCFG_SSTOP_SHIFT (4U)
/*! SSTOP - Shifter Stop bit
* 0b00..Stop bit disabled for transmitter/receiver/match store
* 0b01..Stop bit disabled for transmitter/receiver/match store, receiver/match store will store receive data on
* the configured shift edge when timer in stop condition
* 0b10..Transmitter outputs stop bit value 0 on store, receiver/match store sets error flag if stop bit is not
* 0, receiver/match store will also store receive data on the configured shift edge when timer in stop
* condition
* 0b11..Transmitter outputs stop bit value 1 on store, receiver/match store sets error flag if stop bit is not
* 1, receiver/match store will also store receive data on the configured shift edge when timer in stop
* condition
*/
#define FLEXIO_SHIFTCFG_SSTOP(x) (((uint32_t)(((uint32_t)(x)) << FLEXIO_SHIFTCFG_SSTOP_SHIFT)) & FLEXIO_SHIFTCFG_SSTOP_MASK)
#define FLEXIO_SHIFTCFG_INSRC_MASK (0x100U)
#define FLEXIO_SHIFTCFG_INSRC_SHIFT (8U)
/*! INSRC - Input Source
* 0b0..Pin
* 0b1..Shifter N+1 Output
*/
#define FLEXIO_SHIFTCFG_INSRC(x) (((uint32_t)(((uint32_t)(x)) << FLEXIO_SHIFTCFG_INSRC_SHIFT)) & FLEXIO_SHIFTCFG_INSRC_MASK)
#define FLEXIO_SHIFTCFG_PWIDTH_MASK (0x1F0000U) /* Merged from fields with different position or width, of widths (4, 5), largest definition used */
#define FLEXIO_SHIFTCFG_PWIDTH_SHIFT (16U)
/*! PWIDTH - Parallel Width */
#define FLEXIO_SHIFTCFG_PWIDTH(x) (((uint32_t)(((uint32_t)(x)) << FLEXIO_SHIFTCFG_PWIDTH_SHIFT)) & FLEXIO_SHIFTCFG_PWIDTH_MASK) /* Merged from fields with different position or width, of widths (4, 5), largest definition used */
/*! @} */
/*! @name SHIFTBUF - Shifter Buffer N Register */
/*! @{ */
#define FLEXIO_SHIFTBUF_SHIFTBUF_MASK (0xFFFFFFFFU)
#define FLEXIO_SHIFTBUF_SHIFTBUF_SHIFT (0U)
/*! SHIFTBUF - Shift Buffer */
#define FLEXIO_SHIFTBUF_SHIFTBUF(x) (((uint32_t)(((uint32_t)(x)) << FLEXIO_SHIFTBUF_SHIFTBUF_SHIFT)) & FLEXIO_SHIFTBUF_SHIFTBUF_MASK)
/*! @} */
/*! @name SHIFTBUFBIS - Shifter Buffer N Bit Swapped Register */
/*! @{ */
#define FLEXIO_SHIFTBUFBIS_SHIFTBUFBIS_MASK (0xFFFFFFFFU)
#define FLEXIO_SHIFTBUFBIS_SHIFTBUFBIS_SHIFT (0U)
/*! SHIFTBUFBIS - Shift Buffer */
#define FLEXIO_SHIFTBUFBIS_SHIFTBUFBIS(x) (((uint32_t)(((uint32_t)(x)) << FLEXIO_SHIFTBUFBIS_SHIFTBUFBIS_SHIFT)) & FLEXIO_SHIFTBUFBIS_SHIFTBUFBIS_MASK)
/*! @} */
/*! @name SHIFTBUFBYS - Shifter Buffer N Byte Swapped Register */
/*! @{ */
#define FLEXIO_SHIFTBUFBYS_SHIFTBUFBYS_MASK (0xFFFFFFFFU)
#define FLEXIO_SHIFTBUFBYS_SHIFTBUFBYS_SHIFT (0U)
/*! SHIFTBUFBYS - Shift Buffer */
#define FLEXIO_SHIFTBUFBYS_SHIFTBUFBYS(x) (((uint32_t)(((uint32_t)(x)) << FLEXIO_SHIFTBUFBYS_SHIFTBUFBYS_SHIFT)) & FLEXIO_SHIFTBUFBYS_SHIFTBUFBYS_MASK)
/*! @} */
/*! @name SHIFTBUFBBS - Shifter Buffer N Bit Byte Swapped Register */
/*! @{ */
#define FLEXIO_SHIFTBUFBBS_SHIFTBUFBBS_MASK (0xFFFFFFFFU)
#define FLEXIO_SHIFTBUFBBS_SHIFTBUFBBS_SHIFT (0U)
/*! SHIFTBUFBBS - Shift Buffer */
#define FLEXIO_SHIFTBUFBBS_SHIFTBUFBBS(x) (((uint32_t)(((uint32_t)(x)) << FLEXIO_SHIFTBUFBBS_SHIFTBUFBBS_SHIFT)) & FLEXIO_SHIFTBUFBBS_SHIFTBUFBBS_MASK)
/*! @} */
/*! @name TIMCTL - Timer Control N Register */
/*! @{ */
#define FLEXIO_TIMCTL_TIMOD_MASK (0x3U)
#define FLEXIO_TIMCTL_TIMOD_SHIFT (0U)
/*! TIMOD - Timer Mode
* 0b00..Timer Disabled.
* 0b01..Dual 8-bit counters baud mode.
* 0b10..Dual 8-bit counters PWM high mode.
* 0b11..Single 16-bit counter mode.
*/
#define FLEXIO_TIMCTL_TIMOD(x) (((uint32_t)(((uint32_t)(x)) << FLEXIO_TIMCTL_TIMOD_SHIFT)) & FLEXIO_TIMCTL_TIMOD_MASK)
#define FLEXIO_TIMCTL_PINPOL_MASK (0x80U)
#define FLEXIO_TIMCTL_PINPOL_SHIFT (7U)
/*! PINPOL - Timer Pin Polarity
* 0b0..Pin is active high
* 0b1..Pin is active low
*/
#define FLEXIO_TIMCTL_PINPOL(x) (((uint32_t)(((uint32_t)(x)) << FLEXIO_TIMCTL_PINPOL_SHIFT)) & FLEXIO_TIMCTL_PINPOL_MASK)
#define FLEXIO_TIMCTL_PINSEL_MASK (0x1F00U) /* Merged from fields with different position or width, of widths (4, 5), largest definition used */
#define FLEXIO_TIMCTL_PINSEL_SHIFT (8U)
/*! PINSEL - Timer Pin Select */
#define FLEXIO_TIMCTL_PINSEL(x) (((uint32_t)(((uint32_t)(x)) << FLEXIO_TIMCTL_PINSEL_SHIFT)) & FLEXIO_TIMCTL_PINSEL_MASK) /* Merged from fields with different position or width, of widths (4, 5), largest definition used */
#define FLEXIO_TIMCTL_PINCFG_MASK (0x30000U)
#define FLEXIO_TIMCTL_PINCFG_SHIFT (16U)
/*! PINCFG - Timer Pin Configuration
* 0b00..Timer pin output disabled
* 0b01..Timer pin open drain or bidirectional output enable
* 0b10..Timer pin bidirectional output data
* 0b11..Timer pin output
*/
#define FLEXIO_TIMCTL_PINCFG(x) (((uint32_t)(((uint32_t)(x)) << FLEXIO_TIMCTL_PINCFG_SHIFT)) & FLEXIO_TIMCTL_PINCFG_MASK)
#define FLEXIO_TIMCTL_TRGSRC_MASK (0x400000U)
#define FLEXIO_TIMCTL_TRGSRC_SHIFT (22U)
/*! TRGSRC - Trigger Source
* 0b0..External trigger selected
* 0b1..Internal trigger selected
*/
#define FLEXIO_TIMCTL_TRGSRC(x) (((uint32_t)(((uint32_t)(x)) << FLEXIO_TIMCTL_TRGSRC_SHIFT)) & FLEXIO_TIMCTL_TRGSRC_MASK)
#define FLEXIO_TIMCTL_TRGPOL_MASK (0x800000U)
#define FLEXIO_TIMCTL_TRGPOL_SHIFT (23U)
/*! TRGPOL - Trigger Polarity
* 0b0..Trigger active high
* 0b1..Trigger active low
*/
#define FLEXIO_TIMCTL_TRGPOL(x) (((uint32_t)(((uint32_t)(x)) << FLEXIO_TIMCTL_TRGPOL_SHIFT)) & FLEXIO_TIMCTL_TRGPOL_MASK)
#define FLEXIO_TIMCTL_TRGSEL_MASK (0x3F000000U) /* Merged from fields with different position or width, of widths (5, 6), largest definition used */
#define FLEXIO_TIMCTL_TRGSEL_SHIFT (24U)
/*! TRGSEL - Trigger Select */
#define FLEXIO_TIMCTL_TRGSEL(x) (((uint32_t)(((uint32_t)(x)) << FLEXIO_TIMCTL_TRGSEL_SHIFT)) & FLEXIO_TIMCTL_TRGSEL_MASK) /* Merged from fields with different position or width, of widths (5, 6), largest definition used */
/*! @} */
/*! @name TIMCFG - Timer Configuration N Register */
/*! @{ */
#define FLEXIO_TIMCFG_TSTART_MASK (0x2U)
#define FLEXIO_TIMCFG_TSTART_SHIFT (1U)
/*! TSTART - Timer Start Bit
* 0b0..Start bit disabled
* 0b1..Start bit enabled
*/
#define FLEXIO_TIMCFG_TSTART(x) (((uint32_t)(((uint32_t)(x)) << FLEXIO_TIMCFG_TSTART_SHIFT)) & FLEXIO_TIMCFG_TSTART_MASK)
#define FLEXIO_TIMCFG_TSTOP_MASK (0x30U)
#define FLEXIO_TIMCFG_TSTOP_SHIFT (4U)
/*! TSTOP - Timer Stop Bit
* 0b00..Stop bit disabled
* 0b01..Stop bit is enabled on timer compare
* 0b10..Stop bit is enabled on timer disable
* 0b11..Stop bit is enabled on timer compare and timer disable
*/
#define FLEXIO_TIMCFG_TSTOP(x) (((uint32_t)(((uint32_t)(x)) << FLEXIO_TIMCFG_TSTOP_SHIFT)) & FLEXIO_TIMCFG_TSTOP_MASK)
#define FLEXIO_TIMCFG_TIMENA_MASK (0x700U)
#define FLEXIO_TIMCFG_TIMENA_SHIFT (8U)
/*! TIMENA - Timer Enable
* 0b000..Timer always enabled
* 0b001..Timer enabled on Timer N-1 enable
* 0b010..Timer enabled on Trigger high
* 0b011..Timer enabled on Trigger high and Pin high
* 0b100..Timer enabled on Pin rising edge
* 0b101..Timer enabled on Pin rising edge and Trigger high
* 0b110..Timer enabled on Trigger rising edge
* 0b111..Timer enabled on Trigger rising or falling edge
*/
#define FLEXIO_TIMCFG_TIMENA(x) (((uint32_t)(((uint32_t)(x)) << FLEXIO_TIMCFG_TIMENA_SHIFT)) & FLEXIO_TIMCFG_TIMENA_MASK)
#define FLEXIO_TIMCFG_TIMDIS_MASK (0x7000U)
#define FLEXIO_TIMCFG_TIMDIS_SHIFT (12U)
/*! TIMDIS - Timer Disable
* 0b000..Timer never disabled
* 0b001..Timer disabled on Timer N-1 disable
* 0b010..Timer disabled on Timer compare (upper 8-bits match and decrement)
* 0b011..Timer disabled on Timer compare (upper 8-bits match and decrement) and Trigger Low
* 0b100..Timer disabled on Pin rising or falling edge
* 0b101..Timer disabled on Pin rising or falling edge provided Trigger is high
* 0b110..Timer disabled on Trigger falling edge
* 0b111..Reserved
*/
#define FLEXIO_TIMCFG_TIMDIS(x) (((uint32_t)(((uint32_t)(x)) << FLEXIO_TIMCFG_TIMDIS_SHIFT)) & FLEXIO_TIMCFG_TIMDIS_MASK)
#define FLEXIO_TIMCFG_TIMRST_MASK (0x70000U)
#define FLEXIO_TIMCFG_TIMRST_SHIFT (16U)
/*! TIMRST - Timer Reset
* 0b000..Timer never reset
* 0b001..Reserved
* 0b010..Timer reset on Timer Pin equal to Timer Output
* 0b011..Timer reset on Timer Trigger equal to Timer Output
* 0b100..Timer reset on Timer Pin rising edge
* 0b101..Reserved
* 0b110..Timer reset on Trigger rising edge
* 0b111..Timer reset on Trigger rising or falling edge
*/
#define FLEXIO_TIMCFG_TIMRST(x) (((uint32_t)(((uint32_t)(x)) << FLEXIO_TIMCFG_TIMRST_SHIFT)) & FLEXIO_TIMCFG_TIMRST_MASK)
#define FLEXIO_TIMCFG_TIMDEC_MASK (0x300000U)
#define FLEXIO_TIMCFG_TIMDEC_SHIFT (20U)
/*! TIMDEC - Timer Decrement
* 0b00..Decrement counter on FlexIO clock, Shift clock equals Timer output.
* 0b01..Decrement counter on Trigger input (both edges), Shift clock equals Timer output.
* 0b10..Decrement counter on Pin input (both edges), Shift clock equals Pin input.
* 0b11..Decrement counter on Trigger input (both edges), Shift clock equals Trigger input.
*/
#define FLEXIO_TIMCFG_TIMDEC(x) (((uint32_t)(((uint32_t)(x)) << FLEXIO_TIMCFG_TIMDEC_SHIFT)) & FLEXIO_TIMCFG_TIMDEC_MASK)
#define FLEXIO_TIMCFG_TIMOUT_MASK (0x3000000U)
#define FLEXIO_TIMCFG_TIMOUT_SHIFT (24U)
/*! TIMOUT - Timer Output
* 0b00..Timer output is logic one when enabled and is not affected by timer reset
* 0b01..Timer output is logic zero when enabled and is not affected by timer reset
* 0b10..Timer output is logic one when enabled and on timer reset
* 0b11..Timer output is logic zero when enabled and on timer reset
*/
#define FLEXIO_TIMCFG_TIMOUT(x) (((uint32_t)(((uint32_t)(x)) << FLEXIO_TIMCFG_TIMOUT_SHIFT)) & FLEXIO_TIMCFG_TIMOUT_MASK)
/*! @} */
/*! @name TIMCMP - Timer Compare N Register */
/*! @{ */
#define FLEXIO_TIMCMP_CMP_MASK (0xFFFFU)
#define FLEXIO_TIMCMP_CMP_SHIFT (0U)
/*! CMP - Timer Compare Value */
#define FLEXIO_TIMCMP_CMP(x) (((uint32_t)(((uint32_t)(x)) << FLEXIO_TIMCMP_CMP_SHIFT)) & FLEXIO_TIMCMP_CMP_MASK)
/*! @} */
/*! @name SHIFTBUFNBS - Shifter Buffer N Nibble Byte Swapped Register */
/*! @{ */
#define FLEXIO_SHIFTBUFNBS_SHIFTBUFNBS_MASK (0xFFFFFFFFU)
#define FLEXIO_SHIFTBUFNBS_SHIFTBUFNBS_SHIFT (0U)
/*! SHIFTBUFNBS - Shift Buffer */
#define FLEXIO_SHIFTBUFNBS_SHIFTBUFNBS(x) (((uint32_t)(((uint32_t)(x)) << FLEXIO_SHIFTBUFNBS_SHIFTBUFNBS_SHIFT)) & FLEXIO_SHIFTBUFNBS_SHIFTBUFNBS_MASK)
/*! @} */
/*! @name SHIFTBUFHWS - Shifter Buffer N Half Word Swapped Register */
/*! @{ */
#define FLEXIO_SHIFTBUFHWS_SHIFTBUFHWS_MASK (0xFFFFFFFFU)
#define FLEXIO_SHIFTBUFHWS_SHIFTBUFHWS_SHIFT (0U)
/*! SHIFTBUFHWS - Shift Buffer */
#define FLEXIO_SHIFTBUFHWS_SHIFTBUFHWS(x) (((uint32_t)(((uint32_t)(x)) << FLEXIO_SHIFTBUFHWS_SHIFTBUFHWS_SHIFT)) & FLEXIO_SHIFTBUFHWS_SHIFTBUFHWS_MASK)
/*! @} */
/*! @name SHIFTBUFNIS - Shifter Buffer N Nibble Swapped Register */
/*! @{ */
#define FLEXIO_SHIFTBUFNIS_SHIFTBUFNIS_MASK (0xFFFFFFFFU)
#define FLEXIO_SHIFTBUFNIS_SHIFTBUFNIS_SHIFT (0U)
/*! SHIFTBUFNIS - Shift Buffer */
#define FLEXIO_SHIFTBUFNIS_SHIFTBUFNIS(x) (((uint32_t)(((uint32_t)(x)) << FLEXIO_SHIFTBUFNIS_SHIFTBUFNIS_SHIFT)) & FLEXIO_SHIFTBUFNIS_SHIFTBUFNIS_MASK)
/*! @} */
/*!
* @}
*/ /* end of group FLEXIO_Register_Masks */
/*!
* @}
*/ /* end of group FLEXIO_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 */
#endif /* FLEXIO_H_ */

View File

@ -0,0 +1,358 @@
/*
** ###################################################################
** Processors: MIMXRT1061CVJ5A
** MIMXRT1061CVJ5B
** MIMXRT1061CVL5A
** MIMXRT1061CVL5B
** MIMXRT1061DVJ6A
** MIMXRT1061DVJ6B
** MIMXRT1061DVL6A
** MIMXRT1061DVL6B
** MIMXRT1061XVN5B
** MIMXRT1062CVJ5A
** MIMXRT1062CVJ5B
** MIMXRT1062CVL5A
** MIMXRT1062CVL5B
** MIMXRT1062DVJ6A
** MIMXRT1062DVJ6B
** MIMXRT1062DVL6A
** MIMXRT1062DVL6B
** MIMXRT1062DVN6B
** MIMXRT1062XVN5B
** MIMXRT106ADVL6A
** MIMXRT106CDVL6A
** MIMXRT106FDVL6A
** MIMXRT106LDVL6A
** MIMXRT106SDVL6A
**
** Version: rev. 1.4, 2022-03-25
** Build: b240705
**
** Abstract:
** CMSIS Peripheral Access Layer for FLEXRAM
**
** Copyright 1997-2016 Freescale Semiconductor, Inc.
** Copyright 2016-2024 NXP
** SPDX-License-Identifier: BSD-3-Clause
**
** http: www.nxp.com
** mail: support@nxp.com
**
** Revisions:
** - rev. 0.1 (2017-01-10)
** Initial version.
** - rev. 1.0 (2018-11-16)
** Update header files to align with IMXRT1060RM Rev.0.
** - rev. 1.1 (2018-11-27)
** Update header files to align with IMXRT1060RM Rev.1.
** - rev. 1.2 (2019-04-29)
** Add SET/CLR/TOG register group to register CTRL, STAT, CHANNELCTRL, CH0STAT, CH0OPTS, CH1STAT, CH1OPTS, CH2STAT, CH2OPTS, CH3STAT, CH3OPTS of DCP module.
** - rev. 1.3 (2021-08-10)
** Update header files to align with IMXRT1060RM Rev.3.
** - rev. 1.4 (2022-03-25)
** Add RT1060X device
**
** ###################################################################
*/
/*!
* @file FLEXRAM.h
* @version 1.4
* @date 2022-03-25
* @brief CMSIS Peripheral Access Layer for FLEXRAM
*
* CMSIS Peripheral Access Layer for FLEXRAM
*/
#if !defined(FLEXRAM_H_)
#define FLEXRAM_H_ /**< Symbol preventing repeated inclusion */
#if (defined(CPU_MIMXRT1061CVJ5A) || defined(CPU_MIMXRT1061CVJ5B) || defined(CPU_MIMXRT1061CVL5A) || defined(CPU_MIMXRT1061CVL5B) || defined(CPU_MIMXRT1061DVJ6A) || defined(CPU_MIMXRT1061DVJ6B) || defined(CPU_MIMXRT1061DVL6A) || defined(CPU_MIMXRT1061DVL6B) || defined(CPU_MIMXRT1061XVN5B))
#include "MIMXRT1061_COMMON.h"
#elif (defined(CPU_MIMXRT1062CVJ5A) || defined(CPU_MIMXRT1062CVJ5B) || defined(CPU_MIMXRT1062CVL5A) || defined(CPU_MIMXRT1062CVL5B) || defined(CPU_MIMXRT1062DVJ6A) || defined(CPU_MIMXRT1062DVJ6B) || defined(CPU_MIMXRT1062DVL6A) || defined(CPU_MIMXRT1062DVL6B) || defined(CPU_MIMXRT1062DVN6B) || defined(CPU_MIMXRT1062XVN5B))
#include "MIMXRT1062_COMMON.h"
#elif (defined(CPU_MIMXRT106ADVL6A))
#include "MIMXRT106A_COMMON.h"
#elif (defined(CPU_MIMXRT106CDVL6A))
#include "MIMXRT106C_COMMON.h"
#elif (defined(CPU_MIMXRT106FDVL6A))
#include "MIMXRT106F_COMMON.h"
#elif (defined(CPU_MIMXRT106LDVL6A))
#include "MIMXRT106L_COMMON.h"
#elif (defined(CPU_MIMXRT106SDVL6A))
#include "MIMXRT106S_COMMON.h"
#else
#error "No valid CPU defined!"
#endif
/* ----------------------------------------------------------------------------
-- 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
/* ----------------------------------------------------------------------------
-- FLEXRAM Peripheral Access Layer
---------------------------------------------------------------------------- */
/*!
* @addtogroup FLEXRAM_Peripheral_Access_Layer FLEXRAM Peripheral Access Layer
* @{
*/
/** FLEXRAM - Register Layout Typedef */
typedef struct {
__IO uint32_t TCM_CTRL; /**< TCM CRTL Register, offset: 0x0 */
uint8_t RESERVED_0[12];
__IO uint32_t INT_STATUS; /**< Interrupt Status Register, offset: 0x10 */
__IO uint32_t INT_STAT_EN; /**< Interrupt Status Enable Register, offset: 0x14 */
__IO uint32_t INT_SIG_EN; /**< Interrupt Enable Register, offset: 0x18 */
} FLEXRAM_Type;
/* ----------------------------------------------------------------------------
-- FLEXRAM Register Masks
---------------------------------------------------------------------------- */
/*!
* @addtogroup FLEXRAM_Register_Masks FLEXRAM Register Masks
* @{
*/
/*! @name TCM_CTRL - TCM CRTL Register */
/*! @{ */
#define FLEXRAM_TCM_CTRL_TCM_WWAIT_EN_MASK (0x1U)
#define FLEXRAM_TCM_CTRL_TCM_WWAIT_EN_SHIFT (0U)
/*! TCM_WWAIT_EN - TCM Write Wait Mode Enable
* 0b0..TCM write fast mode: Write RAM accesses are expected to be finished in 1-cycle.
* 0b1..TCM write wait mode: Write RAM accesses are expected to be finished in 2-cycles.
*/
#define FLEXRAM_TCM_CTRL_TCM_WWAIT_EN(x) (((uint32_t)(((uint32_t)(x)) << FLEXRAM_TCM_CTRL_TCM_WWAIT_EN_SHIFT)) & FLEXRAM_TCM_CTRL_TCM_WWAIT_EN_MASK)
#define FLEXRAM_TCM_CTRL_TCM_RWAIT_EN_MASK (0x2U)
#define FLEXRAM_TCM_CTRL_TCM_RWAIT_EN_SHIFT (1U)
/*! TCM_RWAIT_EN - TCM Read Wait Mode Enable
* 0b0..TCM read fast mode: Read RAM accesses are expected to be finished in 1-cycle.
* 0b1..TCM read wait mode: Read RAM accesses are expected to be finished in 2-cycles.
*/
#define FLEXRAM_TCM_CTRL_TCM_RWAIT_EN(x) (((uint32_t)(((uint32_t)(x)) << FLEXRAM_TCM_CTRL_TCM_RWAIT_EN_SHIFT)) & FLEXRAM_TCM_CTRL_TCM_RWAIT_EN_MASK)
#define FLEXRAM_TCM_CTRL_FORCE_CLK_ON_MASK (0x4U)
#define FLEXRAM_TCM_CTRL_FORCE_CLK_ON_SHIFT (2U)
/*! FORCE_CLK_ON - Force RAM Clock Always On */
#define FLEXRAM_TCM_CTRL_FORCE_CLK_ON(x) (((uint32_t)(((uint32_t)(x)) << FLEXRAM_TCM_CTRL_FORCE_CLK_ON_SHIFT)) & FLEXRAM_TCM_CTRL_FORCE_CLK_ON_MASK)
#define FLEXRAM_TCM_CTRL_Reserved_MASK (0xFFFFFFF8U)
#define FLEXRAM_TCM_CTRL_Reserved_SHIFT (3U)
/*! Reserved - Reserved */
#define FLEXRAM_TCM_CTRL_Reserved(x) (((uint32_t)(((uint32_t)(x)) << FLEXRAM_TCM_CTRL_Reserved_SHIFT)) & FLEXRAM_TCM_CTRL_Reserved_MASK)
/*! @} */
/*! @name INT_STATUS - Interrupt Status Register */
/*! @{ */
#define FLEXRAM_INT_STATUS_Reserved0_MASK (0x1U)
#define FLEXRAM_INT_STATUS_Reserved0_SHIFT (0U)
/*! Reserved0 - Reserved */
#define FLEXRAM_INT_STATUS_Reserved0(x) (((uint32_t)(((uint32_t)(x)) << FLEXRAM_INT_STATUS_Reserved0_SHIFT)) & FLEXRAM_INT_STATUS_Reserved0_MASK)
#define FLEXRAM_INT_STATUS_Reserved1_MASK (0x2U)
#define FLEXRAM_INT_STATUS_Reserved1_SHIFT (1U)
/*! Reserved1 - Reserved */
#define FLEXRAM_INT_STATUS_Reserved1(x) (((uint32_t)(((uint32_t)(x)) << FLEXRAM_INT_STATUS_Reserved1_SHIFT)) & FLEXRAM_INT_STATUS_Reserved1_MASK)
#define FLEXRAM_INT_STATUS_Reserved2_MASK (0x4U)
#define FLEXRAM_INT_STATUS_Reserved2_SHIFT (2U)
/*! Reserved2 - Reserved */
#define FLEXRAM_INT_STATUS_Reserved2(x) (((uint32_t)(((uint32_t)(x)) << FLEXRAM_INT_STATUS_Reserved2_SHIFT)) & FLEXRAM_INT_STATUS_Reserved2_MASK)
#define FLEXRAM_INT_STATUS_ITCM_ERR_STATUS_MASK (0x8U)
#define FLEXRAM_INT_STATUS_ITCM_ERR_STATUS_SHIFT (3U)
/*! ITCM_ERR_STATUS - ITCM Access Error Status
* 0b0..ITCM access error does not happen
* 0b1..ITCM access error happens.
*/
#define FLEXRAM_INT_STATUS_ITCM_ERR_STATUS(x) (((uint32_t)(((uint32_t)(x)) << FLEXRAM_INT_STATUS_ITCM_ERR_STATUS_SHIFT)) & FLEXRAM_INT_STATUS_ITCM_ERR_STATUS_MASK)
#define FLEXRAM_INT_STATUS_DTCM_ERR_STATUS_MASK (0x10U)
#define FLEXRAM_INT_STATUS_DTCM_ERR_STATUS_SHIFT (4U)
/*! DTCM_ERR_STATUS - DTCM Access Error Status
* 0b0..DTCM access error does not happen
* 0b1..DTCM access error happens.
*/
#define FLEXRAM_INT_STATUS_DTCM_ERR_STATUS(x) (((uint32_t)(((uint32_t)(x)) << FLEXRAM_INT_STATUS_DTCM_ERR_STATUS_SHIFT)) & FLEXRAM_INT_STATUS_DTCM_ERR_STATUS_MASK)
#define FLEXRAM_INT_STATUS_OCRAM_ERR_STATUS_MASK (0x20U)
#define FLEXRAM_INT_STATUS_OCRAM_ERR_STATUS_SHIFT (5U)
/*! OCRAM_ERR_STATUS - OCRAM Access Error Status
* 0b0..OCRAM access error does not happen
* 0b1..OCRAM access error happens.
*/
#define FLEXRAM_INT_STATUS_OCRAM_ERR_STATUS(x) (((uint32_t)(((uint32_t)(x)) << FLEXRAM_INT_STATUS_OCRAM_ERR_STATUS_SHIFT)) & FLEXRAM_INT_STATUS_OCRAM_ERR_STATUS_MASK)
#define FLEXRAM_INT_STATUS_Reserved_MASK (0xFFFFFFC0U)
#define FLEXRAM_INT_STATUS_Reserved_SHIFT (6U)
/*! Reserved - Reserved */
#define FLEXRAM_INT_STATUS_Reserved(x) (((uint32_t)(((uint32_t)(x)) << FLEXRAM_INT_STATUS_Reserved_SHIFT)) & FLEXRAM_INT_STATUS_Reserved_MASK)
/*! @} */
/*! @name INT_STAT_EN - Interrupt Status Enable Register */
/*! @{ */
#define FLEXRAM_INT_STAT_EN_Reserved0_MASK (0x1U)
#define FLEXRAM_INT_STAT_EN_Reserved0_SHIFT (0U)
/*! Reserved0 - Reserved */
#define FLEXRAM_INT_STAT_EN_Reserved0(x) (((uint32_t)(((uint32_t)(x)) << FLEXRAM_INT_STAT_EN_Reserved0_SHIFT)) & FLEXRAM_INT_STAT_EN_Reserved0_MASK)
#define FLEXRAM_INT_STAT_EN_Reserved1_MASK (0x2U)
#define FLEXRAM_INT_STAT_EN_Reserved1_SHIFT (1U)
/*! Reserved1 - Reserved */
#define FLEXRAM_INT_STAT_EN_Reserved1(x) (((uint32_t)(((uint32_t)(x)) << FLEXRAM_INT_STAT_EN_Reserved1_SHIFT)) & FLEXRAM_INT_STAT_EN_Reserved1_MASK)
#define FLEXRAM_INT_STAT_EN_Reserved2_MASK (0x4U)
#define FLEXRAM_INT_STAT_EN_Reserved2_SHIFT (2U)
/*! Reserved2 - Reserved */
#define FLEXRAM_INT_STAT_EN_Reserved2(x) (((uint32_t)(((uint32_t)(x)) << FLEXRAM_INT_STAT_EN_Reserved2_SHIFT)) & FLEXRAM_INT_STAT_EN_Reserved2_MASK)
#define FLEXRAM_INT_STAT_EN_ITCM_ERR_STAT_EN_MASK (0x8U)
#define FLEXRAM_INT_STAT_EN_ITCM_ERR_STAT_EN_SHIFT (3U)
/*! ITCM_ERR_STAT_EN - ITCM Access Error Status Enable
* 0b0..Masked
* 0b1..Enabled
*/
#define FLEXRAM_INT_STAT_EN_ITCM_ERR_STAT_EN(x) (((uint32_t)(((uint32_t)(x)) << FLEXRAM_INT_STAT_EN_ITCM_ERR_STAT_EN_SHIFT)) & FLEXRAM_INT_STAT_EN_ITCM_ERR_STAT_EN_MASK)
#define FLEXRAM_INT_STAT_EN_DTCM_ERR_STAT_EN_MASK (0x10U)
#define FLEXRAM_INT_STAT_EN_DTCM_ERR_STAT_EN_SHIFT (4U)
/*! DTCM_ERR_STAT_EN - DTCM Access Error Status Enable
* 0b0..Masked
* 0b1..Enabled
*/
#define FLEXRAM_INT_STAT_EN_DTCM_ERR_STAT_EN(x) (((uint32_t)(((uint32_t)(x)) << FLEXRAM_INT_STAT_EN_DTCM_ERR_STAT_EN_SHIFT)) & FLEXRAM_INT_STAT_EN_DTCM_ERR_STAT_EN_MASK)
#define FLEXRAM_INT_STAT_EN_OCRAM_ERR_STAT_EN_MASK (0x20U)
#define FLEXRAM_INT_STAT_EN_OCRAM_ERR_STAT_EN_SHIFT (5U)
/*! OCRAM_ERR_STAT_EN - OCRAM Access Error Status Enable
* 0b0..Masked
* 0b1..Enabled
*/
#define FLEXRAM_INT_STAT_EN_OCRAM_ERR_STAT_EN(x) (((uint32_t)(((uint32_t)(x)) << FLEXRAM_INT_STAT_EN_OCRAM_ERR_STAT_EN_SHIFT)) & FLEXRAM_INT_STAT_EN_OCRAM_ERR_STAT_EN_MASK)
#define FLEXRAM_INT_STAT_EN_Reserved_MASK (0xFFFFFFC0U)
#define FLEXRAM_INT_STAT_EN_Reserved_SHIFT (6U)
/*! Reserved - Reserved */
#define FLEXRAM_INT_STAT_EN_Reserved(x) (((uint32_t)(((uint32_t)(x)) << FLEXRAM_INT_STAT_EN_Reserved_SHIFT)) & FLEXRAM_INT_STAT_EN_Reserved_MASK)
/*! @} */
/*! @name INT_SIG_EN - Interrupt Enable Register */
/*! @{ */
#define FLEXRAM_INT_SIG_EN_Reserved0_MASK (0x1U)
#define FLEXRAM_INT_SIG_EN_Reserved0_SHIFT (0U)
/*! Reserved0 - Reserved */
#define FLEXRAM_INT_SIG_EN_Reserved0(x) (((uint32_t)(((uint32_t)(x)) << FLEXRAM_INT_SIG_EN_Reserved0_SHIFT)) & FLEXRAM_INT_SIG_EN_Reserved0_MASK)
#define FLEXRAM_INT_SIG_EN_Reserved1_MASK (0x2U)
#define FLEXRAM_INT_SIG_EN_Reserved1_SHIFT (1U)
/*! Reserved1 - Reserved */
#define FLEXRAM_INT_SIG_EN_Reserved1(x) (((uint32_t)(((uint32_t)(x)) << FLEXRAM_INT_SIG_EN_Reserved1_SHIFT)) & FLEXRAM_INT_SIG_EN_Reserved1_MASK)
#define FLEXRAM_INT_SIG_EN_Reserved2_MASK (0x4U)
#define FLEXRAM_INT_SIG_EN_Reserved2_SHIFT (2U)
/*! Reserved2 - Reserved */
#define FLEXRAM_INT_SIG_EN_Reserved2(x) (((uint32_t)(((uint32_t)(x)) << FLEXRAM_INT_SIG_EN_Reserved2_SHIFT)) & FLEXRAM_INT_SIG_EN_Reserved2_MASK)
#define FLEXRAM_INT_SIG_EN_ITCM_ERR_SIG_EN_MASK (0x8U)
#define FLEXRAM_INT_SIG_EN_ITCM_ERR_SIG_EN_SHIFT (3U)
/*! ITCM_ERR_SIG_EN - ITCM Access Error Interrupt Enable
* 0b0..Masked
* 0b1..Enabled
*/
#define FLEXRAM_INT_SIG_EN_ITCM_ERR_SIG_EN(x) (((uint32_t)(((uint32_t)(x)) << FLEXRAM_INT_SIG_EN_ITCM_ERR_SIG_EN_SHIFT)) & FLEXRAM_INT_SIG_EN_ITCM_ERR_SIG_EN_MASK)
#define FLEXRAM_INT_SIG_EN_DTCM_ERR_SIG_EN_MASK (0x10U)
#define FLEXRAM_INT_SIG_EN_DTCM_ERR_SIG_EN_SHIFT (4U)
/*! DTCM_ERR_SIG_EN - DTCM Access Error Interrupt Enable
* 0b0..Masked
* 0b1..Enabled
*/
#define FLEXRAM_INT_SIG_EN_DTCM_ERR_SIG_EN(x) (((uint32_t)(((uint32_t)(x)) << FLEXRAM_INT_SIG_EN_DTCM_ERR_SIG_EN_SHIFT)) & FLEXRAM_INT_SIG_EN_DTCM_ERR_SIG_EN_MASK)
#define FLEXRAM_INT_SIG_EN_OCRAM_ERR_SIG_EN_MASK (0x20U)
#define FLEXRAM_INT_SIG_EN_OCRAM_ERR_SIG_EN_SHIFT (5U)
/*! OCRAM_ERR_SIG_EN - OCRAM Access Error Interrupt Enable
* 0b0..Masked
* 0b1..Enabled
*/
#define FLEXRAM_INT_SIG_EN_OCRAM_ERR_SIG_EN(x) (((uint32_t)(((uint32_t)(x)) << FLEXRAM_INT_SIG_EN_OCRAM_ERR_SIG_EN_SHIFT)) & FLEXRAM_INT_SIG_EN_OCRAM_ERR_SIG_EN_MASK)
#define FLEXRAM_INT_SIG_EN_Reserved_MASK (0xFFFFFFC0U)
#define FLEXRAM_INT_SIG_EN_Reserved_SHIFT (6U)
/*! Reserved - Reserved */
#define FLEXRAM_INT_SIG_EN_Reserved(x) (((uint32_t)(((uint32_t)(x)) << FLEXRAM_INT_SIG_EN_Reserved_SHIFT)) & FLEXRAM_INT_SIG_EN_Reserved_MASK)
/*! @} */
/*!
* @}
*/ /* end of group FLEXRAM_Register_Masks */
/*!
* @}
*/ /* end of group FLEXRAM_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 */
#endif /* FLEXRAM_H_ */

View File

@ -0,0 +1,274 @@
/*
** ###################################################################
** Processors: MIMXRT1061CVJ5A
** MIMXRT1061CVJ5B
** MIMXRT1061CVL5A
** MIMXRT1061CVL5B
** MIMXRT1061DVJ6A
** MIMXRT1061DVJ6B
** MIMXRT1061DVL6A
** MIMXRT1061DVL6B
** MIMXRT1061XVN5B
** MIMXRT1062CVJ5A
** MIMXRT1062CVJ5B
** MIMXRT1062CVL5A
** MIMXRT1062CVL5B
** MIMXRT1062DVJ6A
** MIMXRT1062DVJ6B
** MIMXRT1062DVL6A
** MIMXRT1062DVL6B
** MIMXRT1062DVN6B
** MIMXRT1062XVN5B
** MIMXRT106ADVL6A
** MIMXRT106CDVL6A
** MIMXRT106FDVL6A
** MIMXRT106LDVL6A
** MIMXRT106SDVL6A
**
** Version: rev. 1.4, 2022-03-25
** Build: b240705
**
** Abstract:
** CMSIS Peripheral Access Layer for GPC
**
** Copyright 1997-2016 Freescale Semiconductor, Inc.
** Copyright 2016-2024 NXP
** SPDX-License-Identifier: BSD-3-Clause
**
** http: www.nxp.com
** mail: support@nxp.com
**
** Revisions:
** - rev. 0.1 (2017-01-10)
** Initial version.
** - rev. 1.0 (2018-11-16)
** Update header files to align with IMXRT1060RM Rev.0.
** - rev. 1.1 (2018-11-27)
** Update header files to align with IMXRT1060RM Rev.1.
** - rev. 1.2 (2019-04-29)
** Add SET/CLR/TOG register group to register CTRL, STAT, CHANNELCTRL, CH0STAT, CH0OPTS, CH1STAT, CH1OPTS, CH2STAT, CH2OPTS, CH3STAT, CH3OPTS of DCP module.
** - rev. 1.3 (2021-08-10)
** Update header files to align with IMXRT1060RM Rev.3.
** - rev. 1.4 (2022-03-25)
** Add RT1060X device
**
** ###################################################################
*/
/*!
* @file GPC.h
* @version 1.4
* @date 2022-03-25
* @brief CMSIS Peripheral Access Layer for GPC
*
* CMSIS Peripheral Access Layer for GPC
*/
#if !defined(GPC_H_)
#define GPC_H_ /**< Symbol preventing repeated inclusion */
#if (defined(CPU_MIMXRT1061CVJ5A) || defined(CPU_MIMXRT1061CVJ5B) || defined(CPU_MIMXRT1061CVL5A) || defined(CPU_MIMXRT1061CVL5B) || defined(CPU_MIMXRT1061DVJ6A) || defined(CPU_MIMXRT1061DVJ6B) || defined(CPU_MIMXRT1061DVL6A) || defined(CPU_MIMXRT1061DVL6B) || defined(CPU_MIMXRT1061XVN5B))
#include "MIMXRT1061_COMMON.h"
#elif (defined(CPU_MIMXRT1062CVJ5A) || defined(CPU_MIMXRT1062CVJ5B) || defined(CPU_MIMXRT1062CVL5A) || defined(CPU_MIMXRT1062CVL5B) || defined(CPU_MIMXRT1062DVJ6A) || defined(CPU_MIMXRT1062DVJ6B) || defined(CPU_MIMXRT1062DVL6A) || defined(CPU_MIMXRT1062DVL6B) || defined(CPU_MIMXRT1062DVN6B) || defined(CPU_MIMXRT1062XVN5B))
#include "MIMXRT1062_COMMON.h"
#elif (defined(CPU_MIMXRT106ADVL6A))
#include "MIMXRT106A_COMMON.h"
#elif (defined(CPU_MIMXRT106CDVL6A))
#include "MIMXRT106C_COMMON.h"
#elif (defined(CPU_MIMXRT106FDVL6A))
#include "MIMXRT106F_COMMON.h"
#elif (defined(CPU_MIMXRT106LDVL6A))
#include "MIMXRT106L_COMMON.h"
#elif (defined(CPU_MIMXRT106SDVL6A))
#include "MIMXRT106S_COMMON.h"
#else
#error "No valid CPU defined!"
#endif
/* ----------------------------------------------------------------------------
-- 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
/* ----------------------------------------------------------------------------
-- GPC Peripheral Access Layer
---------------------------------------------------------------------------- */
/*!
* @addtogroup GPC_Peripheral_Access_Layer GPC Peripheral Access Layer
* @{
*/
/** GPC - Size of Registers Arrays */
#define GPC_IMR_COUNT 4u
#define GPC_ISR_COUNT 4u
/** GPC - Register Layout Typedef */
typedef struct {
__IO uint32_t CNTR; /**< GPC Interface control register, offset: 0x0 */
uint8_t RESERVED_0[4];
__IO uint32_t IMR[GPC_IMR_COUNT]; /**< IRQ masking register 1..IRQ masking register 4, array offset: 0x8, array step: 0x4 */
__I uint32_t ISR[GPC_ISR_COUNT]; /**< IRQ status resister 1..IRQ status resister 4, array offset: 0x18, array step: 0x4 */
uint8_t RESERVED_1[12];
__IO uint32_t IMR5; /**< IRQ masking register 5, offset: 0x34 */
__I uint32_t ISR5; /**< IRQ status resister 5, offset: 0x38 */
} GPC_Type;
/* ----------------------------------------------------------------------------
-- GPC Register Masks
---------------------------------------------------------------------------- */
/*!
* @addtogroup GPC_Register_Masks GPC Register Masks
* @{
*/
/*! @name CNTR - GPC Interface control register */
/*! @{ */
#define GPC_CNTR_MEGA_PDN_REQ_MASK (0x4U)
#define GPC_CNTR_MEGA_PDN_REQ_SHIFT (2U)
/*! MEGA_PDN_REQ
* 0b0..No Request
* 0b1..Request power down sequence
*/
#define GPC_CNTR_MEGA_PDN_REQ(x) (((uint32_t)(((uint32_t)(x)) << GPC_CNTR_MEGA_PDN_REQ_SHIFT)) & GPC_CNTR_MEGA_PDN_REQ_MASK)
#define GPC_CNTR_MEGA_PUP_REQ_MASK (0x8U)
#define GPC_CNTR_MEGA_PUP_REQ_SHIFT (3U)
/*! MEGA_PUP_REQ
* 0b0..No Request
* 0b1..Request power up sequence
*/
#define GPC_CNTR_MEGA_PUP_REQ(x) (((uint32_t)(((uint32_t)(x)) << GPC_CNTR_MEGA_PUP_REQ_SHIFT)) & GPC_CNTR_MEGA_PUP_REQ_MASK)
#define GPC_CNTR_PDRAM0_PGE_MASK (0x400000U)
#define GPC_CNTR_PDRAM0_PGE_SHIFT (22U)
/*! PDRAM0_PGE
* 0b1..FlexRAM PDRAM0 domain will be powered down when the CPU core is powered down..
* 0b0..FlexRAM PDRAM0 domain will keep power even if the CPU core is powered down.
*/
#define GPC_CNTR_PDRAM0_PGE(x) (((uint32_t)(((uint32_t)(x)) << GPC_CNTR_PDRAM0_PGE_SHIFT)) & GPC_CNTR_PDRAM0_PGE_MASK)
/*! @} */
/*! @name IMR - IRQ masking register 1..IRQ masking register 4 */
/*! @{ */
#define GPC_IMR_IMR1_MASK (0xFFFFFFFFU)
#define GPC_IMR_IMR1_SHIFT (0U)
#define GPC_IMR_IMR1(x) (((uint32_t)(((uint32_t)(x)) << GPC_IMR_IMR1_SHIFT)) & GPC_IMR_IMR1_MASK)
#define GPC_IMR_IMR2_MASK (0xFFFFFFFFU)
#define GPC_IMR_IMR2_SHIFT (0U)
#define GPC_IMR_IMR2(x) (((uint32_t)(((uint32_t)(x)) << GPC_IMR_IMR2_SHIFT)) & GPC_IMR_IMR2_MASK)
#define GPC_IMR_IMR3_MASK (0xFFFFFFFFU)
#define GPC_IMR_IMR3_SHIFT (0U)
#define GPC_IMR_IMR3(x) (((uint32_t)(((uint32_t)(x)) << GPC_IMR_IMR3_SHIFT)) & GPC_IMR_IMR3_MASK)
#define GPC_IMR_IMR4_MASK (0xFFFFFFFFU)
#define GPC_IMR_IMR4_SHIFT (0U)
#define GPC_IMR_IMR4(x) (((uint32_t)(((uint32_t)(x)) << GPC_IMR_IMR4_SHIFT)) & GPC_IMR_IMR4_MASK)
/*! @} */
/*! @name ISR - IRQ status resister 1..IRQ status resister 4 */
/*! @{ */
#define GPC_ISR_ISR1_MASK (0xFFFFFFFFU)
#define GPC_ISR_ISR1_SHIFT (0U)
#define GPC_ISR_ISR1(x) (((uint32_t)(((uint32_t)(x)) << GPC_ISR_ISR1_SHIFT)) & GPC_ISR_ISR1_MASK)
#define GPC_ISR_ISR2_MASK (0xFFFFFFFFU)
#define GPC_ISR_ISR2_SHIFT (0U)
#define GPC_ISR_ISR2(x) (((uint32_t)(((uint32_t)(x)) << GPC_ISR_ISR2_SHIFT)) & GPC_ISR_ISR2_MASK)
#define GPC_ISR_ISR3_MASK (0xFFFFFFFFU)
#define GPC_ISR_ISR3_SHIFT (0U)
#define GPC_ISR_ISR3(x) (((uint32_t)(((uint32_t)(x)) << GPC_ISR_ISR3_SHIFT)) & GPC_ISR_ISR3_MASK)
#define GPC_ISR_ISR4_MASK (0xFFFFFFFFU)
#define GPC_ISR_ISR4_SHIFT (0U)
#define GPC_ISR_ISR4(x) (((uint32_t)(((uint32_t)(x)) << GPC_ISR_ISR4_SHIFT)) & GPC_ISR_ISR4_MASK)
/*! @} */
/*! @name IMR5 - IRQ masking register 5 */
/*! @{ */
#define GPC_IMR5_IMR5_MASK (0xFFFFFFFFU)
#define GPC_IMR5_IMR5_SHIFT (0U)
#define GPC_IMR5_IMR5(x) (((uint32_t)(((uint32_t)(x)) << GPC_IMR5_IMR5_SHIFT)) & GPC_IMR5_IMR5_MASK)
/*! @} */
/*! @name ISR5 - IRQ status resister 5 */
/*! @{ */
#define GPC_ISR5_ISR5_MASK (0xFFFFFFFFU)
#define GPC_ISR5_ISR5_SHIFT (0U)
#define GPC_ISR5_ISR5(x) (((uint32_t)(((uint32_t)(x)) << GPC_ISR5_ISR5_SHIFT)) & GPC_ISR5_ISR5_MASK)
/*! @} */
/*!
* @}
*/ /* end of group GPC_Register_Masks */
/*!
* @}
*/ /* end of group GPC_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 */
#endif /* GPC_H_ */

View File

@ -0,0 +1,600 @@
/*
** ###################################################################
** Processors: MIMXRT1061CVJ5A
** MIMXRT1061CVJ5B
** MIMXRT1061CVL5A
** MIMXRT1061CVL5B
** MIMXRT1061DVJ6A
** MIMXRT1061DVJ6B
** MIMXRT1061DVL6A
** MIMXRT1061DVL6B
** MIMXRT1061XVN5B
** MIMXRT1062CVJ5A
** MIMXRT1062CVJ5B
** MIMXRT1062CVL5A
** MIMXRT1062CVL5B
** MIMXRT1062DVJ6A
** MIMXRT1062DVJ6B
** MIMXRT1062DVL6A
** MIMXRT1062DVL6B
** MIMXRT1062DVN6B
** MIMXRT1062XVN5B
** MIMXRT106ADVL6A
** MIMXRT106CDVL6A
** MIMXRT106FDVL6A
** MIMXRT106LDVL6A
** MIMXRT106SDVL6A
**
** Version: rev. 1.4, 2022-03-25
** Build: b240705
**
** Abstract:
** CMSIS Peripheral Access Layer for GPIO
**
** Copyright 1997-2016 Freescale Semiconductor, Inc.
** Copyright 2016-2024 NXP
** SPDX-License-Identifier: BSD-3-Clause
**
** http: www.nxp.com
** mail: support@nxp.com
**
** Revisions:
** - rev. 0.1 (2017-01-10)
** Initial version.
** - rev. 1.0 (2018-11-16)
** Update header files to align with IMXRT1060RM Rev.0.
** - rev. 1.1 (2018-11-27)
** Update header files to align with IMXRT1060RM Rev.1.
** - rev. 1.2 (2019-04-29)
** Add SET/CLR/TOG register group to register CTRL, STAT, CHANNELCTRL, CH0STAT, CH0OPTS, CH1STAT, CH1OPTS, CH2STAT, CH2OPTS, CH3STAT, CH3OPTS of DCP module.
** - rev. 1.3 (2021-08-10)
** Update header files to align with IMXRT1060RM Rev.3.
** - rev. 1.4 (2022-03-25)
** Add RT1060X device
**
** ###################################################################
*/
/*!
* @file GPIO.h
* @version 1.4
* @date 2022-03-25
* @brief CMSIS Peripheral Access Layer for GPIO
*
* CMSIS Peripheral Access Layer for GPIO
*/
#if !defined(GPIO_H_)
#define GPIO_H_ /**< Symbol preventing repeated inclusion */
#if (defined(CPU_MIMXRT1061CVJ5A) || defined(CPU_MIMXRT1061CVJ5B) || defined(CPU_MIMXRT1061CVL5A) || defined(CPU_MIMXRT1061CVL5B) || defined(CPU_MIMXRT1061DVJ6A) || defined(CPU_MIMXRT1061DVJ6B) || defined(CPU_MIMXRT1061DVL6A) || defined(CPU_MIMXRT1061DVL6B) || defined(CPU_MIMXRT1061XVN5B))
#include "MIMXRT1061_COMMON.h"
#elif (defined(CPU_MIMXRT1062CVJ5A) || defined(CPU_MIMXRT1062CVJ5B) || defined(CPU_MIMXRT1062CVL5A) || defined(CPU_MIMXRT1062CVL5B) || defined(CPU_MIMXRT1062DVJ6A) || defined(CPU_MIMXRT1062DVJ6B) || defined(CPU_MIMXRT1062DVL6A) || defined(CPU_MIMXRT1062DVL6B) || defined(CPU_MIMXRT1062DVN6B) || defined(CPU_MIMXRT1062XVN5B))
#include "MIMXRT1062_COMMON.h"
#elif (defined(CPU_MIMXRT106ADVL6A))
#include "MIMXRT106A_COMMON.h"
#elif (defined(CPU_MIMXRT106CDVL6A))
#include "MIMXRT106C_COMMON.h"
#elif (defined(CPU_MIMXRT106FDVL6A))
#include "MIMXRT106F_COMMON.h"
#elif (defined(CPU_MIMXRT106LDVL6A))
#include "MIMXRT106L_COMMON.h"
#elif (defined(CPU_MIMXRT106SDVL6A))
#include "MIMXRT106S_COMMON.h"
#else
#error "No valid CPU defined!"
#endif
/* ----------------------------------------------------------------------------
-- 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
/* ----------------------------------------------------------------------------
-- GPIO Peripheral Access Layer
---------------------------------------------------------------------------- */
/*!
* @addtogroup GPIO_Peripheral_Access_Layer GPIO Peripheral Access Layer
* @{
*/
/** GPIO - Register Layout Typedef */
typedef struct {
__IO uint32_t DR; /**< GPIO data register, offset: 0x0 */
__IO uint32_t GDIR; /**< GPIO direction register, offset: 0x4 */
__I uint32_t PSR; /**< GPIO pad status register, offset: 0x8 */
__IO uint32_t ICR1; /**< GPIO interrupt configuration register1, offset: 0xC */
__IO uint32_t ICR2; /**< GPIO interrupt configuration register2, offset: 0x10 */
__IO uint32_t IMR; /**< GPIO interrupt mask register, offset: 0x14 */
__IO uint32_t ISR; /**< GPIO interrupt status register, offset: 0x18 */
__IO uint32_t EDGE_SEL; /**< GPIO edge select register, offset: 0x1C */
uint8_t RESERVED_0[100];
__O uint32_t DR_SET; /**< GPIO data register SET, offset: 0x84 */
__O uint32_t DR_CLEAR; /**< GPIO data register CLEAR, offset: 0x88 */
__O uint32_t DR_TOGGLE; /**< GPIO data register TOGGLE, offset: 0x8C */
} GPIO_Type;
/* ----------------------------------------------------------------------------
-- GPIO Register Masks
---------------------------------------------------------------------------- */
/*!
* @addtogroup GPIO_Register_Masks GPIO Register Masks
* @{
*/
/*! @name DR - GPIO data register */
/*! @{ */
#define GPIO_DR_DR_MASK (0xFFFFFFFFU)
#define GPIO_DR_DR_SHIFT (0U)
/*! DR - DR data bits */
#define GPIO_DR_DR(x) (((uint32_t)(((uint32_t)(x)) << GPIO_DR_DR_SHIFT)) & GPIO_DR_DR_MASK)
/*! @} */
/*! @name GDIR - GPIO direction register */
/*! @{ */
#define GPIO_GDIR_GDIR_MASK (0xFFFFFFFFU)
#define GPIO_GDIR_GDIR_SHIFT (0U)
/*! GDIR - GPIO direction bits */
#define GPIO_GDIR_GDIR(x) (((uint32_t)(((uint32_t)(x)) << GPIO_GDIR_GDIR_SHIFT)) & GPIO_GDIR_GDIR_MASK)
/*! @} */
/*! @name PSR - GPIO pad status register */
/*! @{ */
#define GPIO_PSR_PSR_MASK (0xFFFFFFFFU)
#define GPIO_PSR_PSR_SHIFT (0U)
/*! PSR - GPIO pad status bits */
#define GPIO_PSR_PSR(x) (((uint32_t)(((uint32_t)(x)) << GPIO_PSR_PSR_SHIFT)) & GPIO_PSR_PSR_MASK)
/*! @} */
/*! @name ICR1 - GPIO interrupt configuration register1 */
/*! @{ */
#define GPIO_ICR1_ICR0_MASK (0x3U)
#define GPIO_ICR1_ICR0_SHIFT (0U)
/*! ICR0 - Interrupt configuration field for GPIO interrupt 0
* 0b00..Interrupt 0 is low-level sensitive.
* 0b01..Interrupt 0 is high-level sensitive.
* 0b10..Interrupt 0 is rising-edge sensitive.
* 0b11..Interrupt 0 is falling-edge sensitive.
*/
#define GPIO_ICR1_ICR0(x) (((uint32_t)(((uint32_t)(x)) << GPIO_ICR1_ICR0_SHIFT)) & GPIO_ICR1_ICR0_MASK)
#define GPIO_ICR1_ICR1_MASK (0xCU)
#define GPIO_ICR1_ICR1_SHIFT (2U)
/*! ICR1 - Interrupt configuration field for GPIO interrupt 1
* 0b00..Interrupt 1 is low-level sensitive.
* 0b01..Interrupt 1 is high-level sensitive.
* 0b10..Interrupt 1 is rising-edge sensitive.
* 0b11..Interrupt 1 is falling-edge sensitive.
*/
#define GPIO_ICR1_ICR1(x) (((uint32_t)(((uint32_t)(x)) << GPIO_ICR1_ICR1_SHIFT)) & GPIO_ICR1_ICR1_MASK)
#define GPIO_ICR1_ICR2_MASK (0x30U)
#define GPIO_ICR1_ICR2_SHIFT (4U)
/*! ICR2 - Interrupt configuration field for GPIO interrupt 2
* 0b00..Interrupt 2 is low-level sensitive.
* 0b01..Interrupt 2 is high-level sensitive.
* 0b10..Interrupt 2 is rising-edge sensitive.
* 0b11..Interrupt 2 is falling-edge sensitive.
*/
#define GPIO_ICR1_ICR2(x) (((uint32_t)(((uint32_t)(x)) << GPIO_ICR1_ICR2_SHIFT)) & GPIO_ICR1_ICR2_MASK)
#define GPIO_ICR1_ICR3_MASK (0xC0U)
#define GPIO_ICR1_ICR3_SHIFT (6U)
/*! ICR3 - Interrupt configuration field for GPIO interrupt 3
* 0b00..Interrupt 3 is low-level sensitive.
* 0b01..Interrupt 3 is high-level sensitive.
* 0b10..Interrupt 3 is rising-edge sensitive.
* 0b11..Interrupt 3 is falling-edge sensitive.
*/
#define GPIO_ICR1_ICR3(x) (((uint32_t)(((uint32_t)(x)) << GPIO_ICR1_ICR3_SHIFT)) & GPIO_ICR1_ICR3_MASK)
#define GPIO_ICR1_ICR4_MASK (0x300U)
#define GPIO_ICR1_ICR4_SHIFT (8U)
/*! ICR4 - Interrupt configuration field for GPIO interrupt 4
* 0b00..Interrupt 4 is low-level sensitive.
* 0b01..Interrupt 4 is high-level sensitive.
* 0b10..Interrupt 4 is rising-edge sensitive.
* 0b11..Interrupt 4 is falling-edge sensitive.
*/
#define GPIO_ICR1_ICR4(x) (((uint32_t)(((uint32_t)(x)) << GPIO_ICR1_ICR4_SHIFT)) & GPIO_ICR1_ICR4_MASK)
#define GPIO_ICR1_ICR5_MASK (0xC00U)
#define GPIO_ICR1_ICR5_SHIFT (10U)
/*! ICR5 - Interrupt configuration field for GPIO interrupt 5
* 0b00..Interrupt 5 is low-level sensitive.
* 0b01..Interrupt 5 is high-level sensitive.
* 0b10..Interrupt 5 is rising-edge sensitive.
* 0b11..Interrupt 5 is falling-edge sensitive.
*/
#define GPIO_ICR1_ICR5(x) (((uint32_t)(((uint32_t)(x)) << GPIO_ICR1_ICR5_SHIFT)) & GPIO_ICR1_ICR5_MASK)
#define GPIO_ICR1_ICR6_MASK (0x3000U)
#define GPIO_ICR1_ICR6_SHIFT (12U)
/*! ICR6 - Interrupt configuration field for GPIO interrupt 6
* 0b00..Interrupt 6 is low-level sensitive.
* 0b01..Interrupt 6 is high-level sensitive.
* 0b10..Interrupt 6 is rising-edge sensitive.
* 0b11..Interrupt 6 is falling-edge sensitive.
*/
#define GPIO_ICR1_ICR6(x) (((uint32_t)(((uint32_t)(x)) << GPIO_ICR1_ICR6_SHIFT)) & GPIO_ICR1_ICR6_MASK)
#define GPIO_ICR1_ICR7_MASK (0xC000U)
#define GPIO_ICR1_ICR7_SHIFT (14U)
/*! ICR7 - Interrupt configuration field for GPIO interrupt 7
* 0b00..Interrupt 7 is low-level sensitive.
* 0b01..Interrupt 7 is high-level sensitive.
* 0b10..Interrupt 7 is rising-edge sensitive.
* 0b11..Interrupt 7 is falling-edge sensitive.
*/
#define GPIO_ICR1_ICR7(x) (((uint32_t)(((uint32_t)(x)) << GPIO_ICR1_ICR7_SHIFT)) & GPIO_ICR1_ICR7_MASK)
#define GPIO_ICR1_ICR8_MASK (0x30000U)
#define GPIO_ICR1_ICR8_SHIFT (16U)
/*! ICR8 - Interrupt configuration field for GPIO interrupt 8
* 0b00..Interrupt 8 is low-level sensitive.
* 0b01..Interrupt 8 is high-level sensitive.
* 0b10..Interrupt 8 is rising-edge sensitive.
* 0b11..Interrupt 8 is falling-edge sensitive.
*/
#define GPIO_ICR1_ICR8(x) (((uint32_t)(((uint32_t)(x)) << GPIO_ICR1_ICR8_SHIFT)) & GPIO_ICR1_ICR8_MASK)
#define GPIO_ICR1_ICR9_MASK (0xC0000U)
#define GPIO_ICR1_ICR9_SHIFT (18U)
/*! ICR9 - Interrupt configuration field for GPIO interrupt 9
* 0b00..Interrupt 9 is low-level sensitive.
* 0b01..Interrupt 9 is high-level sensitive.
* 0b10..Interrupt 9 is rising-edge sensitive.
* 0b11..Interrupt 9 is falling-edge sensitive.
*/
#define GPIO_ICR1_ICR9(x) (((uint32_t)(((uint32_t)(x)) << GPIO_ICR1_ICR9_SHIFT)) & GPIO_ICR1_ICR9_MASK)
#define GPIO_ICR1_ICR10_MASK (0x300000U)
#define GPIO_ICR1_ICR10_SHIFT (20U)
/*! ICR10 - Interrupt configuration field for GPIO interrupt 10
* 0b00..Interrupt 10 is low-level sensitive.
* 0b01..Interrupt 10 is high-level sensitive.
* 0b10..Interrupt 10 is rising-edge sensitive.
* 0b11..Interrupt 10 is falling-edge sensitive.
*/
#define GPIO_ICR1_ICR10(x) (((uint32_t)(((uint32_t)(x)) << GPIO_ICR1_ICR10_SHIFT)) & GPIO_ICR1_ICR10_MASK)
#define GPIO_ICR1_ICR11_MASK (0xC00000U)
#define GPIO_ICR1_ICR11_SHIFT (22U)
/*! ICR11 - Interrupt configuration field for GPIO interrupt 11
* 0b00..Interrupt 11 is low-level sensitive.
* 0b01..Interrupt 11 is high-level sensitive.
* 0b10..Interrupt 11 is rising-edge sensitive.
* 0b11..Interrupt 11 is falling-edge sensitive.
*/
#define GPIO_ICR1_ICR11(x) (((uint32_t)(((uint32_t)(x)) << GPIO_ICR1_ICR11_SHIFT)) & GPIO_ICR1_ICR11_MASK)
#define GPIO_ICR1_ICR12_MASK (0x3000000U)
#define GPIO_ICR1_ICR12_SHIFT (24U)
/*! ICR12 - Interrupt configuration field for GPIO interrupt 12
* 0b00..Interrupt 12 is low-level sensitive.
* 0b01..Interrupt 12 is high-level sensitive.
* 0b10..Interrupt 12 is rising-edge sensitive.
* 0b11..Interrupt 12 is falling-edge sensitive.
*/
#define GPIO_ICR1_ICR12(x) (((uint32_t)(((uint32_t)(x)) << GPIO_ICR1_ICR12_SHIFT)) & GPIO_ICR1_ICR12_MASK)
#define GPIO_ICR1_ICR13_MASK (0xC000000U)
#define GPIO_ICR1_ICR13_SHIFT (26U)
/*! ICR13 - Interrupt configuration field for GPIO interrupt 13
* 0b00..Interrupt 13 is low-level sensitive.
* 0b01..Interrupt 13 is high-level sensitive.
* 0b10..Interrupt 13 is rising-edge sensitive.
* 0b11..Interrupt 13 is falling-edge sensitive.
*/
#define GPIO_ICR1_ICR13(x) (((uint32_t)(((uint32_t)(x)) << GPIO_ICR1_ICR13_SHIFT)) & GPIO_ICR1_ICR13_MASK)
#define GPIO_ICR1_ICR14_MASK (0x30000000U)
#define GPIO_ICR1_ICR14_SHIFT (28U)
/*! ICR14 - Interrupt configuration field for GPIO interrupt 14
* 0b00..Interrupt 14 is low-level sensitive.
* 0b01..Interrupt 14 is high-level sensitive.
* 0b10..Interrupt 14 is rising-edge sensitive.
* 0b11..Interrupt 14 is falling-edge sensitive.
*/
#define GPIO_ICR1_ICR14(x) (((uint32_t)(((uint32_t)(x)) << GPIO_ICR1_ICR14_SHIFT)) & GPIO_ICR1_ICR14_MASK)
#define GPIO_ICR1_ICR15_MASK (0xC0000000U)
#define GPIO_ICR1_ICR15_SHIFT (30U)
/*! ICR15 - Interrupt configuration field for GPIO interrupt 15
* 0b00..Interrupt 15 is low-level sensitive.
* 0b01..Interrupt 15 is high-level sensitive.
* 0b10..Interrupt 15 is rising-edge sensitive.
* 0b11..Interrupt 15 is falling-edge sensitive.
*/
#define GPIO_ICR1_ICR15(x) (((uint32_t)(((uint32_t)(x)) << GPIO_ICR1_ICR15_SHIFT)) & GPIO_ICR1_ICR15_MASK)
/*! @} */
/*! @name ICR2 - GPIO interrupt configuration register2 */
/*! @{ */
#define GPIO_ICR2_ICR16_MASK (0x3U)
#define GPIO_ICR2_ICR16_SHIFT (0U)
/*! ICR16 - Interrupt configuration field for GPIO interrupt 16
* 0b00..Interrupt 16 is low-level sensitive.
* 0b01..Interrupt 16 is high-level sensitive.
* 0b10..Interrupt 16 is rising-edge sensitive.
* 0b11..Interrupt 16 is falling-edge sensitive.
*/
#define GPIO_ICR2_ICR16(x) (((uint32_t)(((uint32_t)(x)) << GPIO_ICR2_ICR16_SHIFT)) & GPIO_ICR2_ICR16_MASK)
#define GPIO_ICR2_ICR17_MASK (0xCU)
#define GPIO_ICR2_ICR17_SHIFT (2U)
/*! ICR17 - Interrupt configuration field for GPIO interrupt 17
* 0b00..Interrupt 17 is low-level sensitive.
* 0b01..Interrupt 17 is high-level sensitive.
* 0b10..Interrupt 17 is rising-edge sensitive.
* 0b11..Interrupt 17 is falling-edge sensitive.
*/
#define GPIO_ICR2_ICR17(x) (((uint32_t)(((uint32_t)(x)) << GPIO_ICR2_ICR17_SHIFT)) & GPIO_ICR2_ICR17_MASK)
#define GPIO_ICR2_ICR18_MASK (0x30U)
#define GPIO_ICR2_ICR18_SHIFT (4U)
/*! ICR18 - Interrupt configuration field for GPIO interrupt 18
* 0b00..Interrupt 18 is low-level sensitive.
* 0b01..Interrupt 18 is high-level sensitive.
* 0b10..Interrupt 18 is rising-edge sensitive.
* 0b11..Interrupt 18 is falling-edge sensitive.
*/
#define GPIO_ICR2_ICR18(x) (((uint32_t)(((uint32_t)(x)) << GPIO_ICR2_ICR18_SHIFT)) & GPIO_ICR2_ICR18_MASK)
#define GPIO_ICR2_ICR19_MASK (0xC0U)
#define GPIO_ICR2_ICR19_SHIFT (6U)
/*! ICR19 - Interrupt configuration field for GPIO interrupt 19
* 0b00..Interrupt 19 is low-level sensitive.
* 0b01..Interrupt 19 is high-level sensitive.
* 0b10..Interrupt 19 is rising-edge sensitive.
* 0b11..Interrupt 19 is falling-edge sensitive.
*/
#define GPIO_ICR2_ICR19(x) (((uint32_t)(((uint32_t)(x)) << GPIO_ICR2_ICR19_SHIFT)) & GPIO_ICR2_ICR19_MASK)
#define GPIO_ICR2_ICR20_MASK (0x300U)
#define GPIO_ICR2_ICR20_SHIFT (8U)
/*! ICR20 - Interrupt configuration field for GPIO interrupt 20
* 0b00..Interrupt 20 is low-level sensitive.
* 0b01..Interrupt 20 is high-level sensitive.
* 0b10..Interrupt 20 is rising-edge sensitive.
* 0b11..Interrupt 20 is falling-edge sensitive.
*/
#define GPIO_ICR2_ICR20(x) (((uint32_t)(((uint32_t)(x)) << GPIO_ICR2_ICR20_SHIFT)) & GPIO_ICR2_ICR20_MASK)
#define GPIO_ICR2_ICR21_MASK (0xC00U)
#define GPIO_ICR2_ICR21_SHIFT (10U)
/*! ICR21 - Interrupt configuration field for GPIO interrupt 21
* 0b00..Interrupt 21 is low-level sensitive.
* 0b01..Interrupt 21 is high-level sensitive.
* 0b10..Interrupt 21 is rising-edge sensitive.
* 0b11..Interrupt 21 is falling-edge sensitive.
*/
#define GPIO_ICR2_ICR21(x) (((uint32_t)(((uint32_t)(x)) << GPIO_ICR2_ICR21_SHIFT)) & GPIO_ICR2_ICR21_MASK)
#define GPIO_ICR2_ICR22_MASK (0x3000U)
#define GPIO_ICR2_ICR22_SHIFT (12U)
/*! ICR22 - Interrupt configuration field for GPIO interrupt 22
* 0b00..Interrupt 22 is low-level sensitive.
* 0b01..Interrupt 22 is high-level sensitive.
* 0b10..Interrupt 22 is rising-edge sensitive.
* 0b11..Interrupt 22 is falling-edge sensitive.
*/
#define GPIO_ICR2_ICR22(x) (((uint32_t)(((uint32_t)(x)) << GPIO_ICR2_ICR22_SHIFT)) & GPIO_ICR2_ICR22_MASK)
#define GPIO_ICR2_ICR23_MASK (0xC000U)
#define GPIO_ICR2_ICR23_SHIFT (14U)
/*! ICR23 - Interrupt configuration field for GPIO interrupt 23
* 0b00..Interrupt 23 is low-level sensitive.
* 0b01..Interrupt 23 is high-level sensitive.
* 0b10..Interrupt 23 is rising-edge sensitive.
* 0b11..Interrupt 23 is falling-edge sensitive.
*/
#define GPIO_ICR2_ICR23(x) (((uint32_t)(((uint32_t)(x)) << GPIO_ICR2_ICR23_SHIFT)) & GPIO_ICR2_ICR23_MASK)
#define GPIO_ICR2_ICR24_MASK (0x30000U)
#define GPIO_ICR2_ICR24_SHIFT (16U)
/*! ICR24 - Interrupt configuration field for GPIO interrupt 24
* 0b00..Interrupt 24 is low-level sensitive.
* 0b01..Interrupt 24 is high-level sensitive.
* 0b10..Interrupt 24 is rising-edge sensitive.
* 0b11..Interrupt 24 is falling-edge sensitive.
*/
#define GPIO_ICR2_ICR24(x) (((uint32_t)(((uint32_t)(x)) << GPIO_ICR2_ICR24_SHIFT)) & GPIO_ICR2_ICR24_MASK)
#define GPIO_ICR2_ICR25_MASK (0xC0000U)
#define GPIO_ICR2_ICR25_SHIFT (18U)
/*! ICR25 - Interrupt configuration field for GPIO interrupt 25
* 0b00..Interrupt 25 is low-level sensitive.
* 0b01..Interrupt 25 is high-level sensitive.
* 0b10..Interrupt 25 is rising-edge sensitive.
* 0b11..Interrupt 25 is falling-edge sensitive.
*/
#define GPIO_ICR2_ICR25(x) (((uint32_t)(((uint32_t)(x)) << GPIO_ICR2_ICR25_SHIFT)) & GPIO_ICR2_ICR25_MASK)
#define GPIO_ICR2_ICR26_MASK (0x300000U)
#define GPIO_ICR2_ICR26_SHIFT (20U)
/*! ICR26 - Interrupt configuration field for GPIO interrupt 26
* 0b00..Interrupt 26 is low-level sensitive.
* 0b01..Interrupt 26 is high-level sensitive.
* 0b10..Interrupt 26 is rising-edge sensitive.
* 0b11..Interrupt 26 is falling-edge sensitive.
*/
#define GPIO_ICR2_ICR26(x) (((uint32_t)(((uint32_t)(x)) << GPIO_ICR2_ICR26_SHIFT)) & GPIO_ICR2_ICR26_MASK)
#define GPIO_ICR2_ICR27_MASK (0xC00000U)
#define GPIO_ICR2_ICR27_SHIFT (22U)
/*! ICR27 - Interrupt configuration field for GPIO interrupt 27
* 0b00..Interrupt 27 is low-level sensitive.
* 0b01..Interrupt 27 is high-level sensitive.
* 0b10..Interrupt 27 is rising-edge sensitive.
* 0b11..Interrupt 27 is falling-edge sensitive.
*/
#define GPIO_ICR2_ICR27(x) (((uint32_t)(((uint32_t)(x)) << GPIO_ICR2_ICR27_SHIFT)) & GPIO_ICR2_ICR27_MASK)
#define GPIO_ICR2_ICR28_MASK (0x3000000U)
#define GPIO_ICR2_ICR28_SHIFT (24U)
/*! ICR28 - Interrupt configuration field for GPIO interrupt 28
* 0b00..Interrupt 28 is low-level sensitive.
* 0b01..Interrupt 28 is high-level sensitive.
* 0b10..Interrupt 28 is rising-edge sensitive.
* 0b11..Interrupt 28 is falling-edge sensitive.
*/
#define GPIO_ICR2_ICR28(x) (((uint32_t)(((uint32_t)(x)) << GPIO_ICR2_ICR28_SHIFT)) & GPIO_ICR2_ICR28_MASK)
#define GPIO_ICR2_ICR29_MASK (0xC000000U)
#define GPIO_ICR2_ICR29_SHIFT (26U)
/*! ICR29 - Interrupt configuration field for GPIO interrupt 29
* 0b00..Interrupt 29 is low-level sensitive.
* 0b01..Interrupt 29 is high-level sensitive.
* 0b10..Interrupt 29 is rising-edge sensitive.
* 0b11..Interrupt 29 is falling-edge sensitive.
*/
#define GPIO_ICR2_ICR29(x) (((uint32_t)(((uint32_t)(x)) << GPIO_ICR2_ICR29_SHIFT)) & GPIO_ICR2_ICR29_MASK)
#define GPIO_ICR2_ICR30_MASK (0x30000000U)
#define GPIO_ICR2_ICR30_SHIFT (28U)
/*! ICR30 - Interrupt configuration field for GPIO interrupt 30
* 0b00..Interrupt 30 is low-level sensitive.
* 0b01..Interrupt 30 is high-level sensitive.
* 0b10..Interrupt 30 is rising-edge sensitive.
* 0b11..Interrupt 30 is falling-edge sensitive.
*/
#define GPIO_ICR2_ICR30(x) (((uint32_t)(((uint32_t)(x)) << GPIO_ICR2_ICR30_SHIFT)) & GPIO_ICR2_ICR30_MASK)
#define GPIO_ICR2_ICR31_MASK (0xC0000000U)
#define GPIO_ICR2_ICR31_SHIFT (30U)
/*! ICR31 - Interrupt configuration field for GPIO interrupt 31
* 0b00..Interrupt 31 is low-level sensitive.
* 0b01..Interrupt 31 is high-level sensitive.
* 0b10..Interrupt 31 is rising-edge sensitive.
* 0b11..Interrupt 31 is falling-edge sensitive.
*/
#define GPIO_ICR2_ICR31(x) (((uint32_t)(((uint32_t)(x)) << GPIO_ICR2_ICR31_SHIFT)) & GPIO_ICR2_ICR31_MASK)
/*! @} */
/*! @name IMR - GPIO interrupt mask register */
/*! @{ */
#define GPIO_IMR_IMR_MASK (0xFFFFFFFFU)
#define GPIO_IMR_IMR_SHIFT (0U)
/*! IMR - Interrupt Mask bits */
#define GPIO_IMR_IMR(x) (((uint32_t)(((uint32_t)(x)) << GPIO_IMR_IMR_SHIFT)) & GPIO_IMR_IMR_MASK)
/*! @} */
/*! @name ISR - GPIO interrupt status register */
/*! @{ */
#define GPIO_ISR_ISR_MASK (0xFFFFFFFFU)
#define GPIO_ISR_ISR_SHIFT (0U)
/*! ISR - Interrupt status bits */
#define GPIO_ISR_ISR(x) (((uint32_t)(((uint32_t)(x)) << GPIO_ISR_ISR_SHIFT)) & GPIO_ISR_ISR_MASK)
/*! @} */
/*! @name EDGE_SEL - GPIO edge select register */
/*! @{ */
#define GPIO_EDGE_SEL_GPIO_EDGE_SEL_MASK (0xFFFFFFFFU)
#define GPIO_EDGE_SEL_GPIO_EDGE_SEL_SHIFT (0U)
/*! GPIO_EDGE_SEL - Edge select */
#define GPIO_EDGE_SEL_GPIO_EDGE_SEL(x) (((uint32_t)(((uint32_t)(x)) << GPIO_EDGE_SEL_GPIO_EDGE_SEL_SHIFT)) & GPIO_EDGE_SEL_GPIO_EDGE_SEL_MASK)
/*! @} */
/*! @name DR_SET - GPIO data register SET */
/*! @{ */
#define GPIO_DR_SET_DR_SET_MASK (0xFFFFFFFFU)
#define GPIO_DR_SET_DR_SET_SHIFT (0U)
/*! DR_SET - Set */
#define GPIO_DR_SET_DR_SET(x) (((uint32_t)(((uint32_t)(x)) << GPIO_DR_SET_DR_SET_SHIFT)) & GPIO_DR_SET_DR_SET_MASK)
/*! @} */
/*! @name DR_CLEAR - GPIO data register CLEAR */
/*! @{ */
#define GPIO_DR_CLEAR_DR_CLEAR_MASK (0xFFFFFFFFU)
#define GPIO_DR_CLEAR_DR_CLEAR_SHIFT (0U)
/*! DR_CLEAR - Clear */
#define GPIO_DR_CLEAR_DR_CLEAR(x) (((uint32_t)(((uint32_t)(x)) << GPIO_DR_CLEAR_DR_CLEAR_SHIFT)) & GPIO_DR_CLEAR_DR_CLEAR_MASK)
/*! @} */
/*! @name DR_TOGGLE - GPIO data register TOGGLE */
/*! @{ */
#define GPIO_DR_TOGGLE_DR_TOGGLE_MASK (0xFFFFFFFFU)
#define GPIO_DR_TOGGLE_DR_TOGGLE_SHIFT (0U)
/*! DR_TOGGLE - Toggle */
#define GPIO_DR_TOGGLE_DR_TOGGLE(x) (((uint32_t)(((uint32_t)(x)) << GPIO_DR_TOGGLE_DR_TOGGLE_SHIFT)) & GPIO_DR_TOGGLE_DR_TOGGLE_MASK)
/*! @} */
/*!
* @}
*/ /* end of group GPIO_Register_Masks */
/*!
* @}
*/ /* end of group GPIO_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 */
#endif /* GPIO_H_ */

View File

@ -0,0 +1,514 @@
/*
** ###################################################################
** Processors: MIMXRT1061CVJ5A
** MIMXRT1061CVJ5B
** MIMXRT1061CVL5A
** MIMXRT1061CVL5B
** MIMXRT1061DVJ6A
** MIMXRT1061DVJ6B
** MIMXRT1061DVL6A
** MIMXRT1061DVL6B
** MIMXRT1061XVN5B
** MIMXRT1062CVJ5A
** MIMXRT1062CVJ5B
** MIMXRT1062CVL5A
** MIMXRT1062CVL5B
** MIMXRT1062DVJ6A
** MIMXRT1062DVJ6B
** MIMXRT1062DVL6A
** MIMXRT1062DVL6B
** MIMXRT1062DVN6B
** MIMXRT1062XVN5B
** MIMXRT106ADVL6A
** MIMXRT106CDVL6A
** MIMXRT106FDVL6A
** MIMXRT106LDVL6A
** MIMXRT106SDVL6A
**
** Version: rev. 1.4, 2022-03-25
** Build: b240705
**
** Abstract:
** CMSIS Peripheral Access Layer for GPT
**
** Copyright 1997-2016 Freescale Semiconductor, Inc.
** Copyright 2016-2024 NXP
** SPDX-License-Identifier: BSD-3-Clause
**
** http: www.nxp.com
** mail: support@nxp.com
**
** Revisions:
** - rev. 0.1 (2017-01-10)
** Initial version.
** - rev. 1.0 (2018-11-16)
** Update header files to align with IMXRT1060RM Rev.0.
** - rev. 1.1 (2018-11-27)
** Update header files to align with IMXRT1060RM Rev.1.
** - rev. 1.2 (2019-04-29)
** Add SET/CLR/TOG register group to register CTRL, STAT, CHANNELCTRL, CH0STAT, CH0OPTS, CH1STAT, CH1OPTS, CH2STAT, CH2OPTS, CH3STAT, CH3OPTS of DCP module.
** - rev. 1.3 (2021-08-10)
** Update header files to align with IMXRT1060RM Rev.3.
** - rev. 1.4 (2022-03-25)
** Add RT1060X device
**
** ###################################################################
*/
/*!
* @file GPT.h
* @version 1.4
* @date 2022-03-25
* @brief CMSIS Peripheral Access Layer for GPT
*
* CMSIS Peripheral Access Layer for GPT
*/
#if !defined(GPT_H_)
#define GPT_H_ /**< Symbol preventing repeated inclusion */
#if (defined(CPU_MIMXRT1061CVJ5A) || defined(CPU_MIMXRT1061CVJ5B) || defined(CPU_MIMXRT1061CVL5A) || defined(CPU_MIMXRT1061CVL5B) || defined(CPU_MIMXRT1061DVJ6A) || defined(CPU_MIMXRT1061DVJ6B) || defined(CPU_MIMXRT1061DVL6A) || defined(CPU_MIMXRT1061DVL6B) || defined(CPU_MIMXRT1061XVN5B))
#include "MIMXRT1061_COMMON.h"
#elif (defined(CPU_MIMXRT1062CVJ5A) || defined(CPU_MIMXRT1062CVJ5B) || defined(CPU_MIMXRT1062CVL5A) || defined(CPU_MIMXRT1062CVL5B) || defined(CPU_MIMXRT1062DVJ6A) || defined(CPU_MIMXRT1062DVJ6B) || defined(CPU_MIMXRT1062DVL6A) || defined(CPU_MIMXRT1062DVL6B) || defined(CPU_MIMXRT1062DVN6B) || defined(CPU_MIMXRT1062XVN5B))
#include "MIMXRT1062_COMMON.h"
#elif (defined(CPU_MIMXRT106ADVL6A))
#include "MIMXRT106A_COMMON.h"
#elif (defined(CPU_MIMXRT106CDVL6A))
#include "MIMXRT106C_COMMON.h"
#elif (defined(CPU_MIMXRT106FDVL6A))
#include "MIMXRT106F_COMMON.h"
#elif (defined(CPU_MIMXRT106LDVL6A))
#include "MIMXRT106L_COMMON.h"
#elif (defined(CPU_MIMXRT106SDVL6A))
#include "MIMXRT106S_COMMON.h"
#else
#error "No valid CPU defined!"
#endif
/* ----------------------------------------------------------------------------
-- 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
/* ----------------------------------------------------------------------------
-- GPT Peripheral Access Layer
---------------------------------------------------------------------------- */
/*!
* @addtogroup GPT_Peripheral_Access_Layer GPT Peripheral Access Layer
* @{
*/
/** GPT - Size of Registers Arrays */
#define GPT_OCR_COUNT 3u
#define GPT_ICR_COUNT 2u
/** GPT - Register Layout Typedef */
typedef struct {
__IO uint32_t CR; /**< GPT Control Register, offset: 0x0 */
__IO uint32_t PR; /**< GPT Prescaler Register, offset: 0x4 */
__IO uint32_t SR; /**< GPT Status Register, offset: 0x8 */
__IO uint32_t IR; /**< GPT Interrupt Register, offset: 0xC */
__IO uint32_t OCR[GPT_OCR_COUNT]; /**< GPT Output Compare Register, array offset: 0x10, array step: 0x4 */
__I uint32_t ICR[GPT_ICR_COUNT]; /**< GPT Input Capture Register, array offset: 0x1C, array step: 0x4 */
__I uint32_t CNT; /**< GPT Counter Register, offset: 0x24 */
} GPT_Type;
/* ----------------------------------------------------------------------------
-- GPT Register Masks
---------------------------------------------------------------------------- */
/*!
* @addtogroup GPT_Register_Masks GPT Register Masks
* @{
*/
/*! @name CR - GPT Control Register */
/*! @{ */
#define GPT_CR_EN_MASK (0x1U)
#define GPT_CR_EN_SHIFT (0U)
/*! EN - GPT Enable
* 0b0..Disable
* 0b1..Enable
*/
#define GPT_CR_EN(x) (((uint32_t)(((uint32_t)(x)) << GPT_CR_EN_SHIFT)) & GPT_CR_EN_MASK)
#define GPT_CR_ENMOD_MASK (0x2U)
#define GPT_CR_ENMOD_SHIFT (1U)
/*! ENMOD - GPT Enable Mode
* 0b0..Restart counting from their frozen values after GPT is enabled (EN=1).
* 0b1..Reset counting from 0 after GPT is enabled (EN=1).
*/
#define GPT_CR_ENMOD(x) (((uint32_t)(((uint32_t)(x)) << GPT_CR_ENMOD_SHIFT)) & GPT_CR_ENMOD_MASK)
#define GPT_CR_DBGEN_MASK (0x4U)
#define GPT_CR_DBGEN_SHIFT (2U)
/*! DBGEN - GPT Debug Mode Enable
* 0b0..Disable in Debug mode
* 0b1..Enable in Debug mode
*/
#define GPT_CR_DBGEN(x) (((uint32_t)(((uint32_t)(x)) << GPT_CR_DBGEN_SHIFT)) & GPT_CR_DBGEN_MASK)
#define GPT_CR_WAITEN_MASK (0x8U)
#define GPT_CR_WAITEN_SHIFT (3U)
/*! WAITEN - GPT Wait Mode Enable
* 0b0..Disable in Wait mode
* 0b1..Enable in Wait mode
*/
#define GPT_CR_WAITEN(x) (((uint32_t)(((uint32_t)(x)) << GPT_CR_WAITEN_SHIFT)) & GPT_CR_WAITEN_MASK)
#define GPT_CR_DOZEEN_MASK (0x10U)
#define GPT_CR_DOZEEN_SHIFT (4U)
/*! DOZEEN - GPT Doze Mode Enable
* 0b0..Disable in Doze mode
* 0b1..Enable in Doze mode
*/
#define GPT_CR_DOZEEN(x) (((uint32_t)(((uint32_t)(x)) << GPT_CR_DOZEEN_SHIFT)) & GPT_CR_DOZEEN_MASK)
#define GPT_CR_STOPEN_MASK (0x20U)
#define GPT_CR_STOPEN_SHIFT (5U)
/*! STOPEN - GPT Stop Mode Enable
* 0b0..Disable in Stop mode
* 0b1..Enable in Stop mode
*/
#define GPT_CR_STOPEN(x) (((uint32_t)(((uint32_t)(x)) << GPT_CR_STOPEN_SHIFT)) & GPT_CR_STOPEN_MASK)
#define GPT_CR_CLKSRC_MASK (0x1C0U)
#define GPT_CR_CLKSRC_SHIFT (6U)
/*! CLKSRC - Clock Source Select
* 0b000..No clock
* 0b001..Peripheral Clock (ipg_clk)
* 0b010..High Frequency Reference Clock (ipg_clk_highfreq)
* 0b011..External Clock
* 0b100..Low Frequency Reference Clock (ipg_clk_32k)
* 0b101..Oscillator as Reference Clock (ipg_clk_24M)
*/
#define GPT_CR_CLKSRC(x) (((uint32_t)(((uint32_t)(x)) << GPT_CR_CLKSRC_SHIFT)) & GPT_CR_CLKSRC_MASK)
#define GPT_CR_FRR_MASK (0x200U)
#define GPT_CR_FRR_SHIFT (9U)
/*! FRR - Free-Run or Restart Mode
* 0b0..Restart mode. After a compare event, the counter resets to 0x0000_0000 and resumes counting.
* 0b1..Free-Run mode. After a compare event, the counter continues counting until 0xFFFF_FFFF and then rolls over to 0.
*/
#define GPT_CR_FRR(x) (((uint32_t)(((uint32_t)(x)) << GPT_CR_FRR_SHIFT)) & GPT_CR_FRR_MASK)
#define GPT_CR_EN_24M_MASK (0x400U)
#define GPT_CR_EN_24M_SHIFT (10U)
/*! EN_24M - Enable Oscillator Clock Input
* 0b0..Disable
* 0b1..Enable
*/
#define GPT_CR_EN_24M(x) (((uint32_t)(((uint32_t)(x)) << GPT_CR_EN_24M_SHIFT)) & GPT_CR_EN_24M_MASK)
#define GPT_CR_SWR_MASK (0x8000U)
#define GPT_CR_SWR_SHIFT (15U)
/*! SWR - Software Reset
* 0b0..GPT is not in software reset state
* 0b1..GPT is in software reset state
*/
#define GPT_CR_SWR(x) (((uint32_t)(((uint32_t)(x)) << GPT_CR_SWR_SHIFT)) & GPT_CR_SWR_MASK)
#define GPT_CR_IM1_MASK (0x30000U)
#define GPT_CR_IM1_SHIFT (16U)
/*! IM1 - Input Capture Operating Mode for Channel 1
* 0b00..Capture disabled
* 0b01..Capture on rising edge only
* 0b10..Capture on falling edge only
* 0b11..Capture on both edges
*/
#define GPT_CR_IM1(x) (((uint32_t)(((uint32_t)(x)) << GPT_CR_IM1_SHIFT)) & GPT_CR_IM1_MASK)
#define GPT_CR_IM2_MASK (0xC0000U)
#define GPT_CR_IM2_SHIFT (18U)
/*! IM2 - Input Capture Operating Mode for Channel 2
* 0b00..Capture disabled
* 0b01..Capture on rising edge only
* 0b10..Capture on falling edge only
* 0b11..Capture on both edges
*/
#define GPT_CR_IM2(x) (((uint32_t)(((uint32_t)(x)) << GPT_CR_IM2_SHIFT)) & GPT_CR_IM2_MASK)
#define GPT_CR_OM1_MASK (0x700000U)
#define GPT_CR_OM1_SHIFT (20U)
/*! OM1 - Output Compare Operating Mode for Channel 1
* 0b000..Output disabled. No response on pin.
* 0b001..Toggle output pin
* 0b010..Clear output pin
* 0b011..Set output pin
* 0b1xx..Generate a low pulse that is one input clock cycle wide on the output pin. When OMn is first programmed
* as 1xx, the output pin is set to one immediately on the next input clock (if it was not one already).
* "Input clock" here refers to the clock selected by the CLKSRC field of this register.
*/
#define GPT_CR_OM1(x) (((uint32_t)(((uint32_t)(x)) << GPT_CR_OM1_SHIFT)) & GPT_CR_OM1_MASK)
#define GPT_CR_OM2_MASK (0x3800000U)
#define GPT_CR_OM2_SHIFT (23U)
/*! OM2 - Output Compare Operating Mode for Channel 2
* 0b000..Output disabled. No response on pin.
* 0b001..Toggle output pin
* 0b010..Clear output pin
* 0b011..Set output pin
* 0b1xx..Generate a low pulse that is one input clock cycle wide on the output pin. When OMn is first programmed
* as 1xx, the output pin is set to one immediately on the next input clock (if it was not one already).
* "Input clock" here refers to the clock selected by the CLKSRC field of this register.
*/
#define GPT_CR_OM2(x) (((uint32_t)(((uint32_t)(x)) << GPT_CR_OM2_SHIFT)) & GPT_CR_OM2_MASK)
#define GPT_CR_OM3_MASK (0x1C000000U)
#define GPT_CR_OM3_SHIFT (26U)
/*! OM3 - Output Compare Operating Mode for Channel 3
* 0b000..Output disabled. No response on pin.
* 0b001..Toggle output pin
* 0b010..Clear output pin
* 0b011..Set output pin
* 0b1xx..Generate a low pulse that is one input clock cycle wide on the output pin. When OMn is first programmed
* as 1xx, the output pin is set to one immediately on the next input clock (if it was not one already).
* "Input clock" here refers to the clock selected by the CLKSRC field of this register.
*/
#define GPT_CR_OM3(x) (((uint32_t)(((uint32_t)(x)) << GPT_CR_OM3_SHIFT)) & GPT_CR_OM3_MASK)
#define GPT_CR_FO1_MASK (0x20000000U)
#define GPT_CR_FO1_SHIFT (29U)
/*! FO1 - Force Output Compare for Channel 1
* 0b0..No effect
* 0b1..Trigger the programmed response on the pin
*/
#define GPT_CR_FO1(x) (((uint32_t)(((uint32_t)(x)) << GPT_CR_FO1_SHIFT)) & GPT_CR_FO1_MASK)
#define GPT_CR_FO2_MASK (0x40000000U)
#define GPT_CR_FO2_SHIFT (30U)
/*! FO2 - Force Output Compare for Channel 2
* 0b0..No effect
* 0b1..Trigger the programmed response on the pin
*/
#define GPT_CR_FO2(x) (((uint32_t)(((uint32_t)(x)) << GPT_CR_FO2_SHIFT)) & GPT_CR_FO2_MASK)
#define GPT_CR_FO3_MASK (0x80000000U)
#define GPT_CR_FO3_SHIFT (31U)
/*! FO3 - Force Output Compare for Channel 3
* 0b0..No effect
* 0b1..Trigger the programmed response on the pin
*/
#define GPT_CR_FO3(x) (((uint32_t)(((uint32_t)(x)) << GPT_CR_FO3_SHIFT)) & GPT_CR_FO3_MASK)
/*! @} */
/*! @name PR - GPT Prescaler Register */
/*! @{ */
#define GPT_PR_PRESCALER_MASK (0xFFFU)
#define GPT_PR_PRESCALER_SHIFT (0U)
/*! PRESCALER - Prescaler divide value
* 0b000000000000..Divide by 1
* 0b000000000001..Divide by 2
* 0b111111111111..Divide by 4096
*/
#define GPT_PR_PRESCALER(x) (((uint32_t)(((uint32_t)(x)) << GPT_PR_PRESCALER_SHIFT)) & GPT_PR_PRESCALER_MASK)
#define GPT_PR_PRESCALER24M_MASK (0xF000U)
#define GPT_PR_PRESCALER24M_SHIFT (12U)
/*! PRESCALER24M - Prescaler divide value for the oscillator clock
* 0b0000..Divide by 1
* 0b0001..Divide by 2
* 0b1111..Divide by 16
*/
#define GPT_PR_PRESCALER24M(x) (((uint32_t)(((uint32_t)(x)) << GPT_PR_PRESCALER24M_SHIFT)) & GPT_PR_PRESCALER24M_MASK)
/*! @} */
/*! @name SR - GPT Status Register */
/*! @{ */
#define GPT_SR_OF1_MASK (0x1U)
#define GPT_SR_OF1_SHIFT (0U)
/*! OF1 - Output Compare Flag for Channel 1
* 0b0..Compare event has not occurred.
* 0b1..Compare event has occurred.
*/
#define GPT_SR_OF1(x) (((uint32_t)(((uint32_t)(x)) << GPT_SR_OF1_SHIFT)) & GPT_SR_OF1_MASK)
#define GPT_SR_OF2_MASK (0x2U)
#define GPT_SR_OF2_SHIFT (1U)
/*! OF2 - Output Compare Flag for Channel 2
* 0b0..Compare event has not occurred.
* 0b1..Compare event has occurred.
*/
#define GPT_SR_OF2(x) (((uint32_t)(((uint32_t)(x)) << GPT_SR_OF2_SHIFT)) & GPT_SR_OF2_MASK)
#define GPT_SR_OF3_MASK (0x4U)
#define GPT_SR_OF3_SHIFT (2U)
/*! OF3 - Output Compare Flag for Channel 3
* 0b0..Compare event has not occurred.
* 0b1..Compare event has occurred.
*/
#define GPT_SR_OF3(x) (((uint32_t)(((uint32_t)(x)) << GPT_SR_OF3_SHIFT)) & GPT_SR_OF3_MASK)
#define GPT_SR_IF1_MASK (0x8U)
#define GPT_SR_IF1_SHIFT (3U)
/*! IF1 - Input Capture Flag for Channel 1
* 0b0..Capture event has not occurred.
* 0b1..Capture event has occurred.
*/
#define GPT_SR_IF1(x) (((uint32_t)(((uint32_t)(x)) << GPT_SR_IF1_SHIFT)) & GPT_SR_IF1_MASK)
#define GPT_SR_IF2_MASK (0x10U)
#define GPT_SR_IF2_SHIFT (4U)
/*! IF2 - Input Capture Flag for Channel 2
* 0b0..Capture event has not occurred.
* 0b1..Capture event has occurred.
*/
#define GPT_SR_IF2(x) (((uint32_t)(((uint32_t)(x)) << GPT_SR_IF2_SHIFT)) & GPT_SR_IF2_MASK)
#define GPT_SR_ROV_MASK (0x20U)
#define GPT_SR_ROV_SHIFT (5U)
/*! ROV - Rollover Flag
* 0b0..Rollover has not occurred.
* 0b1..Rollover has occurred.
*/
#define GPT_SR_ROV(x) (((uint32_t)(((uint32_t)(x)) << GPT_SR_ROV_SHIFT)) & GPT_SR_ROV_MASK)
/*! @} */
/*! @name IR - GPT Interrupt Register */
/*! @{ */
#define GPT_IR_OF1IE_MASK (0x1U)
#define GPT_IR_OF1IE_SHIFT (0U)
/*! OF1IE - Output Compare Flag for Channel 1 Interrupt Enable
* 0b0..Disable
* 0b1..Enable
*/
#define GPT_IR_OF1IE(x) (((uint32_t)(((uint32_t)(x)) << GPT_IR_OF1IE_SHIFT)) & GPT_IR_OF1IE_MASK)
#define GPT_IR_OF2IE_MASK (0x2U)
#define GPT_IR_OF2IE_SHIFT (1U)
/*! OF2IE - Output Compare Flag for Channel 2 Interrupt Enable
* 0b0..Disable
* 0b1..Enable
*/
#define GPT_IR_OF2IE(x) (((uint32_t)(((uint32_t)(x)) << GPT_IR_OF2IE_SHIFT)) & GPT_IR_OF2IE_MASK)
#define GPT_IR_OF3IE_MASK (0x4U)
#define GPT_IR_OF3IE_SHIFT (2U)
/*! OF3IE - Output Compare Flag for Channel 3 Interrupt Enable
* 0b0..Disable
* 0b1..Enable
*/
#define GPT_IR_OF3IE(x) (((uint32_t)(((uint32_t)(x)) << GPT_IR_OF3IE_SHIFT)) & GPT_IR_OF3IE_MASK)
#define GPT_IR_IF1IE_MASK (0x8U)
#define GPT_IR_IF1IE_SHIFT (3U)
/*! IF1IE - Input Capture Flag for Channel 1 Interrupt Enable
* 0b0..Disable
* 0b1..Enable
*/
#define GPT_IR_IF1IE(x) (((uint32_t)(((uint32_t)(x)) << GPT_IR_IF1IE_SHIFT)) & GPT_IR_IF1IE_MASK)
#define GPT_IR_IF2IE_MASK (0x10U)
#define GPT_IR_IF2IE_SHIFT (4U)
/*! IF2IE - Input Capture Flag for Channel 2 Interrupt Enable
* 0b0..Disable
* 0b1..Enable
*/
#define GPT_IR_IF2IE(x) (((uint32_t)(((uint32_t)(x)) << GPT_IR_IF2IE_SHIFT)) & GPT_IR_IF2IE_MASK)
#define GPT_IR_ROVIE_MASK (0x20U)
#define GPT_IR_ROVIE_SHIFT (5U)
/*! ROVIE - Rollover Interrupt Enable
* 0b0..Disable
* 0b1..Enable
*/
#define GPT_IR_ROVIE(x) (((uint32_t)(((uint32_t)(x)) << GPT_IR_ROVIE_SHIFT)) & GPT_IR_ROVIE_MASK)
/*! @} */
/*! @name OCR - GPT Output Compare Register */
/*! @{ */
#define GPT_OCR_COMP_MASK (0xFFFFFFFFU)
#define GPT_OCR_COMP_SHIFT (0U)
/*! COMP - Compare Value */
#define GPT_OCR_COMP(x) (((uint32_t)(((uint32_t)(x)) << GPT_OCR_COMP_SHIFT)) & GPT_OCR_COMP_MASK)
/*! @} */
/*! @name ICR - GPT Input Capture Register */
/*! @{ */
#define GPT_ICR_CAPT_MASK (0xFFFFFFFFU)
#define GPT_ICR_CAPT_SHIFT (0U)
/*! CAPT - Capture Value */
#define GPT_ICR_CAPT(x) (((uint32_t)(((uint32_t)(x)) << GPT_ICR_CAPT_SHIFT)) & GPT_ICR_CAPT_MASK)
/*! @} */
/*! @name CNT - GPT Counter Register */
/*! @{ */
#define GPT_CNT_COUNT_MASK (0xFFFFFFFFU)
#define GPT_CNT_COUNT_SHIFT (0U)
/*! COUNT - Counter Value */
#define GPT_CNT_COUNT(x) (((uint32_t)(((uint32_t)(x)) << GPT_CNT_COUNT_SHIFT)) & GPT_CNT_COUNT_MASK)
/*! @} */
/*!
* @}
*/ /* end of group GPT_Register_Masks */
/*!
* @}
*/ /* end of group GPT_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 */
#endif /* GPT_H_ */

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,946 @@
/*
** ###################################################################
** Processors: MIMXRT1061CVJ5A
** MIMXRT1061CVJ5B
** MIMXRT1061CVL5A
** MIMXRT1061CVL5B
** MIMXRT1061DVJ6A
** MIMXRT1061DVJ6B
** MIMXRT1061DVL6A
** MIMXRT1061DVL6B
** MIMXRT1061XVN5B
** MIMXRT1062CVJ5A
** MIMXRT1062CVJ5B
** MIMXRT1062CVL5A
** MIMXRT1062CVL5B
** MIMXRT1062DVJ6A
** MIMXRT1062DVJ6B
** MIMXRT1062DVL6A
** MIMXRT1062DVL6B
** MIMXRT1062DVN6B
** MIMXRT1062XVN5B
** MIMXRT106ADVL6A
** MIMXRT106CDVL6A
** MIMXRT106FDVL6A
** MIMXRT106LDVL6A
** MIMXRT106SDVL6A
**
** Version: rev. 1.4, 2022-03-25
** Build: b240705
**
** Abstract:
** CMSIS Peripheral Access Layer for IOMUXC
**
** Copyright 1997-2016 Freescale Semiconductor, Inc.
** Copyright 2016-2024 NXP
** SPDX-License-Identifier: BSD-3-Clause
**
** http: www.nxp.com
** mail: support@nxp.com
**
** Revisions:
** - rev. 0.1 (2017-01-10)
** Initial version.
** - rev. 1.0 (2018-11-16)
** Update header files to align with IMXRT1060RM Rev.0.
** - rev. 1.1 (2018-11-27)
** Update header files to align with IMXRT1060RM Rev.1.
** - rev. 1.2 (2019-04-29)
** Add SET/CLR/TOG register group to register CTRL, STAT, CHANNELCTRL, CH0STAT, CH0OPTS, CH1STAT, CH1OPTS, CH2STAT, CH2OPTS, CH3STAT, CH3OPTS of DCP module.
** - rev. 1.3 (2021-08-10)
** Update header files to align with IMXRT1060RM Rev.3.
** - rev. 1.4 (2022-03-25)
** Add RT1060X device
**
** ###################################################################
*/
/*!
* @file IOMUXC.h
* @version 1.4
* @date 2022-03-25
* @brief CMSIS Peripheral Access Layer for IOMUXC
*
* CMSIS Peripheral Access Layer for IOMUXC
*/
#if !defined(IOMUXC_H_)
#define IOMUXC_H_ /**< Symbol preventing repeated inclusion */
#if (defined(CPU_MIMXRT1061CVJ5A) || defined(CPU_MIMXRT1061CVJ5B) || defined(CPU_MIMXRT1061CVL5A) || defined(CPU_MIMXRT1061CVL5B) || defined(CPU_MIMXRT1061DVJ6A) || defined(CPU_MIMXRT1061DVJ6B) || defined(CPU_MIMXRT1061DVL6A) || defined(CPU_MIMXRT1061DVL6B) || defined(CPU_MIMXRT1061XVN5B))
#include "MIMXRT1061_COMMON.h"
#elif (defined(CPU_MIMXRT1062CVJ5A) || defined(CPU_MIMXRT1062CVJ5B) || defined(CPU_MIMXRT1062CVL5A) || defined(CPU_MIMXRT1062CVL5B) || defined(CPU_MIMXRT1062DVJ6A) || defined(CPU_MIMXRT1062DVJ6B) || defined(CPU_MIMXRT1062DVL6A) || defined(CPU_MIMXRT1062DVL6B) || defined(CPU_MIMXRT1062DVN6B) || defined(CPU_MIMXRT1062XVN5B))
#include "MIMXRT1062_COMMON.h"
#elif (defined(CPU_MIMXRT106ADVL6A))
#include "MIMXRT106A_COMMON.h"
#elif (defined(CPU_MIMXRT106CDVL6A))
#include "MIMXRT106C_COMMON.h"
#elif (defined(CPU_MIMXRT106FDVL6A))
#include "MIMXRT106F_COMMON.h"
#elif (defined(CPU_MIMXRT106LDVL6A))
#include "MIMXRT106L_COMMON.h"
#elif (defined(CPU_MIMXRT106SDVL6A))
#include "MIMXRT106S_COMMON.h"
#else
#error "No valid CPU defined!"
#endif
/* ----------------------------------------------------------------------------
-- Mapping Information
---------------------------------------------------------------------------- */
/*!
* @addtogroup Mapping_Information Mapping Information
* @{
*/
/** Mapping Information */
#if !defined(IOMUXC_SW_MUX_CTL_PAD_T_)
#define IOMUXC_SW_MUX_CTL_PAD_T_
/*!
* @addtogroup iomuxc_pads
* @{ */
/*******************************************************************************
* Definitions
*******************************************************************************/
/*!
* @brief Enumeration for the IOMUXC SW_MUX_CTL_PAD
*
* Defines the enumeration for the IOMUXC SW_MUX_CTL_PAD collections.
*/
typedef enum _iomuxc_sw_mux_ctl_pad
{
kIOMUXC_SW_MUX_CTL_PAD_GPIO_EMC_00 = 0U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_EMC_01 = 1U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_EMC_02 = 2U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_EMC_03 = 3U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_EMC_04 = 4U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_EMC_05 = 5U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_EMC_06 = 6U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_EMC_07 = 7U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_EMC_08 = 8U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_EMC_09 = 9U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_EMC_10 = 10U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_EMC_11 = 11U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_EMC_12 = 12U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_EMC_13 = 13U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_EMC_14 = 14U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_EMC_15 = 15U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_EMC_16 = 16U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_EMC_17 = 17U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_EMC_18 = 18U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_EMC_19 = 19U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_EMC_20 = 20U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_EMC_21 = 21U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_EMC_22 = 22U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_EMC_23 = 23U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_EMC_24 = 24U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_EMC_25 = 25U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_EMC_26 = 26U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_EMC_27 = 27U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_EMC_28 = 28U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_EMC_29 = 29U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_EMC_30 = 30U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_EMC_31 = 31U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_EMC_32 = 32U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_EMC_33 = 33U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_EMC_34 = 34U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_EMC_35 = 35U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_EMC_36 = 36U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_EMC_37 = 37U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_EMC_38 = 38U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_EMC_39 = 39U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_EMC_40 = 40U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_EMC_41 = 41U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_AD_B0_00 = 42U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_AD_B0_01 = 43U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_AD_B0_02 = 44U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_AD_B0_03 = 45U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_AD_B0_04 = 46U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_AD_B0_05 = 47U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_AD_B0_06 = 48U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_AD_B0_07 = 49U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_AD_B0_08 = 50U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_AD_B0_09 = 51U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_AD_B0_10 = 52U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_AD_B0_11 = 53U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_AD_B0_12 = 54U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_AD_B0_13 = 55U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_AD_B0_14 = 56U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_AD_B0_15 = 57U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_AD_B1_00 = 58U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_AD_B1_01 = 59U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_AD_B1_02 = 60U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_AD_B1_03 = 61U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_AD_B1_04 = 62U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_AD_B1_05 = 63U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_AD_B1_06 = 64U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_AD_B1_07 = 65U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_AD_B1_08 = 66U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_AD_B1_09 = 67U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_AD_B1_10 = 68U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_AD_B1_11 = 69U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_AD_B1_12 = 70U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_AD_B1_13 = 71U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_AD_B1_14 = 72U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_AD_B1_15 = 73U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_B0_00 = 74U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_B0_01 = 75U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_B0_02 = 76U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_B0_03 = 77U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_B0_04 = 78U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_B0_05 = 79U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_B0_06 = 80U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_B0_07 = 81U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_B0_08 = 82U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_B0_09 = 83U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_B0_10 = 84U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_B0_11 = 85U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_B0_12 = 86U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_B0_13 = 87U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_B0_14 = 88U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_B0_15 = 89U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_B1_00 = 90U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_B1_01 = 91U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_B1_02 = 92U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_B1_03 = 93U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_B1_04 = 94U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_B1_05 = 95U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_B1_06 = 96U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_B1_07 = 97U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_B1_08 = 98U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_B1_09 = 99U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_B1_10 = 100U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_B1_11 = 101U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_B1_12 = 102U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_B1_13 = 103U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_B1_14 = 104U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_B1_15 = 105U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_SD_B0_00 = 106U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_SD_B0_01 = 107U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_SD_B0_02 = 108U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_SD_B0_03 = 109U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_SD_B0_04 = 110U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_SD_B0_05 = 111U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_SD_B1_00 = 112U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_SD_B1_01 = 113U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_SD_B1_02 = 114U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_SD_B1_03 = 115U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_SD_B1_04 = 116U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_SD_B1_05 = 117U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_SD_B1_06 = 118U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_SD_B1_07 = 119U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_SD_B1_08 = 120U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_SD_B1_09 = 121U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_SD_B1_10 = 122U, /**< IOMUXC SW_MUX_CTL_PAD index */
kIOMUXC_SW_MUX_CTL_PAD_GPIO_SD_B1_11 = 123U, /**< IOMUXC SW_MUX_CTL_PAD index */
} iomuxc_sw_mux_ctl_pad_t;
/* @} */
#endif /* IOMUXC_SW_MUX_CTL_PAD_T_ */
#if !defined(IOMUXC_SW_PAD_CTL_PAD_T_)
#define IOMUXC_SW_PAD_CTL_PAD_T_
/*!
* @addtogroup iomuxc_pads
* @{ */
/*******************************************************************************
* Definitions
*******************************************************************************/
/*!
* @brief Enumeration for the IOMUXC SW_PAD_CTL_PAD
*
* Defines the enumeration for the IOMUXC SW_PAD_CTL_PAD collections.
*/
typedef enum _iomuxc_sw_pad_ctl_pad
{
kIOMUXC_SW_PAD_CTL_PAD_GPIO_EMC_00 = 0U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_EMC_01 = 1U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_EMC_02 = 2U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_EMC_03 = 3U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_EMC_04 = 4U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_EMC_05 = 5U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_EMC_06 = 6U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_EMC_07 = 7U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_EMC_08 = 8U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_EMC_09 = 9U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_EMC_10 = 10U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_EMC_11 = 11U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_EMC_12 = 12U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_EMC_13 = 13U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_EMC_14 = 14U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_EMC_15 = 15U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_EMC_16 = 16U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_EMC_17 = 17U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_EMC_18 = 18U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_EMC_19 = 19U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_EMC_20 = 20U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_EMC_21 = 21U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_EMC_22 = 22U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_EMC_23 = 23U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_EMC_24 = 24U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_EMC_25 = 25U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_EMC_26 = 26U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_EMC_27 = 27U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_EMC_28 = 28U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_EMC_29 = 29U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_EMC_30 = 30U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_EMC_31 = 31U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_EMC_32 = 32U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_EMC_33 = 33U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_EMC_34 = 34U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_EMC_35 = 35U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_EMC_36 = 36U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_EMC_37 = 37U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_EMC_38 = 38U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_EMC_39 = 39U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_EMC_40 = 40U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_EMC_41 = 41U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_AD_B0_00 = 42U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_AD_B0_01 = 43U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_AD_B0_02 = 44U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_AD_B0_03 = 45U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_AD_B0_04 = 46U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_AD_B0_05 = 47U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_AD_B0_06 = 48U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_AD_B0_07 = 49U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_AD_B0_08 = 50U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_AD_B0_09 = 51U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_AD_B0_10 = 52U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_AD_B0_11 = 53U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_AD_B0_12 = 54U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_AD_B0_13 = 55U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_AD_B0_14 = 56U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_AD_B0_15 = 57U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_AD_B1_00 = 58U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_AD_B1_01 = 59U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_AD_B1_02 = 60U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_AD_B1_03 = 61U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_AD_B1_04 = 62U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_AD_B1_05 = 63U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_AD_B1_06 = 64U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_AD_B1_07 = 65U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_AD_B1_08 = 66U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_AD_B1_09 = 67U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_AD_B1_10 = 68U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_AD_B1_11 = 69U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_AD_B1_12 = 70U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_AD_B1_13 = 71U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_AD_B1_14 = 72U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_AD_B1_15 = 73U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_B0_00 = 74U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_B0_01 = 75U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_B0_02 = 76U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_B0_03 = 77U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_B0_04 = 78U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_B0_05 = 79U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_B0_06 = 80U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_B0_07 = 81U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_B0_08 = 82U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_B0_09 = 83U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_B0_10 = 84U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_B0_11 = 85U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_B0_12 = 86U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_B0_13 = 87U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_B0_14 = 88U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_B0_15 = 89U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_B1_00 = 90U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_B1_01 = 91U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_B1_02 = 92U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_B1_03 = 93U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_B1_04 = 94U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_B1_05 = 95U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_B1_06 = 96U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_B1_07 = 97U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_B1_08 = 98U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_B1_09 = 99U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_B1_10 = 100U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_B1_11 = 101U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_B1_12 = 102U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_B1_13 = 103U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_B1_14 = 104U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_B1_15 = 105U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_SD_B0_00 = 106U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_SD_B0_01 = 107U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_SD_B0_02 = 108U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_SD_B0_03 = 109U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_SD_B0_04 = 110U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_SD_B0_05 = 111U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_SD_B1_00 = 112U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_SD_B1_01 = 113U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_SD_B1_02 = 114U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_SD_B1_03 = 115U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_SD_B1_04 = 116U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_SD_B1_05 = 117U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_SD_B1_06 = 118U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_SD_B1_07 = 119U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_SD_B1_08 = 120U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_SD_B1_09 = 121U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_SD_B1_10 = 122U, /**< IOMUXC SW_PAD_CTL_PAD index */
kIOMUXC_SW_PAD_CTL_PAD_GPIO_SD_B1_11 = 123U, /**< IOMUXC SW_PAD_CTL_PAD index */
} iomuxc_sw_pad_ctl_pad_t;
/* @} */
#endif /* IOMUXC_SW_PAD_CTL_PAD_T_ */
#if !defined(IOMUXC_SELECT_INPUT_T_)
#define IOMUXC_SELECT_INPUT_T_
/*!
* @brief Enumeration for the IOMUXC select input
*
* Defines the enumeration for the IOMUXC select input collections.
*/
typedef enum _iomuxc_select_input
{
kIOMUXC_ANATOP_USB_OTG1_ID_SELECT_INPUT = 0U, /**< IOMUXC select input index */
kIOMUXC_ANATOP_USB_OTG2_ID_SELECT_INPUT = 1U, /**< IOMUXC select input index */
kIOMUXC_CCM_PMIC_READY_SELECT_INPUT = 2U, /**< IOMUXC select input index */
kIOMUXC_CSI_DATA02_SELECT_INPUT = 3U, /**< IOMUXC select input index */
kIOMUXC_CSI_DATA03_SELECT_INPUT = 4U, /**< IOMUXC select input index */
kIOMUXC_CSI_DATA04_SELECT_INPUT = 5U, /**< IOMUXC select input index */
kIOMUXC_CSI_DATA05_SELECT_INPUT = 6U, /**< IOMUXC select input index */
kIOMUXC_CSI_DATA06_SELECT_INPUT = 7U, /**< IOMUXC select input index */
kIOMUXC_CSI_DATA07_SELECT_INPUT = 8U, /**< IOMUXC select input index */
kIOMUXC_CSI_DATA08_SELECT_INPUT = 9U, /**< IOMUXC select input index */
kIOMUXC_CSI_DATA09_SELECT_INPUT = 10U, /**< IOMUXC select input index */
kIOMUXC_CSI_HSYNC_SELECT_INPUT = 11U, /**< IOMUXC select input index */
kIOMUXC_CSI_PIXCLK_SELECT_INPUT = 12U, /**< IOMUXC select input index */
kIOMUXC_CSI_VSYNC_SELECT_INPUT = 13U, /**< IOMUXC select input index */
kIOMUXC_ENET_IPG_CLK_RMII_SELECT_INPUT = 14U, /**< IOMUXC select input index */
kIOMUXC_ENET_MDIO_SELECT_INPUT = 15U, /**< IOMUXC select input index */
kIOMUXC_ENET0_RXDATA_SELECT_INPUT = 16U, /**< IOMUXC select input index */
kIOMUXC_ENET1_RXDATA_SELECT_INPUT = 17U, /**< IOMUXC select input index */
kIOMUXC_ENET_RXEN_SELECT_INPUT = 18U, /**< IOMUXC select input index */
kIOMUXC_ENET_RXERR_SELECT_INPUT = 19U, /**< IOMUXC select input index */
kIOMUXC_ENET0_TIMER_SELECT_INPUT = 20U, /**< IOMUXC select input index */
kIOMUXC_ENET_TXCLK_SELECT_INPUT = 21U, /**< IOMUXC select input index */
kIOMUXC_FLEXCAN1_RX_SELECT_INPUT = 22U, /**< IOMUXC select input index */
kIOMUXC_FLEXCAN2_RX_SELECT_INPUT = 23U, /**< IOMUXC select input index */
kIOMUXC_FLEXPWM1_PWMA3_SELECT_INPUT = 24U, /**< IOMUXC select input index */
kIOMUXC_FLEXPWM1_PWMA0_SELECT_INPUT = 25U, /**< IOMUXC select input index */
kIOMUXC_FLEXPWM1_PWMA1_SELECT_INPUT = 26U, /**< IOMUXC select input index */
kIOMUXC_FLEXPWM1_PWMA2_SELECT_INPUT = 27U, /**< IOMUXC select input index */
kIOMUXC_FLEXPWM1_PWMB3_SELECT_INPUT = 28U, /**< IOMUXC select input index */
kIOMUXC_FLEXPWM1_PWMB0_SELECT_INPUT = 29U, /**< IOMUXC select input index */
kIOMUXC_FLEXPWM1_PWMB1_SELECT_INPUT = 30U, /**< IOMUXC select input index */
kIOMUXC_FLEXPWM1_PWMB2_SELECT_INPUT = 31U, /**< IOMUXC select input index */
kIOMUXC_FLEXPWM2_PWMA3_SELECT_INPUT = 32U, /**< IOMUXC select input index */
kIOMUXC_FLEXPWM2_PWMA0_SELECT_INPUT = 33U, /**< IOMUXC select input index */
kIOMUXC_FLEXPWM2_PWMA1_SELECT_INPUT = 34U, /**< IOMUXC select input index */
kIOMUXC_FLEXPWM2_PWMA2_SELECT_INPUT = 35U, /**< IOMUXC select input index */
kIOMUXC_FLEXPWM2_PWMB3_SELECT_INPUT = 36U, /**< IOMUXC select input index */
kIOMUXC_FLEXPWM2_PWMB0_SELECT_INPUT = 37U, /**< IOMUXC select input index */
kIOMUXC_FLEXPWM2_PWMB1_SELECT_INPUT = 38U, /**< IOMUXC select input index */
kIOMUXC_FLEXPWM2_PWMB2_SELECT_INPUT = 39U, /**< IOMUXC select input index */
kIOMUXC_FLEXPWM4_PWMA0_SELECT_INPUT = 40U, /**< IOMUXC select input index */
kIOMUXC_FLEXPWM4_PWMA1_SELECT_INPUT = 41U, /**< IOMUXC select input index */
kIOMUXC_FLEXPWM4_PWMA2_SELECT_INPUT = 42U, /**< IOMUXC select input index */
kIOMUXC_FLEXPWM4_PWMA3_SELECT_INPUT = 43U, /**< IOMUXC select input index */
kIOMUXC_FLEXSPIA_DQS_SELECT_INPUT = 44U, /**< IOMUXC select input index */
kIOMUXC_FLEXSPIA_DATA0_SELECT_INPUT = 45U, /**< IOMUXC select input index */
kIOMUXC_FLEXSPIA_DATA1_SELECT_INPUT = 46U, /**< IOMUXC select input index */
kIOMUXC_FLEXSPIA_DATA2_SELECT_INPUT = 47U, /**< IOMUXC select input index */
kIOMUXC_FLEXSPIA_DATA3_SELECT_INPUT = 48U, /**< IOMUXC select input index */
kIOMUXC_FLEXSPIB_DATA0_SELECT_INPUT = 49U, /**< IOMUXC select input index */
kIOMUXC_FLEXSPIB_DATA1_SELECT_INPUT = 50U, /**< IOMUXC select input index */
kIOMUXC_FLEXSPIB_DATA2_SELECT_INPUT = 51U, /**< IOMUXC select input index */
kIOMUXC_FLEXSPIB_DATA3_SELECT_INPUT = 52U, /**< IOMUXC select input index */
kIOMUXC_FLEXSPIA_SCK_SELECT_INPUT = 53U, /**< IOMUXC select input index */
kIOMUXC_LPI2C1_SCL_SELECT_INPUT = 54U, /**< IOMUXC select input index */
kIOMUXC_LPI2C1_SDA_SELECT_INPUT = 55U, /**< IOMUXC select input index */
kIOMUXC_LPI2C2_SCL_SELECT_INPUT = 56U, /**< IOMUXC select input index */
kIOMUXC_LPI2C2_SDA_SELECT_INPUT = 57U, /**< IOMUXC select input index */
kIOMUXC_LPI2C3_SCL_SELECT_INPUT = 58U, /**< IOMUXC select input index */
kIOMUXC_LPI2C3_SDA_SELECT_INPUT = 59U, /**< IOMUXC select input index */
kIOMUXC_LPI2C4_SCL_SELECT_INPUT = 60U, /**< IOMUXC select input index */
kIOMUXC_LPI2C4_SDA_SELECT_INPUT = 61U, /**< IOMUXC select input index */
kIOMUXC_LPSPI1_PCS0_SELECT_INPUT = 62U, /**< IOMUXC select input index */
kIOMUXC_LPSPI1_SCK_SELECT_INPUT = 63U, /**< IOMUXC select input index */
kIOMUXC_LPSPI1_SDI_SELECT_INPUT = 64U, /**< IOMUXC select input index */
kIOMUXC_LPSPI1_SDO_SELECT_INPUT = 65U, /**< IOMUXC select input index */
kIOMUXC_LPSPI2_PCS0_SELECT_INPUT = 66U, /**< IOMUXC select input index */
kIOMUXC_LPSPI2_SCK_SELECT_INPUT = 67U, /**< IOMUXC select input index */
kIOMUXC_LPSPI2_SDI_SELECT_INPUT = 68U, /**< IOMUXC select input index */
kIOMUXC_LPSPI2_SDO_SELECT_INPUT = 69U, /**< IOMUXC select input index */
kIOMUXC_LPSPI3_PCS0_SELECT_INPUT = 70U, /**< IOMUXC select input index */
kIOMUXC_LPSPI3_SCK_SELECT_INPUT = 71U, /**< IOMUXC select input index */
kIOMUXC_LPSPI3_SDI_SELECT_INPUT = 72U, /**< IOMUXC select input index */
kIOMUXC_LPSPI3_SDO_SELECT_INPUT = 73U, /**< IOMUXC select input index */
kIOMUXC_LPSPI4_PCS0_SELECT_INPUT = 74U, /**< IOMUXC select input index */
kIOMUXC_LPSPI4_SCK_SELECT_INPUT = 75U, /**< IOMUXC select input index */
kIOMUXC_LPSPI4_SDI_SELECT_INPUT = 76U, /**< IOMUXC select input index */
kIOMUXC_LPSPI4_SDO_SELECT_INPUT = 77U, /**< IOMUXC select input index */
kIOMUXC_LPUART2_RX_SELECT_INPUT = 78U, /**< IOMUXC select input index */
kIOMUXC_LPUART2_TX_SELECT_INPUT = 79U, /**< IOMUXC select input index */
kIOMUXC_LPUART3_CTS_B_SELECT_INPUT = 80U, /**< IOMUXC select input index */
kIOMUXC_LPUART3_RX_SELECT_INPUT = 81U, /**< IOMUXC select input index */
kIOMUXC_LPUART3_TX_SELECT_INPUT = 82U, /**< IOMUXC select input index */
kIOMUXC_LPUART4_RX_SELECT_INPUT = 83U, /**< IOMUXC select input index */
kIOMUXC_LPUART4_TX_SELECT_INPUT = 84U, /**< IOMUXC select input index */
kIOMUXC_LPUART5_RX_SELECT_INPUT = 85U, /**< IOMUXC select input index */
kIOMUXC_LPUART5_TX_SELECT_INPUT = 86U, /**< IOMUXC select input index */
kIOMUXC_LPUART6_RX_SELECT_INPUT = 87U, /**< IOMUXC select input index */
kIOMUXC_LPUART6_TX_SELECT_INPUT = 88U, /**< IOMUXC select input index */
kIOMUXC_LPUART7_RX_SELECT_INPUT = 89U, /**< IOMUXC select input index */
kIOMUXC_LPUART7_TX_SELECT_INPUT = 90U, /**< IOMUXC select input index */
kIOMUXC_LPUART8_RX_SELECT_INPUT = 91U, /**< IOMUXC select input index */
kIOMUXC_LPUART8_TX_SELECT_INPUT = 92U, /**< IOMUXC select input index */
kIOMUXC_NMI_SELECT_INPUT = 93U, /**< IOMUXC select input index */
kIOMUXC_QTIMER2_TIMER0_SELECT_INPUT = 94U, /**< IOMUXC select input index */
kIOMUXC_QTIMER2_TIMER1_SELECT_INPUT = 95U, /**< IOMUXC select input index */
kIOMUXC_QTIMER2_TIMER2_SELECT_INPUT = 96U, /**< IOMUXC select input index */
kIOMUXC_QTIMER2_TIMER3_SELECT_INPUT = 97U, /**< IOMUXC select input index */
kIOMUXC_QTIMER3_TIMER0_SELECT_INPUT = 98U, /**< IOMUXC select input index */
kIOMUXC_QTIMER3_TIMER1_SELECT_INPUT = 99U, /**< IOMUXC select input index */
kIOMUXC_QTIMER3_TIMER2_SELECT_INPUT = 100U, /**< IOMUXC select input index */
kIOMUXC_QTIMER3_TIMER3_SELECT_INPUT = 101U, /**< IOMUXC select input index */
kIOMUXC_SAI1_MCLK2_SELECT_INPUT = 102U, /**< IOMUXC select input index */
kIOMUXC_SAI1_RX_BCLK_SELECT_INPUT = 103U, /**< IOMUXC select input index */
kIOMUXC_SAI1_RX_DATA0_SELECT_INPUT = 104U, /**< IOMUXC select input index */
kIOMUXC_SAI1_RX_DATA1_SELECT_INPUT = 105U, /**< IOMUXC select input index */
kIOMUXC_SAI1_RX_DATA2_SELECT_INPUT = 106U, /**< IOMUXC select input index */
kIOMUXC_SAI1_RX_DATA3_SELECT_INPUT = 107U, /**< IOMUXC select input index */
kIOMUXC_SAI1_RX_SYNC_SELECT_INPUT = 108U, /**< IOMUXC select input index */
kIOMUXC_SAI1_TX_BCLK_SELECT_INPUT = 109U, /**< IOMUXC select input index */
kIOMUXC_SAI1_TX_SYNC_SELECT_INPUT = 110U, /**< IOMUXC select input index */
kIOMUXC_SAI2_MCLK2_SELECT_INPUT = 111U, /**< IOMUXC select input index */
kIOMUXC_SAI2_RX_BCLK_SELECT_INPUT = 112U, /**< IOMUXC select input index */
kIOMUXC_SAI2_RX_DATA0_SELECT_INPUT = 113U, /**< IOMUXC select input index */
kIOMUXC_SAI2_RX_SYNC_SELECT_INPUT = 114U, /**< IOMUXC select input index */
kIOMUXC_SAI2_TX_BCLK_SELECT_INPUT = 115U, /**< IOMUXC select input index */
kIOMUXC_SAI2_TX_SYNC_SELECT_INPUT = 116U, /**< IOMUXC select input index */
kIOMUXC_SPDIF_IN_SELECT_INPUT = 117U, /**< IOMUXC select input index */
kIOMUXC_USB_OTG2_OC_SELECT_INPUT = 118U, /**< IOMUXC select input index */
kIOMUXC_USB_OTG1_OC_SELECT_INPUT = 119U, /**< IOMUXC select input index */
kIOMUXC_USDHC1_CD_B_SELECT_INPUT = 120U, /**< IOMUXC select input index */
kIOMUXC_USDHC1_WP_SELECT_INPUT = 121U, /**< IOMUXC select input index */
kIOMUXC_USDHC2_CLK_SELECT_INPUT = 122U, /**< IOMUXC select input index */
kIOMUXC_USDHC2_CD_B_SELECT_INPUT = 123U, /**< IOMUXC select input index */
kIOMUXC_USDHC2_CMD_SELECT_INPUT = 124U, /**< IOMUXC select input index */
kIOMUXC_USDHC2_DATA0_SELECT_INPUT = 125U, /**< IOMUXC select input index */
kIOMUXC_USDHC2_DATA1_SELECT_INPUT = 126U, /**< IOMUXC select input index */
kIOMUXC_USDHC2_DATA2_SELECT_INPUT = 127U, /**< IOMUXC select input index */
kIOMUXC_USDHC2_DATA3_SELECT_INPUT = 128U, /**< IOMUXC select input index */
kIOMUXC_USDHC2_DATA4_SELECT_INPUT = 129U, /**< IOMUXC select input index */
kIOMUXC_USDHC2_DATA5_SELECT_INPUT = 130U, /**< IOMUXC select input index */
kIOMUXC_USDHC2_DATA6_SELECT_INPUT = 131U, /**< IOMUXC select input index */
kIOMUXC_USDHC2_DATA7_SELECT_INPUT = 132U, /**< IOMUXC select input index */
kIOMUXC_USDHC2_WP_SELECT_INPUT = 133U, /**< IOMUXC select input index */
kIOMUXC_XBAR1_IN02_SELECT_INPUT = 134U, /**< IOMUXC select input index */
kIOMUXC_XBAR1_IN03_SELECT_INPUT = 135U, /**< IOMUXC select input index */
kIOMUXC_XBAR1_IN04_SELECT_INPUT = 136U, /**< IOMUXC select input index */
kIOMUXC_XBAR1_IN05_SELECT_INPUT = 137U, /**< IOMUXC select input index */
kIOMUXC_XBAR1_IN06_SELECT_INPUT = 138U, /**< IOMUXC select input index */
kIOMUXC_XBAR1_IN07_SELECT_INPUT = 139U, /**< IOMUXC select input index */
kIOMUXC_XBAR1_IN08_SELECT_INPUT = 140U, /**< IOMUXC select input index */
kIOMUXC_XBAR1_IN09_SELECT_INPUT = 141U, /**< IOMUXC select input index */
kIOMUXC_XBAR1_IN17_SELECT_INPUT = 142U, /**< IOMUXC select input index */
kIOMUXC_XBAR1_IN18_SELECT_INPUT = 143U, /**< IOMUXC select input index */
kIOMUXC_XBAR1_IN20_SELECT_INPUT = 144U, /**< IOMUXC select input index */
kIOMUXC_XBAR1_IN22_SELECT_INPUT = 145U, /**< IOMUXC select input index */
kIOMUXC_XBAR1_IN23_SELECT_INPUT = 146U, /**< IOMUXC select input index */
kIOMUXC_XBAR1_IN24_SELECT_INPUT = 147U, /**< IOMUXC select input index */
kIOMUXC_XBAR1_IN14_SELECT_INPUT = 148U, /**< IOMUXC select input index */
kIOMUXC_XBAR1_IN15_SELECT_INPUT = 149U, /**< IOMUXC select input index */
kIOMUXC_XBAR1_IN16_SELECT_INPUT = 150U, /**< IOMUXC select input index */
kIOMUXC_XBAR1_IN25_SELECT_INPUT = 151U, /**< IOMUXC select input index */
kIOMUXC_XBAR1_IN19_SELECT_INPUT = 152U, /**< IOMUXC select input index */
kIOMUXC_XBAR1_IN21_SELECT_INPUT = 153U, /**< IOMUXC select input index */
} iomuxc_select_input_t;
#endif /* IOMUXC_SELECT_INPUT_T_ */
#if !defined(IOMUXC_SELECT_INPUT_1_T_)
#define IOMUXC_SELECT_INPUT_1_T_
/*!
* @brief Enumeration for the IOMUXC select input
*
* Defines the enumeration for the IOMUXC select input collections.
*/
typedef enum _iomuxc_select_input_1
{
kIOMUXC_ENET2_IPG_CLK_RMII_SELECT_INPUT = 0U, /**< IOMUXC select input index */
kIOMUXC_ENET2_IPP_IND_MAC0_MDIO_SELECT_INPUT = 1U, /**< IOMUXC select input index */
kIOMUXC_ENET2_IPP_IND_MAC0_RXDATA_SELECT_INPUT_0 = 2U, /**< IOMUXC select input index */
kIOMUXC_ENET2_IPP_IND_MAC0_RXDATA_SELECT_INPUT_1 = 3U, /**< IOMUXC select input index */
kIOMUXC_ENET2_IPP_IND_MAC0_RXEN_SELECT_INPUT = 4U, /**< IOMUXC select input index */
kIOMUXC_ENET2_IPP_IND_MAC0_RXERR_SELECT_INPUT = 5U, /**< IOMUXC select input index */
kIOMUXC_ENET2_IPP_IND_MAC0_TIMER_SELECT_INPUT_0 = 6U, /**< IOMUXC select input index */
kIOMUXC_ENET2_IPP_IND_MAC0_TXCLK_SELECT_INPUT = 7U, /**< IOMUXC select input index */
kIOMUXC_FLEXSPI2_IPP_IND_DQS_FA_SELECT_INPUT = 8U, /**< IOMUXC select input index */
kIOMUXC_FLEXSPI2_IPP_IND_IO_FA_BIT0_SELECT_INPUT = 9U, /**< IOMUXC select input index */
kIOMUXC_FLEXSPI2_IPP_IND_IO_FA_BIT1_SELECT_INPUT = 10U, /**< IOMUXC select input index */
kIOMUXC_FLEXSPI2_IPP_IND_IO_FA_BIT2_SELECT_INPUT = 11U, /**< IOMUXC select input index */
kIOMUXC_FLEXSPI2_IPP_IND_IO_FA_BIT3_SELECT_INPUT = 12U, /**< IOMUXC select input index */
kIOMUXC_FLEXSPI2_IPP_IND_IO_FB_BIT0_SELECT_INPUT = 13U, /**< IOMUXC select input index */
kIOMUXC_FLEXSPI2_IPP_IND_IO_FB_BIT1_SELECT_INPUT = 14U, /**< IOMUXC select input index */
kIOMUXC_FLEXSPI2_IPP_IND_IO_FB_BIT2_SELECT_INPUT = 15U, /**< IOMUXC select input index */
kIOMUXC_FLEXSPI2_IPP_IND_IO_FB_BIT3_SELECT_INPUT = 16U, /**< IOMUXC select input index */
kIOMUXC_FLEXSPI2_IPP_IND_SCK_FA_SELECT_INPUT = 17U, /**< IOMUXC select input index */
kIOMUXC_FLEXSPI2_IPP_IND_SCK_FB_SELECT_INPUT = 18U, /**< IOMUXC select input index */
kIOMUXC_GPT1_IPP_IND_CAPIN1_SELECT_INPUT = 19U, /**< IOMUXC select input index */
kIOMUXC_GPT1_IPP_IND_CAPIN2_SELECT_INPUT = 20U, /**< IOMUXC select input index */
kIOMUXC_GPT1_IPP_IND_CLKIN_SELECT_INPUT = 21U, /**< IOMUXC select input index */
kIOMUXC_GPT2_IPP_IND_CAPIN1_SELECT_INPUT = 22U, /**< IOMUXC select input index */
kIOMUXC_GPT2_IPP_IND_CAPIN2_SELECT_INPUT = 23U, /**< IOMUXC select input index */
kIOMUXC_GPT2_IPP_IND_CLKIN_SELECT_INPUT = 24U, /**< IOMUXC select input index */
kIOMUXC_SAI3_IPG_CLK_SAI_MCLK_SELECT_INPUT_2 = 25U, /**< IOMUXC select input index */
kIOMUXC_SAI3_IPP_IND_SAI_RXBCLK_SELECT_INPUT = 26U, /**< IOMUXC select input index */
kIOMUXC_SAI3_IPP_IND_SAI_RXDATA_SELECT_INPUT_0 = 27U, /**< IOMUXC select input index */
kIOMUXC_SAI3_IPP_IND_SAI_RXSYNC_SELECT_INPUT = 28U, /**< IOMUXC select input index */
kIOMUXC_SAI3_IPP_IND_SAI_TXBCLK_SELECT_INPUT = 29U, /**< IOMUXC select input index */
kIOMUXC_SAI3_IPP_IND_SAI_TXSYNC_SELECT_INPUT = 30U, /**< IOMUXC select input index */
kIOMUXC_SEMC_I_IPP_IND_DQS4_SELECT_INPUT = 31U, /**< IOMUXC select input index */
kIOMUXC_CANFD_IPP_IND_CANRX_SELECT_INPUT = 32U, /**< IOMUXC select input index */
} iomuxc_select_input_1_t;
#endif /* IOMUXC_SELECT_INPUT_1_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
/* ----------------------------------------------------------------------------
-- IOMUXC Peripheral Access Layer
---------------------------------------------------------------------------- */
/*!
* @addtogroup IOMUXC_Peripheral_Access_Layer IOMUXC Peripheral Access Layer
* @{
*/
/** IOMUXC - Size of Registers Arrays */
#define IOMUXC_SW_MUX_CTL_PAD_COUNT 124u
#define IOMUXC_SW_PAD_CTL_PAD_COUNT 124u
#define IOMUXC_SELECT_INPUT_COUNT 154u
#define IOMUXC_SW_MUX_CTL_PAD_1_COUNT 22u
#define IOMUXC_SW_PAD_CTL_PAD_1_COUNT 22u
#define IOMUXC_SELECT_INPUT_1_COUNT 33u
/** IOMUXC - Register Layout Typedef */
typedef struct {
uint8_t RESERVED_0[20];
__IO uint32_t SW_MUX_CTL_PAD[IOMUXC_SW_MUX_CTL_PAD_COUNT]; /**< SW_MUX_CTL_PAD_GPIO_EMC_00 SW MUX Control Register..SW_MUX_CTL_PAD_GPIO_SD_B1_11 SW MUX Control Register, array offset: 0x14, array step: 0x4 */
__IO uint32_t SW_PAD_CTL_PAD[IOMUXC_SW_PAD_CTL_PAD_COUNT]; /**< SW_PAD_CTL_PAD_GPIO_EMC_00 SW PAD Control Register..SW_PAD_CTL_PAD_GPIO_SD_B1_11 SW PAD Control Register, array offset: 0x204, array step: 0x4 */
__IO uint32_t SELECT_INPUT[IOMUXC_SELECT_INPUT_COUNT]; /**< ANATOP_USB_OTG1_ID_SELECT_INPUT DAISY Register..XBAR1_IN23_SELECT_INPUT DAISY Register, array offset: 0x3F4, array step: 0x4 */
__IO uint32_t SW_MUX_CTL_PAD_1[IOMUXC_SW_MUX_CTL_PAD_1_COUNT]; /**< SW_MUX_CTL_PAD_GPIO_SPI_B0_00 SW MUX Control Register..SW_MUX_CTL_PAD_GPIO_SPI_B1_07 SW MUX Control Register, array offset: 0x65C, array step: 0x4 */
__IO uint32_t SW_PAD_CTL_PAD_1[IOMUXC_SW_PAD_CTL_PAD_1_COUNT]; /**< SW_PAD_CTL_PAD_GPIO_SPI_B0_00 SW PAD Control Register..SW_PAD_CTL_PAD_GPIO_SPI_B1_07 SW PAD Control Register, array offset: 0x6B4, array step: 0x4 */
__IO uint32_t SELECT_INPUT_1[IOMUXC_SELECT_INPUT_1_COUNT]; /**< ENET2_IPG_CLK_RMII_SELECT_INPUT DAISY Register..CANFD_IPP_IND_CANRX_SELECT_INPUT DAISY Register, array offset: 0x70C, array step: 0x4 */
} IOMUXC_Type;
/* ----------------------------------------------------------------------------
-- IOMUXC Register Masks
---------------------------------------------------------------------------- */
/*!
* @addtogroup IOMUXC_Register_Masks IOMUXC Register Masks
* @{
*/
/*! @name SW_MUX_CTL_PAD - SW_MUX_CTL_PAD_GPIO_EMC_00 SW MUX Control Register..SW_MUX_CTL_PAD_GPIO_SD_B1_11 SW MUX Control Register */
/*! @{ */
#define IOMUXC_SW_MUX_CTL_PAD_MUX_MODE_MASK (0xFU) /* Merged from fields with different position or width, of widths (3, 4), largest definition used */
#define IOMUXC_SW_MUX_CTL_PAD_MUX_MODE_SHIFT (0U)
/*! MUX_MODE - MUX Mode Select Field.
* 0b0000..Select mux mode: ALT0 mux port: USB_OTG1_PWR of instance: usb
* 0b0001..Select mux mode: ALT1 mux port: QTIMER3_TIMER1 of instance: qtimer3
* 0b0010..Select mux mode: ALT2 mux port: LPUART2_RTS_B of instance: lpuart2
* 0b0011..Select mux mode: ALT3 mux port: LPI2C1_SDA of instance: lpi2c1
* 0b0100..Select mux mode: ALT4 mux port: CCM_PMIC_READY of instance: ccm
* 0b0101..Select mux mode: ALT5 mux port: GPIO1_IO17 of instance: gpio1
* 0b0110..Select mux mode: ALT6 mux port: USDHC1_VSELECT of instance: usdhc1
* 0b0111..Select mux mode: ALT7 mux port: KPP_COL07 of instance: kpp
* 0b1000..Select mux mode: ALT8 mux port: ENET2_1588_EVENT0_IN of instance: enet2
* 0b1001..Select mux mode: ALT9 mux port: FLEXIO3_FLEXIO01 of instance: flexio3
*/
#define IOMUXC_SW_MUX_CTL_PAD_MUX_MODE(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SW_MUX_CTL_PAD_MUX_MODE_SHIFT)) & IOMUXC_SW_MUX_CTL_PAD_MUX_MODE_MASK) /* Merged from fields with different position or width, of widths (3, 4), largest definition used */
#define IOMUXC_SW_MUX_CTL_PAD_SION_MASK (0x10U)
#define IOMUXC_SW_MUX_CTL_PAD_SION_SHIFT (4U)
/*! SION - Software Input On Field.
* 0b1..Force input path of pad GPIO_AD_B0_00
* 0b0..Input Path is determined by functionality
*/
#define IOMUXC_SW_MUX_CTL_PAD_SION(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SW_MUX_CTL_PAD_SION_SHIFT)) & IOMUXC_SW_MUX_CTL_PAD_SION_MASK)
/*! @} */
/*! @name SW_PAD_CTL_PAD - SW_PAD_CTL_PAD_GPIO_EMC_00 SW PAD Control Register..SW_PAD_CTL_PAD_GPIO_SD_B1_11 SW PAD Control Register */
/*! @{ */
#define IOMUXC_SW_PAD_CTL_PAD_SRE_MASK (0x1U)
#define IOMUXC_SW_PAD_CTL_PAD_SRE_SHIFT (0U)
/*! SRE - Slew Rate Field
* 0b0..Slow Slew Rate
* 0b1..Fast Slew Rate
*/
#define IOMUXC_SW_PAD_CTL_PAD_SRE(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SW_PAD_CTL_PAD_SRE_SHIFT)) & IOMUXC_SW_PAD_CTL_PAD_SRE_MASK)
#define IOMUXC_SW_PAD_CTL_PAD_DSE_MASK (0x38U)
#define IOMUXC_SW_PAD_CTL_PAD_DSE_SHIFT (3U)
/*! DSE - Drive Strength Field
* 0b000..output driver disabled;
* 0b001..R0(150 Ohm @ 3.3V, 260 Ohm@1.8V)
* 0b010..R0/2
* 0b011..R0/3
* 0b100..R0/4
* 0b101..R0/5
* 0b110..R0/6
* 0b111..R0/7
*/
#define IOMUXC_SW_PAD_CTL_PAD_DSE(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SW_PAD_CTL_PAD_DSE_SHIFT)) & IOMUXC_SW_PAD_CTL_PAD_DSE_MASK)
#define IOMUXC_SW_PAD_CTL_PAD_SPEED_MASK (0xC0U)
#define IOMUXC_SW_PAD_CTL_PAD_SPEED_SHIFT (6U)
/*! SPEED - Speed Field
* 0b00..low(50MHz)
* 0b01..medium(100MHz)
* 0b10..fast(150MHz)
* 0b11..max(200MHz)
*/
#define IOMUXC_SW_PAD_CTL_PAD_SPEED(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SW_PAD_CTL_PAD_SPEED_SHIFT)) & IOMUXC_SW_PAD_CTL_PAD_SPEED_MASK)
#define IOMUXC_SW_PAD_CTL_PAD_ODE_MASK (0x800U)
#define IOMUXC_SW_PAD_CTL_PAD_ODE_SHIFT (11U)
/*! ODE - Open Drain Enable Field
* 0b0..Open Drain Disabled
* 0b1..Open Drain Enabled
*/
#define IOMUXC_SW_PAD_CTL_PAD_ODE(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SW_PAD_CTL_PAD_ODE_SHIFT)) & IOMUXC_SW_PAD_CTL_PAD_ODE_MASK)
#define IOMUXC_SW_PAD_CTL_PAD_PKE_MASK (0x1000U)
#define IOMUXC_SW_PAD_CTL_PAD_PKE_SHIFT (12U)
/*! PKE - Pull / Keep Enable Field
* 0b0..Pull/Keeper Disabled
* 0b1..Pull/Keeper Enabled
*/
#define IOMUXC_SW_PAD_CTL_PAD_PKE(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SW_PAD_CTL_PAD_PKE_SHIFT)) & IOMUXC_SW_PAD_CTL_PAD_PKE_MASK)
#define IOMUXC_SW_PAD_CTL_PAD_PUE_MASK (0x2000U)
#define IOMUXC_SW_PAD_CTL_PAD_PUE_SHIFT (13U)
/*! PUE - Pull / Keep Select Field
* 0b0..Keeper
* 0b1..Pull
*/
#define IOMUXC_SW_PAD_CTL_PAD_PUE(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SW_PAD_CTL_PAD_PUE_SHIFT)) & IOMUXC_SW_PAD_CTL_PAD_PUE_MASK)
#define IOMUXC_SW_PAD_CTL_PAD_PUS_MASK (0xC000U)
#define IOMUXC_SW_PAD_CTL_PAD_PUS_SHIFT (14U)
/*! PUS - Pull Up / Down Config. Field
* 0b00..100K Ohm Pull Down
* 0b01..47K Ohm Pull Up
* 0b10..100K Ohm Pull Up
* 0b11..22K Ohm Pull Up
*/
#define IOMUXC_SW_PAD_CTL_PAD_PUS(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SW_PAD_CTL_PAD_PUS_SHIFT)) & IOMUXC_SW_PAD_CTL_PAD_PUS_MASK)
#define IOMUXC_SW_PAD_CTL_PAD_HYS_MASK (0x10000U)
#define IOMUXC_SW_PAD_CTL_PAD_HYS_SHIFT (16U)
/*! HYS - Hyst. Enable Field
* 0b0..Hysteresis Disabled
* 0b1..Hysteresis Enabled
*/
#define IOMUXC_SW_PAD_CTL_PAD_HYS(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SW_PAD_CTL_PAD_HYS_SHIFT)) & IOMUXC_SW_PAD_CTL_PAD_HYS_MASK)
/*! @} */
/*! @name SELECT_INPUT - ANATOP_USB_OTG1_ID_SELECT_INPUT DAISY Register..XBAR1_IN23_SELECT_INPUT DAISY Register */
/*! @{ */
#define IOMUXC_SELECT_INPUT_DAISY_MASK (0x7U) /* Merged from fields with different position or width, of widths (1, 2, 3), largest definition used */
#define IOMUXC_SELECT_INPUT_DAISY_SHIFT (0U)
/*! DAISY - Selecting Pads Involved in Daisy Chain.
* 0b000..Selecting Pad: GPIO_SD_B1_03 for Mode: ALT6
* 0b001..Selecting Pad: GPIO_AD_B0_12 for Mode: ALT1
* 0b010..Selecting Pad: GPIO_AD_B1_01 for Mode: ALT4
* 0b011..Selecting Pad: GPIO_AD_B1_08 for Mode: ALT3
* 0b100..Selecting Pad: GPIO_EMC_32 for Mode: ALT3
*/
#define IOMUXC_SELECT_INPUT_DAISY(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SELECT_INPUT_DAISY_SHIFT)) & IOMUXC_SELECT_INPUT_DAISY_MASK) /* Merged from fields with different position or width, of widths (1, 2, 3), largest definition used */
/*! @} */
/*! @name SW_MUX_CTL_PAD_1 - SW_MUX_CTL_PAD_GPIO_SPI_B0_00 SW MUX Control Register..SW_MUX_CTL_PAD_GPIO_SPI_B1_07 SW MUX Control Register */
/*! @{ */
#define IOMUXC_SW_MUX_CTL_PAD_1_MUX_MODE_MASK (0x7U)
#define IOMUXC_SW_MUX_CTL_PAD_1_MUX_MODE_SHIFT (0U)
/*! MUX_MODE - MUX Mode Select Field.
* 0b000..Select mux mode: ALT0 mux port: FLEXSPI2_A_DATA00 of instance: flexspi2
* 0b101..Select mux mode: ALT5 mux port: GPIO10_IO02 of instance: gpio10
*/
#define IOMUXC_SW_MUX_CTL_PAD_1_MUX_MODE(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SW_MUX_CTL_PAD_1_MUX_MODE_SHIFT)) & IOMUXC_SW_MUX_CTL_PAD_1_MUX_MODE_MASK)
#define IOMUXC_SW_MUX_CTL_PAD_1_SION_MASK (0x10U)
#define IOMUXC_SW_MUX_CTL_PAD_1_SION_SHIFT (4U)
/*! SION - Software Input On Field.
* 0b1..Force input path of pad GPIO_SPI_B0_00
* 0b0..Input Path is determined by functionality
*/
#define IOMUXC_SW_MUX_CTL_PAD_1_SION(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SW_MUX_CTL_PAD_1_SION_SHIFT)) & IOMUXC_SW_MUX_CTL_PAD_1_SION_MASK)
/*! @} */
/*! @name SW_PAD_CTL_PAD_1 - SW_PAD_CTL_PAD_GPIO_SPI_B0_00 SW PAD Control Register..SW_PAD_CTL_PAD_GPIO_SPI_B1_07 SW PAD Control Register */
/*! @{ */
#define IOMUXC_SW_PAD_CTL_PAD_1_SRE_MASK (0x1U)
#define IOMUXC_SW_PAD_CTL_PAD_1_SRE_SHIFT (0U)
/*! SRE - Slew Rate Field
* 0b0..Slow Slew Rate
* 0b1..Fast Slew Rate
*/
#define IOMUXC_SW_PAD_CTL_PAD_1_SRE(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SW_PAD_CTL_PAD_1_SRE_SHIFT)) & IOMUXC_SW_PAD_CTL_PAD_1_SRE_MASK)
#define IOMUXC_SW_PAD_CTL_PAD_1_DSE_MASK (0x38U)
#define IOMUXC_SW_PAD_CTL_PAD_1_DSE_SHIFT (3U)
/*! DSE - Drive Strength Field
* 0b000..output driver disabled;
* 0b001..R0(150 Ohm @ 3.3V, 260 Ohm@1.8V)
* 0b010..R0/2
* 0b011..R0/3
* 0b100..R0/4
* 0b101..R0/5
* 0b110..R0/6
* 0b111..R0/7
*/
#define IOMUXC_SW_PAD_CTL_PAD_1_DSE(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SW_PAD_CTL_PAD_1_DSE_SHIFT)) & IOMUXC_SW_PAD_CTL_PAD_1_DSE_MASK)
#define IOMUXC_SW_PAD_CTL_PAD_1_SPEED_MASK (0xC0U)
#define IOMUXC_SW_PAD_CTL_PAD_1_SPEED_SHIFT (6U)
/*! SPEED - Speed Field
* 0b00..low(50MHz)
* 0b01..medium(100MHz)
* 0b10..fast(150MHz)
* 0b11..max(200MHz)
*/
#define IOMUXC_SW_PAD_CTL_PAD_1_SPEED(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SW_PAD_CTL_PAD_1_SPEED_SHIFT)) & IOMUXC_SW_PAD_CTL_PAD_1_SPEED_MASK)
#define IOMUXC_SW_PAD_CTL_PAD_1_ODE_MASK (0x800U)
#define IOMUXC_SW_PAD_CTL_PAD_1_ODE_SHIFT (11U)
/*! ODE - Open Drain Enable Field
* 0b0..Open Drain Disabled
* 0b1..Open Drain Enabled
*/
#define IOMUXC_SW_PAD_CTL_PAD_1_ODE(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SW_PAD_CTL_PAD_1_ODE_SHIFT)) & IOMUXC_SW_PAD_CTL_PAD_1_ODE_MASK)
#define IOMUXC_SW_PAD_CTL_PAD_1_PKE_MASK (0x1000U)
#define IOMUXC_SW_PAD_CTL_PAD_1_PKE_SHIFT (12U)
/*! PKE - Pull / Keep Enable Field
* 0b0..Pull/Keeper Disabled
* 0b1..Pull/Keeper Enabled
*/
#define IOMUXC_SW_PAD_CTL_PAD_1_PKE(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SW_PAD_CTL_PAD_1_PKE_SHIFT)) & IOMUXC_SW_PAD_CTL_PAD_1_PKE_MASK)
#define IOMUXC_SW_PAD_CTL_PAD_1_PUE_MASK (0x2000U)
#define IOMUXC_SW_PAD_CTL_PAD_1_PUE_SHIFT (13U)
/*! PUE - Pull / Keep Select Field
* 0b0..Keeper
* 0b1..Pull
*/
#define IOMUXC_SW_PAD_CTL_PAD_1_PUE(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SW_PAD_CTL_PAD_1_PUE_SHIFT)) & IOMUXC_SW_PAD_CTL_PAD_1_PUE_MASK)
#define IOMUXC_SW_PAD_CTL_PAD_1_PUS_MASK (0xC000U)
#define IOMUXC_SW_PAD_CTL_PAD_1_PUS_SHIFT (14U)
/*! PUS - Pull Up / Down Config. Field
* 0b00..100K Ohm Pull Down
* 0b01..47K Ohm Pull Up
* 0b10..100K Ohm Pull Up
* 0b11..22K Ohm Pull Up
*/
#define IOMUXC_SW_PAD_CTL_PAD_1_PUS(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SW_PAD_CTL_PAD_1_PUS_SHIFT)) & IOMUXC_SW_PAD_CTL_PAD_1_PUS_MASK)
#define IOMUXC_SW_PAD_CTL_PAD_1_HYS_MASK (0x10000U)
#define IOMUXC_SW_PAD_CTL_PAD_1_HYS_SHIFT (16U)
/*! HYS - Hyst. Enable Field
* 0b0..Hysteresis Disabled
* 0b1..Hysteresis Enabled
*/
#define IOMUXC_SW_PAD_CTL_PAD_1_HYS(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SW_PAD_CTL_PAD_1_HYS_SHIFT)) & IOMUXC_SW_PAD_CTL_PAD_1_HYS_MASK)
/*! @} */
/*! @name SELECT_INPUT_1 - ENET2_IPG_CLK_RMII_SELECT_INPUT DAISY Register..CANFD_IPP_IND_CANRX_SELECT_INPUT DAISY Register */
/*! @{ */
#define IOMUXC_SELECT_INPUT_1_DAISY_MASK (0x3U) /* Merged from fields with different position or width, of widths (1, 2), largest definition used */
#define IOMUXC_SELECT_INPUT_1_DAISY_SHIFT (0U)
/*! DAISY - Selecting Pads Involved in Daisy Chain.
* 0b00..Selecting Pad: GPIO_SD_B0_00 for Mode: ALT9
* 0b01..Selecting Pad: GPIO_EMC_39 for Mode: ALT9
* 0b10..Selecting Pad: GPIO_AD_B0_09 for Mode: ALT9
* 0b11..Selecting Pad: GPIO_B1_13 for Mode: ALT8
*/
#define IOMUXC_SELECT_INPUT_1_DAISY(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SELECT_INPUT_1_DAISY_SHIFT)) & IOMUXC_SELECT_INPUT_1_DAISY_MASK) /* Merged from fields with different position or width, of widths (1, 2), largest definition used */
/*! @} */
/*!
* @}
*/ /* end of group IOMUXC_Register_Masks */
/*!
* @}
*/ /* end of group IOMUXC_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 */
#endif /* IOMUXC_H_ */

View File

@ -0,0 +1,698 @@
/*
** ###################################################################
** Processors: MIMXRT1061CVJ5A
** MIMXRT1061CVJ5B
** MIMXRT1061CVL5A
** MIMXRT1061CVL5B
** MIMXRT1061DVJ6A
** MIMXRT1061DVJ6B
** MIMXRT1061DVL6A
** MIMXRT1061DVL6B
** MIMXRT1061XVN5B
** MIMXRT1062CVJ5A
** MIMXRT1062CVJ5B
** MIMXRT1062CVL5A
** MIMXRT1062CVL5B
** MIMXRT1062DVJ6A
** MIMXRT1062DVJ6B
** MIMXRT1062DVL6A
** MIMXRT1062DVL6B
** MIMXRT1062DVN6B
** MIMXRT1062XVN5B
** MIMXRT106ADVL6A
** MIMXRT106CDVL6A
** MIMXRT106FDVL6A
** MIMXRT106LDVL6A
** MIMXRT106SDVL6A
**
** Version: rev. 1.4, 2022-03-25
** Build: b240705
**
** Abstract:
** CMSIS Peripheral Access Layer for IOMUXC_SNVS
**
** Copyright 1997-2016 Freescale Semiconductor, Inc.
** Copyright 2016-2024 NXP
** SPDX-License-Identifier: BSD-3-Clause
**
** http: www.nxp.com
** mail: support@nxp.com
**
** Revisions:
** - rev. 0.1 (2017-01-10)
** Initial version.
** - rev. 1.0 (2018-11-16)
** Update header files to align with IMXRT1060RM Rev.0.
** - rev. 1.1 (2018-11-27)
** Update header files to align with IMXRT1060RM Rev.1.
** - rev. 1.2 (2019-04-29)
** Add SET/CLR/TOG register group to register CTRL, STAT, CHANNELCTRL, CH0STAT, CH0OPTS, CH1STAT, CH1OPTS, CH2STAT, CH2OPTS, CH3STAT, CH3OPTS of DCP module.
** - rev. 1.3 (2021-08-10)
** Update header files to align with IMXRT1060RM Rev.3.
** - rev. 1.4 (2022-03-25)
** Add RT1060X device
**
** ###################################################################
*/
/*!
* @file IOMUXC_SNVS.h
* @version 1.4
* @date 2022-03-25
* @brief CMSIS Peripheral Access Layer for IOMUXC_SNVS
*
* CMSIS Peripheral Access Layer for IOMUXC_SNVS
*/
#if !defined(IOMUXC_SNVS_H_)
#define IOMUXC_SNVS_H_ /**< Symbol preventing repeated inclusion */
#if (defined(CPU_MIMXRT1061CVJ5A) || defined(CPU_MIMXRT1061CVJ5B) || defined(CPU_MIMXRT1061CVL5A) || defined(CPU_MIMXRT1061CVL5B) || defined(CPU_MIMXRT1061DVJ6A) || defined(CPU_MIMXRT1061DVJ6B) || defined(CPU_MIMXRT1061DVL6A) || defined(CPU_MIMXRT1061DVL6B) || defined(CPU_MIMXRT1061XVN5B))
#include "MIMXRT1061_COMMON.h"
#elif (defined(CPU_MIMXRT1062CVJ5A) || defined(CPU_MIMXRT1062CVJ5B) || defined(CPU_MIMXRT1062CVL5A) || defined(CPU_MIMXRT1062CVL5B) || defined(CPU_MIMXRT1062DVJ6A) || defined(CPU_MIMXRT1062DVJ6B) || defined(CPU_MIMXRT1062DVL6A) || defined(CPU_MIMXRT1062DVL6B) || defined(CPU_MIMXRT1062DVN6B) || defined(CPU_MIMXRT1062XVN5B))
#include "MIMXRT1062_COMMON.h"
#elif (defined(CPU_MIMXRT106ADVL6A))
#include "MIMXRT106A_COMMON.h"
#elif (defined(CPU_MIMXRT106CDVL6A))
#include "MIMXRT106C_COMMON.h"
#elif (defined(CPU_MIMXRT106FDVL6A))
#include "MIMXRT106F_COMMON.h"
#elif (defined(CPU_MIMXRT106LDVL6A))
#include "MIMXRT106L_COMMON.h"
#elif (defined(CPU_MIMXRT106SDVL6A))
#include "MIMXRT106S_COMMON.h"
#else
#error "No valid CPU defined!"
#endif
/* ----------------------------------------------------------------------------
-- 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
/* ----------------------------------------------------------------------------
-- IOMUXC_SNVS Peripheral Access Layer
---------------------------------------------------------------------------- */
/*!
* @addtogroup IOMUXC_SNVS_Peripheral_Access_Layer IOMUXC_SNVS Peripheral Access Layer
* @{
*/
/** IOMUXC_SNVS - Register Layout Typedef */
typedef struct {
__IO uint32_t SW_MUX_CTL_PAD_WAKEUP; /**< SW_MUX_CTL_PAD_WAKEUP SW MUX Control Register, offset: 0x0 */
__IO uint32_t SW_MUX_CTL_PAD_PMIC_ON_REQ; /**< SW_MUX_CTL_PAD_PMIC_ON_REQ SW MUX Control Register, offset: 0x4 */
__IO uint32_t SW_MUX_CTL_PAD_PMIC_STBY_REQ; /**< SW_MUX_CTL_PAD_PMIC_STBY_REQ SW MUX Control Register, offset: 0x8 */
__IO uint32_t SW_PAD_CTL_PAD_TEST_MODE; /**< SW_PAD_CTL_PAD_TEST_MODE SW PAD Control Register, offset: 0xC */
__IO uint32_t SW_PAD_CTL_PAD_POR_B; /**< SW_PAD_CTL_PAD_POR_B SW PAD Control Register, offset: 0x10 */
__IO uint32_t SW_PAD_CTL_PAD_ONOFF; /**< SW_PAD_CTL_PAD_ONOFF SW PAD Control Register, offset: 0x14 */
__IO uint32_t SW_PAD_CTL_PAD_WAKEUP; /**< SW_PAD_CTL_PAD_WAKEUP SW PAD Control Register, offset: 0x18 */
__IO uint32_t SW_PAD_CTL_PAD_PMIC_ON_REQ; /**< SW_PAD_CTL_PAD_PMIC_ON_REQ SW PAD Control Register, offset: 0x1C */
__IO uint32_t SW_PAD_CTL_PAD_PMIC_STBY_REQ; /**< SW_PAD_CTL_PAD_PMIC_STBY_REQ SW PAD Control Register, offset: 0x20 */
} IOMUXC_SNVS_Type;
/* ----------------------------------------------------------------------------
-- IOMUXC_SNVS Register Masks
---------------------------------------------------------------------------- */
/*!
* @addtogroup IOMUXC_SNVS_Register_Masks IOMUXC_SNVS Register Masks
* @{
*/
/*! @name SW_MUX_CTL_PAD_WAKEUP - SW_MUX_CTL_PAD_WAKEUP SW MUX Control Register */
/*! @{ */
#define IOMUXC_SNVS_SW_MUX_CTL_PAD_WAKEUP_MUX_MODE_MASK (0x7U)
#define IOMUXC_SNVS_SW_MUX_CTL_PAD_WAKEUP_MUX_MODE_SHIFT (0U)
/*! MUX_MODE - MUX Mode Select Field.
* 0b101..Select mux mode: ALT5 mux port: GPIO5_IO00 of instance: gpio5
* 0b111..Select mux mode: ALT7 mux port: NMI of instance: CM7
*/
#define IOMUXC_SNVS_SW_MUX_CTL_PAD_WAKEUP_MUX_MODE(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SNVS_SW_MUX_CTL_PAD_WAKEUP_MUX_MODE_SHIFT)) & IOMUXC_SNVS_SW_MUX_CTL_PAD_WAKEUP_MUX_MODE_MASK)
#define IOMUXC_SNVS_SW_MUX_CTL_PAD_WAKEUP_SION_MASK (0x10U)
#define IOMUXC_SNVS_SW_MUX_CTL_PAD_WAKEUP_SION_SHIFT (4U)
/*! SION - Software Input On Field.
* 0b1..Force input path of pad WAKEUP
* 0b0..Input Path is determined by functionality
*/
#define IOMUXC_SNVS_SW_MUX_CTL_PAD_WAKEUP_SION(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SNVS_SW_MUX_CTL_PAD_WAKEUP_SION_SHIFT)) & IOMUXC_SNVS_SW_MUX_CTL_PAD_WAKEUP_SION_MASK)
/*! @} */
/*! @name SW_MUX_CTL_PAD_PMIC_ON_REQ - SW_MUX_CTL_PAD_PMIC_ON_REQ SW MUX Control Register */
/*! @{ */
#define IOMUXC_SNVS_SW_MUX_CTL_PAD_PMIC_ON_REQ_MUX_MODE_MASK (0x7U)
#define IOMUXC_SNVS_SW_MUX_CTL_PAD_PMIC_ON_REQ_MUX_MODE_SHIFT (0U)
/*! MUX_MODE - MUX Mode Select Field.
* 0b000..Select mux mode: ALT0 mux port: SNVS_PMIC_ON_REQ of instance: snvs
* 0b101..Select mux mode: ALT5 mux port: GPIO5_IO01 of instance: gpio5
*/
#define IOMUXC_SNVS_SW_MUX_CTL_PAD_PMIC_ON_REQ_MUX_MODE(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SNVS_SW_MUX_CTL_PAD_PMIC_ON_REQ_MUX_MODE_SHIFT)) & IOMUXC_SNVS_SW_MUX_CTL_PAD_PMIC_ON_REQ_MUX_MODE_MASK)
#define IOMUXC_SNVS_SW_MUX_CTL_PAD_PMIC_ON_REQ_SION_MASK (0x10U)
#define IOMUXC_SNVS_SW_MUX_CTL_PAD_PMIC_ON_REQ_SION_SHIFT (4U)
/*! SION - Software Input On Field.
* 0b1..Force input path of pad PMIC_ON_REQ
* 0b0..Input Path is determined by functionality
*/
#define IOMUXC_SNVS_SW_MUX_CTL_PAD_PMIC_ON_REQ_SION(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SNVS_SW_MUX_CTL_PAD_PMIC_ON_REQ_SION_SHIFT)) & IOMUXC_SNVS_SW_MUX_CTL_PAD_PMIC_ON_REQ_SION_MASK)
/*! @} */
/*! @name SW_MUX_CTL_PAD_PMIC_STBY_REQ - SW_MUX_CTL_PAD_PMIC_STBY_REQ SW MUX Control Register */
/*! @{ */
#define IOMUXC_SNVS_SW_MUX_CTL_PAD_PMIC_STBY_REQ_MUX_MODE_MASK (0x7U)
#define IOMUXC_SNVS_SW_MUX_CTL_PAD_PMIC_STBY_REQ_MUX_MODE_SHIFT (0U)
/*! MUX_MODE - MUX Mode Select Field.
* 0b000..Select mux mode: ALT0 mux port: CCM_PMIC_STBY_REQ of instance: ccm
* 0b101..Select mux mode: ALT5 mux port: GPIO5_IO02 of instance: gpio5
*/
#define IOMUXC_SNVS_SW_MUX_CTL_PAD_PMIC_STBY_REQ_MUX_MODE(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SNVS_SW_MUX_CTL_PAD_PMIC_STBY_REQ_MUX_MODE_SHIFT)) & IOMUXC_SNVS_SW_MUX_CTL_PAD_PMIC_STBY_REQ_MUX_MODE_MASK)
#define IOMUXC_SNVS_SW_MUX_CTL_PAD_PMIC_STBY_REQ_SION_MASK (0x10U)
#define IOMUXC_SNVS_SW_MUX_CTL_PAD_PMIC_STBY_REQ_SION_SHIFT (4U)
/*! SION - Software Input On Field.
* 0b1..Force input path of pad PMIC_STBY_REQ
* 0b0..Input Path is determined by functionality
*/
#define IOMUXC_SNVS_SW_MUX_CTL_PAD_PMIC_STBY_REQ_SION(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SNVS_SW_MUX_CTL_PAD_PMIC_STBY_REQ_SION_SHIFT)) & IOMUXC_SNVS_SW_MUX_CTL_PAD_PMIC_STBY_REQ_SION_MASK)
/*! @} */
/*! @name SW_PAD_CTL_PAD_TEST_MODE - SW_PAD_CTL_PAD_TEST_MODE SW PAD Control Register */
/*! @{ */
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_TEST_MODE_SRE_MASK (0x1U)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_TEST_MODE_SRE_SHIFT (0U)
/*! SRE - Slew Rate Field
* 0b0..Slow Slew Rate
* 0b1..Fast Slew Rate
*/
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_TEST_MODE_SRE(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SNVS_SW_PAD_CTL_PAD_TEST_MODE_SRE_SHIFT)) & IOMUXC_SNVS_SW_PAD_CTL_PAD_TEST_MODE_SRE_MASK)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_TEST_MODE_DSE_MASK (0x38U)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_TEST_MODE_DSE_SHIFT (3U)
/*! DSE - Drive Strength Field
* 0b000..HI-Z
* 0b001..Dual/Single voltage: 262/260 Ohm @ 1.8V, 247/157 Ohm @ 3.3V
* 0b010..Dual/Single voltage: 134/130 Ohm @ 1.8V, 126/78 Ohm @ 3.3V
* 0b011..Dual/Single voltage: 88/88 Ohm @ 1.8V, 84/53 Ohm @ 3.3V
* 0b100..Dual/Single voltage: 62/65 Ohm @ 1.8V, 57/39 Ohm @ 3.3V
* 0b101..Dual/Single voltage: 51/52 Ohm @ 1.8V, 47/32 Ohm @ 3.3V
* 0b110..Dual/Single voltage: 43/43 Ohm @ 1.8V, 40/26 Ohm @ 3.3V
* 0b111..Dual/Single voltage: 37/37 Ohm @ 1.8V, 34/23 Ohm @ 3.3V
*/
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_TEST_MODE_DSE(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SNVS_SW_PAD_CTL_PAD_TEST_MODE_DSE_SHIFT)) & IOMUXC_SNVS_SW_PAD_CTL_PAD_TEST_MODE_DSE_MASK)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_TEST_MODE_SPEED_MASK (0xC0U)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_TEST_MODE_SPEED_SHIFT (6U)
/*! SPEED - Speed Field
* 0b10..100MHz
*/
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_TEST_MODE_SPEED(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SNVS_SW_PAD_CTL_PAD_TEST_MODE_SPEED_SHIFT)) & IOMUXC_SNVS_SW_PAD_CTL_PAD_TEST_MODE_SPEED_MASK)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_TEST_MODE_ODE_MASK (0x800U)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_TEST_MODE_ODE_SHIFT (11U)
/*! ODE - Open Drain Enable Field
* 0b0..Open Drain Disabled (Output is CMOS)
* 0b1..Open Drain Enabled (Output is Open Drain)
*/
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_TEST_MODE_ODE(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SNVS_SW_PAD_CTL_PAD_TEST_MODE_ODE_SHIFT)) & IOMUXC_SNVS_SW_PAD_CTL_PAD_TEST_MODE_ODE_MASK)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_TEST_MODE_PKE_MASK (0x1000U)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_TEST_MODE_PKE_SHIFT (12U)
/*! PKE - Pull / Keep Enable Field
* 0b0..Pull/Keeper Disabled
* 0b1..Pull/Keeper Enabled
*/
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_TEST_MODE_PKE(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SNVS_SW_PAD_CTL_PAD_TEST_MODE_PKE_SHIFT)) & IOMUXC_SNVS_SW_PAD_CTL_PAD_TEST_MODE_PKE_MASK)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_TEST_MODE_PUE_MASK (0x2000U)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_TEST_MODE_PUE_SHIFT (13U)
/*! PUE - Pull / Keep Select Field Control signal to enable internal pull-up/down resistors or pad keeper functionality.
* 0b0..Keep the previous output value when the output driver is disabled.
* 0b1..Pull-up or pull-down (determined by PUS field).
*/
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_TEST_MODE_PUE(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SNVS_SW_PAD_CTL_PAD_TEST_MODE_PUE_SHIFT)) & IOMUXC_SNVS_SW_PAD_CTL_PAD_TEST_MODE_PUE_MASK)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_TEST_MODE_PUS_MASK (0xC000U)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_TEST_MODE_PUS_SHIFT (14U)
/*! PUS - Pull Up / Down Config. Field Controls signals to select pull-up or pull-down internal resistance strength.
* 0b00..100K Ohm Pull Down
* 0b01..47K Ohm Pull Up
* 0b10..100K Ohm Pull Up
* 0b11..22K Ohm Pull Up
*/
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_TEST_MODE_PUS(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SNVS_SW_PAD_CTL_PAD_TEST_MODE_PUS_SHIFT)) & IOMUXC_SNVS_SW_PAD_CTL_PAD_TEST_MODE_PUS_MASK)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_TEST_MODE_HYS_MASK (0x10000U)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_TEST_MODE_HYS_SHIFT (16U)
/*! HYS - Hyst. Enable Field
* 0b0..Hysteresis Disabled (CMOS input)
* 0b1..Hysteresis Enabled (Schmitt Trigger input)
*/
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_TEST_MODE_HYS(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SNVS_SW_PAD_CTL_PAD_TEST_MODE_HYS_SHIFT)) & IOMUXC_SNVS_SW_PAD_CTL_PAD_TEST_MODE_HYS_MASK)
/*! @} */
/*! @name SW_PAD_CTL_PAD_POR_B - SW_PAD_CTL_PAD_POR_B SW PAD Control Register */
/*! @{ */
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_POR_B_SRE_MASK (0x1U)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_POR_B_SRE_SHIFT (0U)
/*! SRE - Slew Rate Field
* 0b0..Slow Slew Rate
* 0b1..Fast Slew Rate
*/
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_POR_B_SRE(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SNVS_SW_PAD_CTL_PAD_POR_B_SRE_SHIFT)) & IOMUXC_SNVS_SW_PAD_CTL_PAD_POR_B_SRE_MASK)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_POR_B_DSE_MASK (0x38U)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_POR_B_DSE_SHIFT (3U)
/*! DSE - Drive Strength Field
* 0b000..HI-Z
* 0b001..Dual/Single voltage: 262/260 Ohm @ 1.8V, 247/157 Ohm @ 3.3V
* 0b010..Dual/Single voltage: 134/130 Ohm @ 1.8V, 126/78 Ohm @ 3.3V
* 0b011..Dual/Single voltage: 88/88 Ohm @ 1.8V, 84/53 Ohm @ 3.3V
* 0b100..Dual/Single voltage: 62/65 Ohm @ 1.8V, 57/39 Ohm @ 3.3V
* 0b101..Dual/Single voltage: 51/52 Ohm @ 1.8V, 47/32 Ohm @ 3.3V
* 0b110..Dual/Single voltage: 43/43 Ohm @ 1.8V, 40/26 Ohm @ 3.3V
* 0b111..Dual/Single voltage: 37/37 Ohm @ 1.8V, 34/23 Ohm @ 3.3V
*/
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_POR_B_DSE(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SNVS_SW_PAD_CTL_PAD_POR_B_DSE_SHIFT)) & IOMUXC_SNVS_SW_PAD_CTL_PAD_POR_B_DSE_MASK)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_POR_B_SPEED_MASK (0xC0U)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_POR_B_SPEED_SHIFT (6U)
/*! SPEED - Speed Field
* 0b10..100MHz
*/
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_POR_B_SPEED(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SNVS_SW_PAD_CTL_PAD_POR_B_SPEED_SHIFT)) & IOMUXC_SNVS_SW_PAD_CTL_PAD_POR_B_SPEED_MASK)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_POR_B_ODE_MASK (0x800U)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_POR_B_ODE_SHIFT (11U)
/*! ODE - Open Drain Enable Field
* 0b0..Open Drain Disabled (Output is CMOS)
* 0b1..Open Drain Enabled (Output is Open Drain)
*/
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_POR_B_ODE(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SNVS_SW_PAD_CTL_PAD_POR_B_ODE_SHIFT)) & IOMUXC_SNVS_SW_PAD_CTL_PAD_POR_B_ODE_MASK)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_POR_B_PKE_MASK (0x1000U)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_POR_B_PKE_SHIFT (12U)
/*! PKE - Pull / Keep Enable Field
* 0b0..Pull/Keeper Disabled
* 0b1..Pull/Keeper Enabled
*/
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_POR_B_PKE(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SNVS_SW_PAD_CTL_PAD_POR_B_PKE_SHIFT)) & IOMUXC_SNVS_SW_PAD_CTL_PAD_POR_B_PKE_MASK)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_POR_B_PUE_MASK (0x2000U)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_POR_B_PUE_SHIFT (13U)
/*! PUE - Pull / Keep Select Field Control signal to enable internal pull-up/down resistors or pad keeper functionality.
* 0b0..Keep the previous output value when the output driver is disabled.
* 0b1..Pull-up or pull-down (determined by PUS field).
*/
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_POR_B_PUE(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SNVS_SW_PAD_CTL_PAD_POR_B_PUE_SHIFT)) & IOMUXC_SNVS_SW_PAD_CTL_PAD_POR_B_PUE_MASK)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_POR_B_PUS_MASK (0xC000U)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_POR_B_PUS_SHIFT (14U)
/*! PUS - Pull Up / Down Config. Field Controls signals to select pull-up or pull-down internal resistance strength.
* 0b00..100K Ohm Pull Down
* 0b01..47K Ohm Pull Up
* 0b10..100K Ohm Pull Up
* 0b11..22K Ohm Pull Up
*/
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_POR_B_PUS(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SNVS_SW_PAD_CTL_PAD_POR_B_PUS_SHIFT)) & IOMUXC_SNVS_SW_PAD_CTL_PAD_POR_B_PUS_MASK)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_POR_B_HYS_MASK (0x10000U)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_POR_B_HYS_SHIFT (16U)
/*! HYS - Hyst. Enable Field
* 0b0..Hysteresis Disabled (CMOS input)
* 0b1..Hysteresis Enabled (Schmitt Trigger input)
*/
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_POR_B_HYS(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SNVS_SW_PAD_CTL_PAD_POR_B_HYS_SHIFT)) & IOMUXC_SNVS_SW_PAD_CTL_PAD_POR_B_HYS_MASK)
/*! @} */
/*! @name SW_PAD_CTL_PAD_ONOFF - SW_PAD_CTL_PAD_ONOFF SW PAD Control Register */
/*! @{ */
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_ONOFF_SRE_MASK (0x1U)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_ONOFF_SRE_SHIFT (0U)
/*! SRE - Slew Rate Field
* 0b0..Slow Slew Rate
* 0b1..Fast Slew Rate
*/
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_ONOFF_SRE(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SNVS_SW_PAD_CTL_PAD_ONOFF_SRE_SHIFT)) & IOMUXC_SNVS_SW_PAD_CTL_PAD_ONOFF_SRE_MASK)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_ONOFF_DSE_MASK (0x38U)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_ONOFF_DSE_SHIFT (3U)
/*! DSE - Drive Strength Field
* 0b000..HI-Z
* 0b001..Dual/Single voltage: 262/260 Ohm @ 1.8V, 247/157 Ohm @ 3.3V
* 0b010..Dual/Single voltage: 134/130 Ohm @ 1.8V, 126/78 Ohm @ 3.3V
* 0b011..Dual/Single voltage: 88/88 Ohm @ 1.8V, 84/53 Ohm @ 3.3V
* 0b100..Dual/Single voltage: 62/65 Ohm @ 1.8V, 57/39 Ohm @ 3.3V
* 0b101..Dual/Single voltage: 51/52 Ohm @ 1.8V, 47/32 Ohm @ 3.3V
* 0b110..Dual/Single voltage: 43/43 Ohm @ 1.8V, 40/26 Ohm @ 3.3V
* 0b111..Dual/Single voltage: 37/37 Ohm @ 1.8V, 34/23 Ohm @ 3.3V
*/
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_ONOFF_DSE(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SNVS_SW_PAD_CTL_PAD_ONOFF_DSE_SHIFT)) & IOMUXC_SNVS_SW_PAD_CTL_PAD_ONOFF_DSE_MASK)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_ONOFF_SPEED_MASK (0xC0U)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_ONOFF_SPEED_SHIFT (6U)
/*! SPEED - Speed Field
* 0b10..100MHz
*/
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_ONOFF_SPEED(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SNVS_SW_PAD_CTL_PAD_ONOFF_SPEED_SHIFT)) & IOMUXC_SNVS_SW_PAD_CTL_PAD_ONOFF_SPEED_MASK)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_ONOFF_ODE_MASK (0x800U)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_ONOFF_ODE_SHIFT (11U)
/*! ODE - Open Drain Enable Field
* 0b0..Open Drain Disabled (Output is CMOS)
* 0b1..Open Drain Enabled (Output is Open Drain)
*/
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_ONOFF_ODE(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SNVS_SW_PAD_CTL_PAD_ONOFF_ODE_SHIFT)) & IOMUXC_SNVS_SW_PAD_CTL_PAD_ONOFF_ODE_MASK)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_ONOFF_PKE_MASK (0x1000U)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_ONOFF_PKE_SHIFT (12U)
/*! PKE - Pull / Keep Enable Field
* 0b0..Pull/Keeper Disabled
* 0b1..Pull/Keeper Enabled
*/
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_ONOFF_PKE(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SNVS_SW_PAD_CTL_PAD_ONOFF_PKE_SHIFT)) & IOMUXC_SNVS_SW_PAD_CTL_PAD_ONOFF_PKE_MASK)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_ONOFF_PUE_MASK (0x2000U)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_ONOFF_PUE_SHIFT (13U)
/*! PUE - Pull / Keep Select Field Control signal to enable internal pull-up/down resistors or pad keeper functionality.
* 0b0..Keep the previous output value when the output driver is disabled.
* 0b1..Pull-up or pull-down (determined by PUS field).
*/
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_ONOFF_PUE(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SNVS_SW_PAD_CTL_PAD_ONOFF_PUE_SHIFT)) & IOMUXC_SNVS_SW_PAD_CTL_PAD_ONOFF_PUE_MASK)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_ONOFF_PUS_MASK (0xC000U)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_ONOFF_PUS_SHIFT (14U)
/*! PUS - Pull Up / Down Config. Field Controls signals to select pull-up or pull-down internal resistance strength.
* 0b00..100K Ohm Pull Down
* 0b01..47K Ohm Pull Up
* 0b10..100K Ohm Pull Up
* 0b11..22K Ohm Pull Up
*/
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_ONOFF_PUS(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SNVS_SW_PAD_CTL_PAD_ONOFF_PUS_SHIFT)) & IOMUXC_SNVS_SW_PAD_CTL_PAD_ONOFF_PUS_MASK)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_ONOFF_HYS_MASK (0x10000U)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_ONOFF_HYS_SHIFT (16U)
/*! HYS - Hyst. Enable Field
* 0b0..Hysteresis Disabled (CMOS input)
* 0b1..Hysteresis Enabled (Schmitt Trigger input)
*/
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_ONOFF_HYS(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SNVS_SW_PAD_CTL_PAD_ONOFF_HYS_SHIFT)) & IOMUXC_SNVS_SW_PAD_CTL_PAD_ONOFF_HYS_MASK)
/*! @} */
/*! @name SW_PAD_CTL_PAD_WAKEUP - SW_PAD_CTL_PAD_WAKEUP SW PAD Control Register */
/*! @{ */
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_WAKEUP_SRE_MASK (0x1U)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_WAKEUP_SRE_SHIFT (0U)
/*! SRE - Slew Rate Field
* 0b0..Slow Slew Rate
* 0b1..Fast Slew Rate
*/
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_WAKEUP_SRE(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SNVS_SW_PAD_CTL_PAD_WAKEUP_SRE_SHIFT)) & IOMUXC_SNVS_SW_PAD_CTL_PAD_WAKEUP_SRE_MASK)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_WAKEUP_DSE_MASK (0x38U)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_WAKEUP_DSE_SHIFT (3U)
/*! DSE - Drive Strength Field
* 0b000..HI-Z
* 0b001..Dual/Single voltage: 262/260 Ohm @ 1.8V, 247/157 Ohm @ 3.3V
* 0b010..Dual/Single voltage: 134/130 Ohm @ 1.8V, 126/78 Ohm @ 3.3V
* 0b011..Dual/Single voltage: 88/88 Ohm @ 1.8V, 84/53 Ohm @ 3.3V
* 0b100..Dual/Single voltage: 62/65 Ohm @ 1.8V, 57/39 Ohm @ 3.3V
* 0b101..Dual/Single voltage: 51/52 Ohm @ 1.8V, 47/32 Ohm @ 3.3V
* 0b110..Dual/Single voltage: 43/43 Ohm @ 1.8V, 40/26 Ohm @ 3.3V
* 0b111..Dual/Single voltage: 37/37 Ohm @ 1.8V, 34/23 Ohm @ 3.3V
*/
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_WAKEUP_DSE(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SNVS_SW_PAD_CTL_PAD_WAKEUP_DSE_SHIFT)) & IOMUXC_SNVS_SW_PAD_CTL_PAD_WAKEUP_DSE_MASK)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_WAKEUP_SPEED_MASK (0xC0U)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_WAKEUP_SPEED_SHIFT (6U)
/*! SPEED - Speed Field
* 0b10..100MHz
*/
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_WAKEUP_SPEED(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SNVS_SW_PAD_CTL_PAD_WAKEUP_SPEED_SHIFT)) & IOMUXC_SNVS_SW_PAD_CTL_PAD_WAKEUP_SPEED_MASK)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_WAKEUP_ODE_MASK (0x800U)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_WAKEUP_ODE_SHIFT (11U)
/*! ODE - Open Drain Enable Field
* 0b0..Open Drain Disabled (Output is CMOS)
* 0b1..Open Drain Enabled (Output is Open Drain)
*/
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_WAKEUP_ODE(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SNVS_SW_PAD_CTL_PAD_WAKEUP_ODE_SHIFT)) & IOMUXC_SNVS_SW_PAD_CTL_PAD_WAKEUP_ODE_MASK)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_WAKEUP_PKE_MASK (0x1000U)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_WAKEUP_PKE_SHIFT (12U)
/*! PKE - Pull / Keep Enable Field
* 0b0..Pull/Keeper Disabled
* 0b1..Pull/Keeper Enabled
*/
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_WAKEUP_PKE(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SNVS_SW_PAD_CTL_PAD_WAKEUP_PKE_SHIFT)) & IOMUXC_SNVS_SW_PAD_CTL_PAD_WAKEUP_PKE_MASK)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_WAKEUP_PUE_MASK (0x2000U)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_WAKEUP_PUE_SHIFT (13U)
/*! PUE - Pull / Keep Select Field Control signal to enable internal pull-up/down resistors or pad keeper functionality.
* 0b0..Keep the previous output value when the output driver is disabled.
* 0b1..Pull-up or pull-down (determined by PUS field).
*/
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_WAKEUP_PUE(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SNVS_SW_PAD_CTL_PAD_WAKEUP_PUE_SHIFT)) & IOMUXC_SNVS_SW_PAD_CTL_PAD_WAKEUP_PUE_MASK)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_WAKEUP_PUS_MASK (0xC000U)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_WAKEUP_PUS_SHIFT (14U)
/*! PUS - Pull Up / Down Config. Field Controls signals to select pull-up or pull-down internal resistance strength.
* 0b00..100K Ohm Pull Down
* 0b01..47K Ohm Pull Up
* 0b10..100K Ohm Pull Up
* 0b11..22K Ohm Pull Up
*/
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_WAKEUP_PUS(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SNVS_SW_PAD_CTL_PAD_WAKEUP_PUS_SHIFT)) & IOMUXC_SNVS_SW_PAD_CTL_PAD_WAKEUP_PUS_MASK)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_WAKEUP_HYS_MASK (0x10000U)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_WAKEUP_HYS_SHIFT (16U)
/*! HYS - Hyst. Enable Field
* 0b0..Hysteresis Disabled (CMOS input)
* 0b1..Hysteresis Enabled (Schmitt Trigger input)
*/
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_WAKEUP_HYS(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SNVS_SW_PAD_CTL_PAD_WAKEUP_HYS_SHIFT)) & IOMUXC_SNVS_SW_PAD_CTL_PAD_WAKEUP_HYS_MASK)
/*! @} */
/*! @name SW_PAD_CTL_PAD_PMIC_ON_REQ - SW_PAD_CTL_PAD_PMIC_ON_REQ SW PAD Control Register */
/*! @{ */
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_ON_REQ_SRE_MASK (0x1U)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_ON_REQ_SRE_SHIFT (0U)
/*! SRE - Slew Rate Field
* 0b0..Slow Slew Rate
* 0b1..Fast Slew Rate
*/
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_ON_REQ_SRE(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_ON_REQ_SRE_SHIFT)) & IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_ON_REQ_SRE_MASK)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_ON_REQ_DSE_MASK (0x38U)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_ON_REQ_DSE_SHIFT (3U)
/*! DSE - Drive Strength Field
* 0b000..HI-Z
* 0b001..Dual/Single voltage: 262/260 Ohm @ 1.8V, 247/157 Ohm @ 3.3V
* 0b010..Dual/Single voltage: 134/130 Ohm @ 1.8V, 126/78 Ohm @ 3.3V
* 0b011..Dual/Single voltage: 88/88 Ohm @ 1.8V, 84/53 Ohm @ 3.3V
* 0b100..Dual/Single voltage: 62/65 Ohm @ 1.8V, 57/39 Ohm @ 3.3V
* 0b101..Dual/Single voltage: 51/52 Ohm @ 1.8V, 47/32 Ohm @ 3.3V
* 0b110..Dual/Single voltage: 43/43 Ohm @ 1.8V, 40/26 Ohm @ 3.3V
* 0b111..Dual/Single voltage: 37/37 Ohm @ 1.8V, 34/23 Ohm @ 3.3V
*/
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_ON_REQ_DSE(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_ON_REQ_DSE_SHIFT)) & IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_ON_REQ_DSE_MASK)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_ON_REQ_SPEED_MASK (0xC0U)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_ON_REQ_SPEED_SHIFT (6U)
/*! SPEED - Speed Field
* 0b10..100MHz
*/
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_ON_REQ_SPEED(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_ON_REQ_SPEED_SHIFT)) & IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_ON_REQ_SPEED_MASK)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_ON_REQ_ODE_MASK (0x800U)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_ON_REQ_ODE_SHIFT (11U)
/*! ODE - Open Drain Enable Field
* 0b0..Open Drain Disabled (Output is CMOS)
* 0b1..Open Drain Enabled (Output is Open Drain)
*/
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_ON_REQ_ODE(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_ON_REQ_ODE_SHIFT)) & IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_ON_REQ_ODE_MASK)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_ON_REQ_PKE_MASK (0x1000U)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_ON_REQ_PKE_SHIFT (12U)
/*! PKE - Pull / Keep Enable Field
* 0b0..Pull/Keeper Disabled
* 0b1..Pull/Keeper Enabled
*/
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_ON_REQ_PKE(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_ON_REQ_PKE_SHIFT)) & IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_ON_REQ_PKE_MASK)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_ON_REQ_PUE_MASK (0x2000U)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_ON_REQ_PUE_SHIFT (13U)
/*! PUE - Pull / Keep Select Field Control signal to enable internal pull-up/down resistors or pad keeper functionality.
* 0b0..Keep the previous output value when the output driver is disabled.
* 0b1..Pull-up or pull-down (determined by PUS field).
*/
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_ON_REQ_PUE(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_ON_REQ_PUE_SHIFT)) & IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_ON_REQ_PUE_MASK)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_ON_REQ_PUS_MASK (0xC000U)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_ON_REQ_PUS_SHIFT (14U)
/*! PUS - Pull Up / Down Config. Field Controls signals to select pull-up or pull-down internal resistance strength.
* 0b00..100K Ohm Pull Down
* 0b01..47K Ohm Pull Up
* 0b10..100K Ohm Pull Up
* 0b11..22K Ohm Pull Up
*/
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_ON_REQ_PUS(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_ON_REQ_PUS_SHIFT)) & IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_ON_REQ_PUS_MASK)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_ON_REQ_HYS_MASK (0x10000U)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_ON_REQ_HYS_SHIFT (16U)
/*! HYS - Hyst. Enable Field
* 0b0..Hysteresis Disabled (CMOS input)
* 0b1..Hysteresis Enabled (Schmitt Trigger input)
*/
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_ON_REQ_HYS(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_ON_REQ_HYS_SHIFT)) & IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_ON_REQ_HYS_MASK)
/*! @} */
/*! @name SW_PAD_CTL_PAD_PMIC_STBY_REQ - SW_PAD_CTL_PAD_PMIC_STBY_REQ SW PAD Control Register */
/*! @{ */
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_STBY_REQ_SRE_MASK (0x1U)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_STBY_REQ_SRE_SHIFT (0U)
/*! SRE - Slew Rate Field
* 0b0..Slow Slew Rate
* 0b1..Fast Slew Rate
*/
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_STBY_REQ_SRE(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_STBY_REQ_SRE_SHIFT)) & IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_STBY_REQ_SRE_MASK)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_STBY_REQ_DSE_MASK (0x38U)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_STBY_REQ_DSE_SHIFT (3U)
/*! DSE - Drive Strength Field
* 0b000..HI-Z
* 0b001..Dual/Single voltage: 262/260 Ohm @ 1.8V, 247/157 Ohm @ 3.3V
* 0b010..Dual/Single voltage: 134/130 Ohm @ 1.8V, 126/78 Ohm @ 3.3V
* 0b011..Dual/Single voltage: 88/88 Ohm @ 1.8V, 84/53 Ohm @ 3.3V
* 0b100..Dual/Single voltage: 62/65 Ohm @ 1.8V, 57/39 Ohm @ 3.3V
* 0b101..Dual/Single voltage: 51/52 Ohm @ 1.8V, 47/32 Ohm @ 3.3V
* 0b110..Dual/Single voltage: 43/43 Ohm @ 1.8V, 40/26 Ohm @ 3.3V
* 0b111..Dual/Single voltage: 37/37 Ohm @ 1.8V, 34/23 Ohm @ 3.3V
*/
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_STBY_REQ_DSE(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_STBY_REQ_DSE_SHIFT)) & IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_STBY_REQ_DSE_MASK)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_STBY_REQ_SPEED_MASK (0xC0U)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_STBY_REQ_SPEED_SHIFT (6U)
/*! SPEED - Speed Field
* 0b10..100MHz
*/
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_STBY_REQ_SPEED(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_STBY_REQ_SPEED_SHIFT)) & IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_STBY_REQ_SPEED_MASK)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_STBY_REQ_ODE_MASK (0x800U)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_STBY_REQ_ODE_SHIFT (11U)
/*! ODE - Open Drain Enable Field
* 0b0..Open Drain Disabled (Output is CMOS)
* 0b1..Open Drain Enabled (Output is Open Drain)
*/
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_STBY_REQ_ODE(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_STBY_REQ_ODE_SHIFT)) & IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_STBY_REQ_ODE_MASK)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_STBY_REQ_PKE_MASK (0x1000U)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_STBY_REQ_PKE_SHIFT (12U)
/*! PKE - Pull / Keep Enable Field
* 0b0..Pull/Keeper Disabled
* 0b1..Pull/Keeper Enabled
*/
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_STBY_REQ_PKE(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_STBY_REQ_PKE_SHIFT)) & IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_STBY_REQ_PKE_MASK)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_STBY_REQ_PUE_MASK (0x2000U)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_STBY_REQ_PUE_SHIFT (13U)
/*! PUE - Pull / Keep Select Field Control signal to enable internal pull-up/down resistors or pad keeper functionality.
* 0b0..Keep the previous output value when the output driver is disabled.
* 0b1..Pull-up or pull-down (determined by PUS field).
*/
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_STBY_REQ_PUE(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_STBY_REQ_PUE_SHIFT)) & IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_STBY_REQ_PUE_MASK)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_STBY_REQ_PUS_MASK (0xC000U)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_STBY_REQ_PUS_SHIFT (14U)
/*! PUS - Pull Up / Down Config. Field Controls signals to select pull-up or pull-down internal resistance strength.
* 0b00..100K Ohm Pull Down
* 0b01..47K Ohm Pull Up
* 0b10..100K Ohm Pull Up
* 0b11..22K Ohm Pull Up
*/
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_STBY_REQ_PUS(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_STBY_REQ_PUS_SHIFT)) & IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_STBY_REQ_PUS_MASK)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_STBY_REQ_HYS_MASK (0x10000U)
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_STBY_REQ_HYS_SHIFT (16U)
/*! HYS - Hyst. Enable Field
* 0b0..Hysteresis Disabled (CMOS input)
* 0b1..Hysteresis Enabled (Schmitt Trigger input)
*/
#define IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_STBY_REQ_HYS(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_STBY_REQ_HYS_SHIFT)) & IOMUXC_SNVS_SW_PAD_CTL_PAD_PMIC_STBY_REQ_HYS_MASK)
/*! @} */
/*!
* @}
*/ /* end of group IOMUXC_SNVS_Register_Masks */
/*!
* @}
*/ /* end of group IOMUXC_SNVS_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 */
#endif /* IOMUXC_SNVS_H_ */

View File

@ -0,0 +1,242 @@
/*
** ###################################################################
** Processors: MIMXRT1061CVJ5A
** MIMXRT1061CVJ5B
** MIMXRT1061CVL5A
** MIMXRT1061CVL5B
** MIMXRT1061DVJ6A
** MIMXRT1061DVJ6B
** MIMXRT1061DVL6A
** MIMXRT1061DVL6B
** MIMXRT1061XVN5B
** MIMXRT1062CVJ5A
** MIMXRT1062CVJ5B
** MIMXRT1062CVL5A
** MIMXRT1062CVL5B
** MIMXRT1062DVJ6A
** MIMXRT1062DVJ6B
** MIMXRT1062DVL6A
** MIMXRT1062DVL6B
** MIMXRT1062DVN6B
** MIMXRT1062XVN5B
** MIMXRT106ADVL6A
** MIMXRT106CDVL6A
** MIMXRT106FDVL6A
** MIMXRT106LDVL6A
** MIMXRT106SDVL6A
**
** Version: rev. 1.4, 2022-03-25
** Build: b240705
**
** Abstract:
** CMSIS Peripheral Access Layer for IOMUXC_SNVS_GPR
**
** Copyright 1997-2016 Freescale Semiconductor, Inc.
** Copyright 2016-2024 NXP
** SPDX-License-Identifier: BSD-3-Clause
**
** http: www.nxp.com
** mail: support@nxp.com
**
** Revisions:
** - rev. 0.1 (2017-01-10)
** Initial version.
** - rev. 1.0 (2018-11-16)
** Update header files to align with IMXRT1060RM Rev.0.
** - rev. 1.1 (2018-11-27)
** Update header files to align with IMXRT1060RM Rev.1.
** - rev. 1.2 (2019-04-29)
** Add SET/CLR/TOG register group to register CTRL, STAT, CHANNELCTRL, CH0STAT, CH0OPTS, CH1STAT, CH1OPTS, CH2STAT, CH2OPTS, CH3STAT, CH3OPTS of DCP module.
** - rev. 1.3 (2021-08-10)
** Update header files to align with IMXRT1060RM Rev.3.
** - rev. 1.4 (2022-03-25)
** Add RT1060X device
**
** ###################################################################
*/
/*!
* @file IOMUXC_SNVS_GPR.h
* @version 1.4
* @date 2022-03-25
* @brief CMSIS Peripheral Access Layer for IOMUXC_SNVS_GPR
*
* CMSIS Peripheral Access Layer for IOMUXC_SNVS_GPR
*/
#if !defined(IOMUXC_SNVS_GPR_H_)
#define IOMUXC_SNVS_GPR_H_ /**< Symbol preventing repeated inclusion */
#if (defined(CPU_MIMXRT1061CVJ5A) || defined(CPU_MIMXRT1061CVJ5B) || defined(CPU_MIMXRT1061CVL5A) || defined(CPU_MIMXRT1061CVL5B) || defined(CPU_MIMXRT1061DVJ6A) || defined(CPU_MIMXRT1061DVJ6B) || defined(CPU_MIMXRT1061DVL6A) || defined(CPU_MIMXRT1061DVL6B) || defined(CPU_MIMXRT1061XVN5B))
#include "MIMXRT1061_COMMON.h"
#elif (defined(CPU_MIMXRT1062CVJ5A) || defined(CPU_MIMXRT1062CVJ5B) || defined(CPU_MIMXRT1062CVL5A) || defined(CPU_MIMXRT1062CVL5B) || defined(CPU_MIMXRT1062DVJ6A) || defined(CPU_MIMXRT1062DVJ6B) || defined(CPU_MIMXRT1062DVL6A) || defined(CPU_MIMXRT1062DVL6B) || defined(CPU_MIMXRT1062DVN6B) || defined(CPU_MIMXRT1062XVN5B))
#include "MIMXRT1062_COMMON.h"
#elif (defined(CPU_MIMXRT106ADVL6A))
#include "MIMXRT106A_COMMON.h"
#elif (defined(CPU_MIMXRT106CDVL6A))
#include "MIMXRT106C_COMMON.h"
#elif (defined(CPU_MIMXRT106FDVL6A))
#include "MIMXRT106F_COMMON.h"
#elif (defined(CPU_MIMXRT106LDVL6A))
#include "MIMXRT106L_COMMON.h"
#elif (defined(CPU_MIMXRT106SDVL6A))
#include "MIMXRT106S_COMMON.h"
#else
#error "No valid CPU defined!"
#endif
/* ----------------------------------------------------------------------------
-- 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
/* ----------------------------------------------------------------------------
-- IOMUXC_SNVS_GPR Peripheral Access Layer
---------------------------------------------------------------------------- */
/*!
* @addtogroup IOMUXC_SNVS_GPR_Peripheral_Access_Layer IOMUXC_SNVS_GPR Peripheral Access Layer
* @{
*/
/** IOMUXC_SNVS_GPR - Register Layout Typedef */
typedef struct {
uint32_t GPR0; /**< GPR0 General Purpose Register, offset: 0x0 */
uint32_t GPR1; /**< GPR1 General Purpose Register, offset: 0x4 */
uint32_t GPR2; /**< GPR2 General Purpose Register, offset: 0x8 */
__IO uint32_t GPR3; /**< GPR3 General Purpose Register, offset: 0xC */
} IOMUXC_SNVS_GPR_Type;
/* ----------------------------------------------------------------------------
-- IOMUXC_SNVS_GPR Register Masks
---------------------------------------------------------------------------- */
/*!
* @addtogroup IOMUXC_SNVS_GPR_Register_Masks IOMUXC_SNVS_GPR Register Masks
* @{
*/
/*! @name GPR3 - GPR3 General Purpose Register */
/*! @{ */
#define IOMUXC_SNVS_GPR_GPR3_LPSR_MODE_ENABLE_MASK (0x1U)
#define IOMUXC_SNVS_GPR_GPR3_LPSR_MODE_ENABLE_SHIFT (0U)
/*! LPSR_MODE_ENABLE
* 0b0..SNVS domain will reset when system reset happens
* 0b1..SNVS domain will only reset with SNVS POR
*/
#define IOMUXC_SNVS_GPR_GPR3_LPSR_MODE_ENABLE(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SNVS_GPR_GPR3_LPSR_MODE_ENABLE_SHIFT)) & IOMUXC_SNVS_GPR_GPR3_LPSR_MODE_ENABLE_MASK)
#define IOMUXC_SNVS_GPR_GPR3_DCDC_STATUS_CAPT_CLR_MASK (0x2U)
#define IOMUXC_SNVS_GPR_GPR3_DCDC_STATUS_CAPT_CLR_SHIFT (1U)
/*! DCDC_STATUS_CAPT_CLR - DCDC captured status clear */
#define IOMUXC_SNVS_GPR_GPR3_DCDC_STATUS_CAPT_CLR(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SNVS_GPR_GPR3_DCDC_STATUS_CAPT_CLR_SHIFT)) & IOMUXC_SNVS_GPR_GPR3_DCDC_STATUS_CAPT_CLR_MASK)
#define IOMUXC_SNVS_GPR_GPR3_POR_PULL_TYPE_MASK (0xCU)
#define IOMUXC_SNVS_GPR_GPR3_POR_PULL_TYPE_SHIFT (2U)
/*! POR_PULL_TYPE
* 0b00..100 Ohm pull up enabled for POR_B always
* 0b01..Disable pull in SNVS mode, 100 Ohm pull up enabled otherwise
* 0b10..Disable pull of POR_B always
* 0b11..100 Ohm pull down enabled in SNVS mode, 100 Ohm pull up enabled otherwise
*/
#define IOMUXC_SNVS_GPR_GPR3_POR_PULL_TYPE(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SNVS_GPR_GPR3_POR_PULL_TYPE_SHIFT)) & IOMUXC_SNVS_GPR_GPR3_POR_PULL_TYPE_MASK)
#define IOMUXC_SNVS_GPR_GPR3_DCDC_IN_LOW_VOL_MASK (0x10000U)
#define IOMUXC_SNVS_GPR_GPR3_DCDC_IN_LOW_VOL_SHIFT (16U)
/*! DCDC_IN_LOW_VOL
* 0b0..DCDC_IN is ok
* 0b1..DCDC_IN is too low
*/
#define IOMUXC_SNVS_GPR_GPR3_DCDC_IN_LOW_VOL(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SNVS_GPR_GPR3_DCDC_IN_LOW_VOL_SHIFT)) & IOMUXC_SNVS_GPR_GPR3_DCDC_IN_LOW_VOL_MASK)
#define IOMUXC_SNVS_GPR_GPR3_DCDC_OVER_CUR_MASK (0x20000U)
#define IOMUXC_SNVS_GPR_GPR3_DCDC_OVER_CUR_SHIFT (17U)
/*! DCDC_OVER_CUR
* 0b0..No over current detected
* 0b1..Over current detected
*/
#define IOMUXC_SNVS_GPR_GPR3_DCDC_OVER_CUR(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SNVS_GPR_GPR3_DCDC_OVER_CUR_SHIFT)) & IOMUXC_SNVS_GPR_GPR3_DCDC_OVER_CUR_MASK)
#define IOMUXC_SNVS_GPR_GPR3_DCDC_OVER_VOL_MASK (0x40000U)
#define IOMUXC_SNVS_GPR_GPR3_DCDC_OVER_VOL_SHIFT (18U)
/*! DCDC_OVER_VOL
* 0b0..No over voltage detected
* 0b1..Over voltage detected
*/
#define IOMUXC_SNVS_GPR_GPR3_DCDC_OVER_VOL(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SNVS_GPR_GPR3_DCDC_OVER_VOL_SHIFT)) & IOMUXC_SNVS_GPR_GPR3_DCDC_OVER_VOL_MASK)
#define IOMUXC_SNVS_GPR_GPR3_DCDC_STS_DC_OK_MASK (0x80000U)
#define IOMUXC_SNVS_GPR_GPR3_DCDC_STS_DC_OK_SHIFT (19U)
/*! DCDC_STS_DC_OK
* 0b0..DCDC is ramping up and not ready
* 0b1..DCDC is ready
*/
#define IOMUXC_SNVS_GPR_GPR3_DCDC_STS_DC_OK(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SNVS_GPR_GPR3_DCDC_STS_DC_OK_SHIFT)) & IOMUXC_SNVS_GPR_GPR3_DCDC_STS_DC_OK_MASK)
/*! @} */
/*!
* @}
*/ /* end of group IOMUXC_SNVS_GPR_Register_Masks */
/*!
* @}
*/ /* end of group IOMUXC_SNVS_GPR_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 */
#endif /* IOMUXC_SNVS_GPR_H_ */

View File

@ -0,0 +1,289 @@
/*
** ###################################################################
** Processors: MIMXRT1061CVJ5A
** MIMXRT1061CVJ5B
** MIMXRT1061CVL5A
** MIMXRT1061CVL5B
** MIMXRT1061DVJ6A
** MIMXRT1061DVJ6B
** MIMXRT1061DVL6A
** MIMXRT1061DVL6B
** MIMXRT1061XVN5B
** MIMXRT1062CVJ5A
** MIMXRT1062CVJ5B
** MIMXRT1062CVL5A
** MIMXRT1062CVL5B
** MIMXRT1062DVJ6A
** MIMXRT1062DVJ6B
** MIMXRT1062DVL6A
** MIMXRT1062DVL6B
** MIMXRT1062DVN6B
** MIMXRT1062XVN5B
** MIMXRT106ADVL6A
** MIMXRT106CDVL6A
** MIMXRT106FDVL6A
** MIMXRT106LDVL6A
** MIMXRT106SDVL6A
**
** Version: rev. 1.4, 2022-03-25
** Build: b240705
**
** Abstract:
** CMSIS Peripheral Access Layer for KPP
**
** Copyright 1997-2016 Freescale Semiconductor, Inc.
** Copyright 2016-2024 NXP
** SPDX-License-Identifier: BSD-3-Clause
**
** http: www.nxp.com
** mail: support@nxp.com
**
** Revisions:
** - rev. 0.1 (2017-01-10)
** Initial version.
** - rev. 1.0 (2018-11-16)
** Update header files to align with IMXRT1060RM Rev.0.
** - rev. 1.1 (2018-11-27)
** Update header files to align with IMXRT1060RM Rev.1.
** - rev. 1.2 (2019-04-29)
** Add SET/CLR/TOG register group to register CTRL, STAT, CHANNELCTRL, CH0STAT, CH0OPTS, CH1STAT, CH1OPTS, CH2STAT, CH2OPTS, CH3STAT, CH3OPTS of DCP module.
** - rev. 1.3 (2021-08-10)
** Update header files to align with IMXRT1060RM Rev.3.
** - rev. 1.4 (2022-03-25)
** Add RT1060X device
**
** ###################################################################
*/
/*!
* @file KPP.h
* @version 1.4
* @date 2022-03-25
* @brief CMSIS Peripheral Access Layer for KPP
*
* CMSIS Peripheral Access Layer for KPP
*/
#if !defined(KPP_H_)
#define KPP_H_ /**< Symbol preventing repeated inclusion */
#if (defined(CPU_MIMXRT1061CVJ5A) || defined(CPU_MIMXRT1061CVJ5B) || defined(CPU_MIMXRT1061CVL5A) || defined(CPU_MIMXRT1061CVL5B) || defined(CPU_MIMXRT1061DVJ6A) || defined(CPU_MIMXRT1061DVJ6B) || defined(CPU_MIMXRT1061DVL6A) || defined(CPU_MIMXRT1061DVL6B) || defined(CPU_MIMXRT1061XVN5B))
#include "MIMXRT1061_COMMON.h"
#elif (defined(CPU_MIMXRT1062CVJ5A) || defined(CPU_MIMXRT1062CVJ5B) || defined(CPU_MIMXRT1062CVL5A) || defined(CPU_MIMXRT1062CVL5B) || defined(CPU_MIMXRT1062DVJ6A) || defined(CPU_MIMXRT1062DVJ6B) || defined(CPU_MIMXRT1062DVL6A) || defined(CPU_MIMXRT1062DVL6B) || defined(CPU_MIMXRT1062DVN6B) || defined(CPU_MIMXRT1062XVN5B))
#include "MIMXRT1062_COMMON.h"
#elif (defined(CPU_MIMXRT106ADVL6A))
#include "MIMXRT106A_COMMON.h"
#elif (defined(CPU_MIMXRT106CDVL6A))
#include "MIMXRT106C_COMMON.h"
#elif (defined(CPU_MIMXRT106FDVL6A))
#include "MIMXRT106F_COMMON.h"
#elif (defined(CPU_MIMXRT106LDVL6A))
#include "MIMXRT106L_COMMON.h"
#elif (defined(CPU_MIMXRT106SDVL6A))
#include "MIMXRT106S_COMMON.h"
#else
#error "No valid CPU defined!"
#endif
/* ----------------------------------------------------------------------------
-- 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
/* ----------------------------------------------------------------------------
-- KPP Peripheral Access Layer
---------------------------------------------------------------------------- */
/*!
* @addtogroup KPP_Peripheral_Access_Layer KPP Peripheral Access Layer
* @{
*/
/** KPP - Register Layout Typedef */
typedef struct {
__IO uint16_t KPCR; /**< Keypad Control Register, offset: 0x0 */
__IO uint16_t KPSR; /**< Keypad Status Register, offset: 0x2 */
__IO uint16_t KDDR; /**< Keypad Data Direction Register, offset: 0x4 */
__IO uint16_t KPDR; /**< Keypad Data Register, offset: 0x6 */
} KPP_Type;
/* ----------------------------------------------------------------------------
-- KPP Register Masks
---------------------------------------------------------------------------- */
/*!
* @addtogroup KPP_Register_Masks KPP Register Masks
* @{
*/
/*! @name KPCR - Keypad Control Register */
/*! @{ */
#define KPP_KPCR_KRE_MASK (0xFFU)
#define KPP_KPCR_KRE_SHIFT (0U)
/*! KRE - KRE
* 0b00000000..Row is not included in the keypad key press detect.
* 0b00000001..Row is included in the keypad key press detect.
*/
#define KPP_KPCR_KRE(x) (((uint16_t)(((uint16_t)(x)) << KPP_KPCR_KRE_SHIFT)) & KPP_KPCR_KRE_MASK)
#define KPP_KPCR_KCO_MASK (0xFF00U)
#define KPP_KPCR_KCO_SHIFT (8U)
/*! KCO - KCO
* 0b00000000..Column strobe output is totem pole drive.
* 0b00000001..Column strobe output is open drain.
*/
#define KPP_KPCR_KCO(x) (((uint16_t)(((uint16_t)(x)) << KPP_KPCR_KCO_SHIFT)) & KPP_KPCR_KCO_MASK)
/*! @} */
/*! @name KPSR - Keypad Status Register */
/*! @{ */
#define KPP_KPSR_KPKD_MASK (0x1U)
#define KPP_KPSR_KPKD_SHIFT (0U)
/*! KPKD - KPKD
* 0b0..No key presses detected
* 0b1..A key has been depressed
*/
#define KPP_KPSR_KPKD(x) (((uint16_t)(((uint16_t)(x)) << KPP_KPSR_KPKD_SHIFT)) & KPP_KPSR_KPKD_MASK)
#define KPP_KPSR_KPKR_MASK (0x2U)
#define KPP_KPSR_KPKR_SHIFT (1U)
/*! KPKR - KPKR
* 0b0..No key release detected
* 0b1..All keys have been released
*/
#define KPP_KPSR_KPKR(x) (((uint16_t)(((uint16_t)(x)) << KPP_KPSR_KPKR_SHIFT)) & KPP_KPSR_KPKR_MASK)
#define KPP_KPSR_KDSC_MASK (0x4U)
#define KPP_KPSR_KDSC_SHIFT (2U)
/*! KDSC - KDSC
* 0b0..No effect
* 0b1..Set bits that clear the keypad depress synchronizer chain
*/
#define KPP_KPSR_KDSC(x) (((uint16_t)(((uint16_t)(x)) << KPP_KPSR_KDSC_SHIFT)) & KPP_KPSR_KDSC_MASK)
#define KPP_KPSR_KRSS_MASK (0x8U)
#define KPP_KPSR_KRSS_SHIFT (3U)
/*! KRSS - KRSS
* 0b0..No effect
* 0b1..Set bits which sets keypad release synchronizer chain
*/
#define KPP_KPSR_KRSS(x) (((uint16_t)(((uint16_t)(x)) << KPP_KPSR_KRSS_SHIFT)) & KPP_KPSR_KRSS_MASK)
#define KPP_KPSR_KDIE_MASK (0x100U)
#define KPP_KPSR_KDIE_SHIFT (8U)
/*! KDIE - KDIE
* 0b0..No interrupt request is generated when KPKD is set.
* 0b1..An interrupt request is generated when KPKD is set.
*/
#define KPP_KPSR_KDIE(x) (((uint16_t)(((uint16_t)(x)) << KPP_KPSR_KDIE_SHIFT)) & KPP_KPSR_KDIE_MASK)
#define KPP_KPSR_KRIE_MASK (0x200U)
#define KPP_KPSR_KRIE_SHIFT (9U)
/*! KRIE - KRIE
* 0b0..No interrupt request is generated when KPKR is set.
* 0b1..An interrupt request is generated when KPKR is set.
*/
#define KPP_KPSR_KRIE(x) (((uint16_t)(((uint16_t)(x)) << KPP_KPSR_KRIE_SHIFT)) & KPP_KPSR_KRIE_MASK)
/*! @} */
/*! @name KDDR - Keypad Data Direction Register */
/*! @{ */
#define KPP_KDDR_KRDD_MASK (0xFFU)
#define KPP_KDDR_KRDD_SHIFT (0U)
/*! KRDD - KRDD
* 0b00000000..ROWn pin configured as an input.
* 0b00000001..ROWn pin configured as an output.
*/
#define KPP_KDDR_KRDD(x) (((uint16_t)(((uint16_t)(x)) << KPP_KDDR_KRDD_SHIFT)) & KPP_KDDR_KRDD_MASK)
#define KPP_KDDR_KCDD_MASK (0xFF00U)
#define KPP_KDDR_KCDD_SHIFT (8U)
/*! KCDD - KCDD
* 0b00000000..COLn pin is configured as an input.
* 0b00000001..COLn pin is configured as an output.
*/
#define KPP_KDDR_KCDD(x) (((uint16_t)(((uint16_t)(x)) << KPP_KDDR_KCDD_SHIFT)) & KPP_KDDR_KCDD_MASK)
/*! @} */
/*! @name KPDR - Keypad Data Register */
/*! @{ */
#define KPP_KPDR_KRD_MASK (0xFFU)
#define KPP_KPDR_KRD_SHIFT (0U)
/*! KRD - KRD */
#define KPP_KPDR_KRD(x) (((uint16_t)(((uint16_t)(x)) << KPP_KPDR_KRD_SHIFT)) & KPP_KPDR_KRD_MASK)
#define KPP_KPDR_KCD_MASK (0xFF00U)
#define KPP_KPDR_KCD_SHIFT (8U)
/*! KCD - KCD */
#define KPP_KPDR_KCD(x) (((uint16_t)(((uint16_t)(x)) << KPP_KPDR_KCD_SHIFT)) & KPP_KPDR_KCD_MASK)
/*! @} */
/*!
* @}
*/ /* end of group KPP_Register_Masks */
/*!
* @}
*/ /* end of group KPP_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 */
#endif /* KPP_H_ */

View File

@ -0,0 +1,798 @@
/*
** ###################################################################
** Processors: MIMXRT1061CVJ5A
** MIMXRT1061CVJ5B
** MIMXRT1061CVL5A
** MIMXRT1061CVL5B
** MIMXRT1061DVJ6A
** MIMXRT1061DVJ6B
** MIMXRT1061DVL6A
** MIMXRT1061DVL6B
** MIMXRT1061XVN5B
** MIMXRT1062CVJ5A
** MIMXRT1062CVJ5B
** MIMXRT1062CVL5A
** MIMXRT1062CVL5B
** MIMXRT1062DVJ6A
** MIMXRT1062DVJ6B
** MIMXRT1062DVL6A
** MIMXRT1062DVL6B
** MIMXRT1062DVN6B
** MIMXRT1062XVN5B
** MIMXRT106ADVL6A
** MIMXRT106CDVL6A
** MIMXRT106FDVL6A
** MIMXRT106LDVL6A
** MIMXRT106SDVL6A
**
** Version: rev. 1.4, 2022-03-25
** Build: b240705
**
** Abstract:
** CMSIS Peripheral Access Layer for LPSPI
**
** Copyright 1997-2016 Freescale Semiconductor, Inc.
** Copyright 2016-2024 NXP
** SPDX-License-Identifier: BSD-3-Clause
**
** http: www.nxp.com
** mail: support@nxp.com
**
** Revisions:
** - rev. 0.1 (2017-01-10)
** Initial version.
** - rev. 1.0 (2018-11-16)
** Update header files to align with IMXRT1060RM Rev.0.
** - rev. 1.1 (2018-11-27)
** Update header files to align with IMXRT1060RM Rev.1.
** - rev. 1.2 (2019-04-29)
** Add SET/CLR/TOG register group to register CTRL, STAT, CHANNELCTRL, CH0STAT, CH0OPTS, CH1STAT, CH1OPTS, CH2STAT, CH2OPTS, CH3STAT, CH3OPTS of DCP module.
** - rev. 1.3 (2021-08-10)
** Update header files to align with IMXRT1060RM Rev.3.
** - rev. 1.4 (2022-03-25)
** Add RT1060X device
**
** ###################################################################
*/
/*!
* @file LPSPI.h
* @version 1.4
* @date 2022-03-25
* @brief CMSIS Peripheral Access Layer for LPSPI
*
* CMSIS Peripheral Access Layer for LPSPI
*/
#if !defined(LPSPI_H_)
#define LPSPI_H_ /**< Symbol preventing repeated inclusion */
#if (defined(CPU_MIMXRT1061CVJ5A) || defined(CPU_MIMXRT1061CVJ5B) || defined(CPU_MIMXRT1061CVL5A) || defined(CPU_MIMXRT1061CVL5B) || defined(CPU_MIMXRT1061DVJ6A) || defined(CPU_MIMXRT1061DVJ6B) || defined(CPU_MIMXRT1061DVL6A) || defined(CPU_MIMXRT1061DVL6B) || defined(CPU_MIMXRT1061XVN5B))
#include "MIMXRT1061_COMMON.h"
#elif (defined(CPU_MIMXRT1062CVJ5A) || defined(CPU_MIMXRT1062CVJ5B) || defined(CPU_MIMXRT1062CVL5A) || defined(CPU_MIMXRT1062CVL5B) || defined(CPU_MIMXRT1062DVJ6A) || defined(CPU_MIMXRT1062DVJ6B) || defined(CPU_MIMXRT1062DVL6A) || defined(CPU_MIMXRT1062DVL6B) || defined(CPU_MIMXRT1062DVN6B) || defined(CPU_MIMXRT1062XVN5B))
#include "MIMXRT1062_COMMON.h"
#elif (defined(CPU_MIMXRT106ADVL6A))
#include "MIMXRT106A_COMMON.h"
#elif (defined(CPU_MIMXRT106CDVL6A))
#include "MIMXRT106C_COMMON.h"
#elif (defined(CPU_MIMXRT106FDVL6A))
#include "MIMXRT106F_COMMON.h"
#elif (defined(CPU_MIMXRT106LDVL6A))
#include "MIMXRT106L_COMMON.h"
#elif (defined(CPU_MIMXRT106SDVL6A))
#include "MIMXRT106S_COMMON.h"
#else
#error "No valid CPU defined!"
#endif
/* ----------------------------------------------------------------------------
-- 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
/* ----------------------------------------------------------------------------
-- LPSPI Peripheral Access Layer
---------------------------------------------------------------------------- */
/*!
* @addtogroup LPSPI_Peripheral_Access_Layer LPSPI Peripheral Access Layer
* @{
*/
/** LPSPI - Register Layout Typedef */
typedef struct {
__I uint32_t VERID; /**< Version ID, offset: 0x0 */
__I uint32_t PARAM; /**< Parameter, offset: 0x4 */
uint8_t RESERVED_0[8];
__IO uint32_t CR; /**< Control, offset: 0x10 */
__IO uint32_t SR; /**< Status, offset: 0x14 */
__IO uint32_t IER; /**< Interrupt Enable, offset: 0x18 */
__IO uint32_t DER; /**< DMA Enable, offset: 0x1C */
__IO uint32_t CFGR0; /**< Configuration 0, offset: 0x20 */
__IO uint32_t CFGR1; /**< Configuration 1, offset: 0x24 */
uint8_t RESERVED_1[8];
__IO uint32_t DMR0; /**< Data Match 0, offset: 0x30 */
__IO uint32_t DMR1; /**< Data Match 1, offset: 0x34 */
uint8_t RESERVED_2[8];
__IO uint32_t CCR; /**< Clock Configuration, offset: 0x40 */
uint8_t RESERVED_3[20];
__IO uint32_t FCR; /**< FIFO Control, offset: 0x58 */
__I uint32_t FSR; /**< FIFO Status, offset: 0x5C */
__IO uint32_t TCR; /**< Transmit Command, offset: 0x60 */
__O uint32_t TDR; /**< Transmit Data, offset: 0x64 */
uint8_t RESERVED_4[8];
__I uint32_t RSR; /**< Receive Status, offset: 0x70 */
__I uint32_t RDR; /**< Receive Data, offset: 0x74 */
} LPSPI_Type;
/* ----------------------------------------------------------------------------
-- LPSPI Register Masks
---------------------------------------------------------------------------- */
/*!
* @addtogroup LPSPI_Register_Masks LPSPI Register Masks
* @{
*/
/*! @name VERID - Version ID */
/*! @{ */
#define LPSPI_VERID_FEATURE_MASK (0xFFFFU)
#define LPSPI_VERID_FEATURE_SHIFT (0U)
/*! FEATURE - Module Identification Number
* 0b0000000000000100..Standard feature set supporting a 32-bit shift register.
*/
#define LPSPI_VERID_FEATURE(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_VERID_FEATURE_SHIFT)) & LPSPI_VERID_FEATURE_MASK)
#define LPSPI_VERID_MINOR_MASK (0xFF0000U)
#define LPSPI_VERID_MINOR_SHIFT (16U)
/*! MINOR - Minor Version Number */
#define LPSPI_VERID_MINOR(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_VERID_MINOR_SHIFT)) & LPSPI_VERID_MINOR_MASK)
#define LPSPI_VERID_MAJOR_MASK (0xFF000000U)
#define LPSPI_VERID_MAJOR_SHIFT (24U)
/*! MAJOR - Major Version Number */
#define LPSPI_VERID_MAJOR(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_VERID_MAJOR_SHIFT)) & LPSPI_VERID_MAJOR_MASK)
/*! @} */
/*! @name PARAM - Parameter */
/*! @{ */
#define LPSPI_PARAM_TXFIFO_MASK (0xFFU)
#define LPSPI_PARAM_TXFIFO_SHIFT (0U)
/*! TXFIFO - Transmit FIFO Size */
#define LPSPI_PARAM_TXFIFO(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_PARAM_TXFIFO_SHIFT)) & LPSPI_PARAM_TXFIFO_MASK)
#define LPSPI_PARAM_RXFIFO_MASK (0xFF00U)
#define LPSPI_PARAM_RXFIFO_SHIFT (8U)
/*! RXFIFO - Receive FIFO Size */
#define LPSPI_PARAM_RXFIFO(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_PARAM_RXFIFO_SHIFT)) & LPSPI_PARAM_RXFIFO_MASK)
#define LPSPI_PARAM_PCSNUM_MASK (0xFF0000U)
#define LPSPI_PARAM_PCSNUM_SHIFT (16U)
/*! PCSNUM - PCS Number */
#define LPSPI_PARAM_PCSNUM(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_PARAM_PCSNUM_SHIFT)) & LPSPI_PARAM_PCSNUM_MASK)
/*! @} */
/*! @name CR - Control */
/*! @{ */
#define LPSPI_CR_MEN_MASK (0x1U)
#define LPSPI_CR_MEN_SHIFT (0U)
/*! MEN - Module Enable
* 0b0..Module is disabled
* 0b1..Module is enabled
*/
#define LPSPI_CR_MEN(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_CR_MEN_SHIFT)) & LPSPI_CR_MEN_MASK)
#define LPSPI_CR_RST_MASK (0x2U)
#define LPSPI_CR_RST_SHIFT (1U)
/*! RST - Software Reset
* 0b0..Module is not reset
* 0b1..Module is reset
*/
#define LPSPI_CR_RST(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_CR_RST_SHIFT)) & LPSPI_CR_RST_MASK)
#define LPSPI_CR_DOZEN_MASK (0x4U)
#define LPSPI_CR_DOZEN_SHIFT (2U)
/*! DOZEN - Doze Mode Enable
* 0b0..LPSPI module is enabled in Doze mode
* 0b1..LPSPI module is disabled in Doze mode
*/
#define LPSPI_CR_DOZEN(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_CR_DOZEN_SHIFT)) & LPSPI_CR_DOZEN_MASK)
#define LPSPI_CR_DBGEN_MASK (0x8U)
#define LPSPI_CR_DBGEN_SHIFT (3U)
/*! DBGEN - Debug Enable
* 0b0..LPSPI module is disabled when the CPU is halted. When LPSPI is disabled, the PCS will be negated once the
* transmit FIFO is empty regardless of the state of TCR register.
* 0b1..LPSPI module is enabled in debug mode
*/
#define LPSPI_CR_DBGEN(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_CR_DBGEN_SHIFT)) & LPSPI_CR_DBGEN_MASK)
#define LPSPI_CR_RTF_MASK (0x100U)
#define LPSPI_CR_RTF_SHIFT (8U)
/*! RTF - Reset Transmit FIFO
* 0b0..No effect
* 0b1..Reset the Transmit FIFO. The register bit always reads zero.
*/
#define LPSPI_CR_RTF(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_CR_RTF_SHIFT)) & LPSPI_CR_RTF_MASK)
#define LPSPI_CR_RRF_MASK (0x200U)
#define LPSPI_CR_RRF_SHIFT (9U)
/*! RRF - Reset Receive FIFO
* 0b0..No effect
* 0b1..Reset the Receive FIFO. The register bit always reads zero.
*/
#define LPSPI_CR_RRF(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_CR_RRF_SHIFT)) & LPSPI_CR_RRF_MASK)
/*! @} */
/*! @name SR - Status */
/*! @{ */
#define LPSPI_SR_TDF_MASK (0x1U)
#define LPSPI_SR_TDF_SHIFT (0U)
/*! TDF - Transmit Data Flag
* 0b0..Transmit data not requested
* 0b1..Transmit data is requested
*/
#define LPSPI_SR_TDF(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_SR_TDF_SHIFT)) & LPSPI_SR_TDF_MASK)
#define LPSPI_SR_RDF_MASK (0x2U)
#define LPSPI_SR_RDF_SHIFT (1U)
/*! RDF - Receive Data Flag
* 0b0..Receive Data is not ready
* 0b1..Receive data is ready
*/
#define LPSPI_SR_RDF(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_SR_RDF_SHIFT)) & LPSPI_SR_RDF_MASK)
#define LPSPI_SR_WCF_MASK (0x100U)
#define LPSPI_SR_WCF_SHIFT (8U)
/*! WCF - Word Complete Flag
* 0b0..Transfer of a received word has not yet completed
* 0b1..Transfer of a received word has completed
*/
#define LPSPI_SR_WCF(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_SR_WCF_SHIFT)) & LPSPI_SR_WCF_MASK)
#define LPSPI_SR_FCF_MASK (0x200U)
#define LPSPI_SR_FCF_SHIFT (9U)
/*! FCF - Frame Complete Flag
* 0b0..Frame transfer has not completed
* 0b1..Frame transfer has completed
*/
#define LPSPI_SR_FCF(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_SR_FCF_SHIFT)) & LPSPI_SR_FCF_MASK)
#define LPSPI_SR_TCF_MASK (0x400U)
#define LPSPI_SR_TCF_SHIFT (10U)
/*! TCF - Transfer Complete Flag
* 0b0..All transfers have not completed
* 0b1..All transfers have completed
*/
#define LPSPI_SR_TCF(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_SR_TCF_SHIFT)) & LPSPI_SR_TCF_MASK)
#define LPSPI_SR_TEF_MASK (0x800U)
#define LPSPI_SR_TEF_SHIFT (11U)
/*! TEF - Transmit Error Flag
* 0b0..Transmit FIFO underrun has not occurred
* 0b1..Transmit FIFO underrun has occurred
*/
#define LPSPI_SR_TEF(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_SR_TEF_SHIFT)) & LPSPI_SR_TEF_MASK)
#define LPSPI_SR_REF_MASK (0x1000U)
#define LPSPI_SR_REF_SHIFT (12U)
/*! REF - Receive Error Flag
* 0b0..Receive FIFO has not overflowed
* 0b1..Receive FIFO has overflowed
*/
#define LPSPI_SR_REF(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_SR_REF_SHIFT)) & LPSPI_SR_REF_MASK)
#define LPSPI_SR_DMF_MASK (0x2000U)
#define LPSPI_SR_DMF_SHIFT (13U)
/*! DMF - Data Match Flag
* 0b0..Have not received matching data
* 0b1..Have received matching data
*/
#define LPSPI_SR_DMF(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_SR_DMF_SHIFT)) & LPSPI_SR_DMF_MASK)
#define LPSPI_SR_MBF_MASK (0x1000000U)
#define LPSPI_SR_MBF_SHIFT (24U)
/*! MBF - Module Busy Flag
* 0b0..LPSPI is idle
* 0b1..LPSPI is busy
*/
#define LPSPI_SR_MBF(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_SR_MBF_SHIFT)) & LPSPI_SR_MBF_MASK)
/*! @} */
/*! @name IER - Interrupt Enable */
/*! @{ */
#define LPSPI_IER_TDIE_MASK (0x1U)
#define LPSPI_IER_TDIE_SHIFT (0U)
/*! TDIE - Transmit Data Interrupt Enable
* 0b0..Disabled
* 0b1..Enabled
*/
#define LPSPI_IER_TDIE(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_IER_TDIE_SHIFT)) & LPSPI_IER_TDIE_MASK)
#define LPSPI_IER_RDIE_MASK (0x2U)
#define LPSPI_IER_RDIE_SHIFT (1U)
/*! RDIE - Receive Data Interrupt Enable
* 0b0..Disabled
* 0b1..Enabled
*/
#define LPSPI_IER_RDIE(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_IER_RDIE_SHIFT)) & LPSPI_IER_RDIE_MASK)
#define LPSPI_IER_WCIE_MASK (0x100U)
#define LPSPI_IER_WCIE_SHIFT (8U)
/*! WCIE - Word Complete Interrupt Enable
* 0b0..Disabled
* 0b1..Enabled
*/
#define LPSPI_IER_WCIE(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_IER_WCIE_SHIFT)) & LPSPI_IER_WCIE_MASK)
#define LPSPI_IER_FCIE_MASK (0x200U)
#define LPSPI_IER_FCIE_SHIFT (9U)
/*! FCIE - Frame Complete Interrupt Enable
* 0b0..Disabled
* 0b1..Enabled
*/
#define LPSPI_IER_FCIE(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_IER_FCIE_SHIFT)) & LPSPI_IER_FCIE_MASK)
#define LPSPI_IER_TCIE_MASK (0x400U)
#define LPSPI_IER_TCIE_SHIFT (10U)
/*! TCIE - Transfer Complete Interrupt Enable
* 0b0..Disabled
* 0b1..Enabled
*/
#define LPSPI_IER_TCIE(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_IER_TCIE_SHIFT)) & LPSPI_IER_TCIE_MASK)
#define LPSPI_IER_TEIE_MASK (0x800U)
#define LPSPI_IER_TEIE_SHIFT (11U)
/*! TEIE - Transmit Error Interrupt Enable
* 0b0..Disabled
* 0b1..Enabled
*/
#define LPSPI_IER_TEIE(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_IER_TEIE_SHIFT)) & LPSPI_IER_TEIE_MASK)
#define LPSPI_IER_REIE_MASK (0x1000U)
#define LPSPI_IER_REIE_SHIFT (12U)
/*! REIE - Receive Error Interrupt Enable
* 0b0..Disabled
* 0b1..Enabled
*/
#define LPSPI_IER_REIE(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_IER_REIE_SHIFT)) & LPSPI_IER_REIE_MASK)
#define LPSPI_IER_DMIE_MASK (0x2000U)
#define LPSPI_IER_DMIE_SHIFT (13U)
/*! DMIE - Data Match Interrupt Enable
* 0b0..Disabled
* 0b1..Enabled
*/
#define LPSPI_IER_DMIE(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_IER_DMIE_SHIFT)) & LPSPI_IER_DMIE_MASK)
/*! @} */
/*! @name DER - DMA Enable */
/*! @{ */
#define LPSPI_DER_TDDE_MASK (0x1U)
#define LPSPI_DER_TDDE_SHIFT (0U)
/*! TDDE - Transmit Data DMA Enable
* 0b0..DMA request is disabled
* 0b1..DMA request is enabled
*/
#define LPSPI_DER_TDDE(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_DER_TDDE_SHIFT)) & LPSPI_DER_TDDE_MASK)
#define LPSPI_DER_RDDE_MASK (0x2U)
#define LPSPI_DER_RDDE_SHIFT (1U)
/*! RDDE - Receive Data DMA Enable
* 0b0..DMA request is disabled
* 0b1..DMA request is enabled
*/
#define LPSPI_DER_RDDE(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_DER_RDDE_SHIFT)) & LPSPI_DER_RDDE_MASK)
/*! @} */
/*! @name CFGR0 - Configuration 0 */
/*! @{ */
#define LPSPI_CFGR0_HREN_MASK (0x1U)
#define LPSPI_CFGR0_HREN_SHIFT (0U)
/*! HREN - Host Request Enable
* 0b0..Host request is disabled
* 0b1..Host request is enabled
*/
#define LPSPI_CFGR0_HREN(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_CFGR0_HREN_SHIFT)) & LPSPI_CFGR0_HREN_MASK)
#define LPSPI_CFGR0_HRPOL_MASK (0x2U)
#define LPSPI_CFGR0_HRPOL_SHIFT (1U)
/*! HRPOL - Host Request Polarity
* 0b0..HREQ pin is active high provided PCSPOL[1] is clear
* 0b1..HREQ pin is active low provided PCSPOL[1] is clear
*/
#define LPSPI_CFGR0_HRPOL(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_CFGR0_HRPOL_SHIFT)) & LPSPI_CFGR0_HRPOL_MASK)
#define LPSPI_CFGR0_HRSEL_MASK (0x4U)
#define LPSPI_CFGR0_HRSEL_SHIFT (2U)
/*! HRSEL - Host Request Select
* 0b0..Host request input is the HREQ pin
* 0b1..Host request input is the input trigger
*/
#define LPSPI_CFGR0_HRSEL(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_CFGR0_HRSEL_SHIFT)) & LPSPI_CFGR0_HRSEL_MASK)
#define LPSPI_CFGR0_CIRFIFO_MASK (0x100U)
#define LPSPI_CFGR0_CIRFIFO_SHIFT (8U)
/*! CIRFIFO - Circular FIFO Enable
* 0b0..Circular FIFO is disabled
* 0b1..Circular FIFO is enabled
*/
#define LPSPI_CFGR0_CIRFIFO(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_CFGR0_CIRFIFO_SHIFT)) & LPSPI_CFGR0_CIRFIFO_MASK)
#define LPSPI_CFGR0_RDMO_MASK (0x200U)
#define LPSPI_CFGR0_RDMO_SHIFT (9U)
/*! RDMO - Receive Data Match Only
* 0b0..Received data is stored in the receive FIFO as in normal operations
* 0b1..Received data is discarded unless the SR[DMF] = 1
*/
#define LPSPI_CFGR0_RDMO(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_CFGR0_RDMO_SHIFT)) & LPSPI_CFGR0_RDMO_MASK)
/*! @} */
/*! @name CFGR1 - Configuration 1 */
/*! @{ */
#define LPSPI_CFGR1_MASTER_MASK (0x1U)
#define LPSPI_CFGR1_MASTER_SHIFT (0U)
/*! MASTER - Master Mode
* 0b0..Slave mode
* 0b1..Master mode
*/
#define LPSPI_CFGR1_MASTER(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_CFGR1_MASTER_SHIFT)) & LPSPI_CFGR1_MASTER_MASK)
#define LPSPI_CFGR1_SAMPLE_MASK (0x2U)
#define LPSPI_CFGR1_SAMPLE_SHIFT (1U)
/*! SAMPLE - Sample Point
* 0b0..Input data is sampled on SCK edge
* 0b1..Input data is sampled on delayed SCK edge
*/
#define LPSPI_CFGR1_SAMPLE(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_CFGR1_SAMPLE_SHIFT)) & LPSPI_CFGR1_SAMPLE_MASK)
#define LPSPI_CFGR1_AUTOPCS_MASK (0x4U)
#define LPSPI_CFGR1_AUTOPCS_SHIFT (2U)
/*! AUTOPCS - Automatic PCS
* 0b0..Automatic PCS generation is disabled
* 0b1..Automatic PCS generation is enabled
*/
#define LPSPI_CFGR1_AUTOPCS(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_CFGR1_AUTOPCS_SHIFT)) & LPSPI_CFGR1_AUTOPCS_MASK)
#define LPSPI_CFGR1_NOSTALL_MASK (0x8U)
#define LPSPI_CFGR1_NOSTALL_SHIFT (3U)
/*! NOSTALL - No Stall
* 0b0..Transfers stall when the transmit FIFO is empty
* 0b1..Transfers do not stall, allowing transmit FIFO underruns to occur
*/
#define LPSPI_CFGR1_NOSTALL(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_CFGR1_NOSTALL_SHIFT)) & LPSPI_CFGR1_NOSTALL_MASK)
#define LPSPI_CFGR1_PCSPOL_MASK (0xF00U)
#define LPSPI_CFGR1_PCSPOL_SHIFT (8U)
/*! PCSPOL - Peripheral Chip Select Polarity */
#define LPSPI_CFGR1_PCSPOL(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_CFGR1_PCSPOL_SHIFT)) & LPSPI_CFGR1_PCSPOL_MASK)
#define LPSPI_CFGR1_MATCFG_MASK (0x70000U)
#define LPSPI_CFGR1_MATCFG_SHIFT (16U)
/*! MATCFG - Match Configuration
* 0b000..Match is disabled
* 0b001..Reserved
* 0b010..Match is enabled is 1st data word is MATCH0 or MATCH1
* 0b011..Match is enabled on any data word equal MATCH0 or MATCH1
* 0b100..Match is enabled on data match sequence
* 0b101..Match is enabled on data match sequence
* 0b110..Match is enabled
* 0b111..Match is enabled
*/
#define LPSPI_CFGR1_MATCFG(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_CFGR1_MATCFG_SHIFT)) & LPSPI_CFGR1_MATCFG_MASK)
#define LPSPI_CFGR1_PINCFG_MASK (0x3000000U)
#define LPSPI_CFGR1_PINCFG_SHIFT (24U)
/*! PINCFG - Pin Configuration
* 0b00..SIN is used for input data and SOUT is used for output data
* 0b01..SIN is used for both input and output data, only half-duplex serial transfers are supported
* 0b10..SOUT is used for both input and output data, only half-duplex serial transfers are supported
* 0b11..SOUT is used for input data and SIN is used for output data
*/
#define LPSPI_CFGR1_PINCFG(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_CFGR1_PINCFG_SHIFT)) & LPSPI_CFGR1_PINCFG_MASK)
#define LPSPI_CFGR1_OUTCFG_MASK (0x4000000U)
#define LPSPI_CFGR1_OUTCFG_SHIFT (26U)
/*! OUTCFG - Output Configuration
* 0b0..Output data retains last value when chip select is negated
* 0b1..Output data is tristated when chip select is negated
*/
#define LPSPI_CFGR1_OUTCFG(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_CFGR1_OUTCFG_SHIFT)) & LPSPI_CFGR1_OUTCFG_MASK)
#define LPSPI_CFGR1_PCSCFG_MASK (0x8000000U)
#define LPSPI_CFGR1_PCSCFG_SHIFT (27U)
/*! PCSCFG - Peripheral Chip Select Configuration
* 0b0..PCS[3:2] are configured for chip select function
* 0b1..PCS[3:2] are configured for half-duplex 4-bit transfers (PCS[3:2] = DATA[3:2])
*/
#define LPSPI_CFGR1_PCSCFG(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_CFGR1_PCSCFG_SHIFT)) & LPSPI_CFGR1_PCSCFG_MASK)
/*! @} */
/*! @name DMR0 - Data Match 0 */
/*! @{ */
#define LPSPI_DMR0_MATCH0_MASK (0xFFFFFFFFU)
#define LPSPI_DMR0_MATCH0_SHIFT (0U)
/*! MATCH0 - Match 0 Value */
#define LPSPI_DMR0_MATCH0(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_DMR0_MATCH0_SHIFT)) & LPSPI_DMR0_MATCH0_MASK)
/*! @} */
/*! @name DMR1 - Data Match 1 */
/*! @{ */
#define LPSPI_DMR1_MATCH1_MASK (0xFFFFFFFFU)
#define LPSPI_DMR1_MATCH1_SHIFT (0U)
/*! MATCH1 - Match 1 Value */
#define LPSPI_DMR1_MATCH1(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_DMR1_MATCH1_SHIFT)) & LPSPI_DMR1_MATCH1_MASK)
/*! @} */
/*! @name CCR - Clock Configuration */
/*! @{ */
#define LPSPI_CCR_SCKDIV_MASK (0xFFU)
#define LPSPI_CCR_SCKDIV_SHIFT (0U)
/*! SCKDIV - SCK Divider */
#define LPSPI_CCR_SCKDIV(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_CCR_SCKDIV_SHIFT)) & LPSPI_CCR_SCKDIV_MASK)
#define LPSPI_CCR_DBT_MASK (0xFF00U)
#define LPSPI_CCR_DBT_SHIFT (8U)
/*! DBT - Delay Between Transfers */
#define LPSPI_CCR_DBT(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_CCR_DBT_SHIFT)) & LPSPI_CCR_DBT_MASK)
#define LPSPI_CCR_PCSSCK_MASK (0xFF0000U)
#define LPSPI_CCR_PCSSCK_SHIFT (16U)
/*! PCSSCK - PCS-to-SCK Delay */
#define LPSPI_CCR_PCSSCK(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_CCR_PCSSCK_SHIFT)) & LPSPI_CCR_PCSSCK_MASK)
#define LPSPI_CCR_SCKPCS_MASK (0xFF000000U)
#define LPSPI_CCR_SCKPCS_SHIFT (24U)
/*! SCKPCS - SCK-to-PCS Delay */
#define LPSPI_CCR_SCKPCS(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_CCR_SCKPCS_SHIFT)) & LPSPI_CCR_SCKPCS_MASK)
/*! @} */
/*! @name FCR - FIFO Control */
/*! @{ */
#define LPSPI_FCR_TXWATER_MASK (0xFU)
#define LPSPI_FCR_TXWATER_SHIFT (0U)
/*! TXWATER - Transmit FIFO Watermark */
#define LPSPI_FCR_TXWATER(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_FCR_TXWATER_SHIFT)) & LPSPI_FCR_TXWATER_MASK)
#define LPSPI_FCR_RXWATER_MASK (0xF0000U)
#define LPSPI_FCR_RXWATER_SHIFT (16U)
/*! RXWATER - Receive FIFO Watermark */
#define LPSPI_FCR_RXWATER(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_FCR_RXWATER_SHIFT)) & LPSPI_FCR_RXWATER_MASK)
/*! @} */
/*! @name FSR - FIFO Status */
/*! @{ */
#define LPSPI_FSR_TXCOUNT_MASK (0x1FU)
#define LPSPI_FSR_TXCOUNT_SHIFT (0U)
/*! TXCOUNT - Transmit FIFO Count */
#define LPSPI_FSR_TXCOUNT(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_FSR_TXCOUNT_SHIFT)) & LPSPI_FSR_TXCOUNT_MASK)
#define LPSPI_FSR_RXCOUNT_MASK (0x1F0000U)
#define LPSPI_FSR_RXCOUNT_SHIFT (16U)
/*! RXCOUNT - Receive FIFO Count */
#define LPSPI_FSR_RXCOUNT(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_FSR_RXCOUNT_SHIFT)) & LPSPI_FSR_RXCOUNT_MASK)
/*! @} */
/*! @name TCR - Transmit Command */
/*! @{ */
#define LPSPI_TCR_FRAMESZ_MASK (0xFFFU)
#define LPSPI_TCR_FRAMESZ_SHIFT (0U)
/*! FRAMESZ - Frame Size */
#define LPSPI_TCR_FRAMESZ(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_TCR_FRAMESZ_SHIFT)) & LPSPI_TCR_FRAMESZ_MASK)
#define LPSPI_TCR_WIDTH_MASK (0x30000U)
#define LPSPI_TCR_WIDTH_SHIFT (16U)
/*! WIDTH - Transfer Width
* 0b00..1 bit transfer
* 0b01..2 bit transfer
* 0b10..4 bit transfer
* 0b11..Reserved
*/
#define LPSPI_TCR_WIDTH(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_TCR_WIDTH_SHIFT)) & LPSPI_TCR_WIDTH_MASK)
#define LPSPI_TCR_TXMSK_MASK (0x40000U)
#define LPSPI_TCR_TXMSK_SHIFT (18U)
/*! TXMSK - Transmit Data Mask
* 0b0..Normal transfer
* 0b1..Mask transmit data
*/
#define LPSPI_TCR_TXMSK(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_TCR_TXMSK_SHIFT)) & LPSPI_TCR_TXMSK_MASK)
#define LPSPI_TCR_RXMSK_MASK (0x80000U)
#define LPSPI_TCR_RXMSK_SHIFT (19U)
/*! RXMSK - Receive Data Mask
* 0b0..Normal transfer
* 0b1..Receive data is masked
*/
#define LPSPI_TCR_RXMSK(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_TCR_RXMSK_SHIFT)) & LPSPI_TCR_RXMSK_MASK)
#define LPSPI_TCR_CONTC_MASK (0x100000U)
#define LPSPI_TCR_CONTC_SHIFT (20U)
/*! CONTC - Continuing Command
* 0b0..Command word for start of new transfer
* 0b1..Command word for continuing transfer
*/
#define LPSPI_TCR_CONTC(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_TCR_CONTC_SHIFT)) & LPSPI_TCR_CONTC_MASK)
#define LPSPI_TCR_CONT_MASK (0x200000U)
#define LPSPI_TCR_CONT_SHIFT (21U)
/*! CONT - Continuous Transfer
* 0b0..Continuous transfer is disabled
* 0b1..Continuous transfer is enabled
*/
#define LPSPI_TCR_CONT(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_TCR_CONT_SHIFT)) & LPSPI_TCR_CONT_MASK)
#define LPSPI_TCR_BYSW_MASK (0x400000U)
#define LPSPI_TCR_BYSW_SHIFT (22U)
/*! BYSW - Byte Swap
* 0b0..Byte swap is disabled
* 0b1..Byte swap is enabled
*/
#define LPSPI_TCR_BYSW(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_TCR_BYSW_SHIFT)) & LPSPI_TCR_BYSW_MASK)
#define LPSPI_TCR_LSBF_MASK (0x800000U)
#define LPSPI_TCR_LSBF_SHIFT (23U)
/*! LSBF - LSB First
* 0b0..Data is transferred MSB first
* 0b1..Data is transferred LSB first
*/
#define LPSPI_TCR_LSBF(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_TCR_LSBF_SHIFT)) & LPSPI_TCR_LSBF_MASK)
#define LPSPI_TCR_PCS_MASK (0x3000000U)
#define LPSPI_TCR_PCS_SHIFT (24U)
/*! PCS - Peripheral Chip Select
* 0b00..Transfer using PCS[0]
* 0b01..Transfer using PCS[1]
* 0b10..Transfer using PCS[2]
* 0b11..Transfer using PCS[3]
*/
#define LPSPI_TCR_PCS(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_TCR_PCS_SHIFT)) & LPSPI_TCR_PCS_MASK)
#define LPSPI_TCR_PRESCALE_MASK (0x38000000U)
#define LPSPI_TCR_PRESCALE_SHIFT (27U)
/*! PRESCALE - Prescaler Value
* 0b000..Divide by 1
* 0b001..Divide by 2
* 0b010..Divide by 4
* 0b011..Divide by 8
* 0b100..Divide by 16
* 0b101..Divide by 32
* 0b110..Divide by 64
* 0b111..Divide by 128
*/
#define LPSPI_TCR_PRESCALE(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_TCR_PRESCALE_SHIFT)) & LPSPI_TCR_PRESCALE_MASK)
#define LPSPI_TCR_CPHA_MASK (0x40000000U)
#define LPSPI_TCR_CPHA_SHIFT (30U)
/*! CPHA - Clock Phase
* 0b0..Captured
* 0b1..Changed
*/
#define LPSPI_TCR_CPHA(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_TCR_CPHA_SHIFT)) & LPSPI_TCR_CPHA_MASK)
#define LPSPI_TCR_CPOL_MASK (0x80000000U)
#define LPSPI_TCR_CPOL_SHIFT (31U)
/*! CPOL - Clock Polarity
* 0b0..The inactive state value of SCK is low
* 0b1..The inactive state value of SCK is high
*/
#define LPSPI_TCR_CPOL(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_TCR_CPOL_SHIFT)) & LPSPI_TCR_CPOL_MASK)
/*! @} */
/*! @name TDR - Transmit Data */
/*! @{ */
#define LPSPI_TDR_DATA_MASK (0xFFFFFFFFU)
#define LPSPI_TDR_DATA_SHIFT (0U)
/*! DATA - Transmit Data */
#define LPSPI_TDR_DATA(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_TDR_DATA_SHIFT)) & LPSPI_TDR_DATA_MASK)
/*! @} */
/*! @name RSR - Receive Status */
/*! @{ */
#define LPSPI_RSR_SOF_MASK (0x1U)
#define LPSPI_RSR_SOF_SHIFT (0U)
/*! SOF - Start Of Frame
* 0b0..Subsequent data word received after PCS assertion
* 0b1..First data word received after PCS assertion
*/
#define LPSPI_RSR_SOF(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_RSR_SOF_SHIFT)) & LPSPI_RSR_SOF_MASK)
#define LPSPI_RSR_RXEMPTY_MASK (0x2U)
#define LPSPI_RSR_RXEMPTY_SHIFT (1U)
/*! RXEMPTY - RX FIFO Empty
* 0b0..RX FIFO is not empty
* 0b1..RX FIFO is empty
*/
#define LPSPI_RSR_RXEMPTY(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_RSR_RXEMPTY_SHIFT)) & LPSPI_RSR_RXEMPTY_MASK)
/*! @} */
/*! @name RDR - Receive Data */
/*! @{ */
#define LPSPI_RDR_DATA_MASK (0xFFFFFFFFU)
#define LPSPI_RDR_DATA_SHIFT (0U)
/*! DATA - Receive Data */
#define LPSPI_RDR_DATA(x) (((uint32_t)(((uint32_t)(x)) << LPSPI_RDR_DATA_SHIFT)) & LPSPI_RDR_DATA_MASK)
/*! @} */
/*!
* @}
*/ /* end of group LPSPI_Register_Masks */
/*!
* @}
*/ /* end of group LPSPI_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 */
#endif /* LPSPI_H_ */

View File

@ -0,0 +1,285 @@
/*
** ###################################################################
** Processors: MIMXRT1061CVJ5A
** MIMXRT1061CVJ5B
** MIMXRT1061CVL5A
** MIMXRT1061CVL5B
** MIMXRT1061DVJ6A
** MIMXRT1061DVJ6B
** MIMXRT1061DVL6A
** MIMXRT1061DVL6B
** MIMXRT1061XVN5B
** MIMXRT1062CVJ5A
** MIMXRT1062CVJ5B
** MIMXRT1062CVL5A
** MIMXRT1062CVL5B
** MIMXRT1062DVJ6A
** MIMXRT1062DVJ6B
** MIMXRT1062DVL6A
** MIMXRT1062DVL6B
** MIMXRT1062DVN6B
** MIMXRT1062XVN5B
** MIMXRT106ADVL6A
** MIMXRT106CDVL6A
** MIMXRT106FDVL6A
** MIMXRT106LDVL6A
** MIMXRT106SDVL6A
**
** Version: rev. 1.4, 2022-03-25
** Build: b240705
**
** Abstract:
** CMSIS Peripheral Access Layer for PGC
**
** Copyright 1997-2016 Freescale Semiconductor, Inc.
** Copyright 2016-2024 NXP
** SPDX-License-Identifier: BSD-3-Clause
**
** http: www.nxp.com
** mail: support@nxp.com
**
** Revisions:
** - rev. 0.1 (2017-01-10)
** Initial version.
** - rev. 1.0 (2018-11-16)
** Update header files to align with IMXRT1060RM Rev.0.
** - rev. 1.1 (2018-11-27)
** Update header files to align with IMXRT1060RM Rev.1.
** - rev. 1.2 (2019-04-29)
** Add SET/CLR/TOG register group to register CTRL, STAT, CHANNELCTRL, CH0STAT, CH0OPTS, CH1STAT, CH1OPTS, CH2STAT, CH2OPTS, CH3STAT, CH3OPTS of DCP module.
** - rev. 1.3 (2021-08-10)
** Update header files to align with IMXRT1060RM Rev.3.
** - rev. 1.4 (2022-03-25)
** Add RT1060X device
**
** ###################################################################
*/
/*!
* @file PGC.h
* @version 1.4
* @date 2022-03-25
* @brief CMSIS Peripheral Access Layer for PGC
*
* CMSIS Peripheral Access Layer for PGC
*/
#if !defined(PGC_H_)
#define PGC_H_ /**< Symbol preventing repeated inclusion */
#if (defined(CPU_MIMXRT1061CVJ5A) || defined(CPU_MIMXRT1061CVJ5B) || defined(CPU_MIMXRT1061CVL5A) || defined(CPU_MIMXRT1061CVL5B) || defined(CPU_MIMXRT1061DVJ6A) || defined(CPU_MIMXRT1061DVJ6B) || defined(CPU_MIMXRT1061DVL6A) || defined(CPU_MIMXRT1061DVL6B) || defined(CPU_MIMXRT1061XVN5B))
#include "MIMXRT1061_COMMON.h"
#elif (defined(CPU_MIMXRT1062CVJ5A) || defined(CPU_MIMXRT1062CVJ5B) || defined(CPU_MIMXRT1062CVL5A) || defined(CPU_MIMXRT1062CVL5B) || defined(CPU_MIMXRT1062DVJ6A) || defined(CPU_MIMXRT1062DVJ6B) || defined(CPU_MIMXRT1062DVL6A) || defined(CPU_MIMXRT1062DVL6B) || defined(CPU_MIMXRT1062DVN6B) || defined(CPU_MIMXRT1062XVN5B))
#include "MIMXRT1062_COMMON.h"
#elif (defined(CPU_MIMXRT106ADVL6A))
#include "MIMXRT106A_COMMON.h"
#elif (defined(CPU_MIMXRT106CDVL6A))
#include "MIMXRT106C_COMMON.h"
#elif (defined(CPU_MIMXRT106FDVL6A))
#include "MIMXRT106F_COMMON.h"
#elif (defined(CPU_MIMXRT106LDVL6A))
#include "MIMXRT106L_COMMON.h"
#elif (defined(CPU_MIMXRT106SDVL6A))
#include "MIMXRT106S_COMMON.h"
#else
#error "No valid CPU defined!"
#endif
/* ----------------------------------------------------------------------------
-- 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
/* ----------------------------------------------------------------------------
-- PGC Peripheral Access Layer
---------------------------------------------------------------------------- */
/*!
* @addtogroup PGC_Peripheral_Access_Layer PGC Peripheral Access Layer
* @{
*/
/** PGC - Register Layout Typedef */
typedef struct {
uint8_t RESERVED_0[544];
__IO uint32_t MEGA_CTRL; /**< PGC Mega Control Register, offset: 0x220 */
__IO uint32_t MEGA_PUPSCR; /**< PGC Mega Power Up Sequence Control Register, offset: 0x224 */
__IO uint32_t MEGA_PDNSCR; /**< PGC Mega Pull Down Sequence Control Register, offset: 0x228 */
__IO uint32_t MEGA_SR; /**< PGC Mega Power Gating Controller Status Register, offset: 0x22C */
uint8_t RESERVED_1[112];
__IO uint32_t CPU_CTRL; /**< PGC CPU Control Register, offset: 0x2A0 */
__IO uint32_t CPU_PUPSCR; /**< PGC CPU Power Up Sequence Control Register, offset: 0x2A4 */
__IO uint32_t CPU_PDNSCR; /**< PGC CPU Pull Down Sequence Control Register, offset: 0x2A8 */
__IO uint32_t CPU_SR; /**< PGC CPU Power Gating Controller Status Register, offset: 0x2AC */
} PGC_Type;
/* ----------------------------------------------------------------------------
-- PGC Register Masks
---------------------------------------------------------------------------- */
/*!
* @addtogroup PGC_Register_Masks PGC Register Masks
* @{
*/
/*! @name MEGA_CTRL - PGC Mega Control Register */
/*! @{ */
#define PGC_MEGA_CTRL_PCR_MASK (0x1U)
#define PGC_MEGA_CTRL_PCR_SHIFT (0U)
/*! PCR
* 0b0..Do not switch off power even if pdn_req is asserted.
* 0b1..Switch off power when pdn_req is asserted.
*/
#define PGC_MEGA_CTRL_PCR(x) (((uint32_t)(((uint32_t)(x)) << PGC_MEGA_CTRL_PCR_SHIFT)) & PGC_MEGA_CTRL_PCR_MASK)
/*! @} */
/*! @name MEGA_PUPSCR - PGC Mega Power Up Sequence Control Register */
/*! @{ */
#define PGC_MEGA_PUPSCR_SW_MASK (0x3FU)
#define PGC_MEGA_PUPSCR_SW_SHIFT (0U)
#define PGC_MEGA_PUPSCR_SW(x) (((uint32_t)(((uint32_t)(x)) << PGC_MEGA_PUPSCR_SW_SHIFT)) & PGC_MEGA_PUPSCR_SW_MASK)
#define PGC_MEGA_PUPSCR_SW2ISO_MASK (0x3F00U)
#define PGC_MEGA_PUPSCR_SW2ISO_SHIFT (8U)
#define PGC_MEGA_PUPSCR_SW2ISO(x) (((uint32_t)(((uint32_t)(x)) << PGC_MEGA_PUPSCR_SW2ISO_SHIFT)) & PGC_MEGA_PUPSCR_SW2ISO_MASK)
/*! @} */
/*! @name MEGA_PDNSCR - PGC Mega Pull Down Sequence Control Register */
/*! @{ */
#define PGC_MEGA_PDNSCR_ISO_MASK (0x3FU)
#define PGC_MEGA_PDNSCR_ISO_SHIFT (0U)
#define PGC_MEGA_PDNSCR_ISO(x) (((uint32_t)(((uint32_t)(x)) << PGC_MEGA_PDNSCR_ISO_SHIFT)) & PGC_MEGA_PDNSCR_ISO_MASK)
#define PGC_MEGA_PDNSCR_ISO2SW_MASK (0x3F00U)
#define PGC_MEGA_PDNSCR_ISO2SW_SHIFT (8U)
#define PGC_MEGA_PDNSCR_ISO2SW(x) (((uint32_t)(((uint32_t)(x)) << PGC_MEGA_PDNSCR_ISO2SW_SHIFT)) & PGC_MEGA_PDNSCR_ISO2SW_MASK)
/*! @} */
/*! @name MEGA_SR - PGC Mega Power Gating Controller Status Register */
/*! @{ */
#define PGC_MEGA_SR_PSR_MASK (0x1U)
#define PGC_MEGA_SR_PSR_SHIFT (0U)
/*! PSR
* 0b0..The target subsystem was not powered down for the previous power-down request.
* 0b1..The target subsystem was powered down for the previous power-down request.
*/
#define PGC_MEGA_SR_PSR(x) (((uint32_t)(((uint32_t)(x)) << PGC_MEGA_SR_PSR_SHIFT)) & PGC_MEGA_SR_PSR_MASK)
/*! @} */
/*! @name CPU_CTRL - PGC CPU Control Register */
/*! @{ */
#define PGC_CPU_CTRL_PCR_MASK (0x1U)
#define PGC_CPU_CTRL_PCR_SHIFT (0U)
/*! PCR
* 0b0..Do not switch off power even if pdn_req is asserted.
* 0b1..Switch off power when pdn_req is asserted.
*/
#define PGC_CPU_CTRL_PCR(x) (((uint32_t)(((uint32_t)(x)) << PGC_CPU_CTRL_PCR_SHIFT)) & PGC_CPU_CTRL_PCR_MASK)
/*! @} */
/*! @name CPU_PUPSCR - PGC CPU Power Up Sequence Control Register */
/*! @{ */
#define PGC_CPU_PUPSCR_SW_MASK (0x3FU)
#define PGC_CPU_PUPSCR_SW_SHIFT (0U)
#define PGC_CPU_PUPSCR_SW(x) (((uint32_t)(((uint32_t)(x)) << PGC_CPU_PUPSCR_SW_SHIFT)) & PGC_CPU_PUPSCR_SW_MASK)
#define PGC_CPU_PUPSCR_SW2ISO_MASK (0x3F00U)
#define PGC_CPU_PUPSCR_SW2ISO_SHIFT (8U)
#define PGC_CPU_PUPSCR_SW2ISO(x) (((uint32_t)(((uint32_t)(x)) << PGC_CPU_PUPSCR_SW2ISO_SHIFT)) & PGC_CPU_PUPSCR_SW2ISO_MASK)
/*! @} */
/*! @name CPU_PDNSCR - PGC CPU Pull Down Sequence Control Register */
/*! @{ */
#define PGC_CPU_PDNSCR_ISO_MASK (0x3FU)
#define PGC_CPU_PDNSCR_ISO_SHIFT (0U)
#define PGC_CPU_PDNSCR_ISO(x) (((uint32_t)(((uint32_t)(x)) << PGC_CPU_PDNSCR_ISO_SHIFT)) & PGC_CPU_PDNSCR_ISO_MASK)
#define PGC_CPU_PDNSCR_ISO2SW_MASK (0x3F00U)
#define PGC_CPU_PDNSCR_ISO2SW_SHIFT (8U)
#define PGC_CPU_PDNSCR_ISO2SW(x) (((uint32_t)(((uint32_t)(x)) << PGC_CPU_PDNSCR_ISO2SW_SHIFT)) & PGC_CPU_PDNSCR_ISO2SW_MASK)
/*! @} */
/*! @name CPU_SR - PGC CPU Power Gating Controller Status Register */
/*! @{ */
#define PGC_CPU_SR_PSR_MASK (0x1U)
#define PGC_CPU_SR_PSR_SHIFT (0U)
/*! PSR
* 0b0..The target subsystem was not powered down for the previous power-down request.
* 0b1..The target subsystem was powered down for the previous power-down request.
*/
#define PGC_CPU_SR_PSR(x) (((uint32_t)(((uint32_t)(x)) << PGC_CPU_SR_PSR_SHIFT)) & PGC_CPU_SR_PSR_MASK)
/*! @} */
/*!
* @}
*/ /* end of group PGC_Register_Masks */
/*!
* @}
*/ /* end of group PGC_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 */
#endif /* PGC_H_ */

View File

@ -0,0 +1,301 @@
/*
** ###################################################################
** Processors: MIMXRT1061CVJ5A
** MIMXRT1061CVJ5B
** MIMXRT1061CVL5A
** MIMXRT1061CVL5B
** MIMXRT1061DVJ6A
** MIMXRT1061DVJ6B
** MIMXRT1061DVL6A
** MIMXRT1061DVL6B
** MIMXRT1061XVN5B
** MIMXRT1062CVJ5A
** MIMXRT1062CVJ5B
** MIMXRT1062CVL5A
** MIMXRT1062CVL5B
** MIMXRT1062DVJ6A
** MIMXRT1062DVJ6B
** MIMXRT1062DVL6A
** MIMXRT1062DVL6B
** MIMXRT1062DVN6B
** MIMXRT1062XVN5B
** MIMXRT106ADVL6A
** MIMXRT106CDVL6A
** MIMXRT106FDVL6A
** MIMXRT106LDVL6A
** MIMXRT106SDVL6A
**
** Version: rev. 1.4, 2022-03-25
** Build: b240705
**
** Abstract:
** CMSIS Peripheral Access Layer for PIT
**
** Copyright 1997-2016 Freescale Semiconductor, Inc.
** Copyright 2016-2024 NXP
** SPDX-License-Identifier: BSD-3-Clause
**
** http: www.nxp.com
** mail: support@nxp.com
**
** Revisions:
** - rev. 0.1 (2017-01-10)
** Initial version.
** - rev. 1.0 (2018-11-16)
** Update header files to align with IMXRT1060RM Rev.0.
** - rev. 1.1 (2018-11-27)
** Update header files to align with IMXRT1060RM Rev.1.
** - rev. 1.2 (2019-04-29)
** Add SET/CLR/TOG register group to register CTRL, STAT, CHANNELCTRL, CH0STAT, CH0OPTS, CH1STAT, CH1OPTS, CH2STAT, CH2OPTS, CH3STAT, CH3OPTS of DCP module.
** - rev. 1.3 (2021-08-10)
** Update header files to align with IMXRT1060RM Rev.3.
** - rev. 1.4 (2022-03-25)
** Add RT1060X device
**
** ###################################################################
*/
/*!
* @file PIT.h
* @version 1.4
* @date 2022-03-25
* @brief CMSIS Peripheral Access Layer for PIT
*
* CMSIS Peripheral Access Layer for PIT
*/
#if !defined(PIT_H_)
#define PIT_H_ /**< Symbol preventing repeated inclusion */
#if (defined(CPU_MIMXRT1061CVJ5A) || defined(CPU_MIMXRT1061CVJ5B) || defined(CPU_MIMXRT1061CVL5A) || defined(CPU_MIMXRT1061CVL5B) || defined(CPU_MIMXRT1061DVJ6A) || defined(CPU_MIMXRT1061DVJ6B) || defined(CPU_MIMXRT1061DVL6A) || defined(CPU_MIMXRT1061DVL6B) || defined(CPU_MIMXRT1061XVN5B))
#include "MIMXRT1061_COMMON.h"
#elif (defined(CPU_MIMXRT1062CVJ5A) || defined(CPU_MIMXRT1062CVJ5B) || defined(CPU_MIMXRT1062CVL5A) || defined(CPU_MIMXRT1062CVL5B) || defined(CPU_MIMXRT1062DVJ6A) || defined(CPU_MIMXRT1062DVJ6B) || defined(CPU_MIMXRT1062DVL6A) || defined(CPU_MIMXRT1062DVL6B) || defined(CPU_MIMXRT1062DVN6B) || defined(CPU_MIMXRT1062XVN5B))
#include "MIMXRT1062_COMMON.h"
#elif (defined(CPU_MIMXRT106ADVL6A))
#include "MIMXRT106A_COMMON.h"
#elif (defined(CPU_MIMXRT106CDVL6A))
#include "MIMXRT106C_COMMON.h"
#elif (defined(CPU_MIMXRT106FDVL6A))
#include "MIMXRT106F_COMMON.h"
#elif (defined(CPU_MIMXRT106LDVL6A))
#include "MIMXRT106L_COMMON.h"
#elif (defined(CPU_MIMXRT106SDVL6A))
#include "MIMXRT106S_COMMON.h"
#else
#error "No valid CPU defined!"
#endif
/* ----------------------------------------------------------------------------
-- 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
/* ----------------------------------------------------------------------------
-- PIT Peripheral Access Layer
---------------------------------------------------------------------------- */
/*!
* @addtogroup PIT_Peripheral_Access_Layer PIT Peripheral Access Layer
* @{
*/
/** PIT - Size of Registers Arrays */
#define PIT_CHANNEL_COUNT 4u
/** PIT - Register Layout Typedef */
typedef struct {
__IO uint32_t MCR; /**< PIT Module Control Register, offset: 0x0 */
uint8_t RESERVED_0[220];
__I uint32_t LTMR64H; /**< PIT Upper Lifetime Timer Register, offset: 0xE0 */
__I uint32_t LTMR64L; /**< PIT Lower Lifetime Timer Register, offset: 0xE4 */
uint8_t RESERVED_1[24];
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[PIT_CHANNEL_COUNT];
} 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)
/*! FRZ - Freeze
* 0b0..Timers continue to run in Debug mode.
* 0b1..Timers are stopped in Debug mode.
*/
#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)
/*! MDIS - Module Disable for PIT
* 0b0..Clock for standard PIT timers is enabled.
* 0b1..Clock for standard PIT timers is disabled.
*/
#define PIT_MCR_MDIS(x) (((uint32_t)(((uint32_t)(x)) << PIT_MCR_MDIS_SHIFT)) & PIT_MCR_MDIS_MASK)
/*! @} */
/*! @name LTMR64H - PIT Upper Lifetime Timer Register */
/*! @{ */
#define PIT_LTMR64H_LTH_MASK (0xFFFFFFFFU)
#define PIT_LTMR64H_LTH_SHIFT (0U)
/*! LTH - Life Timer value */
#define PIT_LTMR64H_LTH(x) (((uint32_t)(((uint32_t)(x)) << PIT_LTMR64H_LTH_SHIFT)) & PIT_LTMR64H_LTH_MASK)
/*! @} */
/*! @name LTMR64L - PIT Lower Lifetime Timer Register */
/*! @{ */
#define PIT_LTMR64L_LTL_MASK (0xFFFFFFFFU)
#define PIT_LTMR64L_LTL_SHIFT (0U)
/*! LTL - Life Timer value */
#define PIT_LTMR64L_LTL(x) (((uint32_t)(((uint32_t)(x)) << PIT_LTMR64L_LTL_SHIFT)) & PIT_LTMR64L_LTL_MASK)
/*! @} */
/*! @name LDVAL - Timer Load Value Register */
/*! @{ */
#define PIT_LDVAL_TSV_MASK (0xFFFFFFFFU)
#define PIT_LDVAL_TSV_SHIFT (0U)
/*! TSV - Timer Start Value */
#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)
/*! TVL - Current Timer Value */
#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)
/*! TEN - Timer Enable
* 0b0..Timer n is disabled.
* 0b1..Timer n is enabled.
*/
#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)
/*! TIE - Timer Interrupt Enable
* 0b0..Interrupt requests from Timer n are disabled.
* 0b1..Interrupt is requested whenever TIF is set.
*/
#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)
/*! CHN - Chain Mode
* 0b0..Timer is not chained.
* 0b1..Timer is chained to a previous timer. For example, for channel 2, if this field is set, Timer 2 is chained to Timer 1.
*/
#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)
/*! TIF - Timer Interrupt Flag
* 0b0..Timeout has not yet occurred.
* 0b1..Timeout has occurred.
*/
#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 */
/*!
* @}
*/ /* end of group PIT_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 */
#endif /* PIT_H_ */

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,268 @@
/*
** ###################################################################
** Processors: MIMXRT1061CVJ5A
** MIMXRT1061CVJ5B
** MIMXRT1061CVL5A
** MIMXRT1061CVL5B
** MIMXRT1061DVJ6A
** MIMXRT1061DVJ6B
** MIMXRT1061DVL6A
** MIMXRT1061DVL6B
** MIMXRT1061XVN5B
** MIMXRT1062CVJ5A
** MIMXRT1062CVJ5B
** MIMXRT1062CVL5A
** MIMXRT1062CVL5B
** MIMXRT1062DVJ6A
** MIMXRT1062DVJ6B
** MIMXRT1062DVL6A
** MIMXRT1062DVL6B
** MIMXRT1062DVN6B
** MIMXRT1062XVN5B
** MIMXRT106ADVL6A
** MIMXRT106CDVL6A
** MIMXRT106FDVL6A
** MIMXRT106LDVL6A
** MIMXRT106SDVL6A
**
** Version: rev. 1.4, 2022-03-25
** Build: b240705
**
** Abstract:
** CMSIS Peripheral Access Layer for ROMC
**
** Copyright 1997-2016 Freescale Semiconductor, Inc.
** Copyright 2016-2024 NXP
** SPDX-License-Identifier: BSD-3-Clause
**
** http: www.nxp.com
** mail: support@nxp.com
**
** Revisions:
** - rev. 0.1 (2017-01-10)
** Initial version.
** - rev. 1.0 (2018-11-16)
** Update header files to align with IMXRT1060RM Rev.0.
** - rev. 1.1 (2018-11-27)
** Update header files to align with IMXRT1060RM Rev.1.
** - rev. 1.2 (2019-04-29)
** Add SET/CLR/TOG register group to register CTRL, STAT, CHANNELCTRL, CH0STAT, CH0OPTS, CH1STAT, CH1OPTS, CH2STAT, CH2OPTS, CH3STAT, CH3OPTS of DCP module.
** - rev. 1.3 (2021-08-10)
** Update header files to align with IMXRT1060RM Rev.3.
** - rev. 1.4 (2022-03-25)
** Add RT1060X device
**
** ###################################################################
*/
/*!
* @file ROMC.h
* @version 1.4
* @date 2022-03-25
* @brief CMSIS Peripheral Access Layer for ROMC
*
* CMSIS Peripheral Access Layer for ROMC
*/
#if !defined(ROMC_H_)
#define ROMC_H_ /**< Symbol preventing repeated inclusion */
#if (defined(CPU_MIMXRT1061CVJ5A) || defined(CPU_MIMXRT1061CVJ5B) || defined(CPU_MIMXRT1061CVL5A) || defined(CPU_MIMXRT1061CVL5B) || defined(CPU_MIMXRT1061DVJ6A) || defined(CPU_MIMXRT1061DVJ6B) || defined(CPU_MIMXRT1061DVL6A) || defined(CPU_MIMXRT1061DVL6B) || defined(CPU_MIMXRT1061XVN5B))
#include "MIMXRT1061_COMMON.h"
#elif (defined(CPU_MIMXRT1062CVJ5A) || defined(CPU_MIMXRT1062CVJ5B) || defined(CPU_MIMXRT1062CVL5A) || defined(CPU_MIMXRT1062CVL5B) || defined(CPU_MIMXRT1062DVJ6A) || defined(CPU_MIMXRT1062DVJ6B) || defined(CPU_MIMXRT1062DVL6A) || defined(CPU_MIMXRT1062DVL6B) || defined(CPU_MIMXRT1062DVN6B) || defined(CPU_MIMXRT1062XVN5B))
#include "MIMXRT1062_COMMON.h"
#elif (defined(CPU_MIMXRT106ADVL6A))
#include "MIMXRT106A_COMMON.h"
#elif (defined(CPU_MIMXRT106CDVL6A))
#include "MIMXRT106C_COMMON.h"
#elif (defined(CPU_MIMXRT106FDVL6A))
#include "MIMXRT106F_COMMON.h"
#elif (defined(CPU_MIMXRT106LDVL6A))
#include "MIMXRT106L_COMMON.h"
#elif (defined(CPU_MIMXRT106SDVL6A))
#include "MIMXRT106S_COMMON.h"
#else
#error "No valid CPU defined!"
#endif
/* ----------------------------------------------------------------------------
-- 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
/* ----------------------------------------------------------------------------
-- ROMC Peripheral Access Layer
---------------------------------------------------------------------------- */
/*!
* @addtogroup ROMC_Peripheral_Access_Layer ROMC Peripheral Access Layer
* @{
*/
/** ROMC - Size of Registers Arrays */
#define ROMC_ROMPATCHD_COUNT 8u
#define ROMC_ROMPATCHA_COUNT 16u
/** ROMC - Register Layout Typedef */
typedef struct {
uint8_t RESERVED_0[212];
__IO uint32_t ROMPATCHD[ROMC_ROMPATCHD_COUNT]; /**< ROMC Data Registers, array offset: 0xD4, array step: 0x4 */
__IO uint32_t ROMPATCHCNTL; /**< ROMC Control Register, offset: 0xF4 */
uint32_t ROMPATCHENH; /**< ROMC Enable Register High, offset: 0xF8 */
__IO uint32_t ROMPATCHENL; /**< ROMC Enable Register Low, offset: 0xFC */
__IO uint32_t ROMPATCHA[ROMC_ROMPATCHA_COUNT]; /**< ROMC Address Registers, array offset: 0x100, array step: 0x4 */
uint8_t RESERVED_1[200];
__IO uint32_t ROMPATCHSR; /**< ROMC Status Register, offset: 0x208 */
} ROMC_Type;
/* ----------------------------------------------------------------------------
-- ROMC Register Masks
---------------------------------------------------------------------------- */
/*!
* @addtogroup ROMC_Register_Masks ROMC Register Masks
* @{
*/
/*! @name ROMPATCHD - ROMC Data Registers */
/*! @{ */
#define ROMC_ROMPATCHD_DATAX_MASK (0xFFFFFFFFU)
#define ROMC_ROMPATCHD_DATAX_SHIFT (0U)
#define ROMC_ROMPATCHD_DATAX(x) (((uint32_t)(((uint32_t)(x)) << ROMC_ROMPATCHD_DATAX_SHIFT)) & ROMC_ROMPATCHD_DATAX_MASK)
/*! @} */
/*! @name ROMPATCHCNTL - ROMC Control Register */
/*! @{ */
#define ROMC_ROMPATCHCNTL_DATAFIX_MASK (0xFFU)
#define ROMC_ROMPATCHCNTL_DATAFIX_SHIFT (0U)
/*! DATAFIX
* 0b00000000..Address comparator triggers a opcode patch
* 0b00000001..Address comparator triggers a data fix
*/
#define ROMC_ROMPATCHCNTL_DATAFIX(x) (((uint32_t)(((uint32_t)(x)) << ROMC_ROMPATCHCNTL_DATAFIX_SHIFT)) & ROMC_ROMPATCHCNTL_DATAFIX_MASK)
#define ROMC_ROMPATCHCNTL_DIS_MASK (0x20000000U)
#define ROMC_ROMPATCHCNTL_DIS_SHIFT (29U)
/*! DIS
* 0b0..Does not affect any ROMC functions (default)
* 0b1..Disable all ROMC functions: data fixing, and opcode patching
*/
#define ROMC_ROMPATCHCNTL_DIS(x) (((uint32_t)(((uint32_t)(x)) << ROMC_ROMPATCHCNTL_DIS_SHIFT)) & ROMC_ROMPATCHCNTL_DIS_MASK)
/*! @} */
/*! @name ROMPATCHENL - ROMC Enable Register Low */
/*! @{ */
#define ROMC_ROMPATCHENL_ENABLE_MASK (0xFFFFU)
#define ROMC_ROMPATCHENL_ENABLE_SHIFT (0U)
/*! ENABLE
* 0b0000000000000000..Address comparator disabled
* 0b0000000000000001..Address comparator enabled, ROMC will trigger a opcode patch or data fix event upon matching of the associated address
*/
#define ROMC_ROMPATCHENL_ENABLE(x) (((uint32_t)(((uint32_t)(x)) << ROMC_ROMPATCHENL_ENABLE_SHIFT)) & ROMC_ROMPATCHENL_ENABLE_MASK)
/*! @} */
/*! @name ROMPATCHA - ROMC Address Registers */
/*! @{ */
#define ROMC_ROMPATCHA_THUMBX_MASK (0x1U)
#define ROMC_ROMPATCHA_THUMBX_SHIFT (0U)
/*! THUMBX
* 0b0..Arm patch
* 0b1..THUMB patch (ignore if data fix)
*/
#define ROMC_ROMPATCHA_THUMBX(x) (((uint32_t)(((uint32_t)(x)) << ROMC_ROMPATCHA_THUMBX_SHIFT)) & ROMC_ROMPATCHA_THUMBX_MASK)
#define ROMC_ROMPATCHA_ADDRX_MASK (0x7FFFFEU)
#define ROMC_ROMPATCHA_ADDRX_SHIFT (1U)
#define ROMC_ROMPATCHA_ADDRX(x) (((uint32_t)(((uint32_t)(x)) << ROMC_ROMPATCHA_ADDRX_SHIFT)) & ROMC_ROMPATCHA_ADDRX_MASK)
/*! @} */
/*! @name ROMPATCHSR - ROMC Status Register */
/*! @{ */
#define ROMC_ROMPATCHSR_SOURCE_MASK (0x3FU)
#define ROMC_ROMPATCHSR_SOURCE_SHIFT (0U)
/*! SOURCE
* 0b000000..Address Comparator 0 matched
* 0b000001..Address Comparator 1 matched
* 0b001111..Address Comparator 15 matched
*/
#define ROMC_ROMPATCHSR_SOURCE(x) (((uint32_t)(((uint32_t)(x)) << ROMC_ROMPATCHSR_SOURCE_SHIFT)) & ROMC_ROMPATCHSR_SOURCE_MASK)
#define ROMC_ROMPATCHSR_SW_MASK (0x20000U)
#define ROMC_ROMPATCHSR_SW_SHIFT (17U)
/*! SW
* 0b0..no event or comparator collisions
* 0b1..a collision has occurred
*/
#define ROMC_ROMPATCHSR_SW(x) (((uint32_t)(((uint32_t)(x)) << ROMC_ROMPATCHSR_SW_SHIFT)) & ROMC_ROMPATCHSR_SW_MASK)
/*! @} */
/*!
* @}
*/ /* end of group ROMC_Register_Masks */
/*!
* @}
*/ /* end of group ROMC_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 */
#endif /* ROMC_H_ */

View File

@ -0,0 +1,345 @@
/*
** ###################################################################
** Processors: MIMXRT1061CVJ5A
** MIMXRT1061CVJ5B
** MIMXRT1061CVL5A
** MIMXRT1061CVL5B
** MIMXRT1061DVJ6A
** MIMXRT1061DVJ6B
** MIMXRT1061DVL6A
** MIMXRT1061DVL6B
** MIMXRT1061XVN5B
** MIMXRT1062CVJ5A
** MIMXRT1062CVJ5B
** MIMXRT1062CVL5A
** MIMXRT1062CVL5B
** MIMXRT1062DVJ6A
** MIMXRT1062DVJ6B
** MIMXRT1062DVL6A
** MIMXRT1062DVL6B
** MIMXRT1062DVN6B
** MIMXRT1062XVN5B
** MIMXRT106ADVL6A
** MIMXRT106CDVL6A
** MIMXRT106FDVL6A
** MIMXRT106LDVL6A
** MIMXRT106SDVL6A
**
** Version: rev. 1.4, 2022-03-25
** Build: b240705
**
** Abstract:
** CMSIS Peripheral Access Layer for RTWDOG
**
** Copyright 1997-2016 Freescale Semiconductor, Inc.
** Copyright 2016-2024 NXP
** SPDX-License-Identifier: BSD-3-Clause
**
** http: www.nxp.com
** mail: support@nxp.com
**
** Revisions:
** - rev. 0.1 (2017-01-10)
** Initial version.
** - rev. 1.0 (2018-11-16)
** Update header files to align with IMXRT1060RM Rev.0.
** - rev. 1.1 (2018-11-27)
** Update header files to align with IMXRT1060RM Rev.1.
** - rev. 1.2 (2019-04-29)
** Add SET/CLR/TOG register group to register CTRL, STAT, CHANNELCTRL, CH0STAT, CH0OPTS, CH1STAT, CH1OPTS, CH2STAT, CH2OPTS, CH3STAT, CH3OPTS of DCP module.
** - rev. 1.3 (2021-08-10)
** Update header files to align with IMXRT1060RM Rev.3.
** - rev. 1.4 (2022-03-25)
** Add RT1060X device
**
** ###################################################################
*/
/*!
* @file RTWDOG.h
* @version 1.4
* @date 2022-03-25
* @brief CMSIS Peripheral Access Layer for RTWDOG
*
* CMSIS Peripheral Access Layer for RTWDOG
*/
#if !defined(RTWDOG_H_)
#define RTWDOG_H_ /**< Symbol preventing repeated inclusion */
#if (defined(CPU_MIMXRT1061CVJ5A) || defined(CPU_MIMXRT1061CVJ5B) || defined(CPU_MIMXRT1061CVL5A) || defined(CPU_MIMXRT1061CVL5B) || defined(CPU_MIMXRT1061DVJ6A) || defined(CPU_MIMXRT1061DVJ6B) || defined(CPU_MIMXRT1061DVL6A) || defined(CPU_MIMXRT1061DVL6B) || defined(CPU_MIMXRT1061XVN5B))
#include "MIMXRT1061_COMMON.h"
#elif (defined(CPU_MIMXRT1062CVJ5A) || defined(CPU_MIMXRT1062CVJ5B) || defined(CPU_MIMXRT1062CVL5A) || defined(CPU_MIMXRT1062CVL5B) || defined(CPU_MIMXRT1062DVJ6A) || defined(CPU_MIMXRT1062DVJ6B) || defined(CPU_MIMXRT1062DVL6A) || defined(CPU_MIMXRT1062DVL6B) || defined(CPU_MIMXRT1062DVN6B) || defined(CPU_MIMXRT1062XVN5B))
#include "MIMXRT1062_COMMON.h"
#elif (defined(CPU_MIMXRT106ADVL6A))
#include "MIMXRT106A_COMMON.h"
#elif (defined(CPU_MIMXRT106CDVL6A))
#include "MIMXRT106C_COMMON.h"
#elif (defined(CPU_MIMXRT106FDVL6A))
#include "MIMXRT106F_COMMON.h"
#elif (defined(CPU_MIMXRT106LDVL6A))
#include "MIMXRT106L_COMMON.h"
#elif (defined(CPU_MIMXRT106SDVL6A))
#include "MIMXRT106S_COMMON.h"
#else
#error "No valid CPU defined!"
#endif
/* ----------------------------------------------------------------------------
-- 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
/* ----------------------------------------------------------------------------
-- RTWDOG Peripheral Access Layer
---------------------------------------------------------------------------- */
/*!
* @addtogroup RTWDOG_Peripheral_Access_Layer RTWDOG Peripheral Access Layer
* @{
*/
/** RTWDOG - Register Layout Typedef */
typedef struct {
__IO uint32_t CS; /**< Watchdog Control and Status Register, offset: 0x0 */
__IO uint32_t CNT; /**< Watchdog Counter Register, offset: 0x4 */
__IO uint32_t TOVAL; /**< Watchdog Timeout Value Register, offset: 0x8 */
__IO uint32_t WIN; /**< Watchdog Window Register, offset: 0xC */
} RTWDOG_Type;
/* ----------------------------------------------------------------------------
-- RTWDOG Register Masks
---------------------------------------------------------------------------- */
/*!
* @addtogroup RTWDOG_Register_Masks RTWDOG Register Masks
* @{
*/
/*! @name CS - Watchdog Control and Status Register */
/*! @{ */
#define RTWDOG_CS_STOP_MASK (0x1U)
#define RTWDOG_CS_STOP_SHIFT (0U)
/*! STOP - Stop Enable
* 0b0..Watchdog disabled in chip stop mode.
* 0b1..Watchdog enabled in chip stop mode.
*/
#define RTWDOG_CS_STOP(x) (((uint32_t)(((uint32_t)(x)) << RTWDOG_CS_STOP_SHIFT)) & RTWDOG_CS_STOP_MASK)
#define RTWDOG_CS_WAIT_MASK (0x2U)
#define RTWDOG_CS_WAIT_SHIFT (1U)
/*! WAIT - Wait Enable
* 0b0..Watchdog disabled in chip wait mode.
* 0b1..Watchdog enabled in chip wait mode.
*/
#define RTWDOG_CS_WAIT(x) (((uint32_t)(((uint32_t)(x)) << RTWDOG_CS_WAIT_SHIFT)) & RTWDOG_CS_WAIT_MASK)
#define RTWDOG_CS_DBG_MASK (0x4U)
#define RTWDOG_CS_DBG_SHIFT (2U)
/*! DBG - Debug Enable
* 0b0..Watchdog disabled in chip debug mode.
* 0b1..Watchdog enabled in chip debug mode.
*/
#define RTWDOG_CS_DBG(x) (((uint32_t)(((uint32_t)(x)) << RTWDOG_CS_DBG_SHIFT)) & RTWDOG_CS_DBG_MASK)
#define RTWDOG_CS_TST_MASK (0x18U)
#define RTWDOG_CS_TST_SHIFT (3U)
/*! TST - Watchdog Test
* 0b00..Watchdog test mode disabled.
* 0b01..Watchdog user mode enabled. (Watchdog test mode disabled.) After testing the watchdog, software should
* use this setting to indicate that the watchdog is functioning normally in user mode.
* 0b10..Watchdog test mode enabled, only the low byte is used. CNT[CNTLOW] is compared with TOVAL[TOVALLOW].
* 0b11..Watchdog test mode enabled, only the high byte is used. CNT[CNTHIGH] is compared with TOVAL[TOVALHIGH].
*/
#define RTWDOG_CS_TST(x) (((uint32_t)(((uint32_t)(x)) << RTWDOG_CS_TST_SHIFT)) & RTWDOG_CS_TST_MASK)
#define RTWDOG_CS_UPDATE_MASK (0x20U)
#define RTWDOG_CS_UPDATE_SHIFT (5U)
/*! UPDATE - Allow updates
* 0b0..Updates not allowed. After the initial configuration, the watchdog cannot be later modified without forcing a reset.
* 0b1..Updates allowed. Software can modify the watchdog configuration registers within 128 bus clocks after performing the unlock write sequence.
*/
#define RTWDOG_CS_UPDATE(x) (((uint32_t)(((uint32_t)(x)) << RTWDOG_CS_UPDATE_SHIFT)) & RTWDOG_CS_UPDATE_MASK)
#define RTWDOG_CS_INT_MASK (0x40U)
#define RTWDOG_CS_INT_SHIFT (6U)
/*! INT - Watchdog Interrupt
* 0b0..Watchdog interrupts are disabled. Watchdog resets are not delayed.
* 0b1..Watchdog interrupts are enabled. Watchdog resets are delayed by 128 bus clocks from the interrupt vector fetch.
*/
#define RTWDOG_CS_INT(x) (((uint32_t)(((uint32_t)(x)) << RTWDOG_CS_INT_SHIFT)) & RTWDOG_CS_INT_MASK)
#define RTWDOG_CS_EN_MASK (0x80U)
#define RTWDOG_CS_EN_SHIFT (7U)
/*! EN - Watchdog Enable
* 0b0..Watchdog disabled.
* 0b1..Watchdog enabled.
*/
#define RTWDOG_CS_EN(x) (((uint32_t)(((uint32_t)(x)) << RTWDOG_CS_EN_SHIFT)) & RTWDOG_CS_EN_MASK)
#define RTWDOG_CS_CLK_MASK (0x300U)
#define RTWDOG_CS_CLK_SHIFT (8U)
/*! CLK - Watchdog Clock */
#define RTWDOG_CS_CLK(x) (((uint32_t)(((uint32_t)(x)) << RTWDOG_CS_CLK_SHIFT)) & RTWDOG_CS_CLK_MASK)
#define RTWDOG_CS_RCS_MASK (0x400U)
#define RTWDOG_CS_RCS_SHIFT (10U)
/*! RCS - Reconfiguration Success
* 0b0..Reconfiguring WDOG.
* 0b1..Reconfiguration is successful.
*/
#define RTWDOG_CS_RCS(x) (((uint32_t)(((uint32_t)(x)) << RTWDOG_CS_RCS_SHIFT)) & RTWDOG_CS_RCS_MASK)
#define RTWDOG_CS_ULK_MASK (0x800U)
#define RTWDOG_CS_ULK_SHIFT (11U)
/*! ULK - Unlock status
* 0b0..WDOG is locked.
* 0b1..WDOG is unlocked.
*/
#define RTWDOG_CS_ULK(x) (((uint32_t)(((uint32_t)(x)) << RTWDOG_CS_ULK_SHIFT)) & RTWDOG_CS_ULK_MASK)
#define RTWDOG_CS_PRES_MASK (0x1000U)
#define RTWDOG_CS_PRES_SHIFT (12U)
/*! PRES - Watchdog prescaler
* 0b0..256 prescaler disabled.
* 0b1..256 prescaler enabled.
*/
#define RTWDOG_CS_PRES(x) (((uint32_t)(((uint32_t)(x)) << RTWDOG_CS_PRES_SHIFT)) & RTWDOG_CS_PRES_MASK)
#define RTWDOG_CS_CMD32EN_MASK (0x2000U)
#define RTWDOG_CS_CMD32EN_SHIFT (13U)
/*! CMD32EN - Enables or disables WDOG support for 32-bit (otherwise 16-bit or 8-bit) refresh/unlock command write words
* 0b0..Disables support for 32-bit refresh/unlock command write words. Only 16-bit or 8-bit is supported.
* 0b1..Enables support for 32-bit refresh/unlock command write words. 16-bit or 8-bit is NOT supported.
*/
#define RTWDOG_CS_CMD32EN(x) (((uint32_t)(((uint32_t)(x)) << RTWDOG_CS_CMD32EN_SHIFT)) & RTWDOG_CS_CMD32EN_MASK)
#define RTWDOG_CS_FLG_MASK (0x4000U)
#define RTWDOG_CS_FLG_SHIFT (14U)
/*! FLG - Watchdog Interrupt Flag
* 0b0..No interrupt occurred.
* 0b1..An interrupt occurred.
*/
#define RTWDOG_CS_FLG(x) (((uint32_t)(((uint32_t)(x)) << RTWDOG_CS_FLG_SHIFT)) & RTWDOG_CS_FLG_MASK)
#define RTWDOG_CS_WIN_MASK (0x8000U)
#define RTWDOG_CS_WIN_SHIFT (15U)
/*! WIN - Watchdog Window
* 0b0..Window mode disabled.
* 0b1..Window mode enabled.
*/
#define RTWDOG_CS_WIN(x) (((uint32_t)(((uint32_t)(x)) << RTWDOG_CS_WIN_SHIFT)) & RTWDOG_CS_WIN_MASK)
/*! @} */
/*! @name CNT - Watchdog Counter Register */
/*! @{ */
#define RTWDOG_CNT_CNTLOW_MASK (0xFFU)
#define RTWDOG_CNT_CNTLOW_SHIFT (0U)
/*! CNTLOW - Low byte of the Watchdog Counter */
#define RTWDOG_CNT_CNTLOW(x) (((uint32_t)(((uint32_t)(x)) << RTWDOG_CNT_CNTLOW_SHIFT)) & RTWDOG_CNT_CNTLOW_MASK)
#define RTWDOG_CNT_CNTHIGH_MASK (0xFF00U)
#define RTWDOG_CNT_CNTHIGH_SHIFT (8U)
/*! CNTHIGH - High byte of the Watchdog Counter */
#define RTWDOG_CNT_CNTHIGH(x) (((uint32_t)(((uint32_t)(x)) << RTWDOG_CNT_CNTHIGH_SHIFT)) & RTWDOG_CNT_CNTHIGH_MASK)
/*! @} */
/*! @name TOVAL - Watchdog Timeout Value Register */
/*! @{ */
#define RTWDOG_TOVAL_TOVALLOW_MASK (0xFFU)
#define RTWDOG_TOVAL_TOVALLOW_SHIFT (0U)
/*! TOVALLOW - Low byte of the timeout value */
#define RTWDOG_TOVAL_TOVALLOW(x) (((uint32_t)(((uint32_t)(x)) << RTWDOG_TOVAL_TOVALLOW_SHIFT)) & RTWDOG_TOVAL_TOVALLOW_MASK)
#define RTWDOG_TOVAL_TOVALHIGH_MASK (0xFF00U)
#define RTWDOG_TOVAL_TOVALHIGH_SHIFT (8U)
/*! TOVALHIGH - High byte of the timeout value */
#define RTWDOG_TOVAL_TOVALHIGH(x) (((uint32_t)(((uint32_t)(x)) << RTWDOG_TOVAL_TOVALHIGH_SHIFT)) & RTWDOG_TOVAL_TOVALHIGH_MASK)
/*! @} */
/*! @name WIN - Watchdog Window Register */
/*! @{ */
#define RTWDOG_WIN_WINLOW_MASK (0xFFU)
#define RTWDOG_WIN_WINLOW_SHIFT (0U)
/*! WINLOW - Low byte of Watchdog Window */
#define RTWDOG_WIN_WINLOW(x) (((uint32_t)(((uint32_t)(x)) << RTWDOG_WIN_WINLOW_SHIFT)) & RTWDOG_WIN_WINLOW_MASK)
#define RTWDOG_WIN_WINHIGH_MASK (0xFF00U)
#define RTWDOG_WIN_WINHIGH_SHIFT (8U)
/*! WINHIGH - High byte of Watchdog Window */
#define RTWDOG_WIN_WINHIGH(x) (((uint32_t)(((uint32_t)(x)) << RTWDOG_WIN_WINHIGH_SHIFT)) & RTWDOG_WIN_WINHIGH_MASK)
/*! @} */
/*!
* @}
*/ /* end of group RTWDOG_Register_Masks */
/* Extra definition */
#define RTWDOG_UPDATE_KEY (0xD928C520U)
#define RTWDOG_REFRESH_KEY (0xB480A602U)
/*!
* @}
*/ /* end of group RTWDOG_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 */
#endif /* RTWDOG_H_ */

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,777 @@
/*
** ###################################################################
** Processors: MIMXRT1061CVJ5A
** MIMXRT1061CVJ5B
** MIMXRT1061CVL5A
** MIMXRT1061CVL5B
** MIMXRT1061DVJ6A
** MIMXRT1061DVJ6B
** MIMXRT1061DVL6A
** MIMXRT1061DVL6B
** MIMXRT1061XVN5B
** MIMXRT1062CVJ5A
** MIMXRT1062CVJ5B
** MIMXRT1062CVL5A
** MIMXRT1062CVL5B
** MIMXRT1062DVJ6A
** MIMXRT1062DVJ6B
** MIMXRT1062DVL6A
** MIMXRT1062DVL6B
** MIMXRT1062DVN6B
** MIMXRT1062XVN5B
** MIMXRT106ADVL6A
** MIMXRT106CDVL6A
** MIMXRT106FDVL6A
** MIMXRT106LDVL6A
** MIMXRT106SDVL6A
**
** Version: rev. 1.4, 2022-03-25
** Build: b240705
**
** Abstract:
** CMSIS Peripheral Access Layer for SPDIF
**
** Copyright 1997-2016 Freescale Semiconductor, Inc.
** Copyright 2016-2024 NXP
** SPDX-License-Identifier: BSD-3-Clause
**
** http: www.nxp.com
** mail: support@nxp.com
**
** Revisions:
** - rev. 0.1 (2017-01-10)
** Initial version.
** - rev. 1.0 (2018-11-16)
** Update header files to align with IMXRT1060RM Rev.0.
** - rev. 1.1 (2018-11-27)
** Update header files to align with IMXRT1060RM Rev.1.
** - rev. 1.2 (2019-04-29)
** Add SET/CLR/TOG register group to register CTRL, STAT, CHANNELCTRL, CH0STAT, CH0OPTS, CH1STAT, CH1OPTS, CH2STAT, CH2OPTS, CH3STAT, CH3OPTS of DCP module.
** - rev. 1.3 (2021-08-10)
** Update header files to align with IMXRT1060RM Rev.3.
** - rev. 1.4 (2022-03-25)
** Add RT1060X device
**
** ###################################################################
*/
/*!
* @file SPDIF.h
* @version 1.4
* @date 2022-03-25
* @brief CMSIS Peripheral Access Layer for SPDIF
*
* CMSIS Peripheral Access Layer for SPDIF
*/
#if !defined(SPDIF_H_)
#define SPDIF_H_ /**< Symbol preventing repeated inclusion */
#if (defined(CPU_MIMXRT1061CVJ5A) || defined(CPU_MIMXRT1061CVJ5B) || defined(CPU_MIMXRT1061CVL5A) || defined(CPU_MIMXRT1061CVL5B) || defined(CPU_MIMXRT1061DVJ6A) || defined(CPU_MIMXRT1061DVJ6B) || defined(CPU_MIMXRT1061DVL6A) || defined(CPU_MIMXRT1061DVL6B) || defined(CPU_MIMXRT1061XVN5B))
#include "MIMXRT1061_COMMON.h"
#elif (defined(CPU_MIMXRT1062CVJ5A) || defined(CPU_MIMXRT1062CVJ5B) || defined(CPU_MIMXRT1062CVL5A) || defined(CPU_MIMXRT1062CVL5B) || defined(CPU_MIMXRT1062DVJ6A) || defined(CPU_MIMXRT1062DVJ6B) || defined(CPU_MIMXRT1062DVL6A) || defined(CPU_MIMXRT1062DVL6B) || defined(CPU_MIMXRT1062DVN6B) || defined(CPU_MIMXRT1062XVN5B))
#include "MIMXRT1062_COMMON.h"
#elif (defined(CPU_MIMXRT106ADVL6A))
#include "MIMXRT106A_COMMON.h"
#elif (defined(CPU_MIMXRT106CDVL6A))
#include "MIMXRT106C_COMMON.h"
#elif (defined(CPU_MIMXRT106FDVL6A))
#include "MIMXRT106F_COMMON.h"
#elif (defined(CPU_MIMXRT106LDVL6A))
#include "MIMXRT106L_COMMON.h"
#elif (defined(CPU_MIMXRT106SDVL6A))
#include "MIMXRT106S_COMMON.h"
#else
#error "No valid CPU defined!"
#endif
/* ----------------------------------------------------------------------------
-- 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
/* ----------------------------------------------------------------------------
-- SPDIF Peripheral Access Layer
---------------------------------------------------------------------------- */
/*!
* @addtogroup SPDIF_Peripheral_Access_Layer SPDIF Peripheral Access Layer
* @{
*/
/** SPDIF - Register Layout Typedef */
typedef struct {
__IO uint32_t SCR; /**< SPDIF Configuration Register, offset: 0x0 */
__IO uint32_t SRCD; /**< CDText Control Register, offset: 0x4 */
__IO uint32_t SRPC; /**< PhaseConfig Register, offset: 0x8 */
__IO uint32_t SIE; /**< InterruptEn Register, offset: 0xC */
union { /* offset: 0x10 */
__O uint32_t SIC; /**< InterruptClear Register, offset: 0x10 */
__I uint32_t SIS; /**< InterruptStat Register, offset: 0x10 */
};
__I uint32_t SRL; /**< SPDIFRxLeft Register, offset: 0x14 */
__I uint32_t SRR; /**< SPDIFRxRight Register, offset: 0x18 */
__I uint32_t SRCSH; /**< SPDIFRxCChannel_h Register, offset: 0x1C */
__I uint32_t SRCSL; /**< SPDIFRxCChannel_l Register, offset: 0x20 */
__I uint32_t SRU; /**< UchannelRx Register, offset: 0x24 */
__I uint32_t SRQ; /**< QchannelRx Register, offset: 0x28 */
__O uint32_t STL; /**< SPDIFTxLeft Register, offset: 0x2C */
__O uint32_t STR; /**< SPDIFTxRight Register, offset: 0x30 */
__IO uint32_t STCSCH; /**< SPDIFTxCChannelCons_h Register, offset: 0x34 */
__IO uint32_t STCSCL; /**< SPDIFTxCChannelCons_l Register, offset: 0x38 */
uint8_t RESERVED_0[8];
__I uint32_t SRFM; /**< FreqMeas Register, offset: 0x44 */
uint8_t RESERVED_1[8];
__IO uint32_t STC; /**< SPDIFTxClk Register, offset: 0x50 */
} SPDIF_Type;
/* ----------------------------------------------------------------------------
-- SPDIF Register Masks
---------------------------------------------------------------------------- */
/*!
* @addtogroup SPDIF_Register_Masks SPDIF Register Masks
* @{
*/
/*! @name SCR - SPDIF Configuration Register */
/*! @{ */
#define SPDIF_SCR_USRC_SEL_MASK (0x3U)
#define SPDIF_SCR_USRC_SEL_SHIFT (0U)
/*! USrc_Sel - USrc_Sel
* 0b00..No embedded U channel
* 0b01..U channel from SPDIF receive block (CD mode)
* 0b10..Reserved
* 0b11..U channel from on chip transmitter
*/
#define SPDIF_SCR_USRC_SEL(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SCR_USRC_SEL_SHIFT)) & SPDIF_SCR_USRC_SEL_MASK)
#define SPDIF_SCR_TXSEL_MASK (0x1CU)
#define SPDIF_SCR_TXSEL_SHIFT (2U)
/*! TxSel - TxSel
* 0b000..Off and output 0
* 0b001..Feed-through SPDIFIN
* 0b101..Tx Normal operation
*/
#define SPDIF_SCR_TXSEL(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SCR_TXSEL_SHIFT)) & SPDIF_SCR_TXSEL_MASK)
#define SPDIF_SCR_VALCTRL_MASK (0x20U)
#define SPDIF_SCR_VALCTRL_SHIFT (5U)
/*! ValCtrl - ValCtrl
* 0b0..Outgoing Validity always set
* 0b1..Outgoing Validity always clear
*/
#define SPDIF_SCR_VALCTRL(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SCR_VALCTRL_SHIFT)) & SPDIF_SCR_VALCTRL_MASK)
#define SPDIF_SCR_INPUTSRCSEL_MASK (0xC0U)
#define SPDIF_SCR_INPUTSRCSEL_SHIFT (6U)
/*! InputSrcSel - InputSrcSel
* 0b00..SPDIF_IN
* 0b01-0b11..None
*/
#define SPDIF_SCR_INPUTSRCSEL(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SCR_INPUTSRCSEL_SHIFT)) & SPDIF_SCR_INPUTSRCSEL_MASK)
#define SPDIF_SCR_DMA_TX_EN_MASK (0x100U)
#define SPDIF_SCR_DMA_TX_EN_SHIFT (8U)
/*! DMA_TX_En - DMA_TX_En */
#define SPDIF_SCR_DMA_TX_EN(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SCR_DMA_TX_EN_SHIFT)) & SPDIF_SCR_DMA_TX_EN_MASK)
#define SPDIF_SCR_DMA_RX_EN_MASK (0x200U)
#define SPDIF_SCR_DMA_RX_EN_SHIFT (9U)
/*! DMA_Rx_En - DMA_Rx_En */
#define SPDIF_SCR_DMA_RX_EN(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SCR_DMA_RX_EN_SHIFT)) & SPDIF_SCR_DMA_RX_EN_MASK)
#define SPDIF_SCR_TXFIFO_CTRL_MASK (0xC00U)
#define SPDIF_SCR_TXFIFO_CTRL_SHIFT (10U)
/*! TxFIFO_Ctrl - TxFIFO_Ctrl
* 0b00..Send out digital zero on SPDIF Tx
* 0b01..Tx Normal operation
* 0b10..Reset to 1 sample remaining
* 0b11..Reserved
*/
#define SPDIF_SCR_TXFIFO_CTRL(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SCR_TXFIFO_CTRL_SHIFT)) & SPDIF_SCR_TXFIFO_CTRL_MASK)
#define SPDIF_SCR_SOFT_RESET_MASK (0x1000U)
#define SPDIF_SCR_SOFT_RESET_SHIFT (12U)
/*! soft_reset - soft_reset */
#define SPDIF_SCR_SOFT_RESET(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SCR_SOFT_RESET_SHIFT)) & SPDIF_SCR_SOFT_RESET_MASK)
#define SPDIF_SCR_LOW_POWER_MASK (0x2000U)
#define SPDIF_SCR_LOW_POWER_SHIFT (13U)
/*! LOW_POWER - LOW_POWER */
#define SPDIF_SCR_LOW_POWER(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SCR_LOW_POWER_SHIFT)) & SPDIF_SCR_LOW_POWER_MASK)
#define SPDIF_SCR_TXFIFOEMPTY_SEL_MASK (0x18000U)
#define SPDIF_SCR_TXFIFOEMPTY_SEL_SHIFT (15U)
/*! TxFIFOEmpty_Sel - TxFIFOEmpty_Sel
* 0b00..Empty interrupt if 0 sample in Tx left and right FIFOs
* 0b01..Empty interrupt if at most 4 sample in Tx left and right FIFOs
* 0b10..Empty interrupt if at most 8 sample in Tx left and right FIFOs
* 0b11..Empty interrupt if at most 12 sample in Tx left and right FIFOs
*/
#define SPDIF_SCR_TXFIFOEMPTY_SEL(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SCR_TXFIFOEMPTY_SEL_SHIFT)) & SPDIF_SCR_TXFIFOEMPTY_SEL_MASK)
#define SPDIF_SCR_TXAUTOSYNC_MASK (0x20000U)
#define SPDIF_SCR_TXAUTOSYNC_SHIFT (17U)
/*! TxAutoSync - TxAutoSync
* 0b0..Tx FIFO auto sync off
* 0b1..Tx FIFO auto sync on
*/
#define SPDIF_SCR_TXAUTOSYNC(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SCR_TXAUTOSYNC_SHIFT)) & SPDIF_SCR_TXAUTOSYNC_MASK)
#define SPDIF_SCR_RXAUTOSYNC_MASK (0x40000U)
#define SPDIF_SCR_RXAUTOSYNC_SHIFT (18U)
/*! RxAutoSync - RxAutoSync
* 0b0..Rx FIFO auto sync off
* 0b1..RxFIFO auto sync on
*/
#define SPDIF_SCR_RXAUTOSYNC(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SCR_RXAUTOSYNC_SHIFT)) & SPDIF_SCR_RXAUTOSYNC_MASK)
#define SPDIF_SCR_RXFIFOFULL_SEL_MASK (0x180000U)
#define SPDIF_SCR_RXFIFOFULL_SEL_SHIFT (19U)
/*! RxFIFOFull_Sel - RxFIFOFull_Sel
* 0b00..Full interrupt if at least 1 sample in Rx left and right FIFOs
* 0b01..Full interrupt if at least 4 sample in Rx left and right FIFOs
* 0b10..Full interrupt if at least 8 sample in Rx left and right FIFOs
* 0b11..Full interrupt if at least 16 sample in Rx left and right FIFO
*/
#define SPDIF_SCR_RXFIFOFULL_SEL(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SCR_RXFIFOFULL_SEL_SHIFT)) & SPDIF_SCR_RXFIFOFULL_SEL_MASK)
#define SPDIF_SCR_RXFIFO_RST_MASK (0x200000U)
#define SPDIF_SCR_RXFIFO_RST_SHIFT (21U)
/*! RxFIFO_Rst - RxFIFO_Rst
* 0b0..Normal operation
* 0b1..Reset register to 1 sample remaining
*/
#define SPDIF_SCR_RXFIFO_RST(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SCR_RXFIFO_RST_SHIFT)) & SPDIF_SCR_RXFIFO_RST_MASK)
#define SPDIF_SCR_RXFIFO_OFF_ON_MASK (0x400000U)
#define SPDIF_SCR_RXFIFO_OFF_ON_SHIFT (22U)
/*! RxFIFO_Off_On - RxFIFO_Off_On
* 0b0..SPDIF Rx FIFO is on
* 0b1..SPDIF Rx FIFO is off. Does not accept data from interface
*/
#define SPDIF_SCR_RXFIFO_OFF_ON(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SCR_RXFIFO_OFF_ON_SHIFT)) & SPDIF_SCR_RXFIFO_OFF_ON_MASK)
#define SPDIF_SCR_RXFIFO_CTRL_MASK (0x800000U)
#define SPDIF_SCR_RXFIFO_CTRL_SHIFT (23U)
/*! RxFIFO_Ctrl - RxFIFO_Ctrl
* 0b0..Normal operation
* 0b1..Always read zero from Rx data register
*/
#define SPDIF_SCR_RXFIFO_CTRL(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SCR_RXFIFO_CTRL_SHIFT)) & SPDIF_SCR_RXFIFO_CTRL_MASK)
/*! @} */
/*! @name SRCD - CDText Control Register */
/*! @{ */
#define SPDIF_SRCD_USYNCMODE_MASK (0x2U)
#define SPDIF_SRCD_USYNCMODE_SHIFT (1U)
/*! USyncMode - USyncMode
* 0b0..Non-CD data
* 0b1..CD user channel subcode
*/
#define SPDIF_SRCD_USYNCMODE(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SRCD_USYNCMODE_SHIFT)) & SPDIF_SRCD_USYNCMODE_MASK)
/*! @} */
/*! @name SRPC - PhaseConfig Register */
/*! @{ */
#define SPDIF_SRPC_GAINSEL_MASK (0x38U)
#define SPDIF_SRPC_GAINSEL_SHIFT (3U)
/*! GainSel - GainSel
* 0b000..24*(2**10)
* 0b001..16*(2**10)
* 0b010..12*(2**10)
* 0b011..8*(2**10)
* 0b100..6*(2**10)
* 0b101..4*(2**10)
* 0b110..3*(2**10)
*/
#define SPDIF_SRPC_GAINSEL(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SRPC_GAINSEL_SHIFT)) & SPDIF_SRPC_GAINSEL_MASK)
#define SPDIF_SRPC_LOCK_MASK (0x40U)
#define SPDIF_SRPC_LOCK_SHIFT (6U)
/*! LOCK - LOCK */
#define SPDIF_SRPC_LOCK(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SRPC_LOCK_SHIFT)) & SPDIF_SRPC_LOCK_MASK)
#define SPDIF_SRPC_CLKSRC_SEL_MASK (0x780U)
#define SPDIF_SRPC_CLKSRC_SEL_SHIFT (7U)
/*! ClkSrc_Sel - ClkSrc_Sel
* 0b0000..if (DPLL Locked) SPDIF_RxClk else REF_CLK_32K (XTALOSC)
* 0b0001..if (DPLL Locked) SPDIF_RxClk else tx_clk (SPDIF0_CLK_ROOT)
* 0b0011..if (DPLL Locked) SPDIF_RxClk else SPDIF_EXT_CLK
* 0b0101..REF_CLK_32K (XTALOSC)
* 0b0110..tx_clk (SPDIF0_CLK_ROOT)
* 0b1000..SPDIF_EXT_CLK
*/
#define SPDIF_SRPC_CLKSRC_SEL(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SRPC_CLKSRC_SEL_SHIFT)) & SPDIF_SRPC_CLKSRC_SEL_MASK)
/*! @} */
/*! @name SIE - InterruptEn Register */
/*! @{ */
#define SPDIF_SIE_RXFIFOFUL_MASK (0x1U)
#define SPDIF_SIE_RXFIFOFUL_SHIFT (0U)
/*! RxFIFOFul - RxFIFOFul */
#define SPDIF_SIE_RXFIFOFUL(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SIE_RXFIFOFUL_SHIFT)) & SPDIF_SIE_RXFIFOFUL_MASK)
#define SPDIF_SIE_TXEM_MASK (0x2U)
#define SPDIF_SIE_TXEM_SHIFT (1U)
/*! TxEm - TxEm */
#define SPDIF_SIE_TXEM(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SIE_TXEM_SHIFT)) & SPDIF_SIE_TXEM_MASK)
#define SPDIF_SIE_LOCKLOSS_MASK (0x4U)
#define SPDIF_SIE_LOCKLOSS_SHIFT (2U)
/*! LockLoss - LockLoss */
#define SPDIF_SIE_LOCKLOSS(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SIE_LOCKLOSS_SHIFT)) & SPDIF_SIE_LOCKLOSS_MASK)
#define SPDIF_SIE_RXFIFORESYN_MASK (0x8U)
#define SPDIF_SIE_RXFIFORESYN_SHIFT (3U)
/*! RxFIFOResyn - RxFIFOResyn */
#define SPDIF_SIE_RXFIFORESYN(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SIE_RXFIFORESYN_SHIFT)) & SPDIF_SIE_RXFIFORESYN_MASK)
#define SPDIF_SIE_RXFIFOUNOV_MASK (0x10U)
#define SPDIF_SIE_RXFIFOUNOV_SHIFT (4U)
/*! RxFIFOUnOv - RxFIFOUnOv */
#define SPDIF_SIE_RXFIFOUNOV(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SIE_RXFIFOUNOV_SHIFT)) & SPDIF_SIE_RXFIFOUNOV_MASK)
#define SPDIF_SIE_UQERR_MASK (0x20U)
#define SPDIF_SIE_UQERR_SHIFT (5U)
/*! UQErr - UQErr */
#define SPDIF_SIE_UQERR(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SIE_UQERR_SHIFT)) & SPDIF_SIE_UQERR_MASK)
#define SPDIF_SIE_UQSYNC_MASK (0x40U)
#define SPDIF_SIE_UQSYNC_SHIFT (6U)
/*! UQSync - UQSync */
#define SPDIF_SIE_UQSYNC(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SIE_UQSYNC_SHIFT)) & SPDIF_SIE_UQSYNC_MASK)
#define SPDIF_SIE_QRXOV_MASK (0x80U)
#define SPDIF_SIE_QRXOV_SHIFT (7U)
/*! QRxOv - QRxOv */
#define SPDIF_SIE_QRXOV(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SIE_QRXOV_SHIFT)) & SPDIF_SIE_QRXOV_MASK)
#define SPDIF_SIE_QRXFUL_MASK (0x100U)
#define SPDIF_SIE_QRXFUL_SHIFT (8U)
/*! QRxFul - QRxFul */
#define SPDIF_SIE_QRXFUL(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SIE_QRXFUL_SHIFT)) & SPDIF_SIE_QRXFUL_MASK)
#define SPDIF_SIE_URXOV_MASK (0x200U)
#define SPDIF_SIE_URXOV_SHIFT (9U)
/*! URxOv - URxOv */
#define SPDIF_SIE_URXOV(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SIE_URXOV_SHIFT)) & SPDIF_SIE_URXOV_MASK)
#define SPDIF_SIE_URXFUL_MASK (0x400U)
#define SPDIF_SIE_URXFUL_SHIFT (10U)
/*! URxFul - URxFul */
#define SPDIF_SIE_URXFUL(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SIE_URXFUL_SHIFT)) & SPDIF_SIE_URXFUL_MASK)
#define SPDIF_SIE_BITERR_MASK (0x4000U)
#define SPDIF_SIE_BITERR_SHIFT (14U)
/*! BitErr - BitErr */
#define SPDIF_SIE_BITERR(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SIE_BITERR_SHIFT)) & SPDIF_SIE_BITERR_MASK)
#define SPDIF_SIE_SYMERR_MASK (0x8000U)
#define SPDIF_SIE_SYMERR_SHIFT (15U)
/*! SymErr - SymErr */
#define SPDIF_SIE_SYMERR(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SIE_SYMERR_SHIFT)) & SPDIF_SIE_SYMERR_MASK)
#define SPDIF_SIE_VALNOGOOD_MASK (0x10000U)
#define SPDIF_SIE_VALNOGOOD_SHIFT (16U)
/*! ValNoGood - ValNoGood */
#define SPDIF_SIE_VALNOGOOD(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SIE_VALNOGOOD_SHIFT)) & SPDIF_SIE_VALNOGOOD_MASK)
#define SPDIF_SIE_CNEW_MASK (0x20000U)
#define SPDIF_SIE_CNEW_SHIFT (17U)
/*! CNew - CNew */
#define SPDIF_SIE_CNEW(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SIE_CNEW_SHIFT)) & SPDIF_SIE_CNEW_MASK)
#define SPDIF_SIE_TXRESYN_MASK (0x40000U)
#define SPDIF_SIE_TXRESYN_SHIFT (18U)
/*! TxResyn - TxResyn */
#define SPDIF_SIE_TXRESYN(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SIE_TXRESYN_SHIFT)) & SPDIF_SIE_TXRESYN_MASK)
#define SPDIF_SIE_TXUNOV_MASK (0x80000U)
#define SPDIF_SIE_TXUNOV_SHIFT (19U)
/*! TxUnOv - TxUnOv */
#define SPDIF_SIE_TXUNOV(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SIE_TXUNOV_SHIFT)) & SPDIF_SIE_TXUNOV_MASK)
#define SPDIF_SIE_LOCK_MASK (0x100000U)
#define SPDIF_SIE_LOCK_SHIFT (20U)
/*! Lock - Lock */
#define SPDIF_SIE_LOCK(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SIE_LOCK_SHIFT)) & SPDIF_SIE_LOCK_MASK)
/*! @} */
/*! @name SIC - InterruptClear Register */
/*! @{ */
#define SPDIF_SIC_LOCKLOSS_MASK (0x4U)
#define SPDIF_SIC_LOCKLOSS_SHIFT (2U)
/*! LockLoss - LockLoss */
#define SPDIF_SIC_LOCKLOSS(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SIC_LOCKLOSS_SHIFT)) & SPDIF_SIC_LOCKLOSS_MASK)
#define SPDIF_SIC_RXFIFORESYN_MASK (0x8U)
#define SPDIF_SIC_RXFIFORESYN_SHIFT (3U)
/*! RxFIFOResyn - RxFIFOResyn */
#define SPDIF_SIC_RXFIFORESYN(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SIC_RXFIFORESYN_SHIFT)) & SPDIF_SIC_RXFIFORESYN_MASK)
#define SPDIF_SIC_RXFIFOUNOV_MASK (0x10U)
#define SPDIF_SIC_RXFIFOUNOV_SHIFT (4U)
/*! RxFIFOUnOv - RxFIFOUnOv */
#define SPDIF_SIC_RXFIFOUNOV(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SIC_RXFIFOUNOV_SHIFT)) & SPDIF_SIC_RXFIFOUNOV_MASK)
#define SPDIF_SIC_UQERR_MASK (0x20U)
#define SPDIF_SIC_UQERR_SHIFT (5U)
/*! UQErr - UQErr */
#define SPDIF_SIC_UQERR(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SIC_UQERR_SHIFT)) & SPDIF_SIC_UQERR_MASK)
#define SPDIF_SIC_UQSYNC_MASK (0x40U)
#define SPDIF_SIC_UQSYNC_SHIFT (6U)
/*! UQSync - UQSync */
#define SPDIF_SIC_UQSYNC(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SIC_UQSYNC_SHIFT)) & SPDIF_SIC_UQSYNC_MASK)
#define SPDIF_SIC_QRXOV_MASK (0x80U)
#define SPDIF_SIC_QRXOV_SHIFT (7U)
/*! QRxOv - QRxOv */
#define SPDIF_SIC_QRXOV(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SIC_QRXOV_SHIFT)) & SPDIF_SIC_QRXOV_MASK)
#define SPDIF_SIC_URXOV_MASK (0x200U)
#define SPDIF_SIC_URXOV_SHIFT (9U)
/*! URxOv - URxOv */
#define SPDIF_SIC_URXOV(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SIC_URXOV_SHIFT)) & SPDIF_SIC_URXOV_MASK)
#define SPDIF_SIC_BITERR_MASK (0x4000U)
#define SPDIF_SIC_BITERR_SHIFT (14U)
/*! BitErr - BitErr */
#define SPDIF_SIC_BITERR(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SIC_BITERR_SHIFT)) & SPDIF_SIC_BITERR_MASK)
#define SPDIF_SIC_SYMERR_MASK (0x8000U)
#define SPDIF_SIC_SYMERR_SHIFT (15U)
/*! SymErr - SymErr */
#define SPDIF_SIC_SYMERR(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SIC_SYMERR_SHIFT)) & SPDIF_SIC_SYMERR_MASK)
#define SPDIF_SIC_VALNOGOOD_MASK (0x10000U)
#define SPDIF_SIC_VALNOGOOD_SHIFT (16U)
/*! ValNoGood - ValNoGood */
#define SPDIF_SIC_VALNOGOOD(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SIC_VALNOGOOD_SHIFT)) & SPDIF_SIC_VALNOGOOD_MASK)
#define SPDIF_SIC_CNEW_MASK (0x20000U)
#define SPDIF_SIC_CNEW_SHIFT (17U)
/*! CNew - CNew */
#define SPDIF_SIC_CNEW(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SIC_CNEW_SHIFT)) & SPDIF_SIC_CNEW_MASK)
#define SPDIF_SIC_TXRESYN_MASK (0x40000U)
#define SPDIF_SIC_TXRESYN_SHIFT (18U)
/*! TxResyn - TxResyn */
#define SPDIF_SIC_TXRESYN(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SIC_TXRESYN_SHIFT)) & SPDIF_SIC_TXRESYN_MASK)
#define SPDIF_SIC_TXUNOV_MASK (0x80000U)
#define SPDIF_SIC_TXUNOV_SHIFT (19U)
/*! TxUnOv - TxUnOv */
#define SPDIF_SIC_TXUNOV(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SIC_TXUNOV_SHIFT)) & SPDIF_SIC_TXUNOV_MASK)
#define SPDIF_SIC_LOCK_MASK (0x100000U)
#define SPDIF_SIC_LOCK_SHIFT (20U)
/*! Lock - Lock */
#define SPDIF_SIC_LOCK(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SIC_LOCK_SHIFT)) & SPDIF_SIC_LOCK_MASK)
/*! @} */
/*! @name SIS - InterruptStat Register */
/*! @{ */
#define SPDIF_SIS_RXFIFOFUL_MASK (0x1U)
#define SPDIF_SIS_RXFIFOFUL_SHIFT (0U)
/*! RxFIFOFul - RxFIFOFul */
#define SPDIF_SIS_RXFIFOFUL(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SIS_RXFIFOFUL_SHIFT)) & SPDIF_SIS_RXFIFOFUL_MASK)
#define SPDIF_SIS_TXEM_MASK (0x2U)
#define SPDIF_SIS_TXEM_SHIFT (1U)
/*! TxEm - TxEm */
#define SPDIF_SIS_TXEM(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SIS_TXEM_SHIFT)) & SPDIF_SIS_TXEM_MASK)
#define SPDIF_SIS_LOCKLOSS_MASK (0x4U)
#define SPDIF_SIS_LOCKLOSS_SHIFT (2U)
/*! LockLoss - LockLoss */
#define SPDIF_SIS_LOCKLOSS(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SIS_LOCKLOSS_SHIFT)) & SPDIF_SIS_LOCKLOSS_MASK)
#define SPDIF_SIS_RXFIFORESYN_MASK (0x8U)
#define SPDIF_SIS_RXFIFORESYN_SHIFT (3U)
/*! RxFIFOResyn - RxFIFOResyn */
#define SPDIF_SIS_RXFIFORESYN(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SIS_RXFIFORESYN_SHIFT)) & SPDIF_SIS_RXFIFORESYN_MASK)
#define SPDIF_SIS_RXFIFOUNOV_MASK (0x10U)
#define SPDIF_SIS_RXFIFOUNOV_SHIFT (4U)
/*! RxFIFOUnOv - RxFIFOUnOv */
#define SPDIF_SIS_RXFIFOUNOV(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SIS_RXFIFOUNOV_SHIFT)) & SPDIF_SIS_RXFIFOUNOV_MASK)
#define SPDIF_SIS_UQERR_MASK (0x20U)
#define SPDIF_SIS_UQERR_SHIFT (5U)
/*! UQErr - UQErr */
#define SPDIF_SIS_UQERR(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SIS_UQERR_SHIFT)) & SPDIF_SIS_UQERR_MASK)
#define SPDIF_SIS_UQSYNC_MASK (0x40U)
#define SPDIF_SIS_UQSYNC_SHIFT (6U)
/*! UQSync - UQSync */
#define SPDIF_SIS_UQSYNC(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SIS_UQSYNC_SHIFT)) & SPDIF_SIS_UQSYNC_MASK)
#define SPDIF_SIS_QRXOV_MASK (0x80U)
#define SPDIF_SIS_QRXOV_SHIFT (7U)
/*! QRxOv - QRxOv */
#define SPDIF_SIS_QRXOV(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SIS_QRXOV_SHIFT)) & SPDIF_SIS_QRXOV_MASK)
#define SPDIF_SIS_QRXFUL_MASK (0x100U)
#define SPDIF_SIS_QRXFUL_SHIFT (8U)
/*! QRxFul - QRxFul */
#define SPDIF_SIS_QRXFUL(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SIS_QRXFUL_SHIFT)) & SPDIF_SIS_QRXFUL_MASK)
#define SPDIF_SIS_URXOV_MASK (0x200U)
#define SPDIF_SIS_URXOV_SHIFT (9U)
/*! URxOv - URxOv */
#define SPDIF_SIS_URXOV(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SIS_URXOV_SHIFT)) & SPDIF_SIS_URXOV_MASK)
#define SPDIF_SIS_URXFUL_MASK (0x400U)
#define SPDIF_SIS_URXFUL_SHIFT (10U)
/*! URxFul - URxFul */
#define SPDIF_SIS_URXFUL(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SIS_URXFUL_SHIFT)) & SPDIF_SIS_URXFUL_MASK)
#define SPDIF_SIS_BITERR_MASK (0x4000U)
#define SPDIF_SIS_BITERR_SHIFT (14U)
/*! BitErr - BitErr */
#define SPDIF_SIS_BITERR(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SIS_BITERR_SHIFT)) & SPDIF_SIS_BITERR_MASK)
#define SPDIF_SIS_SYMERR_MASK (0x8000U)
#define SPDIF_SIS_SYMERR_SHIFT (15U)
/*! SymErr - SymErr */
#define SPDIF_SIS_SYMERR(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SIS_SYMERR_SHIFT)) & SPDIF_SIS_SYMERR_MASK)
#define SPDIF_SIS_VALNOGOOD_MASK (0x10000U)
#define SPDIF_SIS_VALNOGOOD_SHIFT (16U)
/*! ValNoGood - ValNoGood */
#define SPDIF_SIS_VALNOGOOD(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SIS_VALNOGOOD_SHIFT)) & SPDIF_SIS_VALNOGOOD_MASK)
#define SPDIF_SIS_CNEW_MASK (0x20000U)
#define SPDIF_SIS_CNEW_SHIFT (17U)
/*! CNew - CNew */
#define SPDIF_SIS_CNEW(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SIS_CNEW_SHIFT)) & SPDIF_SIS_CNEW_MASK)
#define SPDIF_SIS_TXRESYN_MASK (0x40000U)
#define SPDIF_SIS_TXRESYN_SHIFT (18U)
/*! TxResyn - TxResyn */
#define SPDIF_SIS_TXRESYN(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SIS_TXRESYN_SHIFT)) & SPDIF_SIS_TXRESYN_MASK)
#define SPDIF_SIS_TXUNOV_MASK (0x80000U)
#define SPDIF_SIS_TXUNOV_SHIFT (19U)
/*! TxUnOv - TxUnOv */
#define SPDIF_SIS_TXUNOV(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SIS_TXUNOV_SHIFT)) & SPDIF_SIS_TXUNOV_MASK)
#define SPDIF_SIS_LOCK_MASK (0x100000U)
#define SPDIF_SIS_LOCK_SHIFT (20U)
/*! Lock - Lock */
#define SPDIF_SIS_LOCK(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SIS_LOCK_SHIFT)) & SPDIF_SIS_LOCK_MASK)
/*! @} */
/*! @name SRL - SPDIFRxLeft Register */
/*! @{ */
#define SPDIF_SRL_RXDATALEFT_MASK (0xFFFFFFU)
#define SPDIF_SRL_RXDATALEFT_SHIFT (0U)
/*! RxDataLeft - RxDataLeft */
#define SPDIF_SRL_RXDATALEFT(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SRL_RXDATALEFT_SHIFT)) & SPDIF_SRL_RXDATALEFT_MASK)
/*! @} */
/*! @name SRR - SPDIFRxRight Register */
/*! @{ */
#define SPDIF_SRR_RXDATARIGHT_MASK (0xFFFFFFU)
#define SPDIF_SRR_RXDATARIGHT_SHIFT (0U)
/*! RxDataRight - RxDataRight */
#define SPDIF_SRR_RXDATARIGHT(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SRR_RXDATARIGHT_SHIFT)) & SPDIF_SRR_RXDATARIGHT_MASK)
/*! @} */
/*! @name SRCSH - SPDIFRxCChannel_h Register */
/*! @{ */
#define SPDIF_SRCSH_RXCCHANNEL_H_MASK (0xFFFFFFU)
#define SPDIF_SRCSH_RXCCHANNEL_H_SHIFT (0U)
/*! RxCChannel_h - RxCChannel_h */
#define SPDIF_SRCSH_RXCCHANNEL_H(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SRCSH_RXCCHANNEL_H_SHIFT)) & SPDIF_SRCSH_RXCCHANNEL_H_MASK)
/*! @} */
/*! @name SRCSL - SPDIFRxCChannel_l Register */
/*! @{ */
#define SPDIF_SRCSL_RXCCHANNEL_L_MASK (0xFFFFFFU)
#define SPDIF_SRCSL_RXCCHANNEL_L_SHIFT (0U)
/*! RxCChannel_l - RxCChannel_l */
#define SPDIF_SRCSL_RXCCHANNEL_L(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SRCSL_RXCCHANNEL_L_SHIFT)) & SPDIF_SRCSL_RXCCHANNEL_L_MASK)
/*! @} */
/*! @name SRU - UchannelRx Register */
/*! @{ */
#define SPDIF_SRU_RXUCHANNEL_MASK (0xFFFFFFU)
#define SPDIF_SRU_RXUCHANNEL_SHIFT (0U)
/*! RxUChannel - RxUChannel */
#define SPDIF_SRU_RXUCHANNEL(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SRU_RXUCHANNEL_SHIFT)) & SPDIF_SRU_RXUCHANNEL_MASK)
/*! @} */
/*! @name SRQ - QchannelRx Register */
/*! @{ */
#define SPDIF_SRQ_RXQCHANNEL_MASK (0xFFFFFFU)
#define SPDIF_SRQ_RXQCHANNEL_SHIFT (0U)
/*! RxQChannel - RxQChannel */
#define SPDIF_SRQ_RXQCHANNEL(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SRQ_RXQCHANNEL_SHIFT)) & SPDIF_SRQ_RXQCHANNEL_MASK)
/*! @} */
/*! @name STL - SPDIFTxLeft Register */
/*! @{ */
#define SPDIF_STL_TXDATALEFT_MASK (0xFFFFFFU)
#define SPDIF_STL_TXDATALEFT_SHIFT (0U)
/*! TxDataLeft - TxDataLeft */
#define SPDIF_STL_TXDATALEFT(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_STL_TXDATALEFT_SHIFT)) & SPDIF_STL_TXDATALEFT_MASK)
/*! @} */
/*! @name STR - SPDIFTxRight Register */
/*! @{ */
#define SPDIF_STR_TXDATARIGHT_MASK (0xFFFFFFU)
#define SPDIF_STR_TXDATARIGHT_SHIFT (0U)
/*! TxDataRight - TxDataRight */
#define SPDIF_STR_TXDATARIGHT(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_STR_TXDATARIGHT_SHIFT)) & SPDIF_STR_TXDATARIGHT_MASK)
/*! @} */
/*! @name STCSCH - SPDIFTxCChannelCons_h Register */
/*! @{ */
#define SPDIF_STCSCH_TXCCHANNELCONS_H_MASK (0xFFFFFFU)
#define SPDIF_STCSCH_TXCCHANNELCONS_H_SHIFT (0U)
/*! TxCChannelCons_h - TxCChannelCons_h */
#define SPDIF_STCSCH_TXCCHANNELCONS_H(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_STCSCH_TXCCHANNELCONS_H_SHIFT)) & SPDIF_STCSCH_TXCCHANNELCONS_H_MASK)
/*! @} */
/*! @name STCSCL - SPDIFTxCChannelCons_l Register */
/*! @{ */
#define SPDIF_STCSCL_TXCCHANNELCONS_L_MASK (0xFFFFFFU)
#define SPDIF_STCSCL_TXCCHANNELCONS_L_SHIFT (0U)
/*! TxCChannelCons_l - TxCChannelCons_l */
#define SPDIF_STCSCL_TXCCHANNELCONS_L(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_STCSCL_TXCCHANNELCONS_L_SHIFT)) & SPDIF_STCSCL_TXCCHANNELCONS_L_MASK)
/*! @} */
/*! @name SRFM - FreqMeas Register */
/*! @{ */
#define SPDIF_SRFM_FREQMEAS_MASK (0xFFFFFFU)
#define SPDIF_SRFM_FREQMEAS_SHIFT (0U)
/*! FreqMeas - FreqMeas */
#define SPDIF_SRFM_FREQMEAS(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_SRFM_FREQMEAS_SHIFT)) & SPDIF_SRFM_FREQMEAS_MASK)
/*! @} */
/*! @name STC - SPDIFTxClk Register */
/*! @{ */
#define SPDIF_STC_TXCLK_DF_MASK (0x7FU)
#define SPDIF_STC_TXCLK_DF_SHIFT (0U)
/*! TxClk_DF - TxClk_DF
* 0b0000000..divider factor is 1
* 0b0000001..divider factor is 2
* 0b1111111..divider factor is 128
*/
#define SPDIF_STC_TXCLK_DF(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_STC_TXCLK_DF_SHIFT)) & SPDIF_STC_TXCLK_DF_MASK)
#define SPDIF_STC_TX_ALL_CLK_EN_MASK (0x80U)
#define SPDIF_STC_TX_ALL_CLK_EN_SHIFT (7U)
/*! tx_all_clk_en - tx_all_clk_en
* 0b0..disable transfer clock.
* 0b1..enable transfer clock.
*/
#define SPDIF_STC_TX_ALL_CLK_EN(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_STC_TX_ALL_CLK_EN_SHIFT)) & SPDIF_STC_TX_ALL_CLK_EN_MASK)
#define SPDIF_STC_TXCLK_SOURCE_MASK (0x700U)
#define SPDIF_STC_TXCLK_SOURCE_SHIFT (8U)
/*! TxClk_Source - TxClk_Source
* 0b000..REF_CLK_32K input (XTALOSC 32 kHz clock)
* 0b001..tx_clk input (from SPDIF0_CLK_ROOT. See clock control block for more information.)
* 0b011..SPDIF_EXT_CLK, from pads
* 0b101..ipg_clk input (frequency divided)
*/
#define SPDIF_STC_TXCLK_SOURCE(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_STC_TXCLK_SOURCE_SHIFT)) & SPDIF_STC_TXCLK_SOURCE_MASK)
#define SPDIF_STC_SYSCLK_DF_MASK (0xFF800U)
#define SPDIF_STC_SYSCLK_DF_SHIFT (11U)
/*! SYSCLK_DF - SYSCLK_DF
* 0b000000000..no clock signal
* 0b000000001..divider factor is 2
* 0b111111111..divider factor is 512
*/
#define SPDIF_STC_SYSCLK_DF(x) (((uint32_t)(((uint32_t)(x)) << SPDIF_STC_SYSCLK_DF_SHIFT)) & SPDIF_STC_SYSCLK_DF_MASK)
/*! @} */
/*!
* @}
*/ /* end of group SPDIF_Register_Masks */
/*!
* @}
*/ /* end of group SPDIF_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 */
#endif /* SPDIF_H_ */

View File

@ -0,0 +1,390 @@
/*
** ###################################################################
** Processors: MIMXRT1061CVJ5A
** MIMXRT1061CVJ5B
** MIMXRT1061CVL5A
** MIMXRT1061CVL5B
** MIMXRT1061DVJ6A
** MIMXRT1061DVJ6B
** MIMXRT1061DVL6A
** MIMXRT1061DVL6B
** MIMXRT1061XVN5B
** MIMXRT1062CVJ5A
** MIMXRT1062CVJ5B
** MIMXRT1062CVL5A
** MIMXRT1062CVL5B
** MIMXRT1062DVJ6A
** MIMXRT1062DVJ6B
** MIMXRT1062DVL6A
** MIMXRT1062DVL6B
** MIMXRT1062DVN6B
** MIMXRT1062XVN5B
** MIMXRT106ADVL6A
** MIMXRT106CDVL6A
** MIMXRT106FDVL6A
** MIMXRT106LDVL6A
** MIMXRT106SDVL6A
**
** Version: rev. 1.4, 2022-03-25
** Build: b240705
**
** Abstract:
** CMSIS Peripheral Access Layer for SRC
**
** Copyright 1997-2016 Freescale Semiconductor, Inc.
** Copyright 2016-2024 NXP
** SPDX-License-Identifier: BSD-3-Clause
**
** http: www.nxp.com
** mail: support@nxp.com
**
** Revisions:
** - rev. 0.1 (2017-01-10)
** Initial version.
** - rev. 1.0 (2018-11-16)
** Update header files to align with IMXRT1060RM Rev.0.
** - rev. 1.1 (2018-11-27)
** Update header files to align with IMXRT1060RM Rev.1.
** - rev. 1.2 (2019-04-29)
** Add SET/CLR/TOG register group to register CTRL, STAT, CHANNELCTRL, CH0STAT, CH0OPTS, CH1STAT, CH1OPTS, CH2STAT, CH2OPTS, CH3STAT, CH3OPTS of DCP module.
** - rev. 1.3 (2021-08-10)
** Update header files to align with IMXRT1060RM Rev.3.
** - rev. 1.4 (2022-03-25)
** Add RT1060X device
**
** ###################################################################
*/
/*!
* @file SRC.h
* @version 1.4
* @date 2022-03-25
* @brief CMSIS Peripheral Access Layer for SRC
*
* CMSIS Peripheral Access Layer for SRC
*/
#if !defined(SRC_H_)
#define SRC_H_ /**< Symbol preventing repeated inclusion */
#if (defined(CPU_MIMXRT1061CVJ5A) || defined(CPU_MIMXRT1061CVJ5B) || defined(CPU_MIMXRT1061CVL5A) || defined(CPU_MIMXRT1061CVL5B) || defined(CPU_MIMXRT1061DVJ6A) || defined(CPU_MIMXRT1061DVJ6B) || defined(CPU_MIMXRT1061DVL6A) || defined(CPU_MIMXRT1061DVL6B) || defined(CPU_MIMXRT1061XVN5B))
#include "MIMXRT1061_COMMON.h"
#elif (defined(CPU_MIMXRT1062CVJ5A) || defined(CPU_MIMXRT1062CVJ5B) || defined(CPU_MIMXRT1062CVL5A) || defined(CPU_MIMXRT1062CVL5B) || defined(CPU_MIMXRT1062DVJ6A) || defined(CPU_MIMXRT1062DVJ6B) || defined(CPU_MIMXRT1062DVL6A) || defined(CPU_MIMXRT1062DVL6B) || defined(CPU_MIMXRT1062DVN6B) || defined(CPU_MIMXRT1062XVN5B))
#include "MIMXRT1062_COMMON.h"
#elif (defined(CPU_MIMXRT106ADVL6A))
#include "MIMXRT106A_COMMON.h"
#elif (defined(CPU_MIMXRT106CDVL6A))
#include "MIMXRT106C_COMMON.h"
#elif (defined(CPU_MIMXRT106FDVL6A))
#include "MIMXRT106F_COMMON.h"
#elif (defined(CPU_MIMXRT106LDVL6A))
#include "MIMXRT106L_COMMON.h"
#elif (defined(CPU_MIMXRT106SDVL6A))
#include "MIMXRT106S_COMMON.h"
#else
#error "No valid CPU defined!"
#endif
/* ----------------------------------------------------------------------------
-- 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
/* ----------------------------------------------------------------------------
-- SRC Peripheral Access Layer
---------------------------------------------------------------------------- */
/*!
* @addtogroup SRC_Peripheral_Access_Layer SRC Peripheral Access Layer
* @{
*/
/** SRC - Size of Registers Arrays */
#define SRC_GPR_COUNT 10u
/** SRC - Register Layout Typedef */
typedef struct {
__IO uint32_t SCR; /**< SRC Control Register, offset: 0x0 */
__I uint32_t SBMR1; /**< SRC Boot Mode Register 1, offset: 0x4 */
__IO uint32_t SRSR; /**< SRC Reset Status Register, offset: 0x8 */
uint8_t RESERVED_0[16];
__I uint32_t SBMR2; /**< SRC Boot Mode Register 2, offset: 0x1C */
__IO uint32_t GPR[SRC_GPR_COUNT]; /**< SRC General Purpose Register 1..SRC General Purpose Register 10, array offset: 0x20, array step: 0x4 */
} SRC_Type;
/* ----------------------------------------------------------------------------
-- SRC Register Masks
---------------------------------------------------------------------------- */
/*!
* @addtogroup SRC_Register_Masks SRC Register Masks
* @{
*/
/*! @name SCR - SRC Control Register */
/*! @{ */
#define SRC_SCR_MASK_WDOG_RST_MASK (0x780U)
#define SRC_SCR_MASK_WDOG_RST_SHIFT (7U)
/*! mask_wdog_rst
* 0b0101..wdog_rst_b is masked
* 0b1010..wdog_rst_b is not masked (default)
*/
#define SRC_SCR_MASK_WDOG_RST(x) (((uint32_t)(((uint32_t)(x)) << SRC_SCR_MASK_WDOG_RST_SHIFT)) & SRC_SCR_MASK_WDOG_RST_MASK)
#define SRC_SCR_CORE0_RST_MASK (0x2000U)
#define SRC_SCR_CORE0_RST_SHIFT (13U)
/*! core0_rst
* 0b0..do not assert core0 reset
* 0b1..assert core0 reset
*/
#define SRC_SCR_CORE0_RST(x) (((uint32_t)(((uint32_t)(x)) << SRC_SCR_CORE0_RST_SHIFT)) & SRC_SCR_CORE0_RST_MASK)
#define SRC_SCR_CORE0_DBG_RST_MASK (0x20000U)
#define SRC_SCR_CORE0_DBG_RST_SHIFT (17U)
/*! core0_dbg_rst
* 0b0..do not assert core0 debug reset
* 0b1..assert core0 debug reset
*/
#define SRC_SCR_CORE0_DBG_RST(x) (((uint32_t)(((uint32_t)(x)) << SRC_SCR_CORE0_DBG_RST_SHIFT)) & SRC_SCR_CORE0_DBG_RST_MASK)
#define SRC_SCR_DBG_RST_MSK_PG_MASK (0x2000000U)
#define SRC_SCR_DBG_RST_MSK_PG_SHIFT (25U)
/*! dbg_rst_msk_pg
* 0b0..do not mask core debug resets (debug resets will be asserted after power gating event)
* 0b1..mask core debug resets (debug resets won't be asserted after power gating event)
*/
#define SRC_SCR_DBG_RST_MSK_PG(x) (((uint32_t)(((uint32_t)(x)) << SRC_SCR_DBG_RST_MSK_PG_SHIFT)) & SRC_SCR_DBG_RST_MSK_PG_MASK)
#define SRC_SCR_MASK_WDOG3_RST_MASK (0xF0000000U)
#define SRC_SCR_MASK_WDOG3_RST_SHIFT (28U)
/*! mask_wdog3_rst
* 0b0101..wdog3_rst_b is masked
* 0b1010..wdog3_rst_b is not masked
*/
#define SRC_SCR_MASK_WDOG3_RST(x) (((uint32_t)(((uint32_t)(x)) << SRC_SCR_MASK_WDOG3_RST_SHIFT)) & SRC_SCR_MASK_WDOG3_RST_MASK)
/*! @} */
/*! @name SBMR1 - SRC Boot Mode Register 1 */
/*! @{ */
#define SRC_SBMR1_BOOT_CFG1_MASK (0xFFU)
#define SRC_SBMR1_BOOT_CFG1_SHIFT (0U)
#define SRC_SBMR1_BOOT_CFG1(x) (((uint32_t)(((uint32_t)(x)) << SRC_SBMR1_BOOT_CFG1_SHIFT)) & SRC_SBMR1_BOOT_CFG1_MASK)
#define SRC_SBMR1_BOOT_CFG2_MASK (0xFF00U)
#define SRC_SBMR1_BOOT_CFG2_SHIFT (8U)
#define SRC_SBMR1_BOOT_CFG2(x) (((uint32_t)(((uint32_t)(x)) << SRC_SBMR1_BOOT_CFG2_SHIFT)) & SRC_SBMR1_BOOT_CFG2_MASK)
#define SRC_SBMR1_BOOT_CFG3_MASK (0xFF0000U)
#define SRC_SBMR1_BOOT_CFG3_SHIFT (16U)
#define SRC_SBMR1_BOOT_CFG3(x) (((uint32_t)(((uint32_t)(x)) << SRC_SBMR1_BOOT_CFG3_SHIFT)) & SRC_SBMR1_BOOT_CFG3_MASK)
#define SRC_SBMR1_BOOT_CFG4_MASK (0xFF000000U)
#define SRC_SBMR1_BOOT_CFG4_SHIFT (24U)
#define SRC_SBMR1_BOOT_CFG4(x) (((uint32_t)(((uint32_t)(x)) << SRC_SBMR1_BOOT_CFG4_SHIFT)) & SRC_SBMR1_BOOT_CFG4_MASK)
/*! @} */
/*! @name SRSR - SRC Reset Status Register */
/*! @{ */
#define SRC_SRSR_IPP_RESET_B_MASK (0x1U)
#define SRC_SRSR_IPP_RESET_B_SHIFT (0U)
/*! ipp_reset_b
* 0b0..Reset is not a result of ipp_reset_b pin.
* 0b1..Reset is a result of ipp_reset_b pin.
*/
#define SRC_SRSR_IPP_RESET_B(x) (((uint32_t)(((uint32_t)(x)) << SRC_SRSR_IPP_RESET_B_SHIFT)) & SRC_SRSR_IPP_RESET_B_MASK)
#define SRC_SRSR_LOCKUP_SYSRESETREQ_MASK (0x2U)
#define SRC_SRSR_LOCKUP_SYSRESETREQ_SHIFT (1U)
/*! lockup_sysresetreq
* 0b0..Reset is not a result of the mentioned case.
* 0b1..Reset is a result of the mentioned case.
*/
#define SRC_SRSR_LOCKUP_SYSRESETREQ(x) (((uint32_t)(((uint32_t)(x)) << SRC_SRSR_LOCKUP_SYSRESETREQ_SHIFT)) & SRC_SRSR_LOCKUP_SYSRESETREQ_MASK)
#define SRC_SRSR_CSU_RESET_B_MASK (0x4U)
#define SRC_SRSR_CSU_RESET_B_SHIFT (2U)
/*! csu_reset_b
* 0b0..Reset is not a result of the csu_reset_b event.
* 0b1..Reset is a result of the csu_reset_b event.
*/
#define SRC_SRSR_CSU_RESET_B(x) (((uint32_t)(((uint32_t)(x)) << SRC_SRSR_CSU_RESET_B_SHIFT)) & SRC_SRSR_CSU_RESET_B_MASK)
#define SRC_SRSR_IPP_USER_RESET_B_MASK (0x8U)
#define SRC_SRSR_IPP_USER_RESET_B_SHIFT (3U)
/*! ipp_user_reset_b
* 0b0..Reset is not a result of the ipp_user_reset_b qualified as COLD reset event.
* 0b1..Reset is a result of the ipp_user_reset_b qualified as COLD reset event.
*/
#define SRC_SRSR_IPP_USER_RESET_B(x) (((uint32_t)(((uint32_t)(x)) << SRC_SRSR_IPP_USER_RESET_B_SHIFT)) & SRC_SRSR_IPP_USER_RESET_B_MASK)
#define SRC_SRSR_WDOG_RST_B_MASK (0x10U)
#define SRC_SRSR_WDOG_RST_B_SHIFT (4U)
/*! wdog_rst_b
* 0b0..Reset is not a result of the watchdog time-out event.
* 0b1..Reset is a result of the watchdog time-out event.
*/
#define SRC_SRSR_WDOG_RST_B(x) (((uint32_t)(((uint32_t)(x)) << SRC_SRSR_WDOG_RST_B_SHIFT)) & SRC_SRSR_WDOG_RST_B_MASK)
#define SRC_SRSR_JTAG_RST_B_MASK (0x20U)
#define SRC_SRSR_JTAG_RST_B_SHIFT (5U)
/*! jtag_rst_b
* 0b0..Reset is not a result of HIGH-Z reset from JTAG.
* 0b1..Reset is a result of HIGH-Z reset from JTAG.
*/
#define SRC_SRSR_JTAG_RST_B(x) (((uint32_t)(((uint32_t)(x)) << SRC_SRSR_JTAG_RST_B_SHIFT)) & SRC_SRSR_JTAG_RST_B_MASK)
#define SRC_SRSR_JTAG_SW_RST_MASK (0x40U)
#define SRC_SRSR_JTAG_SW_RST_SHIFT (6U)
/*! jtag_sw_rst
* 0b0..Reset is not a result of the mentioned case.
* 0b1..Reset is a result of the mentioned case.
*/
#define SRC_SRSR_JTAG_SW_RST(x) (((uint32_t)(((uint32_t)(x)) << SRC_SRSR_JTAG_SW_RST_SHIFT)) & SRC_SRSR_JTAG_SW_RST_MASK)
#define SRC_SRSR_WDOG3_RST_B_MASK (0x80U)
#define SRC_SRSR_WDOG3_RST_B_SHIFT (7U)
/*! wdog3_rst_b
* 0b0..Reset is not a result of the watchdog3 time-out event.
* 0b1..Reset is a result of the watchdog3 time-out event.
*/
#define SRC_SRSR_WDOG3_RST_B(x) (((uint32_t)(((uint32_t)(x)) << SRC_SRSR_WDOG3_RST_B_SHIFT)) & SRC_SRSR_WDOG3_RST_B_MASK)
#define SRC_SRSR_TEMPSENSE_RST_B_MASK (0x100U)
#define SRC_SRSR_TEMPSENSE_RST_B_SHIFT (8U)
/*! tempsense_rst_b
* 0b0..Reset is not a result of software reset from Temperature Sensor.
* 0b1..Reset is a result of software reset from Temperature Sensor.
*/
#define SRC_SRSR_TEMPSENSE_RST_B(x) (((uint32_t)(((uint32_t)(x)) << SRC_SRSR_TEMPSENSE_RST_B_SHIFT)) & SRC_SRSR_TEMPSENSE_RST_B_MASK)
/*! @} */
/*! @name SBMR2 - SRC Boot Mode Register 2 */
/*! @{ */
#define SRC_SBMR2_SEC_CONFIG_MASK (0x3U)
#define SRC_SBMR2_SEC_CONFIG_SHIFT (0U)
#define SRC_SBMR2_SEC_CONFIG(x) (((uint32_t)(((uint32_t)(x)) << SRC_SBMR2_SEC_CONFIG_SHIFT)) & SRC_SBMR2_SEC_CONFIG_MASK)
#define SRC_SBMR2_BT_FUSE_SEL_MASK (0x10U)
#define SRC_SBMR2_BT_FUSE_SEL_SHIFT (4U)
#define SRC_SBMR2_BT_FUSE_SEL(x) (((uint32_t)(((uint32_t)(x)) << SRC_SBMR2_BT_FUSE_SEL_SHIFT)) & SRC_SBMR2_BT_FUSE_SEL_MASK)
#define SRC_SBMR2_BMOD_MASK (0x3000000U)
#define SRC_SBMR2_BMOD_SHIFT (24U)
#define SRC_SBMR2_BMOD(x) (((uint32_t)(((uint32_t)(x)) << SRC_SBMR2_BMOD_SHIFT)) & SRC_SBMR2_BMOD_MASK)
/*! @} */
/*! @name GPR - SRC General Purpose Register 1..SRC General Purpose Register 10 */
/*! @{ */
#define SRC_GPR_PERSISTENT_ARG0_MASK (0xFFFFFFFFU)
#define SRC_GPR_PERSISTENT_ARG0_SHIFT (0U)
#define SRC_GPR_PERSISTENT_ARG0(x) (((uint32_t)(((uint32_t)(x)) << SRC_GPR_PERSISTENT_ARG0_SHIFT)) & SRC_GPR_PERSISTENT_ARG0_MASK)
#define SRC_GPR_PERSISTENT_ENTRY0_MASK (0xFFFFFFFFU)
#define SRC_GPR_PERSISTENT_ENTRY0_SHIFT (0U)
#define SRC_GPR_PERSISTENT_ENTRY0(x) (((uint32_t)(((uint32_t)(x)) << SRC_GPR_PERSISTENT_ENTRY0_SHIFT)) & SRC_GPR_PERSISTENT_ENTRY0_MASK)
#define SRC_GPR_PERSIST_REDUNDANT_BOOT_MASK (0xC000000U)
#define SRC_GPR_PERSIST_REDUNDANT_BOOT_SHIFT (26U)
#define SRC_GPR_PERSIST_REDUNDANT_BOOT(x) (((uint32_t)(((uint32_t)(x)) << SRC_GPR_PERSIST_REDUNDANT_BOOT_SHIFT)) & SRC_GPR_PERSIST_REDUNDANT_BOOT_MASK)
#define SRC_GPR_PERSIST_SECONDARY_BOOT_MASK (0x40000000U)
#define SRC_GPR_PERSIST_SECONDARY_BOOT_SHIFT (30U)
#define SRC_GPR_PERSIST_SECONDARY_BOOT(x) (((uint32_t)(((uint32_t)(x)) << SRC_GPR_PERSIST_SECONDARY_BOOT_SHIFT)) & SRC_GPR_PERSIST_SECONDARY_BOOT_MASK)
/*! @} */
/*!
* @}
*/ /* end of group SRC_Register_Masks */
/* Backward compatibility */
#define SRC_SCR_MWDR_MASK SRC_SCR_MASK_WDOG_RST_MASK
#define SRC_SCR_MWDR_SHIFT SRC_SCR_MASK_WDOG_RST_SHIFT
#define SRC_SCR_MWDR(x) SRC_SCR_MASK_WDOG_RST(x)
#define SRC_SRSR_WDOG_MASK SRC_SRSR_WDOG_RST_B_MASK
#define SRC_SRSR_WDOG_SHIFT SRC_SRSR_WDOG_RST_B_SHIFT
#define SRC_SRSR_WDOG(x) SRC_SRSR_WDOG_RST_B(x)
#define SRC_SRSR_JTAG_MASK SRC_SRSR_JTAG_RST_B_MASK
#define SRC_SRSR_JTAG_SHIFT SRC_SRSR_JTAG_RST_B_SHIFT
#define SRC_SRSR_JTAG(x) SRC_SRSR_JTAG_RST_B(x)
#define SRC_SRSR_SJC_MASK SRC_SRSR_JTAG_SW_RST_MASK
#define SRC_SRSR_SJC_SHIFT SRC_SRSR_JTAG_SW_RST_SHIFT
#define SRC_SRSR_SJC(x) SRC_SRSR_JTAG_SW_RST(x)
#define SRC_SRSR_TSR_MASK SRC_SRSR_TEMPSENSE_RST_B_MASK
#define SRC_SRSR_TSR_SHIFT SRC_SRSR_TEMPSENSE_RST_B_SHIFT
#define SRC_SRSR_TSR(x) SRC_SRSR_TEMPSENSE_RST_B(x)
/* Extra definition */
#define SRC_SRSR_W1C_BITS_MASK ( SRC_SRSR_WDOG3_RST_B_MASK \
| SRC_SRSR_JTAG_SW_RST_MASK \
| SRC_SRSR_JTAG_RST_B_MASK \
| SRC_SRSR_WDOG_RST_B_MASK \
| SRC_SRSR_IPP_USER_RESET_B_MASK \
| SRC_SRSR_CSU_RESET_B_MASK \
| SRC_SRSR_LOCKUP_SYSRESETREQ_MASK \
| SRC_SRSR_IPP_RESET_B_MASK)
/*!
* @}
*/ /* end of group SRC_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 */
#endif /* SRC_H_ */

View File

@ -0,0 +1,441 @@
/*
** ###################################################################
** Processors: MIMXRT1061CVJ5A
** MIMXRT1061CVJ5B
** MIMXRT1061CVL5A
** MIMXRT1061CVL5B
** MIMXRT1061DVJ6A
** MIMXRT1061DVJ6B
** MIMXRT1061DVL6A
** MIMXRT1061DVL6B
** MIMXRT1061XVN5B
** MIMXRT1062CVJ5A
** MIMXRT1062CVJ5B
** MIMXRT1062CVL5A
** MIMXRT1062CVL5B
** MIMXRT1062DVJ6A
** MIMXRT1062DVJ6B
** MIMXRT1062DVL6A
** MIMXRT1062DVL6B
** MIMXRT1062DVN6B
** MIMXRT1062XVN5B
** MIMXRT106ADVL6A
** MIMXRT106CDVL6A
** MIMXRT106FDVL6A
** MIMXRT106LDVL6A
** MIMXRT106SDVL6A
**
** Version: rev. 1.4, 2022-03-25
** Build: b240705
**
** Abstract:
** CMSIS Peripheral Access Layer for TEMPMON
**
** Copyright 1997-2016 Freescale Semiconductor, Inc.
** Copyright 2016-2024 NXP
** SPDX-License-Identifier: BSD-3-Clause
**
** http: www.nxp.com
** mail: support@nxp.com
**
** Revisions:
** - rev. 0.1 (2017-01-10)
** Initial version.
** - rev. 1.0 (2018-11-16)
** Update header files to align with IMXRT1060RM Rev.0.
** - rev. 1.1 (2018-11-27)
** Update header files to align with IMXRT1060RM Rev.1.
** - rev. 1.2 (2019-04-29)
** Add SET/CLR/TOG register group to register CTRL, STAT, CHANNELCTRL, CH0STAT, CH0OPTS, CH1STAT, CH1OPTS, CH2STAT, CH2OPTS, CH3STAT, CH3OPTS of DCP module.
** - rev. 1.3 (2021-08-10)
** Update header files to align with IMXRT1060RM Rev.3.
** - rev. 1.4 (2022-03-25)
** Add RT1060X device
**
** ###################################################################
*/
/*!
* @file TEMPMON.h
* @version 1.4
* @date 2022-03-25
* @brief CMSIS Peripheral Access Layer for TEMPMON
*
* CMSIS Peripheral Access Layer for TEMPMON
*/
#if !defined(TEMPMON_H_)
#define TEMPMON_H_ /**< Symbol preventing repeated inclusion */
#if (defined(CPU_MIMXRT1061CVJ5A) || defined(CPU_MIMXRT1061CVJ5B) || defined(CPU_MIMXRT1061CVL5A) || defined(CPU_MIMXRT1061CVL5B) || defined(CPU_MIMXRT1061DVJ6A) || defined(CPU_MIMXRT1061DVJ6B) || defined(CPU_MIMXRT1061DVL6A) || defined(CPU_MIMXRT1061DVL6B) || defined(CPU_MIMXRT1061XVN5B))
#include "MIMXRT1061_COMMON.h"
#elif (defined(CPU_MIMXRT1062CVJ5A) || defined(CPU_MIMXRT1062CVJ5B) || defined(CPU_MIMXRT1062CVL5A) || defined(CPU_MIMXRT1062CVL5B) || defined(CPU_MIMXRT1062DVJ6A) || defined(CPU_MIMXRT1062DVJ6B) || defined(CPU_MIMXRT1062DVL6A) || defined(CPU_MIMXRT1062DVL6B) || defined(CPU_MIMXRT1062DVN6B) || defined(CPU_MIMXRT1062XVN5B))
#include "MIMXRT1062_COMMON.h"
#elif (defined(CPU_MIMXRT106ADVL6A))
#include "MIMXRT106A_COMMON.h"
#elif (defined(CPU_MIMXRT106CDVL6A))
#include "MIMXRT106C_COMMON.h"
#elif (defined(CPU_MIMXRT106FDVL6A))
#include "MIMXRT106F_COMMON.h"
#elif (defined(CPU_MIMXRT106LDVL6A))
#include "MIMXRT106L_COMMON.h"
#elif (defined(CPU_MIMXRT106SDVL6A))
#include "MIMXRT106S_COMMON.h"
#else
#error "No valid CPU defined!"
#endif
/* ----------------------------------------------------------------------------
-- 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
/* ----------------------------------------------------------------------------
-- TEMPMON Peripheral Access Layer
---------------------------------------------------------------------------- */
/*!
* @addtogroup TEMPMON_Peripheral_Access_Layer TEMPMON Peripheral Access Layer
* @{
*/
/** TEMPMON - Register Layout Typedef */
typedef struct {
uint8_t RESERVED_0[384];
__IO uint32_t TEMPSENSE0; /**< Tempsensor Control Register 0, offset: 0x180 */
__IO uint32_t TEMPSENSE0_SET; /**< Tempsensor Control Register 0, offset: 0x184 */
__IO uint32_t TEMPSENSE0_CLR; /**< Tempsensor Control Register 0, offset: 0x188 */
__IO uint32_t TEMPSENSE0_TOG; /**< Tempsensor Control Register 0, offset: 0x18C */
__IO uint32_t TEMPSENSE1; /**< Tempsensor Control Register 1, offset: 0x190 */
__IO uint32_t TEMPSENSE1_SET; /**< Tempsensor Control Register 1, offset: 0x194 */
__IO uint32_t TEMPSENSE1_CLR; /**< Tempsensor Control Register 1, offset: 0x198 */
__IO uint32_t TEMPSENSE1_TOG; /**< Tempsensor Control Register 1, offset: 0x19C */
uint8_t RESERVED_1[240];
__IO uint32_t TEMPSENSE2; /**< Tempsensor Control Register 2, offset: 0x290 */
__IO uint32_t TEMPSENSE2_SET; /**< Tempsensor Control Register 2, offset: 0x294 */
__IO uint32_t TEMPSENSE2_CLR; /**< Tempsensor Control Register 2, offset: 0x298 */
__IO uint32_t TEMPSENSE2_TOG; /**< Tempsensor Control Register 2, offset: 0x29C */
} TEMPMON_Type;
/* ----------------------------------------------------------------------------
-- TEMPMON Register Masks
---------------------------------------------------------------------------- */
/*!
* @addtogroup TEMPMON_Register_Masks TEMPMON Register Masks
* @{
*/
/*! @name TEMPSENSE0 - Tempsensor Control Register 0 */
/*! @{ */
#define TEMPMON_TEMPSENSE0_POWER_DOWN_MASK (0x1U)
#define TEMPMON_TEMPSENSE0_POWER_DOWN_SHIFT (0U)
/*! POWER_DOWN
* 0b0..Enable power to the temperature sensor.
* 0b1..Power down the temperature sensor.
*/
#define TEMPMON_TEMPSENSE0_POWER_DOWN(x) (((uint32_t)(((uint32_t)(x)) << TEMPMON_TEMPSENSE0_POWER_DOWN_SHIFT)) & TEMPMON_TEMPSENSE0_POWER_DOWN_MASK)
#define TEMPMON_TEMPSENSE0_MEASURE_TEMP_MASK (0x2U)
#define TEMPMON_TEMPSENSE0_MEASURE_TEMP_SHIFT (1U)
/*! MEASURE_TEMP
* 0b0..Do not start the measurement process.
* 0b1..Start the measurement process.
*/
#define TEMPMON_TEMPSENSE0_MEASURE_TEMP(x) (((uint32_t)(((uint32_t)(x)) << TEMPMON_TEMPSENSE0_MEASURE_TEMP_SHIFT)) & TEMPMON_TEMPSENSE0_MEASURE_TEMP_MASK)
#define TEMPMON_TEMPSENSE0_FINISHED_MASK (0x4U)
#define TEMPMON_TEMPSENSE0_FINISHED_SHIFT (2U)
/*! FINISHED
* 0b0..Last measurement is not ready yet.
* 0b1..Last measurement is valid.
*/
#define TEMPMON_TEMPSENSE0_FINISHED(x) (((uint32_t)(((uint32_t)(x)) << TEMPMON_TEMPSENSE0_FINISHED_SHIFT)) & TEMPMON_TEMPSENSE0_FINISHED_MASK)
#define TEMPMON_TEMPSENSE0_TEMP_CNT_MASK (0xFFF00U)
#define TEMPMON_TEMPSENSE0_TEMP_CNT_SHIFT (8U)
#define TEMPMON_TEMPSENSE0_TEMP_CNT(x) (((uint32_t)(((uint32_t)(x)) << TEMPMON_TEMPSENSE0_TEMP_CNT_SHIFT)) & TEMPMON_TEMPSENSE0_TEMP_CNT_MASK)
#define TEMPMON_TEMPSENSE0_ALARM_VALUE_MASK (0xFFF00000U)
#define TEMPMON_TEMPSENSE0_ALARM_VALUE_SHIFT (20U)
#define TEMPMON_TEMPSENSE0_ALARM_VALUE(x) (((uint32_t)(((uint32_t)(x)) << TEMPMON_TEMPSENSE0_ALARM_VALUE_SHIFT)) & TEMPMON_TEMPSENSE0_ALARM_VALUE_MASK)
/*! @} */
/*! @name TEMPSENSE0_SET - Tempsensor Control Register 0 */
/*! @{ */
#define TEMPMON_TEMPSENSE0_SET_POWER_DOWN_MASK (0x1U)
#define TEMPMON_TEMPSENSE0_SET_POWER_DOWN_SHIFT (0U)
/*! POWER_DOWN
* 0b0..Enable power to the temperature sensor.
* 0b1..Power down the temperature sensor.
*/
#define TEMPMON_TEMPSENSE0_SET_POWER_DOWN(x) (((uint32_t)(((uint32_t)(x)) << TEMPMON_TEMPSENSE0_SET_POWER_DOWN_SHIFT)) & TEMPMON_TEMPSENSE0_SET_POWER_DOWN_MASK)
#define TEMPMON_TEMPSENSE0_SET_MEASURE_TEMP_MASK (0x2U)
#define TEMPMON_TEMPSENSE0_SET_MEASURE_TEMP_SHIFT (1U)
/*! MEASURE_TEMP
* 0b0..Do not start the measurement process.
* 0b1..Start the measurement process.
*/
#define TEMPMON_TEMPSENSE0_SET_MEASURE_TEMP(x) (((uint32_t)(((uint32_t)(x)) << TEMPMON_TEMPSENSE0_SET_MEASURE_TEMP_SHIFT)) & TEMPMON_TEMPSENSE0_SET_MEASURE_TEMP_MASK)
#define TEMPMON_TEMPSENSE0_SET_FINISHED_MASK (0x4U)
#define TEMPMON_TEMPSENSE0_SET_FINISHED_SHIFT (2U)
/*! FINISHED
* 0b0..Last measurement is not ready yet.
* 0b1..Last measurement is valid.
*/
#define TEMPMON_TEMPSENSE0_SET_FINISHED(x) (((uint32_t)(((uint32_t)(x)) << TEMPMON_TEMPSENSE0_SET_FINISHED_SHIFT)) & TEMPMON_TEMPSENSE0_SET_FINISHED_MASK)
#define TEMPMON_TEMPSENSE0_SET_TEMP_CNT_MASK (0xFFF00U)
#define TEMPMON_TEMPSENSE0_SET_TEMP_CNT_SHIFT (8U)
#define TEMPMON_TEMPSENSE0_SET_TEMP_CNT(x) (((uint32_t)(((uint32_t)(x)) << TEMPMON_TEMPSENSE0_SET_TEMP_CNT_SHIFT)) & TEMPMON_TEMPSENSE0_SET_TEMP_CNT_MASK)
#define TEMPMON_TEMPSENSE0_SET_ALARM_VALUE_MASK (0xFFF00000U)
#define TEMPMON_TEMPSENSE0_SET_ALARM_VALUE_SHIFT (20U)
#define TEMPMON_TEMPSENSE0_SET_ALARM_VALUE(x) (((uint32_t)(((uint32_t)(x)) << TEMPMON_TEMPSENSE0_SET_ALARM_VALUE_SHIFT)) & TEMPMON_TEMPSENSE0_SET_ALARM_VALUE_MASK)
/*! @} */
/*! @name TEMPSENSE0_CLR - Tempsensor Control Register 0 */
/*! @{ */
#define TEMPMON_TEMPSENSE0_CLR_POWER_DOWN_MASK (0x1U)
#define TEMPMON_TEMPSENSE0_CLR_POWER_DOWN_SHIFT (0U)
/*! POWER_DOWN
* 0b0..Enable power to the temperature sensor.
* 0b1..Power down the temperature sensor.
*/
#define TEMPMON_TEMPSENSE0_CLR_POWER_DOWN(x) (((uint32_t)(((uint32_t)(x)) << TEMPMON_TEMPSENSE0_CLR_POWER_DOWN_SHIFT)) & TEMPMON_TEMPSENSE0_CLR_POWER_DOWN_MASK)
#define TEMPMON_TEMPSENSE0_CLR_MEASURE_TEMP_MASK (0x2U)
#define TEMPMON_TEMPSENSE0_CLR_MEASURE_TEMP_SHIFT (1U)
/*! MEASURE_TEMP
* 0b0..Do not start the measurement process.
* 0b1..Start the measurement process.
*/
#define TEMPMON_TEMPSENSE0_CLR_MEASURE_TEMP(x) (((uint32_t)(((uint32_t)(x)) << TEMPMON_TEMPSENSE0_CLR_MEASURE_TEMP_SHIFT)) & TEMPMON_TEMPSENSE0_CLR_MEASURE_TEMP_MASK)
#define TEMPMON_TEMPSENSE0_CLR_FINISHED_MASK (0x4U)
#define TEMPMON_TEMPSENSE0_CLR_FINISHED_SHIFT (2U)
/*! FINISHED
* 0b0..Last measurement is not ready yet.
* 0b1..Last measurement is valid.
*/
#define TEMPMON_TEMPSENSE0_CLR_FINISHED(x) (((uint32_t)(((uint32_t)(x)) << TEMPMON_TEMPSENSE0_CLR_FINISHED_SHIFT)) & TEMPMON_TEMPSENSE0_CLR_FINISHED_MASK)
#define TEMPMON_TEMPSENSE0_CLR_TEMP_CNT_MASK (0xFFF00U)
#define TEMPMON_TEMPSENSE0_CLR_TEMP_CNT_SHIFT (8U)
#define TEMPMON_TEMPSENSE0_CLR_TEMP_CNT(x) (((uint32_t)(((uint32_t)(x)) << TEMPMON_TEMPSENSE0_CLR_TEMP_CNT_SHIFT)) & TEMPMON_TEMPSENSE0_CLR_TEMP_CNT_MASK)
#define TEMPMON_TEMPSENSE0_CLR_ALARM_VALUE_MASK (0xFFF00000U)
#define TEMPMON_TEMPSENSE0_CLR_ALARM_VALUE_SHIFT (20U)
#define TEMPMON_TEMPSENSE0_CLR_ALARM_VALUE(x) (((uint32_t)(((uint32_t)(x)) << TEMPMON_TEMPSENSE0_CLR_ALARM_VALUE_SHIFT)) & TEMPMON_TEMPSENSE0_CLR_ALARM_VALUE_MASK)
/*! @} */
/*! @name TEMPSENSE0_TOG - Tempsensor Control Register 0 */
/*! @{ */
#define TEMPMON_TEMPSENSE0_TOG_POWER_DOWN_MASK (0x1U)
#define TEMPMON_TEMPSENSE0_TOG_POWER_DOWN_SHIFT (0U)
/*! POWER_DOWN
* 0b0..Enable power to the temperature sensor.
* 0b1..Power down the temperature sensor.
*/
#define TEMPMON_TEMPSENSE0_TOG_POWER_DOWN(x) (((uint32_t)(((uint32_t)(x)) << TEMPMON_TEMPSENSE0_TOG_POWER_DOWN_SHIFT)) & TEMPMON_TEMPSENSE0_TOG_POWER_DOWN_MASK)
#define TEMPMON_TEMPSENSE0_TOG_MEASURE_TEMP_MASK (0x2U)
#define TEMPMON_TEMPSENSE0_TOG_MEASURE_TEMP_SHIFT (1U)
/*! MEASURE_TEMP
* 0b0..Do not start the measurement process.
* 0b1..Start the measurement process.
*/
#define TEMPMON_TEMPSENSE0_TOG_MEASURE_TEMP(x) (((uint32_t)(((uint32_t)(x)) << TEMPMON_TEMPSENSE0_TOG_MEASURE_TEMP_SHIFT)) & TEMPMON_TEMPSENSE0_TOG_MEASURE_TEMP_MASK)
#define TEMPMON_TEMPSENSE0_TOG_FINISHED_MASK (0x4U)
#define TEMPMON_TEMPSENSE0_TOG_FINISHED_SHIFT (2U)
/*! FINISHED
* 0b0..Last measurement is not ready yet.
* 0b1..Last measurement is valid.
*/
#define TEMPMON_TEMPSENSE0_TOG_FINISHED(x) (((uint32_t)(((uint32_t)(x)) << TEMPMON_TEMPSENSE0_TOG_FINISHED_SHIFT)) & TEMPMON_TEMPSENSE0_TOG_FINISHED_MASK)
#define TEMPMON_TEMPSENSE0_TOG_TEMP_CNT_MASK (0xFFF00U)
#define TEMPMON_TEMPSENSE0_TOG_TEMP_CNT_SHIFT (8U)
#define TEMPMON_TEMPSENSE0_TOG_TEMP_CNT(x) (((uint32_t)(((uint32_t)(x)) << TEMPMON_TEMPSENSE0_TOG_TEMP_CNT_SHIFT)) & TEMPMON_TEMPSENSE0_TOG_TEMP_CNT_MASK)
#define TEMPMON_TEMPSENSE0_TOG_ALARM_VALUE_MASK (0xFFF00000U)
#define TEMPMON_TEMPSENSE0_TOG_ALARM_VALUE_SHIFT (20U)
#define TEMPMON_TEMPSENSE0_TOG_ALARM_VALUE(x) (((uint32_t)(((uint32_t)(x)) << TEMPMON_TEMPSENSE0_TOG_ALARM_VALUE_SHIFT)) & TEMPMON_TEMPSENSE0_TOG_ALARM_VALUE_MASK)
/*! @} */
/*! @name TEMPSENSE1 - Tempsensor Control Register 1 */
/*! @{ */
#define TEMPMON_TEMPSENSE1_MEASURE_FREQ_MASK (0xFFFFU)
#define TEMPMON_TEMPSENSE1_MEASURE_FREQ_SHIFT (0U)
/*! MEASURE_FREQ
* 0b0000000000000000..Defines a single measurement with no repeat.
* 0b0000000000000001..Updates the temperature value at a RTC clock rate.
* 0b0000000000000010..Updates the temperature value at a RTC/2 clock rate.
* 0b1111111111111111..Determines a two second sample period with a 32.768KHz RTC clock. Exact timings depend on the accuracy of the RTC clock.
*/
#define TEMPMON_TEMPSENSE1_MEASURE_FREQ(x) (((uint32_t)(((uint32_t)(x)) << TEMPMON_TEMPSENSE1_MEASURE_FREQ_SHIFT)) & TEMPMON_TEMPSENSE1_MEASURE_FREQ_MASK)
/*! @} */
/*! @name TEMPSENSE1_SET - Tempsensor Control Register 1 */
/*! @{ */
#define TEMPMON_TEMPSENSE1_SET_MEASURE_FREQ_MASK (0xFFFFU)
#define TEMPMON_TEMPSENSE1_SET_MEASURE_FREQ_SHIFT (0U)
/*! MEASURE_FREQ
* 0b0000000000000000..Defines a single measurement with no repeat.
* 0b0000000000000001..Updates the temperature value at a RTC clock rate.
* 0b0000000000000010..Updates the temperature value at a RTC/2 clock rate.
* 0b1111111111111111..Determines a two second sample period with a 32.768KHz RTC clock. Exact timings depend on the accuracy of the RTC clock.
*/
#define TEMPMON_TEMPSENSE1_SET_MEASURE_FREQ(x) (((uint32_t)(((uint32_t)(x)) << TEMPMON_TEMPSENSE1_SET_MEASURE_FREQ_SHIFT)) & TEMPMON_TEMPSENSE1_SET_MEASURE_FREQ_MASK)
/*! @} */
/*! @name TEMPSENSE1_CLR - Tempsensor Control Register 1 */
/*! @{ */
#define TEMPMON_TEMPSENSE1_CLR_MEASURE_FREQ_MASK (0xFFFFU)
#define TEMPMON_TEMPSENSE1_CLR_MEASURE_FREQ_SHIFT (0U)
/*! MEASURE_FREQ
* 0b0000000000000000..Defines a single measurement with no repeat.
* 0b0000000000000001..Updates the temperature value at a RTC clock rate.
* 0b0000000000000010..Updates the temperature value at a RTC/2 clock rate.
* 0b1111111111111111..Determines a two second sample period with a 32.768KHz RTC clock. Exact timings depend on the accuracy of the RTC clock.
*/
#define TEMPMON_TEMPSENSE1_CLR_MEASURE_FREQ(x) (((uint32_t)(((uint32_t)(x)) << TEMPMON_TEMPSENSE1_CLR_MEASURE_FREQ_SHIFT)) & TEMPMON_TEMPSENSE1_CLR_MEASURE_FREQ_MASK)
/*! @} */
/*! @name TEMPSENSE1_TOG - Tempsensor Control Register 1 */
/*! @{ */
#define TEMPMON_TEMPSENSE1_TOG_MEASURE_FREQ_MASK (0xFFFFU)
#define TEMPMON_TEMPSENSE1_TOG_MEASURE_FREQ_SHIFT (0U)
/*! MEASURE_FREQ
* 0b0000000000000000..Defines a single measurement with no repeat.
* 0b0000000000000001..Updates the temperature value at a RTC clock rate.
* 0b0000000000000010..Updates the temperature value at a RTC/2 clock rate.
* 0b1111111111111111..Determines a two second sample period with a 32.768KHz RTC clock. Exact timings depend on the accuracy of the RTC clock.
*/
#define TEMPMON_TEMPSENSE1_TOG_MEASURE_FREQ(x) (((uint32_t)(((uint32_t)(x)) << TEMPMON_TEMPSENSE1_TOG_MEASURE_FREQ_SHIFT)) & TEMPMON_TEMPSENSE1_TOG_MEASURE_FREQ_MASK)
/*! @} */
/*! @name TEMPSENSE2 - Tempsensor Control Register 2 */
/*! @{ */
#define TEMPMON_TEMPSENSE2_LOW_ALARM_VALUE_MASK (0xFFFU)
#define TEMPMON_TEMPSENSE2_LOW_ALARM_VALUE_SHIFT (0U)
#define TEMPMON_TEMPSENSE2_LOW_ALARM_VALUE(x) (((uint32_t)(((uint32_t)(x)) << TEMPMON_TEMPSENSE2_LOW_ALARM_VALUE_SHIFT)) & TEMPMON_TEMPSENSE2_LOW_ALARM_VALUE_MASK)
#define TEMPMON_TEMPSENSE2_PANIC_ALARM_VALUE_MASK (0xFFF0000U)
#define TEMPMON_TEMPSENSE2_PANIC_ALARM_VALUE_SHIFT (16U)
#define TEMPMON_TEMPSENSE2_PANIC_ALARM_VALUE(x) (((uint32_t)(((uint32_t)(x)) << TEMPMON_TEMPSENSE2_PANIC_ALARM_VALUE_SHIFT)) & TEMPMON_TEMPSENSE2_PANIC_ALARM_VALUE_MASK)
/*! @} */
/*! @name TEMPSENSE2_SET - Tempsensor Control Register 2 */
/*! @{ */
#define TEMPMON_TEMPSENSE2_SET_LOW_ALARM_VALUE_MASK (0xFFFU)
#define TEMPMON_TEMPSENSE2_SET_LOW_ALARM_VALUE_SHIFT (0U)
#define TEMPMON_TEMPSENSE2_SET_LOW_ALARM_VALUE(x) (((uint32_t)(((uint32_t)(x)) << TEMPMON_TEMPSENSE2_SET_LOW_ALARM_VALUE_SHIFT)) & TEMPMON_TEMPSENSE2_SET_LOW_ALARM_VALUE_MASK)
#define TEMPMON_TEMPSENSE2_SET_PANIC_ALARM_VALUE_MASK (0xFFF0000U)
#define TEMPMON_TEMPSENSE2_SET_PANIC_ALARM_VALUE_SHIFT (16U)
#define TEMPMON_TEMPSENSE2_SET_PANIC_ALARM_VALUE(x) (((uint32_t)(((uint32_t)(x)) << TEMPMON_TEMPSENSE2_SET_PANIC_ALARM_VALUE_SHIFT)) & TEMPMON_TEMPSENSE2_SET_PANIC_ALARM_VALUE_MASK)
/*! @} */
/*! @name TEMPSENSE2_CLR - Tempsensor Control Register 2 */
/*! @{ */
#define TEMPMON_TEMPSENSE2_CLR_LOW_ALARM_VALUE_MASK (0xFFFU)
#define TEMPMON_TEMPSENSE2_CLR_LOW_ALARM_VALUE_SHIFT (0U)
#define TEMPMON_TEMPSENSE2_CLR_LOW_ALARM_VALUE(x) (((uint32_t)(((uint32_t)(x)) << TEMPMON_TEMPSENSE2_CLR_LOW_ALARM_VALUE_SHIFT)) & TEMPMON_TEMPSENSE2_CLR_LOW_ALARM_VALUE_MASK)
#define TEMPMON_TEMPSENSE2_CLR_PANIC_ALARM_VALUE_MASK (0xFFF0000U)
#define TEMPMON_TEMPSENSE2_CLR_PANIC_ALARM_VALUE_SHIFT (16U)
#define TEMPMON_TEMPSENSE2_CLR_PANIC_ALARM_VALUE(x) (((uint32_t)(((uint32_t)(x)) << TEMPMON_TEMPSENSE2_CLR_PANIC_ALARM_VALUE_SHIFT)) & TEMPMON_TEMPSENSE2_CLR_PANIC_ALARM_VALUE_MASK)
/*! @} */
/*! @name TEMPSENSE2_TOG - Tempsensor Control Register 2 */
/*! @{ */
#define TEMPMON_TEMPSENSE2_TOG_LOW_ALARM_VALUE_MASK (0xFFFU)
#define TEMPMON_TEMPSENSE2_TOG_LOW_ALARM_VALUE_SHIFT (0U)
#define TEMPMON_TEMPSENSE2_TOG_LOW_ALARM_VALUE(x) (((uint32_t)(((uint32_t)(x)) << TEMPMON_TEMPSENSE2_TOG_LOW_ALARM_VALUE_SHIFT)) & TEMPMON_TEMPSENSE2_TOG_LOW_ALARM_VALUE_MASK)
#define TEMPMON_TEMPSENSE2_TOG_PANIC_ALARM_VALUE_MASK (0xFFF0000U)
#define TEMPMON_TEMPSENSE2_TOG_PANIC_ALARM_VALUE_SHIFT (16U)
#define TEMPMON_TEMPSENSE2_TOG_PANIC_ALARM_VALUE(x) (((uint32_t)(((uint32_t)(x)) << TEMPMON_TEMPSENSE2_TOG_PANIC_ALARM_VALUE_SHIFT)) & TEMPMON_TEMPSENSE2_TOG_PANIC_ALARM_VALUE_MASK)
/*! @} */
/*!
* @}
*/ /* end of group TEMPMON_Register_Masks */
/*!
* @}
*/ /* end of group TEMPMON_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 */
#endif /* TEMPMON_H_ */

View File

@ -0,0 +1,654 @@
/*
** ###################################################################
** Processors: MIMXRT1061CVJ5A
** MIMXRT1061CVJ5B
** MIMXRT1061CVL5A
** MIMXRT1061CVL5B
** MIMXRT1061DVJ6A
** MIMXRT1061DVJ6B
** MIMXRT1061DVL6A
** MIMXRT1061DVL6B
** MIMXRT1061XVN5B
** MIMXRT1062CVJ5A
** MIMXRT1062CVJ5B
** MIMXRT1062CVL5A
** MIMXRT1062CVL5B
** MIMXRT1062DVJ6A
** MIMXRT1062DVJ6B
** MIMXRT1062DVL6A
** MIMXRT1062DVL6B
** MIMXRT1062DVN6B
** MIMXRT1062XVN5B
** MIMXRT106ADVL6A
** MIMXRT106CDVL6A
** MIMXRT106FDVL6A
** MIMXRT106LDVL6A
** MIMXRT106SDVL6A
**
** Version: rev. 1.4, 2022-03-25
** Build: b240705
**
** Abstract:
** CMSIS Peripheral Access Layer for TMR
**
** Copyright 1997-2016 Freescale Semiconductor, Inc.
** Copyright 2016-2024 NXP
** SPDX-License-Identifier: BSD-3-Clause
**
** http: www.nxp.com
** mail: support@nxp.com
**
** Revisions:
** - rev. 0.1 (2017-01-10)
** Initial version.
** - rev. 1.0 (2018-11-16)
** Update header files to align with IMXRT1060RM Rev.0.
** - rev. 1.1 (2018-11-27)
** Update header files to align with IMXRT1060RM Rev.1.
** - rev. 1.2 (2019-04-29)
** Add SET/CLR/TOG register group to register CTRL, STAT, CHANNELCTRL, CH0STAT, CH0OPTS, CH1STAT, CH1OPTS, CH2STAT, CH2OPTS, CH3STAT, CH3OPTS of DCP module.
** - rev. 1.3 (2021-08-10)
** Update header files to align with IMXRT1060RM Rev.3.
** - rev. 1.4 (2022-03-25)
** Add RT1060X device
**
** ###################################################################
*/
/*!
* @file TMR.h
* @version 1.4
* @date 2022-03-25
* @brief CMSIS Peripheral Access Layer for TMR
*
* CMSIS Peripheral Access Layer for TMR
*/
#if !defined(TMR_H_)
#define TMR_H_ /**< Symbol preventing repeated inclusion */
#if (defined(CPU_MIMXRT1061CVJ5A) || defined(CPU_MIMXRT1061CVJ5B) || defined(CPU_MIMXRT1061CVL5A) || defined(CPU_MIMXRT1061CVL5B) || defined(CPU_MIMXRT1061DVJ6A) || defined(CPU_MIMXRT1061DVJ6B) || defined(CPU_MIMXRT1061DVL6A) || defined(CPU_MIMXRT1061DVL6B) || defined(CPU_MIMXRT1061XVN5B))
#include "MIMXRT1061_COMMON.h"
#elif (defined(CPU_MIMXRT1062CVJ5A) || defined(CPU_MIMXRT1062CVJ5B) || defined(CPU_MIMXRT1062CVL5A) || defined(CPU_MIMXRT1062CVL5B) || defined(CPU_MIMXRT1062DVJ6A) || defined(CPU_MIMXRT1062DVJ6B) || defined(CPU_MIMXRT1062DVL6A) || defined(CPU_MIMXRT1062DVL6B) || defined(CPU_MIMXRT1062DVN6B) || defined(CPU_MIMXRT1062XVN5B))
#include "MIMXRT1062_COMMON.h"
#elif (defined(CPU_MIMXRT106ADVL6A))
#include "MIMXRT106A_COMMON.h"
#elif (defined(CPU_MIMXRT106CDVL6A))
#include "MIMXRT106C_COMMON.h"
#elif (defined(CPU_MIMXRT106FDVL6A))
#include "MIMXRT106F_COMMON.h"
#elif (defined(CPU_MIMXRT106LDVL6A))
#include "MIMXRT106L_COMMON.h"
#elif (defined(CPU_MIMXRT106SDVL6A))
#include "MIMXRT106S_COMMON.h"
#else
#error "No valid CPU defined!"
#endif
/* ----------------------------------------------------------------------------
-- 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
/* ----------------------------------------------------------------------------
-- TMR Peripheral Access Layer
---------------------------------------------------------------------------- */
/*!
* @addtogroup TMR_Peripheral_Access_Layer TMR Peripheral Access Layer
* @{
*/
/** TMR - Size of Registers Arrays */
#define TMR_CHANNEL_COUNT 4u
/** TMR - Register Layout Typedef */
typedef struct {
struct { /* offset: 0x0, array step: 0x20 */
__IO uint16_t COMP1; /**< Timer Channel Compare Register 1, array offset: 0x0, array step: 0x20 */
__IO uint16_t COMP2; /**< Timer Channel Compare Register 2, array offset: 0x2, array step: 0x20 */
__IO uint16_t CAPT; /**< Timer Channel Capture Register, array offset: 0x4, array step: 0x20 */
__IO uint16_t LOAD; /**< Timer Channel Load Register, array offset: 0x6, array step: 0x20 */
__IO uint16_t HOLD; /**< Timer Channel Hold Register, array offset: 0x8, array step: 0x20 */
__IO uint16_t CNTR; /**< Timer Channel Counter Register, array offset: 0xA, array step: 0x20 */
__IO uint16_t CTRL; /**< Timer Channel Control Register, array offset: 0xC, array step: 0x20 */
__IO uint16_t SCTRL; /**< Timer Channel Status and Control Register, array offset: 0xE, array step: 0x20 */
__IO uint16_t CMPLD1; /**< Timer Channel Comparator Load Register 1, array offset: 0x10, array step: 0x20 */
__IO uint16_t CMPLD2; /**< Timer Channel Comparator Load Register 2, array offset: 0x12, array step: 0x20 */
__IO uint16_t CSCTRL; /**< Timer Channel Comparator Status and Control Register, array offset: 0x14, array step: 0x20 */
__IO uint16_t FILT; /**< Timer Channel Input Filter Register, array offset: 0x16, array step: 0x20 */
__IO uint16_t DMA; /**< Timer Channel DMA Enable Register, array offset: 0x18, array step: 0x20 */
uint8_t RESERVED_0[4];
__IO uint16_t ENBL; /**< Timer Channel Enable Register, array offset: 0x1E, array step: 0x20, valid indices: [0] */
} CHANNEL[TMR_CHANNEL_COUNT];
} TMR_Type;
/* ----------------------------------------------------------------------------
-- TMR Register Masks
---------------------------------------------------------------------------- */
/*!
* @addtogroup TMR_Register_Masks TMR Register Masks
* @{
*/
/*! @name COMP1 - Timer Channel Compare Register 1 */
/*! @{ */
#define TMR_COMP1_COMPARISON_1_MASK (0xFFFFU)
#define TMR_COMP1_COMPARISON_1_SHIFT (0U)
/*! COMPARISON_1 - Comparison Value 1 */
#define TMR_COMP1_COMPARISON_1(x) (((uint16_t)(((uint16_t)(x)) << TMR_COMP1_COMPARISON_1_SHIFT)) & TMR_COMP1_COMPARISON_1_MASK)
/*! @} */
/* The count of TMR_COMP1 */
#define TMR_COMP1_COUNT (4U)
/*! @name COMP2 - Timer Channel Compare Register 2 */
/*! @{ */
#define TMR_COMP2_COMPARISON_2_MASK (0xFFFFU)
#define TMR_COMP2_COMPARISON_2_SHIFT (0U)
/*! COMPARISON_2 - Comparison Value 2 */
#define TMR_COMP2_COMPARISON_2(x) (((uint16_t)(((uint16_t)(x)) << TMR_COMP2_COMPARISON_2_SHIFT)) & TMR_COMP2_COMPARISON_2_MASK)
/*! @} */
/* The count of TMR_COMP2 */
#define TMR_COMP2_COUNT (4U)
/*! @name CAPT - Timer Channel Capture Register */
/*! @{ */
#define TMR_CAPT_CAPTURE_MASK (0xFFFFU)
#define TMR_CAPT_CAPTURE_SHIFT (0U)
/*! CAPTURE - Capture Value */
#define TMR_CAPT_CAPTURE(x) (((uint16_t)(((uint16_t)(x)) << TMR_CAPT_CAPTURE_SHIFT)) & TMR_CAPT_CAPTURE_MASK)
/*! @} */
/* The count of TMR_CAPT */
#define TMR_CAPT_COUNT (4U)
/*! @name LOAD - Timer Channel Load Register */
/*! @{ */
#define TMR_LOAD_LOAD_MASK (0xFFFFU)
#define TMR_LOAD_LOAD_SHIFT (0U)
/*! LOAD - Timer Load Register */
#define TMR_LOAD_LOAD(x) (((uint16_t)(((uint16_t)(x)) << TMR_LOAD_LOAD_SHIFT)) & TMR_LOAD_LOAD_MASK)
/*! @} */
/* The count of TMR_LOAD */
#define TMR_LOAD_COUNT (4U)
/*! @name HOLD - Timer Channel Hold Register */
/*! @{ */
#define TMR_HOLD_HOLD_MASK (0xFFFFU)
#define TMR_HOLD_HOLD_SHIFT (0U)
/*! HOLD - HOLD */
#define TMR_HOLD_HOLD(x) (((uint16_t)(((uint16_t)(x)) << TMR_HOLD_HOLD_SHIFT)) & TMR_HOLD_HOLD_MASK)
/*! @} */
/* The count of TMR_HOLD */
#define TMR_HOLD_COUNT (4U)
/*! @name CNTR - Timer Channel Counter Register */
/*! @{ */
#define TMR_CNTR_COUNTER_MASK (0xFFFFU)
#define TMR_CNTR_COUNTER_SHIFT (0U)
/*! COUNTER - COUNTER */
#define TMR_CNTR_COUNTER(x) (((uint16_t)(((uint16_t)(x)) << TMR_CNTR_COUNTER_SHIFT)) & TMR_CNTR_COUNTER_MASK)
/*! @} */
/* The count of TMR_CNTR */
#define TMR_CNTR_COUNT (4U)
/*! @name CTRL - Timer Channel Control Register */
/*! @{ */
#define TMR_CTRL_OUTMODE_MASK (0x7U)
#define TMR_CTRL_OUTMODE_SHIFT (0U)
/*! OUTMODE - Output Mode
* 0b000..Asserted while counter is active
* 0b001..Clear OFLAG output on successful compare
* 0b010..Set OFLAG output on successful compare
* 0b011..Toggle OFLAG output on successful compare
* 0b100..Toggle OFLAG output using alternating compare registers
* 0b101..Set on compare, cleared on secondary source input edge
* 0b110..Set on compare, cleared on counter rollover
* 0b111..Enable gated clock output while counter is active
*/
#define TMR_CTRL_OUTMODE(x) (((uint16_t)(((uint16_t)(x)) << TMR_CTRL_OUTMODE_SHIFT)) & TMR_CTRL_OUTMODE_MASK)
#define TMR_CTRL_COINIT_MASK (0x8U)
#define TMR_CTRL_COINIT_SHIFT (3U)
/*! COINIT - Co-Channel Initialization
* 0b0..Co-channel counter/timers cannot force a re-initialization of this counter/timer
* 0b1..Co-channel counter/timers may force a re-initialization of this counter/timer
*/
#define TMR_CTRL_COINIT(x) (((uint16_t)(((uint16_t)(x)) << TMR_CTRL_COINIT_SHIFT)) & TMR_CTRL_COINIT_MASK)
#define TMR_CTRL_DIR_MASK (0x10U)
#define TMR_CTRL_DIR_SHIFT (4U)
/*! DIR - Count Direction
* 0b0..Count up.
* 0b1..Count down.
*/
#define TMR_CTRL_DIR(x) (((uint16_t)(((uint16_t)(x)) << TMR_CTRL_DIR_SHIFT)) & TMR_CTRL_DIR_MASK)
#define TMR_CTRL_LENGTH_MASK (0x20U)
#define TMR_CTRL_LENGTH_SHIFT (5U)
/*! LENGTH - Count Length
* 0b0..Count until roll over at $FFFF and continue from $0000.
* 0b1..Count until compare, then re-initialize. If counting up, a successful compare occurs when the counter
* reaches a COMP1 value. If counting down, a successful compare occurs when the counter reaches a COMP2 value.
* When output mode $4 is used, alternating values of COMP1 and COMP2 are used to generate successful
* comparisons. For example, the counter counts until a COMP1 value is reached, re-initializes, counts until COMP2
* value is reached, re-initializes, counts until COMP1 value is reached, and so on.
*/
#define TMR_CTRL_LENGTH(x) (((uint16_t)(((uint16_t)(x)) << TMR_CTRL_LENGTH_SHIFT)) & TMR_CTRL_LENGTH_MASK)
#define TMR_CTRL_ONCE_MASK (0x40U)
#define TMR_CTRL_ONCE_SHIFT (6U)
/*! ONCE - Count Once
* 0b0..Count repeatedly.
* 0b1..Count until compare and then stop. If counting up, a successful compare occurs when the counter reaches a
* COMP1 value. If counting down, a successful compare occurs when the counter reaches a COMP2 value. When
* output mode $4 is used, the counter re-initializes after reaching the COMP1 value, continues to count to
* the COMP2 value, and then stops.
*/
#define TMR_CTRL_ONCE(x) (((uint16_t)(((uint16_t)(x)) << TMR_CTRL_ONCE_SHIFT)) & TMR_CTRL_ONCE_MASK)
#define TMR_CTRL_SCS_MASK (0x180U)
#define TMR_CTRL_SCS_SHIFT (7U)
/*! SCS - Secondary Count Source
* 0b00..Counter 0 input pin
* 0b01..Counter 1 input pin
* 0b10..Counter 2 input pin
* 0b11..Counter 3 input pin
*/
#define TMR_CTRL_SCS(x) (((uint16_t)(((uint16_t)(x)) << TMR_CTRL_SCS_SHIFT)) & TMR_CTRL_SCS_MASK)
#define TMR_CTRL_PCS_MASK (0x1E00U)
#define TMR_CTRL_PCS_SHIFT (9U)
/*! PCS - Primary Count Source
* 0b0000..Counter 0 input pin
* 0b0001..Counter 1 input pin
* 0b0010..Counter 2 input pin
* 0b0011..Counter 3 input pin
* 0b0100..Counter 0 output
* 0b0101..Counter 1 output
* 0b0110..Counter 2 output
* 0b0111..Counter 3 output
* 0b1000..IP bus clock divide by 1 prescaler
* 0b1001..IP bus clock divide by 2 prescaler
* 0b1010..IP bus clock divide by 4 prescaler
* 0b1011..IP bus clock divide by 8 prescaler
* 0b1100..IP bus clock divide by 16 prescaler
* 0b1101..IP bus clock divide by 32 prescaler
* 0b1110..IP bus clock divide by 64 prescaler
* 0b1111..IP bus clock divide by 128 prescaler
*/
#define TMR_CTRL_PCS(x) (((uint16_t)(((uint16_t)(x)) << TMR_CTRL_PCS_SHIFT)) & TMR_CTRL_PCS_MASK)
#define TMR_CTRL_CM_MASK (0xE000U)
#define TMR_CTRL_CM_SHIFT (13U)
/*! CM - Count Mode
* 0b000..No operation
* 0b001..Count rising edges of primary sourceRising edges are counted only when SCTRL[IPS] = 0. Falling edges
* are counted when SCTRL[IPS] = 1. If the primary count source is IP bus clock divide by 1, only rising
* edges are counted regardless of the value of SCTRL[IPS].
* 0b010..Count rising and falling edges of primary sourceIP bus clock divide by 1 cannot be used as a primary count source in edge count mode.
* 0b011..Count rising edges of primary source while secondary input high active
* 0b100..Quadrature count mode, uses primary and secondary sources
* 0b101..Count rising edges of primary source; secondary source specifies directionRising edges are counted only
* when SCTRL[IPS] = 0. Falling edges are counted when SCTRL[IPS] = 1.
* 0b110..Edge of secondary source triggers primary count until compare
* 0b111..Cascaded counter mode (up/down)The primary count source must be set to one of the counter outputs.
*/
#define TMR_CTRL_CM(x) (((uint16_t)(((uint16_t)(x)) << TMR_CTRL_CM_SHIFT)) & TMR_CTRL_CM_MASK)
/*! @} */
/* The count of TMR_CTRL */
#define TMR_CTRL_COUNT (4U)
/*! @name SCTRL - Timer Channel Status and Control Register */
/*! @{ */
#define TMR_SCTRL_OEN_MASK (0x1U)
#define TMR_SCTRL_OEN_SHIFT (0U)
/*! OEN - Output Enable
* 0b0..The external pin is configured as an input.
* 0b1..The OFLAG output signal is driven on the external pin. Other timer groups using this external pin as
* their input see the driven value. The polarity of the signal is determined by OPS.
*/
#define TMR_SCTRL_OEN(x) (((uint16_t)(((uint16_t)(x)) << TMR_SCTRL_OEN_SHIFT)) & TMR_SCTRL_OEN_MASK)
#define TMR_SCTRL_OPS_MASK (0x2U)
#define TMR_SCTRL_OPS_SHIFT (1U)
/*! OPS - Output Polarity Select
* 0b0..True polarity.
* 0b1..Inverted polarity.
*/
#define TMR_SCTRL_OPS(x) (((uint16_t)(((uint16_t)(x)) << TMR_SCTRL_OPS_SHIFT)) & TMR_SCTRL_OPS_MASK)
#define TMR_SCTRL_FORCE_MASK (0x4U)
#define TMR_SCTRL_FORCE_SHIFT (2U)
/*! FORCE - Force OFLAG Output */
#define TMR_SCTRL_FORCE(x) (((uint16_t)(((uint16_t)(x)) << TMR_SCTRL_FORCE_SHIFT)) & TMR_SCTRL_FORCE_MASK)
#define TMR_SCTRL_VAL_MASK (0x8U)
#define TMR_SCTRL_VAL_SHIFT (3U)
/*! VAL - Forced OFLAG Value */
#define TMR_SCTRL_VAL(x) (((uint16_t)(((uint16_t)(x)) << TMR_SCTRL_VAL_SHIFT)) & TMR_SCTRL_VAL_MASK)
#define TMR_SCTRL_EEOF_MASK (0x10U)
#define TMR_SCTRL_EEOF_SHIFT (4U)
/*! EEOF - Enable External OFLAG Force */
#define TMR_SCTRL_EEOF(x) (((uint16_t)(((uint16_t)(x)) << TMR_SCTRL_EEOF_SHIFT)) & TMR_SCTRL_EEOF_MASK)
#define TMR_SCTRL_MSTR_MASK (0x20U)
#define TMR_SCTRL_MSTR_SHIFT (5U)
/*! MSTR - Master Mode */
#define TMR_SCTRL_MSTR(x) (((uint16_t)(((uint16_t)(x)) << TMR_SCTRL_MSTR_SHIFT)) & TMR_SCTRL_MSTR_MASK)
#define TMR_SCTRL_CAPTURE_MODE_MASK (0xC0U)
#define TMR_SCTRL_CAPTURE_MODE_SHIFT (6U)
/*! CAPTURE_MODE - Input Capture Mode
* 0b00..Capture function is disabled
* 0b01..Load capture register on rising edge (when IPS=0) or falling edge (when IPS=1) of input
* 0b10..Load capture register on falling edge (when IPS=0) or rising edge (when IPS=1) of input
* 0b11..Load capture register on both edges of input
*/
#define TMR_SCTRL_CAPTURE_MODE(x) (((uint16_t)(((uint16_t)(x)) << TMR_SCTRL_CAPTURE_MODE_SHIFT)) & TMR_SCTRL_CAPTURE_MODE_MASK)
#define TMR_SCTRL_INPUT_MASK (0x100U)
#define TMR_SCTRL_INPUT_SHIFT (8U)
/*! INPUT - External Input Signal */
#define TMR_SCTRL_INPUT(x) (((uint16_t)(((uint16_t)(x)) << TMR_SCTRL_INPUT_SHIFT)) & TMR_SCTRL_INPUT_MASK)
#define TMR_SCTRL_IPS_MASK (0x200U)
#define TMR_SCTRL_IPS_SHIFT (9U)
/*! IPS - Input Polarity Select */
#define TMR_SCTRL_IPS(x) (((uint16_t)(((uint16_t)(x)) << TMR_SCTRL_IPS_SHIFT)) & TMR_SCTRL_IPS_MASK)
#define TMR_SCTRL_IEFIE_MASK (0x400U)
#define TMR_SCTRL_IEFIE_SHIFT (10U)
/*! IEFIE - Input Edge Flag Interrupt Enable */
#define TMR_SCTRL_IEFIE(x) (((uint16_t)(((uint16_t)(x)) << TMR_SCTRL_IEFIE_SHIFT)) & TMR_SCTRL_IEFIE_MASK)
#define TMR_SCTRL_IEF_MASK (0x800U)
#define TMR_SCTRL_IEF_SHIFT (11U)
/*! IEF - Input Edge Flag */
#define TMR_SCTRL_IEF(x) (((uint16_t)(((uint16_t)(x)) << TMR_SCTRL_IEF_SHIFT)) & TMR_SCTRL_IEF_MASK)
#define TMR_SCTRL_TOFIE_MASK (0x1000U)
#define TMR_SCTRL_TOFIE_SHIFT (12U)
/*! TOFIE - Timer Overflow Flag Interrupt Enable */
#define TMR_SCTRL_TOFIE(x) (((uint16_t)(((uint16_t)(x)) << TMR_SCTRL_TOFIE_SHIFT)) & TMR_SCTRL_TOFIE_MASK)
#define TMR_SCTRL_TOF_MASK (0x2000U)
#define TMR_SCTRL_TOF_SHIFT (13U)
/*! TOF - Timer Overflow Flag */
#define TMR_SCTRL_TOF(x) (((uint16_t)(((uint16_t)(x)) << TMR_SCTRL_TOF_SHIFT)) & TMR_SCTRL_TOF_MASK)
#define TMR_SCTRL_TCFIE_MASK (0x4000U)
#define TMR_SCTRL_TCFIE_SHIFT (14U)
/*! TCFIE - Timer Compare Flag Interrupt Enable */
#define TMR_SCTRL_TCFIE(x) (((uint16_t)(((uint16_t)(x)) << TMR_SCTRL_TCFIE_SHIFT)) & TMR_SCTRL_TCFIE_MASK)
#define TMR_SCTRL_TCF_MASK (0x8000U)
#define TMR_SCTRL_TCF_SHIFT (15U)
/*! TCF - Timer Compare Flag */
#define TMR_SCTRL_TCF(x) (((uint16_t)(((uint16_t)(x)) << TMR_SCTRL_TCF_SHIFT)) & TMR_SCTRL_TCF_MASK)
/*! @} */
/* The count of TMR_SCTRL */
#define TMR_SCTRL_COUNT (4U)
/*! @name CMPLD1 - Timer Channel Comparator Load Register 1 */
/*! @{ */
#define TMR_CMPLD1_COMPARATOR_LOAD_1_MASK (0xFFFFU)
#define TMR_CMPLD1_COMPARATOR_LOAD_1_SHIFT (0U)
/*! COMPARATOR_LOAD_1 - COMPARATOR_LOAD_1 */
#define TMR_CMPLD1_COMPARATOR_LOAD_1(x) (((uint16_t)(((uint16_t)(x)) << TMR_CMPLD1_COMPARATOR_LOAD_1_SHIFT)) & TMR_CMPLD1_COMPARATOR_LOAD_1_MASK)
/*! @} */
/* The count of TMR_CMPLD1 */
#define TMR_CMPLD1_COUNT (4U)
/*! @name CMPLD2 - Timer Channel Comparator Load Register 2 */
/*! @{ */
#define TMR_CMPLD2_COMPARATOR_LOAD_2_MASK (0xFFFFU)
#define TMR_CMPLD2_COMPARATOR_LOAD_2_SHIFT (0U)
/*! COMPARATOR_LOAD_2 - COMPARATOR_LOAD_2 */
#define TMR_CMPLD2_COMPARATOR_LOAD_2(x) (((uint16_t)(((uint16_t)(x)) << TMR_CMPLD2_COMPARATOR_LOAD_2_SHIFT)) & TMR_CMPLD2_COMPARATOR_LOAD_2_MASK)
/*! @} */
/* The count of TMR_CMPLD2 */
#define TMR_CMPLD2_COUNT (4U)
/*! @name CSCTRL - Timer Channel Comparator Status and Control Register */
/*! @{ */
#define TMR_CSCTRL_CL1_MASK (0x3U)
#define TMR_CSCTRL_CL1_SHIFT (0U)
/*! CL1 - Compare Load Control 1
* 0b00..Never preload
* 0b01..Load upon successful compare with the value in COMP1
* 0b10..Load upon successful compare with the value in COMP2
* 0b11..Reserved
*/
#define TMR_CSCTRL_CL1(x) (((uint16_t)(((uint16_t)(x)) << TMR_CSCTRL_CL1_SHIFT)) & TMR_CSCTRL_CL1_MASK)
#define TMR_CSCTRL_CL2_MASK (0xCU)
#define TMR_CSCTRL_CL2_SHIFT (2U)
/*! CL2 - Compare Load Control 2
* 0b00..Never preload
* 0b01..Load upon successful compare with the value in COMP1
* 0b10..Load upon successful compare with the value in COMP2
* 0b11..Reserved
*/
#define TMR_CSCTRL_CL2(x) (((uint16_t)(((uint16_t)(x)) << TMR_CSCTRL_CL2_SHIFT)) & TMR_CSCTRL_CL2_MASK)
#define TMR_CSCTRL_TCF1_MASK (0x10U)
#define TMR_CSCTRL_TCF1_SHIFT (4U)
/*! TCF1 - Timer Compare 1 Interrupt Flag */
#define TMR_CSCTRL_TCF1(x) (((uint16_t)(((uint16_t)(x)) << TMR_CSCTRL_TCF1_SHIFT)) & TMR_CSCTRL_TCF1_MASK)
#define TMR_CSCTRL_TCF2_MASK (0x20U)
#define TMR_CSCTRL_TCF2_SHIFT (5U)
/*! TCF2 - Timer Compare 2 Interrupt Flag */
#define TMR_CSCTRL_TCF2(x) (((uint16_t)(((uint16_t)(x)) << TMR_CSCTRL_TCF2_SHIFT)) & TMR_CSCTRL_TCF2_MASK)
#define TMR_CSCTRL_TCF1EN_MASK (0x40U)
#define TMR_CSCTRL_TCF1EN_SHIFT (6U)
/*! TCF1EN - Timer Compare 1 Interrupt Enable */
#define TMR_CSCTRL_TCF1EN(x) (((uint16_t)(((uint16_t)(x)) << TMR_CSCTRL_TCF1EN_SHIFT)) & TMR_CSCTRL_TCF1EN_MASK)
#define TMR_CSCTRL_TCF2EN_MASK (0x80U)
#define TMR_CSCTRL_TCF2EN_SHIFT (7U)
/*! TCF2EN - Timer Compare 2 Interrupt Enable */
#define TMR_CSCTRL_TCF2EN(x) (((uint16_t)(((uint16_t)(x)) << TMR_CSCTRL_TCF2EN_SHIFT)) & TMR_CSCTRL_TCF2EN_MASK)
#define TMR_CSCTRL_OFLAG_MASK (0x100U)
#define TMR_CSCTRL_OFLAG_SHIFT (8U)
/*! OFLAG - Output flag */
#define TMR_CSCTRL_OFLAG(x) (((uint16_t)(((uint16_t)(x)) << TMR_CSCTRL_OFLAG_SHIFT)) & TMR_CSCTRL_OFLAG_MASK)
#define TMR_CSCTRL_UP_MASK (0x200U)
#define TMR_CSCTRL_UP_SHIFT (9U)
/*! UP - Counting Direction Indicator
* 0b0..The last count was in the DOWN direction.
* 0b1..The last count was in the UP direction.
*/
#define TMR_CSCTRL_UP(x) (((uint16_t)(((uint16_t)(x)) << TMR_CSCTRL_UP_SHIFT)) & TMR_CSCTRL_UP_MASK)
#define TMR_CSCTRL_TCI_MASK (0x400U)
#define TMR_CSCTRL_TCI_SHIFT (10U)
/*! TCI - Triggered Count Initialization Control
* 0b0..Stop counter upon receiving a second trigger event while still counting from the first trigger event.
* 0b1..Reload the counter upon receiving a second trigger event while still counting from the first trigger event.
*/
#define TMR_CSCTRL_TCI(x) (((uint16_t)(((uint16_t)(x)) << TMR_CSCTRL_TCI_SHIFT)) & TMR_CSCTRL_TCI_MASK)
#define TMR_CSCTRL_ROC_MASK (0x800U)
#define TMR_CSCTRL_ROC_SHIFT (11U)
/*! ROC - Reload on Capture
* 0b0..Do not reload the counter on a capture event.
* 0b1..Reload the counter on a capture event.
*/
#define TMR_CSCTRL_ROC(x) (((uint16_t)(((uint16_t)(x)) << TMR_CSCTRL_ROC_SHIFT)) & TMR_CSCTRL_ROC_MASK)
#define TMR_CSCTRL_ALT_LOAD_MASK (0x1000U)
#define TMR_CSCTRL_ALT_LOAD_SHIFT (12U)
/*! ALT_LOAD - Alternative Load Enable
* 0b0..Counter can be re-initialized only with the LOAD register.
* 0b1..Counter can be re-initialized with the LOAD or CMPLD2 registers depending on count direction.
*/
#define TMR_CSCTRL_ALT_LOAD(x) (((uint16_t)(((uint16_t)(x)) << TMR_CSCTRL_ALT_LOAD_SHIFT)) & TMR_CSCTRL_ALT_LOAD_MASK)
#define TMR_CSCTRL_FAULT_MASK (0x2000U)
#define TMR_CSCTRL_FAULT_SHIFT (13U)
/*! FAULT - Fault Enable
* 0b0..Fault function disabled.
* 0b1..Fault function enabled.
*/
#define TMR_CSCTRL_FAULT(x) (((uint16_t)(((uint16_t)(x)) << TMR_CSCTRL_FAULT_SHIFT)) & TMR_CSCTRL_FAULT_MASK)
#define TMR_CSCTRL_DBG_EN_MASK (0xC000U)
#define TMR_CSCTRL_DBG_EN_SHIFT (14U)
/*! DBG_EN - Debug Actions Enable
* 0b00..Continue with normal operation during debug mode. (default)
* 0b01..Halt TMR counter during debug mode.
* 0b10..Force TMR output to logic 0 (prior to consideration of SCTRL[OPS]).
* 0b11..Both halt counter and force output to 0 during debug mode.
*/
#define TMR_CSCTRL_DBG_EN(x) (((uint16_t)(((uint16_t)(x)) << TMR_CSCTRL_DBG_EN_SHIFT)) & TMR_CSCTRL_DBG_EN_MASK)
/*! @} */
/* The count of TMR_CSCTRL */
#define TMR_CSCTRL_COUNT (4U)
/*! @name FILT - Timer Channel Input Filter Register */
/*! @{ */
#define TMR_FILT_FILT_PER_MASK (0xFFU)
#define TMR_FILT_FILT_PER_SHIFT (0U)
/*! FILT_PER - Input Filter Sample Period */
#define TMR_FILT_FILT_PER(x) (((uint16_t)(((uint16_t)(x)) << TMR_FILT_FILT_PER_SHIFT)) & TMR_FILT_FILT_PER_MASK)
#define TMR_FILT_FILT_CNT_MASK (0x700U)
#define TMR_FILT_FILT_CNT_SHIFT (8U)
/*! FILT_CNT - Input Filter Sample Count */
#define TMR_FILT_FILT_CNT(x) (((uint16_t)(((uint16_t)(x)) << TMR_FILT_FILT_CNT_SHIFT)) & TMR_FILT_FILT_CNT_MASK)
/*! @} */
/* The count of TMR_FILT */
#define TMR_FILT_COUNT (4U)
/*! @name DMA - Timer Channel DMA Enable Register */
/*! @{ */
#define TMR_DMA_IEFDE_MASK (0x1U)
#define TMR_DMA_IEFDE_SHIFT (0U)
/*! IEFDE - Input Edge Flag DMA Enable */
#define TMR_DMA_IEFDE(x) (((uint16_t)(((uint16_t)(x)) << TMR_DMA_IEFDE_SHIFT)) & TMR_DMA_IEFDE_MASK)
#define TMR_DMA_CMPLD1DE_MASK (0x2U)
#define TMR_DMA_CMPLD1DE_SHIFT (1U)
/*! CMPLD1DE - Comparator Preload Register 1 DMA Enable */
#define TMR_DMA_CMPLD1DE(x) (((uint16_t)(((uint16_t)(x)) << TMR_DMA_CMPLD1DE_SHIFT)) & TMR_DMA_CMPLD1DE_MASK)
#define TMR_DMA_CMPLD2DE_MASK (0x4U)
#define TMR_DMA_CMPLD2DE_SHIFT (2U)
/*! CMPLD2DE - Comparator Preload Register 2 DMA Enable */
#define TMR_DMA_CMPLD2DE(x) (((uint16_t)(((uint16_t)(x)) << TMR_DMA_CMPLD2DE_SHIFT)) & TMR_DMA_CMPLD2DE_MASK)
/*! @} */
/* The count of TMR_DMA */
#define TMR_DMA_COUNT (4U)
/*! @name ENBL - Timer Channel Enable Register */
/*! @{ */
#define TMR_ENBL_ENBL_MASK (0xFU)
#define TMR_ENBL_ENBL_SHIFT (0U)
/*! ENBL - Timer Channel Enable
* 0b0000..Timer channel is disabled.
* 0b0001..Timer channel is enabled. (default)
*/
#define TMR_ENBL_ENBL(x) (((uint16_t)(((uint16_t)(x)) << TMR_ENBL_ENBL_SHIFT)) & TMR_ENBL_ENBL_MASK)
/*! @} */
/* The count of TMR_ENBL */
#define TMR_ENBL_COUNT (4U)
/*!
* @}
*/ /* end of group TMR_Register_Masks */
/*!
* @}
*/ /* end of group TMR_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 */
#endif /* TMR_H_ */

View File

@ -0,0 +1,914 @@
/*
** ###################################################################
** Processors: MIMXRT1061CVJ5A
** MIMXRT1061CVJ5B
** MIMXRT1061CVL5A
** MIMXRT1061CVL5B
** MIMXRT1061DVJ6A
** MIMXRT1061DVJ6B
** MIMXRT1061DVL6A
** MIMXRT1061DVL6B
** MIMXRT1061XVN5B
** MIMXRT1062CVJ5A
** MIMXRT1062CVJ5B
** MIMXRT1062CVL5A
** MIMXRT1062CVL5B
** MIMXRT1062DVJ6A
** MIMXRT1062DVJ6B
** MIMXRT1062DVL6A
** MIMXRT1062DVL6B
** MIMXRT1062DVN6B
** MIMXRT1062XVN5B
** MIMXRT106ADVL6A
** MIMXRT106CDVL6A
** MIMXRT106FDVL6A
** MIMXRT106LDVL6A
** MIMXRT106SDVL6A
**
** Version: rev. 1.4, 2022-03-25
** Build: b240705
**
** Abstract:
** CMSIS Peripheral Access Layer for TRNG
**
** Copyright 1997-2016 Freescale Semiconductor, Inc.
** Copyright 2016-2024 NXP
** SPDX-License-Identifier: BSD-3-Clause
**
** http: www.nxp.com
** mail: support@nxp.com
**
** Revisions:
** - rev. 0.1 (2017-01-10)
** Initial version.
** - rev. 1.0 (2018-11-16)
** Update header files to align with IMXRT1060RM Rev.0.
** - rev. 1.1 (2018-11-27)
** Update header files to align with IMXRT1060RM Rev.1.
** - rev. 1.2 (2019-04-29)
** Add SET/CLR/TOG register group to register CTRL, STAT, CHANNELCTRL, CH0STAT, CH0OPTS, CH1STAT, CH1OPTS, CH2STAT, CH2OPTS, CH3STAT, CH3OPTS of DCP module.
** - rev. 1.3 (2021-08-10)
** Update header files to align with IMXRT1060RM Rev.3.
** - rev. 1.4 (2022-03-25)
** Add RT1060X device
**
** ###################################################################
*/
/*!
* @file TRNG.h
* @version 1.4
* @date 2022-03-25
* @brief CMSIS Peripheral Access Layer for TRNG
*
* CMSIS Peripheral Access Layer for TRNG
*/
#if !defined(TRNG_H_)
#define TRNG_H_ /**< Symbol preventing repeated inclusion */
#if (defined(CPU_MIMXRT1061CVJ5A) || defined(CPU_MIMXRT1061CVJ5B) || defined(CPU_MIMXRT1061CVL5A) || defined(CPU_MIMXRT1061CVL5B) || defined(CPU_MIMXRT1061DVJ6A) || defined(CPU_MIMXRT1061DVJ6B) || defined(CPU_MIMXRT1061DVL6A) || defined(CPU_MIMXRT1061DVL6B) || defined(CPU_MIMXRT1061XVN5B))
#include "MIMXRT1061_COMMON.h"
#elif (defined(CPU_MIMXRT1062CVJ5A) || defined(CPU_MIMXRT1062CVJ5B) || defined(CPU_MIMXRT1062CVL5A) || defined(CPU_MIMXRT1062CVL5B) || defined(CPU_MIMXRT1062DVJ6A) || defined(CPU_MIMXRT1062DVJ6B) || defined(CPU_MIMXRT1062DVL6A) || defined(CPU_MIMXRT1062DVL6B) || defined(CPU_MIMXRT1062DVN6B) || defined(CPU_MIMXRT1062XVN5B))
#include "MIMXRT1062_COMMON.h"
#elif (defined(CPU_MIMXRT106ADVL6A))
#include "MIMXRT106A_COMMON.h"
#elif (defined(CPU_MIMXRT106CDVL6A))
#include "MIMXRT106C_COMMON.h"
#elif (defined(CPU_MIMXRT106FDVL6A))
#include "MIMXRT106F_COMMON.h"
#elif (defined(CPU_MIMXRT106LDVL6A))
#include "MIMXRT106L_COMMON.h"
#elif (defined(CPU_MIMXRT106SDVL6A))
#include "MIMXRT106S_COMMON.h"
#else
#error "No valid CPU defined!"
#endif
/* ----------------------------------------------------------------------------
-- 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
/* ----------------------------------------------------------------------------
-- TRNG Peripheral Access Layer
---------------------------------------------------------------------------- */
/*!
* @addtogroup TRNG_Peripheral_Access_Layer TRNG Peripheral Access Layer
* @{
*/
/** TRNG - Size of Registers Arrays */
#define TRNG_ENTA_COUNT 16u
/** TRNG - Register Layout Typedef */
typedef struct {
__IO uint32_t MCTL; /**< Miscellaneous Control Register, offset: 0x0 */
__IO uint32_t SCMISC; /**< Statistical Check Miscellaneous Register, offset: 0x4 */
__IO uint32_t PKRRNG; /**< Poker Range Register, offset: 0x8 */
union { /* offset: 0xC */
__IO uint32_t PKRMAX; /**< Poker Maximum Limit Register, offset: 0xC */
__I uint32_t PKRSQ; /**< Poker Square Calculation Result Register, offset: 0xC */
};
__IO uint32_t SDCTL; /**< Seed Control Register, offset: 0x10 */
union { /* offset: 0x14 */
__IO uint32_t SBLIM; /**< Sparse Bit Limit Register, offset: 0x14 */
__I uint32_t TOTSAM; /**< Total Samples Register, offset: 0x14 */
};
__IO uint32_t FRQMIN; /**< Frequency Count Minimum Limit Register, offset: 0x18 */
union { /* offset: 0x1C */
__I uint32_t FRQCNT; /**< Frequency Count Register, offset: 0x1C */
__IO uint32_t FRQMAX; /**< Frequency Count Maximum Limit Register, offset: 0x1C */
};
union { /* offset: 0x20 */
__I uint32_t SCMC; /**< Statistical Check Monobit Count Register, offset: 0x20 */
__IO uint32_t SCML; /**< Statistical Check Monobit Limit Register, offset: 0x20 */
};
union { /* offset: 0x24 */
__I uint32_t SCR1C; /**< Statistical Check Run Length 1 Count Register, offset: 0x24 */
__IO uint32_t SCR1L; /**< Statistical Check Run Length 1 Limit Register, offset: 0x24 */
};
union { /* offset: 0x28 */
__I uint32_t SCR2C; /**< Statistical Check Run Length 2 Count Register, offset: 0x28 */
__IO uint32_t SCR2L; /**< Statistical Check Run Length 2 Limit Register, offset: 0x28 */
};
union { /* offset: 0x2C */
__I uint32_t SCR3C; /**< Statistical Check Run Length 3 Count Register, offset: 0x2C */
__IO uint32_t SCR3L; /**< Statistical Check Run Length 3 Limit Register, offset: 0x2C */
};
union { /* offset: 0x30 */
__I uint32_t SCR4C; /**< Statistical Check Run Length 4 Count Register, offset: 0x30 */
__IO uint32_t SCR4L; /**< Statistical Check Run Length 4 Limit Register, offset: 0x30 */
};
union { /* offset: 0x34 */
__I uint32_t SCR5C; /**< Statistical Check Run Length 5 Count Register, offset: 0x34 */
__IO uint32_t SCR5L; /**< Statistical Check Run Length 5 Limit Register, offset: 0x34 */
};
union { /* offset: 0x38 */
__I uint32_t SCR6PC; /**< Statistical Check Run Length 6+ Count Register, offset: 0x38 */
__IO uint32_t SCR6PL; /**< Statistical Check Run Length 6+ Limit Register, offset: 0x38 */
};
__I uint32_t STATUS; /**< Status Register, offset: 0x3C */
__I uint32_t ENT[TRNG_ENTA_COUNT]; /**< Entropy Read Register, array offset: 0x40, array step: 0x4 */
__I uint32_t PKRCNT10; /**< Statistical Check Poker Count 1 and 0 Register, offset: 0x80 */
__I uint32_t PKRCNT32; /**< Statistical Check Poker Count 3 and 2 Register, offset: 0x84 */
__I uint32_t PKRCNT54; /**< Statistical Check Poker Count 5 and 4 Register, offset: 0x88 */
__I uint32_t PKRCNT76; /**< Statistical Check Poker Count 7 and 6 Register, offset: 0x8C */
__I uint32_t PKRCNT98; /**< Statistical Check Poker Count 9 and 8 Register, offset: 0x90 */
__I uint32_t PKRCNTBA; /**< Statistical Check Poker Count B and A Register, offset: 0x94 */
__I uint32_t PKRCNTDC; /**< Statistical Check Poker Count D and C Register, offset: 0x98 */
__I uint32_t PKRCNTFE; /**< Statistical Check Poker Count F and E Register, offset: 0x9C */
__IO uint32_t SEC_CFG; /**< Security Configuration Register, offset: 0xA0 */
__IO uint32_t INT_CTRL; /**< Interrupt Control Register, offset: 0xA4 */
__IO uint32_t INT_MASK; /**< Mask Register, offset: 0xA8 */
__I uint32_t INT_STATUS; /**< Interrupt Status Register, offset: 0xAC */
uint8_t RESERVED_0[64];
__I uint32_t VID1; /**< Version ID Register (MS), offset: 0xF0 */
__I uint32_t VID2; /**< Version ID Register (LS), offset: 0xF4 */
} TRNG_Type;
/* ----------------------------------------------------------------------------
-- TRNG Register Masks
---------------------------------------------------------------------------- */
/*!
* @addtogroup TRNG_Register_Masks TRNG Register Masks
* @{
*/
/*! @name MCTL - Miscellaneous Control Register */
/*! @{ */
#define TRNG_MCTL_SAMP_MODE_MASK (0x3U)
#define TRNG_MCTL_SAMP_MODE_SHIFT (0U)
/*! SAMP_MODE
* 0b00..use Von Neumann data into both Entropy shifter and Statistical Checker
* 0b01..use raw data into both Entropy shifter and Statistical Checker
* 0b10..use Von Neumann data into Entropy shifter. Use raw data into Statistical Checker
* 0b11..undefined/reserved.
*/
#define TRNG_MCTL_SAMP_MODE(x) (((uint32_t)(((uint32_t)(x)) << TRNG_MCTL_SAMP_MODE_SHIFT)) & TRNG_MCTL_SAMP_MODE_MASK)
#define TRNG_MCTL_OSC_DIV_MASK (0xCU)
#define TRNG_MCTL_OSC_DIV_SHIFT (2U)
/*! OSC_DIV
* 0b00..use ring oscillator with no divide
* 0b01..use ring oscillator divided-by-2
* 0b10..use ring oscillator divided-by-4
* 0b11..use ring oscillator divided-by-8
*/
#define TRNG_MCTL_OSC_DIV(x) (((uint32_t)(((uint32_t)(x)) << TRNG_MCTL_OSC_DIV_SHIFT)) & TRNG_MCTL_OSC_DIV_MASK)
#define TRNG_MCTL_UNUSED4_MASK (0x10U)
#define TRNG_MCTL_UNUSED4_SHIFT (4U)
#define TRNG_MCTL_UNUSED4(x) (((uint32_t)(((uint32_t)(x)) << TRNG_MCTL_UNUSED4_SHIFT)) & TRNG_MCTL_UNUSED4_MASK)
#define TRNG_MCTL_UNUSED5_MASK (0x20U)
#define TRNG_MCTL_UNUSED5_SHIFT (5U)
#define TRNG_MCTL_UNUSED5(x) (((uint32_t)(((uint32_t)(x)) << TRNG_MCTL_UNUSED5_SHIFT)) & TRNG_MCTL_UNUSED5_MASK)
#define TRNG_MCTL_RST_DEF_MASK (0x40U)
#define TRNG_MCTL_RST_DEF_SHIFT (6U)
#define TRNG_MCTL_RST_DEF(x) (((uint32_t)(((uint32_t)(x)) << TRNG_MCTL_RST_DEF_SHIFT)) & TRNG_MCTL_RST_DEF_MASK)
#define TRNG_MCTL_FOR_SCLK_MASK (0x80U)
#define TRNG_MCTL_FOR_SCLK_SHIFT (7U)
#define TRNG_MCTL_FOR_SCLK(x) (((uint32_t)(((uint32_t)(x)) << TRNG_MCTL_FOR_SCLK_SHIFT)) & TRNG_MCTL_FOR_SCLK_MASK)
#define TRNG_MCTL_FCT_FAIL_MASK (0x100U)
#define TRNG_MCTL_FCT_FAIL_SHIFT (8U)
#define TRNG_MCTL_FCT_FAIL(x) (((uint32_t)(((uint32_t)(x)) << TRNG_MCTL_FCT_FAIL_SHIFT)) & TRNG_MCTL_FCT_FAIL_MASK)
#define TRNG_MCTL_FCT_VAL_MASK (0x200U)
#define TRNG_MCTL_FCT_VAL_SHIFT (9U)
#define TRNG_MCTL_FCT_VAL(x) (((uint32_t)(((uint32_t)(x)) << TRNG_MCTL_FCT_VAL_SHIFT)) & TRNG_MCTL_FCT_VAL_MASK)
#define TRNG_MCTL_ENT_VAL_MASK (0x400U)
#define TRNG_MCTL_ENT_VAL_SHIFT (10U)
#define TRNG_MCTL_ENT_VAL(x) (((uint32_t)(((uint32_t)(x)) << TRNG_MCTL_ENT_VAL_SHIFT)) & TRNG_MCTL_ENT_VAL_MASK)
#define TRNG_MCTL_TST_OUT_MASK (0x800U)
#define TRNG_MCTL_TST_OUT_SHIFT (11U)
#define TRNG_MCTL_TST_OUT(x) (((uint32_t)(((uint32_t)(x)) << TRNG_MCTL_TST_OUT_SHIFT)) & TRNG_MCTL_TST_OUT_MASK)
#define TRNG_MCTL_ERR_MASK (0x1000U)
#define TRNG_MCTL_ERR_SHIFT (12U)
#define TRNG_MCTL_ERR(x) (((uint32_t)(((uint32_t)(x)) << TRNG_MCTL_ERR_SHIFT)) & TRNG_MCTL_ERR_MASK)
#define TRNG_MCTL_TSTOP_OK_MASK (0x2000U)
#define TRNG_MCTL_TSTOP_OK_SHIFT (13U)
#define TRNG_MCTL_TSTOP_OK(x) (((uint32_t)(((uint32_t)(x)) << TRNG_MCTL_TSTOP_OK_SHIFT)) & TRNG_MCTL_TSTOP_OK_MASK)
#define TRNG_MCTL_LRUN_CONT_MASK (0x4000U)
#define TRNG_MCTL_LRUN_CONT_SHIFT (14U)
#define TRNG_MCTL_LRUN_CONT(x) (((uint32_t)(((uint32_t)(x)) << TRNG_MCTL_LRUN_CONT_SHIFT)) & TRNG_MCTL_LRUN_CONT_MASK)
#define TRNG_MCTL_PRGM_MASK (0x10000U)
#define TRNG_MCTL_PRGM_SHIFT (16U)
#define TRNG_MCTL_PRGM(x) (((uint32_t)(((uint32_t)(x)) << TRNG_MCTL_PRGM_SHIFT)) & TRNG_MCTL_PRGM_MASK)
/*! @} */
/*! @name SCMISC - Statistical Check Miscellaneous Register */
/*! @{ */
#define TRNG_SCMISC_LRUN_MAX_MASK (0xFFU)
#define TRNG_SCMISC_LRUN_MAX_SHIFT (0U)
#define TRNG_SCMISC_LRUN_MAX(x) (((uint32_t)(((uint32_t)(x)) << TRNG_SCMISC_LRUN_MAX_SHIFT)) & TRNG_SCMISC_LRUN_MAX_MASK)
#define TRNG_SCMISC_RTY_CT_MASK (0xF0000U)
#define TRNG_SCMISC_RTY_CT_SHIFT (16U)
#define TRNG_SCMISC_RTY_CT(x) (((uint32_t)(((uint32_t)(x)) << TRNG_SCMISC_RTY_CT_SHIFT)) & TRNG_SCMISC_RTY_CT_MASK)
/*! @} */
/*! @name PKRRNG - Poker Range Register */
/*! @{ */
#define TRNG_PKRRNG_PKR_RNG_MASK (0xFFFFU)
#define TRNG_PKRRNG_PKR_RNG_SHIFT (0U)
#define TRNG_PKRRNG_PKR_RNG(x) (((uint32_t)(((uint32_t)(x)) << TRNG_PKRRNG_PKR_RNG_SHIFT)) & TRNG_PKRRNG_PKR_RNG_MASK)
/*! @} */
/*! @name PKRMAX - Poker Maximum Limit Register */
/*! @{ */
#define TRNG_PKRMAX_PKR_MAX_MASK (0xFFFFFFU)
#define TRNG_PKRMAX_PKR_MAX_SHIFT (0U)
/*! PKR_MAX - Poker Maximum Limit. */
#define TRNG_PKRMAX_PKR_MAX(x) (((uint32_t)(((uint32_t)(x)) << TRNG_PKRMAX_PKR_MAX_SHIFT)) & TRNG_PKRMAX_PKR_MAX_MASK)
/*! @} */
/*! @name PKRSQ - Poker Square Calculation Result Register */
/*! @{ */
#define TRNG_PKRSQ_PKR_SQ_MASK (0xFFFFFFU)
#define TRNG_PKRSQ_PKR_SQ_SHIFT (0U)
/*! PKR_SQ - Poker Square Calculation Result. */
#define TRNG_PKRSQ_PKR_SQ(x) (((uint32_t)(((uint32_t)(x)) << TRNG_PKRSQ_PKR_SQ_SHIFT)) & TRNG_PKRSQ_PKR_SQ_MASK)
/*! @} */
/*! @name SDCTL - Seed Control Register */
/*! @{ */
#define TRNG_SDCTL_SAMP_SIZE_MASK (0xFFFFU)
#define TRNG_SDCTL_SAMP_SIZE_SHIFT (0U)
#define TRNG_SDCTL_SAMP_SIZE(x) (((uint32_t)(((uint32_t)(x)) << TRNG_SDCTL_SAMP_SIZE_SHIFT)) & TRNG_SDCTL_SAMP_SIZE_MASK)
#define TRNG_SDCTL_ENT_DLY_MASK (0xFFFF0000U)
#define TRNG_SDCTL_ENT_DLY_SHIFT (16U)
#define TRNG_SDCTL_ENT_DLY(x) (((uint32_t)(((uint32_t)(x)) << TRNG_SDCTL_ENT_DLY_SHIFT)) & TRNG_SDCTL_ENT_DLY_MASK)
/*! @} */
/*! @name SBLIM - Sparse Bit Limit Register */
/*! @{ */
#define TRNG_SBLIM_SB_LIM_MASK (0x3FFU)
#define TRNG_SBLIM_SB_LIM_SHIFT (0U)
#define TRNG_SBLIM_SB_LIM(x) (((uint32_t)(((uint32_t)(x)) << TRNG_SBLIM_SB_LIM_SHIFT)) & TRNG_SBLIM_SB_LIM_MASK)
/*! @} */
/*! @name TOTSAM - Total Samples Register */
/*! @{ */
#define TRNG_TOTSAM_TOT_SAM_MASK (0xFFFFFU)
#define TRNG_TOTSAM_TOT_SAM_SHIFT (0U)
#define TRNG_TOTSAM_TOT_SAM(x) (((uint32_t)(((uint32_t)(x)) << TRNG_TOTSAM_TOT_SAM_SHIFT)) & TRNG_TOTSAM_TOT_SAM_MASK)
/*! @} */
/*! @name FRQMIN - Frequency Count Minimum Limit Register */
/*! @{ */
#define TRNG_FRQMIN_FRQ_MIN_MASK (0x3FFFFFU)
#define TRNG_FRQMIN_FRQ_MIN_SHIFT (0U)
#define TRNG_FRQMIN_FRQ_MIN(x) (((uint32_t)(((uint32_t)(x)) << TRNG_FRQMIN_FRQ_MIN_SHIFT)) & TRNG_FRQMIN_FRQ_MIN_MASK)
/*! @} */
/*! @name FRQCNT - Frequency Count Register */
/*! @{ */
#define TRNG_FRQCNT_FRQ_CT_MASK (0x3FFFFFU)
#define TRNG_FRQCNT_FRQ_CT_SHIFT (0U)
#define TRNG_FRQCNT_FRQ_CT(x) (((uint32_t)(((uint32_t)(x)) << TRNG_FRQCNT_FRQ_CT_SHIFT)) & TRNG_FRQCNT_FRQ_CT_MASK)
/*! @} */
/*! @name FRQMAX - Frequency Count Maximum Limit Register */
/*! @{ */
#define TRNG_FRQMAX_FRQ_MAX_MASK (0x3FFFFFU)
#define TRNG_FRQMAX_FRQ_MAX_SHIFT (0U)
#define TRNG_FRQMAX_FRQ_MAX(x) (((uint32_t)(((uint32_t)(x)) << TRNG_FRQMAX_FRQ_MAX_SHIFT)) & TRNG_FRQMAX_FRQ_MAX_MASK)
/*! @} */
/*! @name SCMC - Statistical Check Monobit Count Register */
/*! @{ */
#define TRNG_SCMC_MONO_CT_MASK (0xFFFFU)
#define TRNG_SCMC_MONO_CT_SHIFT (0U)
#define TRNG_SCMC_MONO_CT(x) (((uint32_t)(((uint32_t)(x)) << TRNG_SCMC_MONO_CT_SHIFT)) & TRNG_SCMC_MONO_CT_MASK)
/*! @} */
/*! @name SCML - Statistical Check Monobit Limit Register */
/*! @{ */
#define TRNG_SCML_MONO_MAX_MASK (0xFFFFU)
#define TRNG_SCML_MONO_MAX_SHIFT (0U)
#define TRNG_SCML_MONO_MAX(x) (((uint32_t)(((uint32_t)(x)) << TRNG_SCML_MONO_MAX_SHIFT)) & TRNG_SCML_MONO_MAX_MASK)
#define TRNG_SCML_MONO_RNG_MASK (0xFFFF0000U)
#define TRNG_SCML_MONO_RNG_SHIFT (16U)
#define TRNG_SCML_MONO_RNG(x) (((uint32_t)(((uint32_t)(x)) << TRNG_SCML_MONO_RNG_SHIFT)) & TRNG_SCML_MONO_RNG_MASK)
/*! @} */
/*! @name SCR1C - Statistical Check Run Length 1 Count Register */
/*! @{ */
#define TRNG_SCR1C_R1_0_CT_MASK (0x7FFFU)
#define TRNG_SCR1C_R1_0_CT_SHIFT (0U)
#define TRNG_SCR1C_R1_0_CT(x) (((uint32_t)(((uint32_t)(x)) << TRNG_SCR1C_R1_0_CT_SHIFT)) & TRNG_SCR1C_R1_0_CT_MASK)
#define TRNG_SCR1C_R1_1_CT_MASK (0x7FFF0000U)
#define TRNG_SCR1C_R1_1_CT_SHIFT (16U)
#define TRNG_SCR1C_R1_1_CT(x) (((uint32_t)(((uint32_t)(x)) << TRNG_SCR1C_R1_1_CT_SHIFT)) & TRNG_SCR1C_R1_1_CT_MASK)
/*! @} */
/*! @name SCR1L - Statistical Check Run Length 1 Limit Register */
/*! @{ */
#define TRNG_SCR1L_RUN1_MAX_MASK (0x7FFFU)
#define TRNG_SCR1L_RUN1_MAX_SHIFT (0U)
#define TRNG_SCR1L_RUN1_MAX(x) (((uint32_t)(((uint32_t)(x)) << TRNG_SCR1L_RUN1_MAX_SHIFT)) & TRNG_SCR1L_RUN1_MAX_MASK)
#define TRNG_SCR1L_RUN1_RNG_MASK (0x7FFF0000U)
#define TRNG_SCR1L_RUN1_RNG_SHIFT (16U)
#define TRNG_SCR1L_RUN1_RNG(x) (((uint32_t)(((uint32_t)(x)) << TRNG_SCR1L_RUN1_RNG_SHIFT)) & TRNG_SCR1L_RUN1_RNG_MASK)
/*! @} */
/*! @name SCR2C - Statistical Check Run Length 2 Count Register */
/*! @{ */
#define TRNG_SCR2C_R2_0_CT_MASK (0x3FFFU)
#define TRNG_SCR2C_R2_0_CT_SHIFT (0U)
#define TRNG_SCR2C_R2_0_CT(x) (((uint32_t)(((uint32_t)(x)) << TRNG_SCR2C_R2_0_CT_SHIFT)) & TRNG_SCR2C_R2_0_CT_MASK)
#define TRNG_SCR2C_R2_1_CT_MASK (0x3FFF0000U)
#define TRNG_SCR2C_R2_1_CT_SHIFT (16U)
#define TRNG_SCR2C_R2_1_CT(x) (((uint32_t)(((uint32_t)(x)) << TRNG_SCR2C_R2_1_CT_SHIFT)) & TRNG_SCR2C_R2_1_CT_MASK)
/*! @} */
/*! @name SCR2L - Statistical Check Run Length 2 Limit Register */
/*! @{ */
#define TRNG_SCR2L_RUN2_MAX_MASK (0x3FFFU)
#define TRNG_SCR2L_RUN2_MAX_SHIFT (0U)
#define TRNG_SCR2L_RUN2_MAX(x) (((uint32_t)(((uint32_t)(x)) << TRNG_SCR2L_RUN2_MAX_SHIFT)) & TRNG_SCR2L_RUN2_MAX_MASK)
#define TRNG_SCR2L_RUN2_RNG_MASK (0x3FFF0000U)
#define TRNG_SCR2L_RUN2_RNG_SHIFT (16U)
#define TRNG_SCR2L_RUN2_RNG(x) (((uint32_t)(((uint32_t)(x)) << TRNG_SCR2L_RUN2_RNG_SHIFT)) & TRNG_SCR2L_RUN2_RNG_MASK)
/*! @} */
/*! @name SCR3C - Statistical Check Run Length 3 Count Register */
/*! @{ */
#define TRNG_SCR3C_R3_0_CT_MASK (0x1FFFU)
#define TRNG_SCR3C_R3_0_CT_SHIFT (0U)
#define TRNG_SCR3C_R3_0_CT(x) (((uint32_t)(((uint32_t)(x)) << TRNG_SCR3C_R3_0_CT_SHIFT)) & TRNG_SCR3C_R3_0_CT_MASK)
#define TRNG_SCR3C_R3_1_CT_MASK (0x1FFF0000U)
#define TRNG_SCR3C_R3_1_CT_SHIFT (16U)
#define TRNG_SCR3C_R3_1_CT(x) (((uint32_t)(((uint32_t)(x)) << TRNG_SCR3C_R3_1_CT_SHIFT)) & TRNG_SCR3C_R3_1_CT_MASK)
/*! @} */
/*! @name SCR3L - Statistical Check Run Length 3 Limit Register */
/*! @{ */
#define TRNG_SCR3L_RUN3_MAX_MASK (0x1FFFU)
#define TRNG_SCR3L_RUN3_MAX_SHIFT (0U)
#define TRNG_SCR3L_RUN3_MAX(x) (((uint32_t)(((uint32_t)(x)) << TRNG_SCR3L_RUN3_MAX_SHIFT)) & TRNG_SCR3L_RUN3_MAX_MASK)
#define TRNG_SCR3L_RUN3_RNG_MASK (0x1FFF0000U)
#define TRNG_SCR3L_RUN3_RNG_SHIFT (16U)
#define TRNG_SCR3L_RUN3_RNG(x) (((uint32_t)(((uint32_t)(x)) << TRNG_SCR3L_RUN3_RNG_SHIFT)) & TRNG_SCR3L_RUN3_RNG_MASK)
/*! @} */
/*! @name SCR4C - Statistical Check Run Length 4 Count Register */
/*! @{ */
#define TRNG_SCR4C_R4_0_CT_MASK (0xFFFU)
#define TRNG_SCR4C_R4_0_CT_SHIFT (0U)
#define TRNG_SCR4C_R4_0_CT(x) (((uint32_t)(((uint32_t)(x)) << TRNG_SCR4C_R4_0_CT_SHIFT)) & TRNG_SCR4C_R4_0_CT_MASK)
#define TRNG_SCR4C_R4_1_CT_MASK (0xFFF0000U)
#define TRNG_SCR4C_R4_1_CT_SHIFT (16U)
#define TRNG_SCR4C_R4_1_CT(x) (((uint32_t)(((uint32_t)(x)) << TRNG_SCR4C_R4_1_CT_SHIFT)) & TRNG_SCR4C_R4_1_CT_MASK)
/*! @} */
/*! @name SCR4L - Statistical Check Run Length 4 Limit Register */
/*! @{ */
#define TRNG_SCR4L_RUN4_MAX_MASK (0xFFFU)
#define TRNG_SCR4L_RUN4_MAX_SHIFT (0U)
#define TRNG_SCR4L_RUN4_MAX(x) (((uint32_t)(((uint32_t)(x)) << TRNG_SCR4L_RUN4_MAX_SHIFT)) & TRNG_SCR4L_RUN4_MAX_MASK)
#define TRNG_SCR4L_RUN4_RNG_MASK (0xFFF0000U)
#define TRNG_SCR4L_RUN4_RNG_SHIFT (16U)
#define TRNG_SCR4L_RUN4_RNG(x) (((uint32_t)(((uint32_t)(x)) << TRNG_SCR4L_RUN4_RNG_SHIFT)) & TRNG_SCR4L_RUN4_RNG_MASK)
/*! @} */
/*! @name SCR5C - Statistical Check Run Length 5 Count Register */
/*! @{ */
#define TRNG_SCR5C_R5_0_CT_MASK (0x7FFU)
#define TRNG_SCR5C_R5_0_CT_SHIFT (0U)
#define TRNG_SCR5C_R5_0_CT(x) (((uint32_t)(((uint32_t)(x)) << TRNG_SCR5C_R5_0_CT_SHIFT)) & TRNG_SCR5C_R5_0_CT_MASK)
#define TRNG_SCR5C_R5_1_CT_MASK (0x7FF0000U)
#define TRNG_SCR5C_R5_1_CT_SHIFT (16U)
#define TRNG_SCR5C_R5_1_CT(x) (((uint32_t)(((uint32_t)(x)) << TRNG_SCR5C_R5_1_CT_SHIFT)) & TRNG_SCR5C_R5_1_CT_MASK)
/*! @} */
/*! @name SCR5L - Statistical Check Run Length 5 Limit Register */
/*! @{ */
#define TRNG_SCR5L_RUN5_MAX_MASK (0x7FFU)
#define TRNG_SCR5L_RUN5_MAX_SHIFT (0U)
#define TRNG_SCR5L_RUN5_MAX(x) (((uint32_t)(((uint32_t)(x)) << TRNG_SCR5L_RUN5_MAX_SHIFT)) & TRNG_SCR5L_RUN5_MAX_MASK)
#define TRNG_SCR5L_RUN5_RNG_MASK (0x7FF0000U)
#define TRNG_SCR5L_RUN5_RNG_SHIFT (16U)
#define TRNG_SCR5L_RUN5_RNG(x) (((uint32_t)(((uint32_t)(x)) << TRNG_SCR5L_RUN5_RNG_SHIFT)) & TRNG_SCR5L_RUN5_RNG_MASK)
/*! @} */
/*! @name SCR6PC - Statistical Check Run Length 6+ Count Register */
/*! @{ */
#define TRNG_SCR6PC_R6P_0_CT_MASK (0x7FFU)
#define TRNG_SCR6PC_R6P_0_CT_SHIFT (0U)
#define TRNG_SCR6PC_R6P_0_CT(x) (((uint32_t)(((uint32_t)(x)) << TRNG_SCR6PC_R6P_0_CT_SHIFT)) & TRNG_SCR6PC_R6P_0_CT_MASK)
#define TRNG_SCR6PC_R6P_1_CT_MASK (0x7FF0000U)
#define TRNG_SCR6PC_R6P_1_CT_SHIFT (16U)
#define TRNG_SCR6PC_R6P_1_CT(x) (((uint32_t)(((uint32_t)(x)) << TRNG_SCR6PC_R6P_1_CT_SHIFT)) & TRNG_SCR6PC_R6P_1_CT_MASK)
/*! @} */
/*! @name SCR6PL - Statistical Check Run Length 6+ Limit Register */
/*! @{ */
#define TRNG_SCR6PL_RUN6P_MAX_MASK (0x7FFU)
#define TRNG_SCR6PL_RUN6P_MAX_SHIFT (0U)
#define TRNG_SCR6PL_RUN6P_MAX(x) (((uint32_t)(((uint32_t)(x)) << TRNG_SCR6PL_RUN6P_MAX_SHIFT)) & TRNG_SCR6PL_RUN6P_MAX_MASK)
#define TRNG_SCR6PL_RUN6P_RNG_MASK (0x7FF0000U)
#define TRNG_SCR6PL_RUN6P_RNG_SHIFT (16U)
#define TRNG_SCR6PL_RUN6P_RNG(x) (((uint32_t)(((uint32_t)(x)) << TRNG_SCR6PL_RUN6P_RNG_SHIFT)) & TRNG_SCR6PL_RUN6P_RNG_MASK)
/*! @} */
/*! @name STATUS - Status Register */
/*! @{ */
#define TRNG_STATUS_TF1BR0_MASK (0x1U)
#define TRNG_STATUS_TF1BR0_SHIFT (0U)
#define TRNG_STATUS_TF1BR0(x) (((uint32_t)(((uint32_t)(x)) << TRNG_STATUS_TF1BR0_SHIFT)) & TRNG_STATUS_TF1BR0_MASK)
#define TRNG_STATUS_TF1BR1_MASK (0x2U)
#define TRNG_STATUS_TF1BR1_SHIFT (1U)
#define TRNG_STATUS_TF1BR1(x) (((uint32_t)(((uint32_t)(x)) << TRNG_STATUS_TF1BR1_SHIFT)) & TRNG_STATUS_TF1BR1_MASK)
#define TRNG_STATUS_TF2BR0_MASK (0x4U)
#define TRNG_STATUS_TF2BR0_SHIFT (2U)
#define TRNG_STATUS_TF2BR0(x) (((uint32_t)(((uint32_t)(x)) << TRNG_STATUS_TF2BR0_SHIFT)) & TRNG_STATUS_TF2BR0_MASK)
#define TRNG_STATUS_TF2BR1_MASK (0x8U)
#define TRNG_STATUS_TF2BR1_SHIFT (3U)
#define TRNG_STATUS_TF2BR1(x) (((uint32_t)(((uint32_t)(x)) << TRNG_STATUS_TF2BR1_SHIFT)) & TRNG_STATUS_TF2BR1_MASK)
#define TRNG_STATUS_TF3BR0_MASK (0x10U)
#define TRNG_STATUS_TF3BR0_SHIFT (4U)
#define TRNG_STATUS_TF3BR0(x) (((uint32_t)(((uint32_t)(x)) << TRNG_STATUS_TF3BR0_SHIFT)) & TRNG_STATUS_TF3BR0_MASK)
#define TRNG_STATUS_TF3BR1_MASK (0x20U)
#define TRNG_STATUS_TF3BR1_SHIFT (5U)
#define TRNG_STATUS_TF3BR1(x) (((uint32_t)(((uint32_t)(x)) << TRNG_STATUS_TF3BR1_SHIFT)) & TRNG_STATUS_TF3BR1_MASK)
#define TRNG_STATUS_TF4BR0_MASK (0x40U)
#define TRNG_STATUS_TF4BR0_SHIFT (6U)
#define TRNG_STATUS_TF4BR0(x) (((uint32_t)(((uint32_t)(x)) << TRNG_STATUS_TF4BR0_SHIFT)) & TRNG_STATUS_TF4BR0_MASK)
#define TRNG_STATUS_TF4BR1_MASK (0x80U)
#define TRNG_STATUS_TF4BR1_SHIFT (7U)
#define TRNG_STATUS_TF4BR1(x) (((uint32_t)(((uint32_t)(x)) << TRNG_STATUS_TF4BR1_SHIFT)) & TRNG_STATUS_TF4BR1_MASK)
#define TRNG_STATUS_TF5BR0_MASK (0x100U)
#define TRNG_STATUS_TF5BR0_SHIFT (8U)
#define TRNG_STATUS_TF5BR0(x) (((uint32_t)(((uint32_t)(x)) << TRNG_STATUS_TF5BR0_SHIFT)) & TRNG_STATUS_TF5BR0_MASK)
#define TRNG_STATUS_TF5BR1_MASK (0x200U)
#define TRNG_STATUS_TF5BR1_SHIFT (9U)
#define TRNG_STATUS_TF5BR1(x) (((uint32_t)(((uint32_t)(x)) << TRNG_STATUS_TF5BR1_SHIFT)) & TRNG_STATUS_TF5BR1_MASK)
#define TRNG_STATUS_TF6PBR0_MASK (0x400U)
#define TRNG_STATUS_TF6PBR0_SHIFT (10U)
#define TRNG_STATUS_TF6PBR0(x) (((uint32_t)(((uint32_t)(x)) << TRNG_STATUS_TF6PBR0_SHIFT)) & TRNG_STATUS_TF6PBR0_MASK)
#define TRNG_STATUS_TF6PBR1_MASK (0x800U)
#define TRNG_STATUS_TF6PBR1_SHIFT (11U)
#define TRNG_STATUS_TF6PBR1(x) (((uint32_t)(((uint32_t)(x)) << TRNG_STATUS_TF6PBR1_SHIFT)) & TRNG_STATUS_TF6PBR1_MASK)
#define TRNG_STATUS_TFSB_MASK (0x1000U)
#define TRNG_STATUS_TFSB_SHIFT (12U)
#define TRNG_STATUS_TFSB(x) (((uint32_t)(((uint32_t)(x)) << TRNG_STATUS_TFSB_SHIFT)) & TRNG_STATUS_TFSB_MASK)
#define TRNG_STATUS_TFLR_MASK (0x2000U)
#define TRNG_STATUS_TFLR_SHIFT (13U)
#define TRNG_STATUS_TFLR(x) (((uint32_t)(((uint32_t)(x)) << TRNG_STATUS_TFLR_SHIFT)) & TRNG_STATUS_TFLR_MASK)
#define TRNG_STATUS_TFP_MASK (0x4000U)
#define TRNG_STATUS_TFP_SHIFT (14U)
#define TRNG_STATUS_TFP(x) (((uint32_t)(((uint32_t)(x)) << TRNG_STATUS_TFP_SHIFT)) & TRNG_STATUS_TFP_MASK)
#define TRNG_STATUS_TFMB_MASK (0x8000U)
#define TRNG_STATUS_TFMB_SHIFT (15U)
#define TRNG_STATUS_TFMB(x) (((uint32_t)(((uint32_t)(x)) << TRNG_STATUS_TFMB_SHIFT)) & TRNG_STATUS_TFMB_MASK)
#define TRNG_STATUS_RETRY_CT_MASK (0xF0000U)
#define TRNG_STATUS_RETRY_CT_SHIFT (16U)
#define TRNG_STATUS_RETRY_CT(x) (((uint32_t)(((uint32_t)(x)) << TRNG_STATUS_RETRY_CT_SHIFT)) & TRNG_STATUS_RETRY_CT_MASK)
/*! @} */
/*! @name ENT - Entropy Read Register */
/*! @{ */
#define TRNG_ENT_ENT_MASK (0xFFFFFFFFU)
#define TRNG_ENT_ENT_SHIFT (0U)
#define TRNG_ENT_ENT(x) (((uint32_t)(((uint32_t)(x)) << TRNG_ENT_ENT_SHIFT)) & TRNG_ENT_ENT_MASK)
/*! @} */
/* The count of TRNG_ENT */
#define TRNG_ENT_COUNT (16U)
/*! @name PKRCNT10 - Statistical Check Poker Count 1 and 0 Register */
/*! @{ */
#define TRNG_PKRCNT10_PKR_0_CT_MASK (0xFFFFU)
#define TRNG_PKRCNT10_PKR_0_CT_SHIFT (0U)
#define TRNG_PKRCNT10_PKR_0_CT(x) (((uint32_t)(((uint32_t)(x)) << TRNG_PKRCNT10_PKR_0_CT_SHIFT)) & TRNG_PKRCNT10_PKR_0_CT_MASK)
#define TRNG_PKRCNT10_PKR_1_CT_MASK (0xFFFF0000U)
#define TRNG_PKRCNT10_PKR_1_CT_SHIFT (16U)
#define TRNG_PKRCNT10_PKR_1_CT(x) (((uint32_t)(((uint32_t)(x)) << TRNG_PKRCNT10_PKR_1_CT_SHIFT)) & TRNG_PKRCNT10_PKR_1_CT_MASK)
/*! @} */
/*! @name PKRCNT32 - Statistical Check Poker Count 3 and 2 Register */
/*! @{ */
#define TRNG_PKRCNT32_PKR_2_CT_MASK (0xFFFFU)
#define TRNG_PKRCNT32_PKR_2_CT_SHIFT (0U)
#define TRNG_PKRCNT32_PKR_2_CT(x) (((uint32_t)(((uint32_t)(x)) << TRNG_PKRCNT32_PKR_2_CT_SHIFT)) & TRNG_PKRCNT32_PKR_2_CT_MASK)
#define TRNG_PKRCNT32_PKR_3_CT_MASK (0xFFFF0000U)
#define TRNG_PKRCNT32_PKR_3_CT_SHIFT (16U)
#define TRNG_PKRCNT32_PKR_3_CT(x) (((uint32_t)(((uint32_t)(x)) << TRNG_PKRCNT32_PKR_3_CT_SHIFT)) & TRNG_PKRCNT32_PKR_3_CT_MASK)
/*! @} */
/*! @name PKRCNT54 - Statistical Check Poker Count 5 and 4 Register */
/*! @{ */
#define TRNG_PKRCNT54_PKR_4_CT_MASK (0xFFFFU)
#define TRNG_PKRCNT54_PKR_4_CT_SHIFT (0U)
#define TRNG_PKRCNT54_PKR_4_CT(x) (((uint32_t)(((uint32_t)(x)) << TRNG_PKRCNT54_PKR_4_CT_SHIFT)) & TRNG_PKRCNT54_PKR_4_CT_MASK)
#define TRNG_PKRCNT54_PKR_5_CT_MASK (0xFFFF0000U)
#define TRNG_PKRCNT54_PKR_5_CT_SHIFT (16U)
#define TRNG_PKRCNT54_PKR_5_CT(x) (((uint32_t)(((uint32_t)(x)) << TRNG_PKRCNT54_PKR_5_CT_SHIFT)) & TRNG_PKRCNT54_PKR_5_CT_MASK)
/*! @} */
/*! @name PKRCNT76 - Statistical Check Poker Count 7 and 6 Register */
/*! @{ */
#define TRNG_PKRCNT76_PKR_6_CT_MASK (0xFFFFU)
#define TRNG_PKRCNT76_PKR_6_CT_SHIFT (0U)
#define TRNG_PKRCNT76_PKR_6_CT(x) (((uint32_t)(((uint32_t)(x)) << TRNG_PKRCNT76_PKR_6_CT_SHIFT)) & TRNG_PKRCNT76_PKR_6_CT_MASK)
#define TRNG_PKRCNT76_PKR_7_CT_MASK (0xFFFF0000U)
#define TRNG_PKRCNT76_PKR_7_CT_SHIFT (16U)
#define TRNG_PKRCNT76_PKR_7_CT(x) (((uint32_t)(((uint32_t)(x)) << TRNG_PKRCNT76_PKR_7_CT_SHIFT)) & TRNG_PKRCNT76_PKR_7_CT_MASK)
/*! @} */
/*! @name PKRCNT98 - Statistical Check Poker Count 9 and 8 Register */
/*! @{ */
#define TRNG_PKRCNT98_PKR_8_CT_MASK (0xFFFFU)
#define TRNG_PKRCNT98_PKR_8_CT_SHIFT (0U)
#define TRNG_PKRCNT98_PKR_8_CT(x) (((uint32_t)(((uint32_t)(x)) << TRNG_PKRCNT98_PKR_8_CT_SHIFT)) & TRNG_PKRCNT98_PKR_8_CT_MASK)
#define TRNG_PKRCNT98_PKR_9_CT_MASK (0xFFFF0000U)
#define TRNG_PKRCNT98_PKR_9_CT_SHIFT (16U)
#define TRNG_PKRCNT98_PKR_9_CT(x) (((uint32_t)(((uint32_t)(x)) << TRNG_PKRCNT98_PKR_9_CT_SHIFT)) & TRNG_PKRCNT98_PKR_9_CT_MASK)
/*! @} */
/*! @name PKRCNTBA - Statistical Check Poker Count B and A Register */
/*! @{ */
#define TRNG_PKRCNTBA_PKR_A_CT_MASK (0xFFFFU)
#define TRNG_PKRCNTBA_PKR_A_CT_SHIFT (0U)
#define TRNG_PKRCNTBA_PKR_A_CT(x) (((uint32_t)(((uint32_t)(x)) << TRNG_PKRCNTBA_PKR_A_CT_SHIFT)) & TRNG_PKRCNTBA_PKR_A_CT_MASK)
#define TRNG_PKRCNTBA_PKR_B_CT_MASK (0xFFFF0000U)
#define TRNG_PKRCNTBA_PKR_B_CT_SHIFT (16U)
#define TRNG_PKRCNTBA_PKR_B_CT(x) (((uint32_t)(((uint32_t)(x)) << TRNG_PKRCNTBA_PKR_B_CT_SHIFT)) & TRNG_PKRCNTBA_PKR_B_CT_MASK)
/*! @} */
/*! @name PKRCNTDC - Statistical Check Poker Count D and C Register */
/*! @{ */
#define TRNG_PKRCNTDC_PKR_C_CT_MASK (0xFFFFU)
#define TRNG_PKRCNTDC_PKR_C_CT_SHIFT (0U)
#define TRNG_PKRCNTDC_PKR_C_CT(x) (((uint32_t)(((uint32_t)(x)) << TRNG_PKRCNTDC_PKR_C_CT_SHIFT)) & TRNG_PKRCNTDC_PKR_C_CT_MASK)
#define TRNG_PKRCNTDC_PKR_D_CT_MASK (0xFFFF0000U)
#define TRNG_PKRCNTDC_PKR_D_CT_SHIFT (16U)
#define TRNG_PKRCNTDC_PKR_D_CT(x) (((uint32_t)(((uint32_t)(x)) << TRNG_PKRCNTDC_PKR_D_CT_SHIFT)) & TRNG_PKRCNTDC_PKR_D_CT_MASK)
/*! @} */
/*! @name PKRCNTFE - Statistical Check Poker Count F and E Register */
/*! @{ */
#define TRNG_PKRCNTFE_PKR_E_CT_MASK (0xFFFFU)
#define TRNG_PKRCNTFE_PKR_E_CT_SHIFT (0U)
#define TRNG_PKRCNTFE_PKR_E_CT(x) (((uint32_t)(((uint32_t)(x)) << TRNG_PKRCNTFE_PKR_E_CT_SHIFT)) & TRNG_PKRCNTFE_PKR_E_CT_MASK)
#define TRNG_PKRCNTFE_PKR_F_CT_MASK (0xFFFF0000U)
#define TRNG_PKRCNTFE_PKR_F_CT_SHIFT (16U)
#define TRNG_PKRCNTFE_PKR_F_CT(x) (((uint32_t)(((uint32_t)(x)) << TRNG_PKRCNTFE_PKR_F_CT_SHIFT)) & TRNG_PKRCNTFE_PKR_F_CT_MASK)
/*! @} */
/*! @name SEC_CFG - Security Configuration Register */
/*! @{ */
#define TRNG_SEC_CFG_UNUSED0_MASK (0x1U)
#define TRNG_SEC_CFG_UNUSED0_SHIFT (0U)
#define TRNG_SEC_CFG_UNUSED0(x) (((uint32_t)(((uint32_t)(x)) << TRNG_SEC_CFG_UNUSED0_SHIFT)) & TRNG_SEC_CFG_UNUSED0_MASK)
#define TRNG_SEC_CFG_NO_PRGM_MASK (0x2U)
#define TRNG_SEC_CFG_NO_PRGM_SHIFT (1U)
/*! NO_PRGM
* 0b0..Programability of registers controlled only by the Miscellaneous Control Register's access mode bit.
* 0b1..Overides Miscellaneous Control Register access mode and prevents TRNG register programming.
*/
#define TRNG_SEC_CFG_NO_PRGM(x) (((uint32_t)(((uint32_t)(x)) << TRNG_SEC_CFG_NO_PRGM_SHIFT)) & TRNG_SEC_CFG_NO_PRGM_MASK)
#define TRNG_SEC_CFG_UNUSED2_MASK (0x4U)
#define TRNG_SEC_CFG_UNUSED2_SHIFT (2U)
#define TRNG_SEC_CFG_UNUSED2(x) (((uint32_t)(((uint32_t)(x)) << TRNG_SEC_CFG_UNUSED2_SHIFT)) & TRNG_SEC_CFG_UNUSED2_MASK)
/*! @} */
/*! @name INT_CTRL - Interrupt Control Register */
/*! @{ */
#define TRNG_INT_CTRL_HW_ERR_MASK (0x1U)
#define TRNG_INT_CTRL_HW_ERR_SHIFT (0U)
/*! HW_ERR
* 0b0..Corresponding bit of INT_STATUS register cleared.
* 0b1..Corresponding bit of INT_STATUS register active.
*/
#define TRNG_INT_CTRL_HW_ERR(x) (((uint32_t)(((uint32_t)(x)) << TRNG_INT_CTRL_HW_ERR_SHIFT)) & TRNG_INT_CTRL_HW_ERR_MASK)
#define TRNG_INT_CTRL_ENT_VAL_MASK (0x2U)
#define TRNG_INT_CTRL_ENT_VAL_SHIFT (1U)
/*! ENT_VAL
* 0b0..Same behavior as bit 0 of this register.
* 0b1..Same behavior as bit 0 of this register.
*/
#define TRNG_INT_CTRL_ENT_VAL(x) (((uint32_t)(((uint32_t)(x)) << TRNG_INT_CTRL_ENT_VAL_SHIFT)) & TRNG_INT_CTRL_ENT_VAL_MASK)
#define TRNG_INT_CTRL_FRQ_CT_FAIL_MASK (0x4U)
#define TRNG_INT_CTRL_FRQ_CT_FAIL_SHIFT (2U)
/*! FRQ_CT_FAIL
* 0b0..Same behavior as bit 0 of this register.
* 0b1..Same behavior as bit 0 of this register.
*/
#define TRNG_INT_CTRL_FRQ_CT_FAIL(x) (((uint32_t)(((uint32_t)(x)) << TRNG_INT_CTRL_FRQ_CT_FAIL_SHIFT)) & TRNG_INT_CTRL_FRQ_CT_FAIL_MASK)
#define TRNG_INT_CTRL_UNUSED_MASK (0xFFFFFFF8U)
#define TRNG_INT_CTRL_UNUSED_SHIFT (3U)
#define TRNG_INT_CTRL_UNUSED(x) (((uint32_t)(((uint32_t)(x)) << TRNG_INT_CTRL_UNUSED_SHIFT)) & TRNG_INT_CTRL_UNUSED_MASK)
/*! @} */
/*! @name INT_MASK - Mask Register */
/*! @{ */
#define TRNG_INT_MASK_HW_ERR_MASK (0x1U)
#define TRNG_INT_MASK_HW_ERR_SHIFT (0U)
/*! HW_ERR
* 0b0..Corresponding interrupt of INT_STATUS is masked.
* 0b1..Corresponding bit of INT_STATUS is active.
*/
#define TRNG_INT_MASK_HW_ERR(x) (((uint32_t)(((uint32_t)(x)) << TRNG_INT_MASK_HW_ERR_SHIFT)) & TRNG_INT_MASK_HW_ERR_MASK)
#define TRNG_INT_MASK_ENT_VAL_MASK (0x2U)
#define TRNG_INT_MASK_ENT_VAL_SHIFT (1U)
/*! ENT_VAL
* 0b0..Same behavior as bit 0 of this register.
* 0b1..Same behavior as bit 0 of this register.
*/
#define TRNG_INT_MASK_ENT_VAL(x) (((uint32_t)(((uint32_t)(x)) << TRNG_INT_MASK_ENT_VAL_SHIFT)) & TRNG_INT_MASK_ENT_VAL_MASK)
#define TRNG_INT_MASK_FRQ_CT_FAIL_MASK (0x4U)
#define TRNG_INT_MASK_FRQ_CT_FAIL_SHIFT (2U)
/*! FRQ_CT_FAIL
* 0b0..Same behavior as bit 0 of this register.
* 0b1..Same behavior as bit 0 of this register.
*/
#define TRNG_INT_MASK_FRQ_CT_FAIL(x) (((uint32_t)(((uint32_t)(x)) << TRNG_INT_MASK_FRQ_CT_FAIL_SHIFT)) & TRNG_INT_MASK_FRQ_CT_FAIL_MASK)
/*! @} */
/*! @name INT_STATUS - Interrupt Status Register */
/*! @{ */
#define TRNG_INT_STATUS_HW_ERR_MASK (0x1U)
#define TRNG_INT_STATUS_HW_ERR_SHIFT (0U)
/*! HW_ERR
* 0b0..no error
* 0b1..error detected.
*/
#define TRNG_INT_STATUS_HW_ERR(x) (((uint32_t)(((uint32_t)(x)) << TRNG_INT_STATUS_HW_ERR_SHIFT)) & TRNG_INT_STATUS_HW_ERR_MASK)
#define TRNG_INT_STATUS_ENT_VAL_MASK (0x2U)
#define TRNG_INT_STATUS_ENT_VAL_SHIFT (1U)
/*! ENT_VAL
* 0b0..Busy generation entropy. Any value read is invalid.
* 0b1..TRNG can be stopped and entropy is valid if read.
*/
#define TRNG_INT_STATUS_ENT_VAL(x) (((uint32_t)(((uint32_t)(x)) << TRNG_INT_STATUS_ENT_VAL_SHIFT)) & TRNG_INT_STATUS_ENT_VAL_MASK)
#define TRNG_INT_STATUS_FRQ_CT_FAIL_MASK (0x4U)
#define TRNG_INT_STATUS_FRQ_CT_FAIL_SHIFT (2U)
/*! FRQ_CT_FAIL
* 0b0..No hardware nor self test frequency errors.
* 0b1..The frequency counter has detected a failure.
*/
#define TRNG_INT_STATUS_FRQ_CT_FAIL(x) (((uint32_t)(((uint32_t)(x)) << TRNG_INT_STATUS_FRQ_CT_FAIL_SHIFT)) & TRNG_INT_STATUS_FRQ_CT_FAIL_MASK)
/*! @} */
/*! @name VID1 - Version ID Register (MS) */
/*! @{ */
#define TRNG_VID1_MIN_REV_MASK (0xFFU)
#define TRNG_VID1_MIN_REV_SHIFT (0U)
/*! MIN_REV
* 0b00000000..Minor revision number for TRNG.
*/
#define TRNG_VID1_MIN_REV(x) (((uint32_t)(((uint32_t)(x)) << TRNG_VID1_MIN_REV_SHIFT)) & TRNG_VID1_MIN_REV_MASK)
#define TRNG_VID1_MAJ_REV_MASK (0xFF00U)
#define TRNG_VID1_MAJ_REV_SHIFT (8U)
/*! MAJ_REV
* 0b00000001..Major revision number for TRNG.
*/
#define TRNG_VID1_MAJ_REV(x) (((uint32_t)(((uint32_t)(x)) << TRNG_VID1_MAJ_REV_SHIFT)) & TRNG_VID1_MAJ_REV_MASK)
#define TRNG_VID1_IP_ID_MASK (0xFFFF0000U)
#define TRNG_VID1_IP_ID_SHIFT (16U)
/*! IP_ID
* 0b0000000000110000..ID for TRNG.
*/
#define TRNG_VID1_IP_ID(x) (((uint32_t)(((uint32_t)(x)) << TRNG_VID1_IP_ID_SHIFT)) & TRNG_VID1_IP_ID_MASK)
/*! @} */
/*! @name VID2 - Version ID Register (LS) */
/*! @{ */
#define TRNG_VID2_CONFIG_OPT_MASK (0xFFU)
#define TRNG_VID2_CONFIG_OPT_SHIFT (0U)
/*! CONFIG_OPT
* 0b00000000..TRNG_CONFIG_OPT for TRNG.
*/
#define TRNG_VID2_CONFIG_OPT(x) (((uint32_t)(((uint32_t)(x)) << TRNG_VID2_CONFIG_OPT_SHIFT)) & TRNG_VID2_CONFIG_OPT_MASK)
#define TRNG_VID2_ECO_REV_MASK (0xFF00U)
#define TRNG_VID2_ECO_REV_SHIFT (8U)
/*! ECO_REV
* 0b00000000..TRNG_ECO_REV for TRNG.
*/
#define TRNG_VID2_ECO_REV(x) (((uint32_t)(((uint32_t)(x)) << TRNG_VID2_ECO_REV_SHIFT)) & TRNG_VID2_ECO_REV_MASK)
#define TRNG_VID2_INTG_OPT_MASK (0xFF0000U)
#define TRNG_VID2_INTG_OPT_SHIFT (16U)
/*! INTG_OPT
* 0b00000000..INTG_OPT for TRNG.
*/
#define TRNG_VID2_INTG_OPT(x) (((uint32_t)(((uint32_t)(x)) << TRNG_VID2_INTG_OPT_SHIFT)) & TRNG_VID2_INTG_OPT_MASK)
#define TRNG_VID2_ERA_MASK (0xFF000000U)
#define TRNG_VID2_ERA_SHIFT (24U)
/*! ERA
* 0b00000000..COMPILE_OPT for TRNG.
*/
#define TRNG_VID2_ERA(x) (((uint32_t)(((uint32_t)(x)) << TRNG_VID2_ERA_SHIFT)) & TRNG_VID2_ERA_MASK)
/*! @} */
/*!
* @}
*/ /* end of group TRNG_Register_Masks */
/*!
* @}
*/ /* end of group TRNG_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 */
#endif /* TRNG_H_ */

Some files were not shown because too many files have changed in this diff Show More