Merge pull request #10653 from dylad/pr/saml1x_support

cpu/saml1x: add support for SAML10 and SAML11 MCUs (Cortex-M23)
This commit is contained in:
Alexandre Abadie 2019-01-22 08:53:06 +01:00 committed by GitHub
commit 7e3c382547
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
214 changed files with 65373 additions and 72 deletions

View File

@ -0,0 +1,3 @@
MODULE = boards_common_saml1x
include $(RIOTBASE)/Makefile.base

View File

@ -0,0 +1,3 @@
ifneq (,$(filter saul_default,$(USEMODULE)))
USEMODULE += saul_gpio
endif

View File

@ -0,0 +1,13 @@
# Put defined MCU peripherals here (in alphabetical order)
FEATURES_PROVIDED += periph_adc
FEATURES_PROVIDED += periph_i2c
FEATURES_PROVIDED += periph_rtc
FEATURES_PROVIDED += periph_rtt
FEATURES_PROVIDED += periph_spi
FEATURES_PROVIDED += periph_timer
FEATURES_PROVIDED += periph_uart
# The board MPU family (used for grouping by the CI system)
FEATURES_MCU_GROUP = cortex_m23
include $(RIOTCPU)/saml1x/Makefile.features

View File

@ -0,0 +1,12 @@
# define the cpu used by the saml11 board
export CPU = saml1x
# set edbg device type
EDBG_DEVICE_TYPE = mchp_cm23
USEMODULE += boards_common_saml1x
include $(RIOTMAKE)/boards/sam0.inc.mk
# add the common header files to the include path
INCLUDES += -I$(RIOTBOARD)/common/saml1x/include

View File

@ -0,0 +1,44 @@
/*
* Copyright (C) 2019 Mesotic SAS
*
* This file is subject to the terms and conditions of the GNU Lesser
* General Public License v2.1. See the file LICENSE in the top level
* directory for more details.
*/
/**
* @ingroup boards_common_saml1x
* @{
*
* @file board.c
* @brief Board specific implementations for the Microchip
* SAML10 and SAML11 Xplained Pro board
*
* @author Dylan Laduranty <dylan.laduranty@mesotic.com>
*
* @}
*/
#include "cpu.h"
#include "board.h"
#include "periph/gpio.h"
void led_init(void);
void board_init(void)
{
/* initialize the boards LEDs */
led_init();
/* initialize the CPU */
cpu_init();
}
/**
* @brief Initialize the boards on-board LED
*/
void led_init(void)
{
gpio_init(GPIO_PIN(PA, 7), GPIO_OUT);
}

View File

@ -0,0 +1,76 @@
/*
* Copyright (C) 2019 Mesotic SAS
*
* This file is subject to the terms and conditions of the GNU Lesser
* General Public License v2.1. See the file LICENSE in the top level
* directory for more details.
*/
/**
* @defgroup boards_common_saml1x Microchip SAML1X
* @ingroup boards
* @brief Support for SAML10 and SAML11 boards
* @{
*
* @file
* @brief Board specific definitions for the Microchip
* SAML10 & SAML11 Xplained Pro board.
*
* @author Dylan Laduranty <dylan.laduranty@mesotic.com>
*/
#ifndef BOARD_H
#define BOARD_H
#include "cpu.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* @name PORT selection macros
* @{
*/
#ifdef CPU_FAM_SAML11
#define _PORT PORT_SEC
#else
#define _PORT PORT
#endif
/** @} */
/**
* @name LED pin definitions and handlers
* @{
*/
#define LED0_PIN GPIO_PIN(PA, 7)
#define LED_PORT _PORT->Group[PA]
#define LED0_MASK (1 << 7)
#define LED0_ON (LED_PORT.OUTCLR.reg = LED0_MASK)
#define LED0_OFF (LED_PORT.OUTSET.reg = LED0_MASK)
#define LED0_TOGGLE (LED_PORT.OUTTGL.reg = LED0_MASK)
/** @} */
/**
* @name SW0 (Button) pin definitions
* @{
*/
#define BTN0_PORT _PORT->Group[PA]
#define BTN0_PIN GPIO_PIN(PA, 27)
#define BTN0_MODE GPIO_IN_PU
/** @} */
/**
* @brief Initialize board specific hardware, including clock, LEDs and std-IO
*/
void board_init(void);
#ifdef __cplusplus
}
#endif
#endif /* BOARD_H */
/** @} */

View File

@ -0,0 +1,53 @@
/*
* Copyright (C) 2019 Mesotic SAS
*
* This file is subject to the terms and conditions of the GNU Lesser
* General Public License v2.1. See the file LICENSE in the top level
* directory for more details.
*/
/**
* @ingroup boards_common_saml1x
* @{
*
* @file
* @brief Board specific configuration of direct mapped GPIOs
*
* @author Dylan Laduranty <dylan.laduranty@mesotic.com>
*/
#ifndef GPIO_PARAMS_H
#define GPIO_PARAMS_H
#include "board.h"
#include "saul/periph.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* @brief GPIO pin configuration
*/
static const saul_gpio_params_t saul_gpio_params[] =
{
{
.name = "LED(orange)",
.pin = LED0_PIN,
.mode = GPIO_OUT,
.flags = (SAUL_GPIO_INVERTED | SAUL_GPIO_INIT_CLEAR)
},
{
.name = "Button(SW0)",
.pin = BTN0_PIN,
.mode = BTN0_MODE,
.flags = SAUL_GPIO_INVERTED
},
};
#ifdef __cplusplus
}
#endif
#endif /* GPIO_PARAMS_H */
/** @} */

View File

@ -0,0 +1,155 @@
/*
* Copyright (C) 2019 Mesotic SAS
*
* This file is subject to the terms and conditions of the GNU Lesser
* General Public License v2.1. See the file LICENSE in the top level
* directory for more details.
*/
/**
* @ingroup boards_common_saml1x
* @{
*
* @file
* @brief Peripheral MCU configuration for the Microchip
* SAML10 & SAML11 Xplained Pro board
*
* @author Dylan Laduranty <dylan.laduranty@mesotic.com>
*/
#ifndef PERIPH_CONF_H
#define PERIPH_CONF_H
#include "periph_cpu.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* @brief GCLK reference speed
*/
#define CLOCK_CORECLOCK (16000000U)
/**
* @name Timer peripheral configuration
* @{
*/
#define TIMER_NUMOF (1U)
#define TIMER_0_EN 1
/* Timer 0 configuration */
#define TIMER_0_DEV TC0->COUNT32
#define TIMER_0_CHANNELS 1
#define TIMER_0_MAX_VALUE (0xffffffff)
#define TIMER_0_ISR isr_tc0
/** @} */
/**
* @name UART configuration
* @{
*/
static const uart_conf_t uart_config[] = {
{ /* Virtual COM Port */
.dev = &SERCOM2->USART,
.rx_pin = GPIO_PIN(PA,25),
.tx_pin = GPIO_PIN(PA,24),
.mux = GPIO_MUX_D,
.rx_pad = UART_PAD_RX_3,
.tx_pad = UART_PAD_TX_2,
.flags = UART_FLAG_NONE,
.gclk_src = GCLK_PCHCTRL_GEN_GCLK0
}
};
/* interrupt function name mapping */
#define UART_0_ISR isr_sercom2_2
#define UART_NUMOF (sizeof(uart_config) / sizeof(uart_config[0]))
/** @} */
/**
* @name SPI configuration
* @{
*/
static const spi_conf_t spi_config[] = {
{
.dev = &(SERCOM0->SPI),
.miso_pin = GPIO_PIN(PA, 4),
.mosi_pin = GPIO_PIN(PA, 14),
.clk_pin = GPIO_PIN(PA, 15),
.miso_mux = GPIO_MUX_D,
.mosi_mux = GPIO_MUX_D,
.clk_mux = GPIO_MUX_D,
.miso_pad = SPI_PAD_MISO_0,
.mosi_pad = SPI_PAD_MOSI_2_SCK_3
}
};
#define SPI_NUMOF (sizeof(spi_config) / sizeof(spi_config[0]))
/** @} */
/**
* @name I2C configuration
* @{
*/
static const i2c_conf_t i2c_config[] = {
{
.dev = &(SERCOM1->I2CM),
.speed = I2C_SPEED_NORMAL,
.scl_pin = GPIO_PIN(PA, 17),
.sda_pin = GPIO_PIN(PA, 16),
.mux = GPIO_MUX_C,
.gclk_src = GCLK_PCHCTRL_GEN_GCLK0,
.flags = I2C_FLAG_NONE
}
};
#define I2C_NUMOF (sizeof(i2c_config) / sizeof(i2c_config[0]))
/** @} */
/**
* @name RTC configuration
* @{
*/
#define RTC_NUMOF (1)
#define EXTERNAL_OSC32_SOURCE 1
#define INTERNAL_OSC32_SOURCE 0
#define ULTRA_LOW_POWER_INTERNAL_OSC_SOURCE 0
/** @} */
/**
* @name RTT configuration
* @{
*/
#define RTT_FREQUENCY (32768U)
#define RTT_MAX_VALUE (0xffffffffU)
#define RTT_NUMOF (1)
/** @} */
/**
* @name ADC Configuration
* @{
*/
#define ADC_NUMOF (1U)
/* ADC 0 Default values */
#define ADC_0_CLK_SOURCE 0 /* GCLK_GENERATOR_0 */
#define ADC_0_PRESCALER ADC_CTRLB_PRESCALER_DIV256
static const adc_conf_chan_t adc_channels[] = {
/* port, pin, muxpos */
{GPIO_PIN(PA, 10), ADC_INPUTCTRL_MUXPOS(ADC_INPUTCTRL_MUXPOS_AIN8)},
};
#define ADC_0_NEG_INPUT ADC_INPUTCTRL_MUXNEG(0x18u)
#define ADC_0_REF_DEFAULT ADC_REFCTRL_REFSEL_INTVCC2
/** @} */
#ifdef __cplusplus
}
#endif
#endif /* PERIPH_CONF_H */
/** @} */

View File

@ -0,0 +1,4 @@
MODULE = board
DIRS = $(RIOTBOARD)/common/saml1x
include $(RIOTBASE)/Makefile.base

View File

@ -0,0 +1 @@
include $(RIOTBOARD)/common/saml1x/Makefile.dep

View File

@ -0,0 +1 @@
include $(RIOTBOARD)/common/saml1x/Makefile.features

View File

@ -0,0 +1,5 @@
export CPU_FAM = saml10
export CPU_MODEL = saml10e16a
export CFLAGS += -D__SAML10E16A__
include $(RIOTBOARD)/common/saml1x/Makefile.include

View File

@ -0,0 +1,75 @@
/**
@defgroup boards_saml10-xpro Microchip SAML10 Xplained Pro
@ingroup boards
@brief Support for the Microchip SAML10 Xplained Pro board.
## Overview
The `SAML10 Xplained Pro` is an ultra-low power evaluation board by Microchip
featuring a ATSAML10E16A SoC. The SoC includes a SAML10 ARM Cortex-M23 micro-
controller. For programming the MCU comes with 16KB of RAM and 64KB of flash
memory.
## Hardware
![saml10-xpro image](https://www.microchip.com/_ImagedCopy/SAML10%20Xpro%20Front%20Title.jpg)
### MCU
| MCU | ATSAML10E16A |
|:------------- |:--------------------- |
| Family | ARM Cortex-M23 |
| Vendor | Microchip |
| RAM | 16KB |
| Flash | 64KB |
| Frequency | up to 32MHz |
| FPU | no |
| Timers | 3 (16-bit) |
| ADCs | 1x 12-bit (10 channels) |
| UARTs | max 3 (shared with SPI and I2C) |
| SPIs | max 3 (see UART) |
| I2Cs | max 3 (see UART) |
| Vcc | 1.6V - 3.6V |
| Datasheet | [Datasheet](http://ww1.microchip.com/downloads/en/DeviceDoc/SAM-L10L11%20Family-DataSheet%20-%20DS60001513B.pdf) |
| Board Manual | [Board Manual](http://ww1.microchip.com/downloads/en/DeviceDoc/70005359B.pdf)|
### User Interface
1 User button and 1 LED:
| Device | PIN |
|:------ |:--- |
| LED0 | PA07 |
| SW0 (button) | PA27 |
## Implementation Status
| Device | ID | Supported | Comments |
|:------------- |:------------- |:------------- |:------------- |
| MCU | saml10 | partly | PLL clock not implemented |
| Low-level driver | GPIO | yes | |
| | PWM | no | |
| | UART | yes | |
| | I2C | no | |
| | SPI | no | |
| | USB | no | |
| | RTT | no | |
| | RTC | no | |
| | RNG | no | |
| | Timer | yes | |
| | ADC | no | |
## Flashing the device
Connect the device to your Micro-USB cable.
The standard method for flashing RIOT to the saml10-xpro is using EDBG.
## Supported Toolchains
For using the saml10-xpro board we strongly recommend the usage of the
[GNU Tools for ARM Embedded Processors](https://launchpad.net/gcc-arm-embedded)
toolchain.
*/

View File

@ -0,0 +1,4 @@
MODULE = board
DIRS = $(RIOTBOARD)/common/saml1x
include $(RIOTBASE)/Makefile.base

View File

@ -0,0 +1 @@
include $(RIOTBOARD)/common/saml1x/Makefile.dep

View File

@ -0,0 +1 @@
include $(RIOTBOARD)/common/saml1x/Makefile.features

View File

@ -0,0 +1,5 @@
export CPU_FAM = saml11
export CPU_MODEL = saml11e16a
export CFLAGS += -D__SAML11E16A__
include $(RIOTBOARD)/common/saml1x/Makefile.include

View File

@ -0,0 +1,77 @@
/**
@defgroup boards_saml11-xpro Microchip SAML11 Xplained Pro
@ingroup boards
@brief Support for the Microchip SAML11 Xplained Pro board.
## Overview
The `SAML11 Xplained Pro` is an ultra-low power evaluation board by Microchip
featuring a ATSAML11E16A SoC. The SoC includes a SAML11 ARM Cortex-M23 micro-
controller. For programming the MCU comes with 16KB of RAM and 64KB of flash
memory. In addition, this SoC features the ARM TrustZone technology.
## Hardware
![saml11-xpro image](https://www.microchip.com/_ImagedCopy/SAML11%20Xpro%20Front%20Title.jpg)
### MCU
| MCU | ATSAML11E14A |
|:------------- |:--------------------- |
| Family | ARM Cortex-M23 |
| Vendor | Microchip |
| RAM | 16KB |
| Flash | 64KB |
| Frequency | up to 32MHz |
| FPU | no |
| Timers | 3 (16-bit) |
| ADCs | 1x 12-bit (10 channels) |
| UARTs | max 3 (shared with SPI and I2C) |
| SPIs | max 3 (see UART) |
| I2Cs | max 3 (see UART) |
| Vcc | 1.6V - 3.6V |
| Datasheet | [Datasheet](http://ww1.microchip.com/downloads/en/DeviceDoc/SAM-L10L11%20Family-DataSheet%20-%20DS60001513B.pdf) |
| Board Manual | [Board Manual](http://ww1.microchip.com/downloads/en/DeviceDoc/70005359B.pdf)|
### User Interface
1 User button and 1 LED:
| Device | PIN |
|:------ |:--- |
| LED0 | PA07 |
| SW0 (button) | PA27 |
## Implementation Status
| Device | ID | Supported | Comments |
|:------------- |:------------- |:------------- |:------------- |
| MCU | saml11 | partly | PLL clock not implemented |
| Low-level driver | GPIO | yes | |
| | PWM | no | |
| | UART | yes | |
| | I2C | no | |
| | SPI | no | |
| | USB | no | |
| | RTT | no | |
| | RTC | no | |
| | RNG | no | |
| | Timer | yes | |
| | ADC | no | |
## Flashing the device
Connect the device to your Micro-USB cable.
The standard method for flashing RIOT to the saml11-xpro is using EDBG.
## Supported Toolchains
For using the saml11-xpro board we strongly recommend the usage of the
[GNU Tools for ARM Embedded Processors](https://launchpad.net/gcc-arm-embedded)
toolchain.
*/

View File

@ -65,7 +65,8 @@ void cortexm_init(void)
/* configure the vector table location to internal flash */
#if defined(CPU_ARCH_CORTEX_M3) || defined(CPU_ARCH_CORTEX_M4) || \
defined(CPU_ARCH_CORTEX_M4F) || defined(CPU_ARCH_CORTEX_M7) || \
(defined(CPU_ARCH_CORTEX_M0PLUS) && (__VTOR_PRESENT == 1))
(defined(CPU_ARCH_CORTEX_M0PLUS) || defined(CPU_ARCH_CORTEX_M23) \
&& (__VTOR_PRESENT == 1))
SCB->VTOR = (uint32_t)&_isr_vectors;
#endif

View File

@ -59,7 +59,8 @@ bool mpu_enabled(void) {
}
int mpu_configure(uint_fast8_t region, uintptr_t base, uint_fast32_t attr) {
#if __MPU_PRESENT
/* Todo enable MPU support for Cortex-M23/M33 */
#if __MPU_PRESENT && !defined(CPU_ARCH_CORTEX_M23)
assert(region < MPU_NUM_REGIONS);
MPU->RNR = region;

View File

@ -187,7 +187,8 @@ char *thread_stack_init(thread_task_func_t task_func,
* For the Cortex-M3 and Cortex-M4 we write them continuously onto the stack
* as they can be read/written continuously by stack instructions. */
#if defined(CPU_ARCH_CORTEX_M0) || defined(CPU_ARCH_CORTEX_M0PLUS)
#if defined(CPU_ARCH_CORTEX_M0) || defined(CPU_ARCH_CORTEX_M0PLUS) \
|| defined(CPU_ARCH_CORTEX_M23)
/* start with r7 - r4 */
for (int i = 7; i >= 4; i--) {
stk--;
@ -286,7 +287,8 @@ void __attribute__((naked)) __attribute__((used)) isr_pendsv(void) {
/* {r0-r3,r12,LR,PC,xPSR,s0-s15,FPSCR} are saved automatically on exception entry */
".thumb_func \n"
"mrs r0, psp \n" /* get stack pointer from user mode */
#if defined(CPU_ARCH_CORTEX_M0) || defined(CPU_ARCH_CORTEX_M0PLUS)
#if defined(CPU_ARCH_CORTEX_M0) || defined(CPU_ARCH_CORTEX_M0PLUS) \
|| defined(CPU_ARCH_CORTEX_M23)
"mov r12, sp \n" /* remember the exception SP */
"mov sp, r0 \n" /* set user mode SP as active SP */
/* we can not push high registers directly, so we move R11-R8 into
@ -326,7 +328,8 @@ void __attribute__((naked)) __attribute__((used)) isr_svc(void) {
/* restore context and return from exception */
".thumb_func \n"
"context_restore: \n"
#if defined(CPU_ARCH_CORTEX_M0) || defined(CPU_ARCH_CORTEX_M0PLUS)
#if defined(CPU_ARCH_CORTEX_M0) || defined(CPU_ARCH_CORTEX_M0PLUS) \
|| defined(CPU_ARCH_CORTEX_M23)
"mov lr, sp \n" /* save MSR stack pointer for later */
"ldr r0, =sched_active_thread \n" /* load address of current TCB */
"ldr r0, [r0] \n" /* dereference TCB */

View File

@ -188,7 +188,8 @@ __attribute__((naked)) void hard_fault_default(void)
" use_psp: \n" /* else { */
"mrs r0, psp \n" /* r0 = psp */
" out: \n" /* } */
#if (__CORTEX_M == 0)
#if defined(CPU_ARCH_CORTEX_M0) || defined(CPU_ARCH_CORTEX_M0PLUS) \
|| defined(CPU_ARCH_CORTEX_M23)
"push {r4-r7} \n" /* save r4..r7 to the stack */
"mov r3, r8 \n" /* */
"mov r4, r9 \n" /* */
@ -208,9 +209,10 @@ __attribute__((naked)) void hard_fault_default(void)
);
}
#if (__CORTEX_M == 0)
/* Cortex-M0 and Cortex-M0+ lack the extended fault status registers found in
* Cortex-M3 and above. */
#if defined(CPU_ARCH_CORTEX_M0) || defined(CPU_ARCH_CORTEX_M0PLUS) \
|| defined(CPU_ARCH_CORTEX_M23)
/* Cortex-M0, Cortex-M0+ and Cortex-M23 lack the extended fault status
registers found in Cortex-M3 and above. */
#define CPU_HAS_EXTENDED_FAULT_REGISTERS 0
#else
#define CPU_HAS_EXTENDED_FAULT_REGISTERS 1
@ -261,11 +263,12 @@ __attribute__((used)) void hard_fault_handler(uint32_t* sp, uint32_t corrupted,
/* Reconstruct original stack pointer before fault occurred */
orig_sp = sp + 8;
#ifdef SCB_CCR_STKALIGN_Msk
if (psr & SCB_CCR_STKALIGN_Msk) {
/* Stack was not 8-byte aligned */
orig_sp += 1;
}
#endif /* SCB_CCR_STKALIGN_Msk */
puts("\nContext before hardfault:");
/* TODO: printf in ISR context might be a bad idea */
@ -315,7 +318,8 @@ __attribute__((used)) void hard_fault_handler(uint32_t* sp, uint32_t corrupted,
"mov lr, r1\n"
"mov sp, %[orig_sp]\n"
"mov r1, %[extra_stack]\n"
#if (__CORTEX_M == 0)
#if defined(CPU_ARCH_CORTEX_M0) || defined(CPU_ARCH_CORTEX_M0PLUS) \
|| defined(CPU_ARCH_CORTEX_M23)
"ldm r1!, {r4-r7}\n"
"mov r8, r4\n"
"mov r9, r5\n"

View File

@ -6,12 +6,18 @@ ifneq (,$(filter samd21g18a samd21j18a saml21j18b saml21j18a samr21g18a samr30g1
ROM_LEN ?= 0x40000
RAM_LEN ?= 0x8000
endif
ifneq (,$(filter saml10e16a saml11e16a,$(CPU_MODEL)))
ROM_LEN ?= 64K
RAM_LEN ?= 16K
endif
ROM_START_ADDR ?= 0x00000000
RAM_START_ADDR ?= 0x20000000
# this CPU implementation doesn't use CMSIS initialization
export CFLAGS += -DDONT_USE_CMSIS_INIT
export CFLAGS += -DDONT_USE_PREDEFINED_CORE_HANDLERS
export CFLAGS += -DDONT_USE_PREDEFINED_PERIPHERALS_HANDLERS
# For Cortex-M cpu we use the common cortexm.ld linker script
LINKER_SCRIPT ?= cortexm.ld

View File

@ -22,7 +22,11 @@
#define CPU_CONF_H
#include "cpu_conf_common.h"
#if defined(CPU_SAML1X)
#include "vendor/sam23.h"
#else
#include "vendor/sam0.h"
#endif
#ifdef __cplusplus
extern "C" {

View File

@ -69,7 +69,11 @@ typedef uint32_t gpio_t;
* @brief Macro for accessing GPIO pins
* @{
*/
#ifdef CPU_FAM_SAML11
#define GPIO_PIN(x, y) (((gpio_t)(&PORT_SEC->Group[x])) | y)
#else
#define GPIO_PIN(x, y) (((gpio_t)(&PORT->Group[x])) | y)
#endif
/**
* @brief Available ports on the SAMD21 & SAML21
@ -94,7 +98,11 @@ enum {
* @name Power mode configuration
* @{
*/
#ifdef CPU_FAM_SAML11
#define PM_NUM_MODES (2)
#else
#define PM_NUM_MODES (3)
#endif
/** @} */
#ifndef DOXYGEN
@ -127,6 +135,7 @@ typedef enum {
/**
* @brief Available MUX values for configuring a pin's alternate function
*/
#ifndef SAM_MUX_T
typedef enum {
GPIO_MUX_A = 0x0, /**< select peripheral function A */
GPIO_MUX_B = 0x1, /**< select peripheral function B */
@ -137,6 +146,7 @@ typedef enum {
GPIO_MUX_G = 0x6, /**< select peripheral function G */
GPIO_MUX_H = 0x7, /**< select peripheral function H */
} gpio_mux_t;
#endif
/**
* @brief Available values for SERCOM UART RX pad selection
@ -298,6 +308,8 @@ static inline int sercom_id(void *sercom)
{
#if defined(CPU_FAM_SAMD21)
return ((((uint32_t)sercom) >> 10) & 0x7) - 2;
#elif defined (CPU_FAM_SAML10) || defined (CPU_FAM_SAML11)
return ((((uint32_t)sercom) >> 10) & 0x7) - 1;
#elif defined(CPU_FAM_SAML21) || defined(CPU_FAM_SAMR30)
/* Left side handles SERCOM0-4 while right side handles unaligned address of SERCOM5 */
return ((((uint32_t)sercom) >> 10) & 0x7) + ((((uint32_t)sercom) >> 22) & 0x04);
@ -313,12 +325,15 @@ static inline void sercom_clk_en(void *sercom)
{
#if defined(CPU_FAM_SAMD21)
PM->APBCMASK.reg |= (PM_APBCMASK_SERCOM0 << sercom_id(sercom));
#elif defined(CPU_FAM_SAML21) || defined(CPU_FAM_SAMR30)
#else
if (sercom_id(sercom) < 5) {
MCLK->APBCMASK.reg |= (MCLK_APBCMASK_SERCOM0 << sercom_id(sercom));
} else {
}
#if defined(CPU_FAM_SAML21)
else {
MCLK->APBDMASK.reg |= (MCLK_APBDMASK_SERCOM5);
}
#endif /* CPU_FAM_SAML21 */
#endif
}
@ -331,12 +346,15 @@ static inline void sercom_clk_dis(void *sercom)
{
#if defined(CPU_FAM_SAMD21)
PM->APBCMASK.reg &= ~(PM_APBCMASK_SERCOM0 << sercom_id(sercom));
#elif defined(CPU_FAM_SAML21) || defined(CPU_FAM_SAMR30)
#else
if (sercom_id(sercom) < 5) {
MCLK->APBCMASK.reg &= ~(MCLK_APBCMASK_SERCOM0 << sercom_id(sercom));
} else {
}
#if defined (CPU_FAM_SAML21)
else {
MCLK->APBDMASK.reg &= ~(MCLK_APBDMASK_SERCOM5);
}
#endif /* CPU_FAM_SAML21 */
#endif
}
@ -352,14 +370,17 @@ static inline void sercom_set_gen(void *sercom, uint32_t gclk)
GCLK->CLKCTRL.reg = (GCLK_CLKCTRL_CLKEN | gclk |
(SERCOM0_GCLK_ID_CORE + sercom_id(sercom)));
while (GCLK->STATUS.reg & GCLK_STATUS_SYNCBUSY) {}
#elif defined(CPU_FAM_SAML21) || defined(CPU_FAM_SAMR30)
#else
if (sercom_id(sercom) < 5) {
GCLK->PCHCTRL[SERCOM0_GCLK_ID_CORE + sercom_id(sercom)].reg =
(GCLK_PCHCTRL_CHEN | gclk);
} else {
}
#if defined(CPU_FAM_SAML21)
else {
GCLK->PCHCTRL[SERCOM5_GCLK_ID_CORE].reg =
(GCLK_PCHCTRL_CHEN | gclk);
}
#endif /* CPU_FAM_SAML21 */
#endif
}

78
cpu/sam0_common/include/vendor/sam23.h vendored Normal file
View File

@ -0,0 +1,78 @@
/*
* Copyright (C) 2018 Mesotic SAS
*
* This file is subject to the terms and conditions of the GNU Lesser
* General Public License v2.1. See the file LICENSE in the top level
* directory for more details.
*/
/**
* @ingroup cpu_saml1x
* @{
*
* @file
* @brief Wrapper include file for including the specific
* SAML10/SAML11 vendor header
*
* @author Dylan Laduranty <dylan.laduranty@mesotic.com>
*/
#ifndef SAM23_H
#define SAM23_H
#ifdef __cplusplus
extern "C" {
#endif
/* Workaround redefinition of LITTLE_ENDIAN macro (part1) */
#ifdef LITTLE_ENDIAN
#define __TMP_LITTLE_ENDIAN LITTLE_ENDIAN
#undef LITTLE_ENDIAN
#endif
#if defined(CPU_MODEL_SAML10D14A)
#include "vendor/saml10/include/saml10d14a.h"
#elif defined(CPU_MODEL_SAML10D15A)
#include "vendor/saml10/include/saml10d15a.h"
#elif defined(CPU_MODEL_SAML10D16A)
#include "vendor/saml10/include/saml10d16a.h"
#elif defined(CPU_MODEL_SAML10E14A)
#include "vendor/saml10/include/saml10e14a.h"
#elif defined(CPU_MODEL_SAML10E15A)
#include "vendor/saml10/include/saml10e15a.h"
#elif defined(CPU_MODEL_SAML10E16A)
#include "vendor/saml10/include/saml10e16a.h"
#elif defined(CPU_MODEL_SAML11D14A)
#include "vendor/saml11/include/saml11d14a.h"
#elif defined(CPU_MODEL_SAML11D15A)
#include "vendor/saml11/include/saml11d15a.h"
#elif defined(CPU_MODEL_SAML11D16A)
#include "vendor/saml11/include/saml11d16a.h"
#elif defined(CPU_MODEL_SAML11E14A)
#include "vendor/saml11/include/saml11e14a.h"
#elif defined(CPU_MODEL_SAML11E15A)
#include "vendor/saml11/include/saml11e15a.h"
#elif defined(CPU_MODEL_SAML11E16A)
#include "vendor/saml11/include/saml11e16a.h"
#else
#error "Unsupported SAM23 variant."
#endif
/* Workaround redefinition of LITTLE_ENDIAN macro (part2) */
#ifdef LITTLE_ENDIAN
#undef LITTLE_ENDIAN
#endif
#ifdef __TMP_LITTLE_ENDIAN
#define LITTLE_ENDIAN __TMP_LITTLE_ENDIAN
#endif
#ifdef __cplusplus
}
#endif
#endif /* SAM23_H */
/** @} */

View File

@ -0,0 +1,64 @@
/**
* \file
*
* \brief Component version header file
*
* Copyright (c) 2018 Atmel Corporation, a wholly owned subsidiary of Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
#ifndef _COMPONENT_VERSION_H_INCLUDED
#define _COMPONENT_VERSION_H_INCLUDED
#define COMPONENT_VERSION_MAJOR 1
#define COMPONENT_VERSION_MINOR 0
//
// The COMPONENT_VERSION define is composed of the major and the minor version number.
//
// The last four digits of the COMPONENT_VERSION is the minor version with leading zeros.
// The rest of the COMPONENT_VERSION is the major version.
//
#define COMPONENT_VERSION 10000
//
// The build number does not refer to the component, but to the build number
// of the device pack that provides the component.
//
#define BUILD_NUMBER 142
//
// The COMPONENT_VERSION_STRING is a string (enclosed in ") that can be used for logging or embedding.
//
#define COMPONENT_VERSION_STRING "1.0"
//
// The COMPONENT_DATE_STRING contains a timestamp of when the pack was generated.
//
// The COMPONENT_DATE_STRING is written out using the following strftime pattern.
//
// "%Y-%m-%d %H:%M:%S"
//
//
#define COMPONENT_DATE_STRING "2018-09-06 14:18:38"
#endif/* #ifndef _COMPONENT_VERSION_H_INCLUDED */

View File

@ -0,0 +1,661 @@
/**
* \file
*
* \brief Component description for AC
*
* Copyright (c) 2018 Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* 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
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
/* file generated from device description version 2018-08-31T13:51:50Z */
#ifndef _SAML10_AC_COMPONENT_H_
#define _SAML10_AC_COMPONENT_H_
#define _SAML10_AC_COMPONENT_ /**< \deprecated Backward compatibility for ASF */
/** \addtogroup SAML_SAML10 Analog Comparators
* @{
*/
/* ========================================================================== */
/** SOFTWARE API DEFINITION FOR AC */
/* ========================================================================== */
#define AC_U2245 /**< (AC) Module ID */
#define REV_AC 0x102 /**< (AC) Module revision */
/* -------- AC_CTRLA : (AC Offset: 0x00) (R/W 8) Control A -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t SWRST:1; /**< bit: 0 Software Reset */
uint8_t ENABLE:1; /**< bit: 1 Enable */
uint8_t :6; /**< bit: 2..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} AC_CTRLA_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define AC_CTRLA_OFFSET (0x00) /**< (AC_CTRLA) Control A Offset */
#define AC_CTRLA_RESETVALUE _U_(0x00) /**< (AC_CTRLA) Control A Reset Value */
#define AC_CTRLA_SWRST_Pos 0 /**< (AC_CTRLA) Software Reset Position */
#define AC_CTRLA_SWRST_Msk (_U_(0x1) << AC_CTRLA_SWRST_Pos) /**< (AC_CTRLA) Software Reset Mask */
#define AC_CTRLA_SWRST AC_CTRLA_SWRST_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use AC_CTRLA_SWRST_Msk instead */
#define AC_CTRLA_ENABLE_Pos 1 /**< (AC_CTRLA) Enable Position */
#define AC_CTRLA_ENABLE_Msk (_U_(0x1) << AC_CTRLA_ENABLE_Pos) /**< (AC_CTRLA) Enable Mask */
#define AC_CTRLA_ENABLE AC_CTRLA_ENABLE_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use AC_CTRLA_ENABLE_Msk instead */
#define AC_CTRLA_MASK _U_(0x03) /**< \deprecated (AC_CTRLA) Register MASK (Use AC_CTRLA_Msk instead) */
#define AC_CTRLA_Msk _U_(0x03) /**< (AC_CTRLA) Register Mask */
/* -------- AC_CTRLB : (AC Offset: 0x01) (/W 8) Control B -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t START0:1; /**< bit: 0 Comparator 0 Start Comparison */
uint8_t START1:1; /**< bit: 1 Comparator 1 Start Comparison */
uint8_t :6; /**< bit: 2..7 Reserved */
} bit; /**< Structure used for bit access */
struct {
uint8_t START:2; /**< bit: 0..1 Comparator x Start Comparison */
uint8_t :6; /**< bit: 2..7 Reserved */
} vec; /**< Structure used for vec access */
uint8_t reg; /**< Type used for register access */
} AC_CTRLB_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define AC_CTRLB_OFFSET (0x01) /**< (AC_CTRLB) Control B Offset */
#define AC_CTRLB_RESETVALUE _U_(0x00) /**< (AC_CTRLB) Control B Reset Value */
#define AC_CTRLB_START0_Pos 0 /**< (AC_CTRLB) Comparator 0 Start Comparison Position */
#define AC_CTRLB_START0_Msk (_U_(0x1) << AC_CTRLB_START0_Pos) /**< (AC_CTRLB) Comparator 0 Start Comparison Mask */
#define AC_CTRLB_START0 AC_CTRLB_START0_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use AC_CTRLB_START0_Msk instead */
#define AC_CTRLB_START1_Pos 1 /**< (AC_CTRLB) Comparator 1 Start Comparison Position */
#define AC_CTRLB_START1_Msk (_U_(0x1) << AC_CTRLB_START1_Pos) /**< (AC_CTRLB) Comparator 1 Start Comparison Mask */
#define AC_CTRLB_START1 AC_CTRLB_START1_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use AC_CTRLB_START1_Msk instead */
#define AC_CTRLB_MASK _U_(0x03) /**< \deprecated (AC_CTRLB) Register MASK (Use AC_CTRLB_Msk instead) */
#define AC_CTRLB_Msk _U_(0x03) /**< (AC_CTRLB) Register Mask */
#define AC_CTRLB_START_Pos 0 /**< (AC_CTRLB Position) Comparator x Start Comparison */
#define AC_CTRLB_START_Msk (_U_(0x3) << AC_CTRLB_START_Pos) /**< (AC_CTRLB Mask) START */
#define AC_CTRLB_START(value) (AC_CTRLB_START_Msk & ((value) << AC_CTRLB_START_Pos))
/* -------- AC_EVCTRL : (AC Offset: 0x02) (R/W 16) Event Control -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint16_t COMPEO0:1; /**< bit: 0 Comparator 0 Event Output Enable */
uint16_t COMPEO1:1; /**< bit: 1 Comparator 1 Event Output Enable */
uint16_t :2; /**< bit: 2..3 Reserved */
uint16_t WINEO0:1; /**< bit: 4 Window 0 Event Output Enable */
uint16_t :3; /**< bit: 5..7 Reserved */
uint16_t COMPEI0:1; /**< bit: 8 Comparator 0 Event Input Enable */
uint16_t COMPEI1:1; /**< bit: 9 Comparator 1 Event Input Enable */
uint16_t :2; /**< bit: 10..11 Reserved */
uint16_t INVEI0:1; /**< bit: 12 Comparator 0 Input Event Invert Enable */
uint16_t INVEI1:1; /**< bit: 13 Comparator 1 Input Event Invert Enable */
uint16_t :2; /**< bit: 14..15 Reserved */
} bit; /**< Structure used for bit access */
struct {
uint16_t COMPEO:2; /**< bit: 0..1 Comparator x Event Output Enable */
uint16_t :2; /**< bit: 2..3 Reserved */
uint16_t WINEO:1; /**< bit: 4 Window x Event Output Enable */
uint16_t :3; /**< bit: 5..7 Reserved */
uint16_t COMPEI:2; /**< bit: 8..9 Comparator x Event Input Enable */
uint16_t :2; /**< bit: 10..11 Reserved */
uint16_t INVEI:2; /**< bit: 12..13 Comparator x Input Event Invert Enable */
uint16_t :2; /**< bit: 14..15 Reserved */
} vec; /**< Structure used for vec access */
uint16_t reg; /**< Type used for register access */
} AC_EVCTRL_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define AC_EVCTRL_OFFSET (0x02) /**< (AC_EVCTRL) Event Control Offset */
#define AC_EVCTRL_RESETVALUE _U_(0x00) /**< (AC_EVCTRL) Event Control Reset Value */
#define AC_EVCTRL_COMPEO0_Pos 0 /**< (AC_EVCTRL) Comparator 0 Event Output Enable Position */
#define AC_EVCTRL_COMPEO0_Msk (_U_(0x1) << AC_EVCTRL_COMPEO0_Pos) /**< (AC_EVCTRL) Comparator 0 Event Output Enable Mask */
#define AC_EVCTRL_COMPEO0 AC_EVCTRL_COMPEO0_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use AC_EVCTRL_COMPEO0_Msk instead */
#define AC_EVCTRL_COMPEO1_Pos 1 /**< (AC_EVCTRL) Comparator 1 Event Output Enable Position */
#define AC_EVCTRL_COMPEO1_Msk (_U_(0x1) << AC_EVCTRL_COMPEO1_Pos) /**< (AC_EVCTRL) Comparator 1 Event Output Enable Mask */
#define AC_EVCTRL_COMPEO1 AC_EVCTRL_COMPEO1_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use AC_EVCTRL_COMPEO1_Msk instead */
#define AC_EVCTRL_WINEO0_Pos 4 /**< (AC_EVCTRL) Window 0 Event Output Enable Position */
#define AC_EVCTRL_WINEO0_Msk (_U_(0x1) << AC_EVCTRL_WINEO0_Pos) /**< (AC_EVCTRL) Window 0 Event Output Enable Mask */
#define AC_EVCTRL_WINEO0 AC_EVCTRL_WINEO0_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use AC_EVCTRL_WINEO0_Msk instead */
#define AC_EVCTRL_COMPEI0_Pos 8 /**< (AC_EVCTRL) Comparator 0 Event Input Enable Position */
#define AC_EVCTRL_COMPEI0_Msk (_U_(0x1) << AC_EVCTRL_COMPEI0_Pos) /**< (AC_EVCTRL) Comparator 0 Event Input Enable Mask */
#define AC_EVCTRL_COMPEI0 AC_EVCTRL_COMPEI0_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use AC_EVCTRL_COMPEI0_Msk instead */
#define AC_EVCTRL_COMPEI1_Pos 9 /**< (AC_EVCTRL) Comparator 1 Event Input Enable Position */
#define AC_EVCTRL_COMPEI1_Msk (_U_(0x1) << AC_EVCTRL_COMPEI1_Pos) /**< (AC_EVCTRL) Comparator 1 Event Input Enable Mask */
#define AC_EVCTRL_COMPEI1 AC_EVCTRL_COMPEI1_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use AC_EVCTRL_COMPEI1_Msk instead */
#define AC_EVCTRL_INVEI0_Pos 12 /**< (AC_EVCTRL) Comparator 0 Input Event Invert Enable Position */
#define AC_EVCTRL_INVEI0_Msk (_U_(0x1) << AC_EVCTRL_INVEI0_Pos) /**< (AC_EVCTRL) Comparator 0 Input Event Invert Enable Mask */
#define AC_EVCTRL_INVEI0 AC_EVCTRL_INVEI0_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use AC_EVCTRL_INVEI0_Msk instead */
#define AC_EVCTRL_INVEI1_Pos 13 /**< (AC_EVCTRL) Comparator 1 Input Event Invert Enable Position */
#define AC_EVCTRL_INVEI1_Msk (_U_(0x1) << AC_EVCTRL_INVEI1_Pos) /**< (AC_EVCTRL) Comparator 1 Input Event Invert Enable Mask */
#define AC_EVCTRL_INVEI1 AC_EVCTRL_INVEI1_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use AC_EVCTRL_INVEI1_Msk instead */
#define AC_EVCTRL_MASK _U_(0x3313) /**< \deprecated (AC_EVCTRL) Register MASK (Use AC_EVCTRL_Msk instead) */
#define AC_EVCTRL_Msk _U_(0x3313) /**< (AC_EVCTRL) Register Mask */
#define AC_EVCTRL_COMPEO_Pos 0 /**< (AC_EVCTRL Position) Comparator x Event Output Enable */
#define AC_EVCTRL_COMPEO_Msk (_U_(0x3) << AC_EVCTRL_COMPEO_Pos) /**< (AC_EVCTRL Mask) COMPEO */
#define AC_EVCTRL_COMPEO(value) (AC_EVCTRL_COMPEO_Msk & ((value) << AC_EVCTRL_COMPEO_Pos))
#define AC_EVCTRL_WINEO_Pos 4 /**< (AC_EVCTRL Position) Window x Event Output Enable */
#define AC_EVCTRL_WINEO_Msk (_U_(0x1) << AC_EVCTRL_WINEO_Pos) /**< (AC_EVCTRL Mask) WINEO */
#define AC_EVCTRL_WINEO(value) (AC_EVCTRL_WINEO_Msk & ((value) << AC_EVCTRL_WINEO_Pos))
#define AC_EVCTRL_COMPEI_Pos 8 /**< (AC_EVCTRL Position) Comparator x Event Input Enable */
#define AC_EVCTRL_COMPEI_Msk (_U_(0x3) << AC_EVCTRL_COMPEI_Pos) /**< (AC_EVCTRL Mask) COMPEI */
#define AC_EVCTRL_COMPEI(value) (AC_EVCTRL_COMPEI_Msk & ((value) << AC_EVCTRL_COMPEI_Pos))
#define AC_EVCTRL_INVEI_Pos 12 /**< (AC_EVCTRL Position) Comparator x Input Event Invert Enable */
#define AC_EVCTRL_INVEI_Msk (_U_(0x3) << AC_EVCTRL_INVEI_Pos) /**< (AC_EVCTRL Mask) INVEI */
#define AC_EVCTRL_INVEI(value) (AC_EVCTRL_INVEI_Msk & ((value) << AC_EVCTRL_INVEI_Pos))
/* -------- AC_INTENCLR : (AC Offset: 0x04) (R/W 8) Interrupt Enable Clear -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t COMP0:1; /**< bit: 0 Comparator 0 Interrupt Enable */
uint8_t COMP1:1; /**< bit: 1 Comparator 1 Interrupt Enable */
uint8_t :2; /**< bit: 2..3 Reserved */
uint8_t WIN0:1; /**< bit: 4 Window 0 Interrupt Enable */
uint8_t :3; /**< bit: 5..7 Reserved */
} bit; /**< Structure used for bit access */
struct {
uint8_t COMP:2; /**< bit: 0..1 Comparator x Interrupt Enable */
uint8_t :2; /**< bit: 2..3 Reserved */
uint8_t WIN:1; /**< bit: 4 Window x Interrupt Enable */
uint8_t :3; /**< bit: 5..7 Reserved */
} vec; /**< Structure used for vec access */
uint8_t reg; /**< Type used for register access */
} AC_INTENCLR_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define AC_INTENCLR_OFFSET (0x04) /**< (AC_INTENCLR) Interrupt Enable Clear Offset */
#define AC_INTENCLR_RESETVALUE _U_(0x00) /**< (AC_INTENCLR) Interrupt Enable Clear Reset Value */
#define AC_INTENCLR_COMP0_Pos 0 /**< (AC_INTENCLR) Comparator 0 Interrupt Enable Position */
#define AC_INTENCLR_COMP0_Msk (_U_(0x1) << AC_INTENCLR_COMP0_Pos) /**< (AC_INTENCLR) Comparator 0 Interrupt Enable Mask */
#define AC_INTENCLR_COMP0 AC_INTENCLR_COMP0_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use AC_INTENCLR_COMP0_Msk instead */
#define AC_INTENCLR_COMP1_Pos 1 /**< (AC_INTENCLR) Comparator 1 Interrupt Enable Position */
#define AC_INTENCLR_COMP1_Msk (_U_(0x1) << AC_INTENCLR_COMP1_Pos) /**< (AC_INTENCLR) Comparator 1 Interrupt Enable Mask */
#define AC_INTENCLR_COMP1 AC_INTENCLR_COMP1_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use AC_INTENCLR_COMP1_Msk instead */
#define AC_INTENCLR_WIN0_Pos 4 /**< (AC_INTENCLR) Window 0 Interrupt Enable Position */
#define AC_INTENCLR_WIN0_Msk (_U_(0x1) << AC_INTENCLR_WIN0_Pos) /**< (AC_INTENCLR) Window 0 Interrupt Enable Mask */
#define AC_INTENCLR_WIN0 AC_INTENCLR_WIN0_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use AC_INTENCLR_WIN0_Msk instead */
#define AC_INTENCLR_MASK _U_(0x13) /**< \deprecated (AC_INTENCLR) Register MASK (Use AC_INTENCLR_Msk instead) */
#define AC_INTENCLR_Msk _U_(0x13) /**< (AC_INTENCLR) Register Mask */
#define AC_INTENCLR_COMP_Pos 0 /**< (AC_INTENCLR Position) Comparator x Interrupt Enable */
#define AC_INTENCLR_COMP_Msk (_U_(0x3) << AC_INTENCLR_COMP_Pos) /**< (AC_INTENCLR Mask) COMP */
#define AC_INTENCLR_COMP(value) (AC_INTENCLR_COMP_Msk & ((value) << AC_INTENCLR_COMP_Pos))
#define AC_INTENCLR_WIN_Pos 4 /**< (AC_INTENCLR Position) Window x Interrupt Enable */
#define AC_INTENCLR_WIN_Msk (_U_(0x1) << AC_INTENCLR_WIN_Pos) /**< (AC_INTENCLR Mask) WIN */
#define AC_INTENCLR_WIN(value) (AC_INTENCLR_WIN_Msk & ((value) << AC_INTENCLR_WIN_Pos))
/* -------- AC_INTENSET : (AC Offset: 0x05) (R/W 8) Interrupt Enable Set -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t COMP0:1; /**< bit: 0 Comparator 0 Interrupt Enable */
uint8_t COMP1:1; /**< bit: 1 Comparator 1 Interrupt Enable */
uint8_t :2; /**< bit: 2..3 Reserved */
uint8_t WIN0:1; /**< bit: 4 Window 0 Interrupt Enable */
uint8_t :3; /**< bit: 5..7 Reserved */
} bit; /**< Structure used for bit access */
struct {
uint8_t COMP:2; /**< bit: 0..1 Comparator x Interrupt Enable */
uint8_t :2; /**< bit: 2..3 Reserved */
uint8_t WIN:1; /**< bit: 4 Window x Interrupt Enable */
uint8_t :3; /**< bit: 5..7 Reserved */
} vec; /**< Structure used for vec access */
uint8_t reg; /**< Type used for register access */
} AC_INTENSET_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define AC_INTENSET_OFFSET (0x05) /**< (AC_INTENSET) Interrupt Enable Set Offset */
#define AC_INTENSET_RESETVALUE _U_(0x00) /**< (AC_INTENSET) Interrupt Enable Set Reset Value */
#define AC_INTENSET_COMP0_Pos 0 /**< (AC_INTENSET) Comparator 0 Interrupt Enable Position */
#define AC_INTENSET_COMP0_Msk (_U_(0x1) << AC_INTENSET_COMP0_Pos) /**< (AC_INTENSET) Comparator 0 Interrupt Enable Mask */
#define AC_INTENSET_COMP0 AC_INTENSET_COMP0_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use AC_INTENSET_COMP0_Msk instead */
#define AC_INTENSET_COMP1_Pos 1 /**< (AC_INTENSET) Comparator 1 Interrupt Enable Position */
#define AC_INTENSET_COMP1_Msk (_U_(0x1) << AC_INTENSET_COMP1_Pos) /**< (AC_INTENSET) Comparator 1 Interrupt Enable Mask */
#define AC_INTENSET_COMP1 AC_INTENSET_COMP1_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use AC_INTENSET_COMP1_Msk instead */
#define AC_INTENSET_WIN0_Pos 4 /**< (AC_INTENSET) Window 0 Interrupt Enable Position */
#define AC_INTENSET_WIN0_Msk (_U_(0x1) << AC_INTENSET_WIN0_Pos) /**< (AC_INTENSET) Window 0 Interrupt Enable Mask */
#define AC_INTENSET_WIN0 AC_INTENSET_WIN0_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use AC_INTENSET_WIN0_Msk instead */
#define AC_INTENSET_MASK _U_(0x13) /**< \deprecated (AC_INTENSET) Register MASK (Use AC_INTENSET_Msk instead) */
#define AC_INTENSET_Msk _U_(0x13) /**< (AC_INTENSET) Register Mask */
#define AC_INTENSET_COMP_Pos 0 /**< (AC_INTENSET Position) Comparator x Interrupt Enable */
#define AC_INTENSET_COMP_Msk (_U_(0x3) << AC_INTENSET_COMP_Pos) /**< (AC_INTENSET Mask) COMP */
#define AC_INTENSET_COMP(value) (AC_INTENSET_COMP_Msk & ((value) << AC_INTENSET_COMP_Pos))
#define AC_INTENSET_WIN_Pos 4 /**< (AC_INTENSET Position) Window x Interrupt Enable */
#define AC_INTENSET_WIN_Msk (_U_(0x1) << AC_INTENSET_WIN_Pos) /**< (AC_INTENSET Mask) WIN */
#define AC_INTENSET_WIN(value) (AC_INTENSET_WIN_Msk & ((value) << AC_INTENSET_WIN_Pos))
/* -------- AC_INTFLAG : (AC Offset: 0x06) (R/W 8) Interrupt Flag Status and Clear -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union { // __I to avoid read-modify-write on write-to-clear register
struct {
__I uint8_t COMP0:1; /**< bit: 0 Comparator 0 */
__I uint8_t COMP1:1; /**< bit: 1 Comparator 1 */
__I uint8_t :2; /**< bit: 2..3 Reserved */
__I uint8_t WIN0:1; /**< bit: 4 Window 0 */
__I uint8_t :3; /**< bit: 5..7 Reserved */
} bit; /**< Structure used for bit access */
struct {
__I uint8_t COMP:2; /**< bit: 0..1 Comparator x */
__I uint8_t :2; /**< bit: 2..3 Reserved */
__I uint8_t WIN:1; /**< bit: 4 Window x */
__I uint8_t :3; /**< bit: 5..7 Reserved */
} vec; /**< Structure used for vec access */
uint8_t reg; /**< Type used for register access */
} AC_INTFLAG_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define AC_INTFLAG_OFFSET (0x06) /**< (AC_INTFLAG) Interrupt Flag Status and Clear Offset */
#define AC_INTFLAG_RESETVALUE _U_(0x00) /**< (AC_INTFLAG) Interrupt Flag Status and Clear Reset Value */
#define AC_INTFLAG_COMP0_Pos 0 /**< (AC_INTFLAG) Comparator 0 Position */
#define AC_INTFLAG_COMP0_Msk (_U_(0x1) << AC_INTFLAG_COMP0_Pos) /**< (AC_INTFLAG) Comparator 0 Mask */
#define AC_INTFLAG_COMP0 AC_INTFLAG_COMP0_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use AC_INTFLAG_COMP0_Msk instead */
#define AC_INTFLAG_COMP1_Pos 1 /**< (AC_INTFLAG) Comparator 1 Position */
#define AC_INTFLAG_COMP1_Msk (_U_(0x1) << AC_INTFLAG_COMP1_Pos) /**< (AC_INTFLAG) Comparator 1 Mask */
#define AC_INTFLAG_COMP1 AC_INTFLAG_COMP1_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use AC_INTFLAG_COMP1_Msk instead */
#define AC_INTFLAG_WIN0_Pos 4 /**< (AC_INTFLAG) Window 0 Position */
#define AC_INTFLAG_WIN0_Msk (_U_(0x1) << AC_INTFLAG_WIN0_Pos) /**< (AC_INTFLAG) Window 0 Mask */
#define AC_INTFLAG_WIN0 AC_INTFLAG_WIN0_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use AC_INTFLAG_WIN0_Msk instead */
#define AC_INTFLAG_MASK _U_(0x13) /**< \deprecated (AC_INTFLAG) Register MASK (Use AC_INTFLAG_Msk instead) */
#define AC_INTFLAG_Msk _U_(0x13) /**< (AC_INTFLAG) Register Mask */
#define AC_INTFLAG_COMP_Pos 0 /**< (AC_INTFLAG Position) Comparator x */
#define AC_INTFLAG_COMP_Msk (_U_(0x3) << AC_INTFLAG_COMP_Pos) /**< (AC_INTFLAG Mask) COMP */
#define AC_INTFLAG_COMP(value) (AC_INTFLAG_COMP_Msk & ((value) << AC_INTFLAG_COMP_Pos))
#define AC_INTFLAG_WIN_Pos 4 /**< (AC_INTFLAG Position) Window x */
#define AC_INTFLAG_WIN_Msk (_U_(0x1) << AC_INTFLAG_WIN_Pos) /**< (AC_INTFLAG Mask) WIN */
#define AC_INTFLAG_WIN(value) (AC_INTFLAG_WIN_Msk & ((value) << AC_INTFLAG_WIN_Pos))
/* -------- AC_STATUSA : (AC Offset: 0x07) (R/ 8) Status A -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t STATE0:1; /**< bit: 0 Comparator 0 Current State */
uint8_t STATE1:1; /**< bit: 1 Comparator 1 Current State */
uint8_t :2; /**< bit: 2..3 Reserved */
uint8_t WSTATE0:2; /**< bit: 4..5 Window 0 Current State */
uint8_t :2; /**< bit: 6..7 Reserved */
} bit; /**< Structure used for bit access */
struct {
uint8_t STATE:2; /**< bit: 0..1 Comparator x Current State */
uint8_t :6; /**< bit: 2..7 Reserved */
} vec; /**< Structure used for vec access */
uint8_t reg; /**< Type used for register access */
} AC_STATUSA_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define AC_STATUSA_OFFSET (0x07) /**< (AC_STATUSA) Status A Offset */
#define AC_STATUSA_RESETVALUE _U_(0x00) /**< (AC_STATUSA) Status A Reset Value */
#define AC_STATUSA_STATE0_Pos 0 /**< (AC_STATUSA) Comparator 0 Current State Position */
#define AC_STATUSA_STATE0_Msk (_U_(0x1) << AC_STATUSA_STATE0_Pos) /**< (AC_STATUSA) Comparator 0 Current State Mask */
#define AC_STATUSA_STATE0 AC_STATUSA_STATE0_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use AC_STATUSA_STATE0_Msk instead */
#define AC_STATUSA_STATE1_Pos 1 /**< (AC_STATUSA) Comparator 1 Current State Position */
#define AC_STATUSA_STATE1_Msk (_U_(0x1) << AC_STATUSA_STATE1_Pos) /**< (AC_STATUSA) Comparator 1 Current State Mask */
#define AC_STATUSA_STATE1 AC_STATUSA_STATE1_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use AC_STATUSA_STATE1_Msk instead */
#define AC_STATUSA_WSTATE0_Pos 4 /**< (AC_STATUSA) Window 0 Current State Position */
#define AC_STATUSA_WSTATE0_Msk (_U_(0x3) << AC_STATUSA_WSTATE0_Pos) /**< (AC_STATUSA) Window 0 Current State Mask */
#define AC_STATUSA_WSTATE0(value) (AC_STATUSA_WSTATE0_Msk & ((value) << AC_STATUSA_WSTATE0_Pos))
#define AC_STATUSA_WSTATE0_ABOVE_Val _U_(0x0) /**< (AC_STATUSA) Signal is above window */
#define AC_STATUSA_WSTATE0_INSIDE_Val _U_(0x1) /**< (AC_STATUSA) Signal is inside window */
#define AC_STATUSA_WSTATE0_BELOW_Val _U_(0x2) /**< (AC_STATUSA) Signal is below window */
#define AC_STATUSA_WSTATE0_ABOVE (AC_STATUSA_WSTATE0_ABOVE_Val << AC_STATUSA_WSTATE0_Pos) /**< (AC_STATUSA) Signal is above window Position */
#define AC_STATUSA_WSTATE0_INSIDE (AC_STATUSA_WSTATE0_INSIDE_Val << AC_STATUSA_WSTATE0_Pos) /**< (AC_STATUSA) Signal is inside window Position */
#define AC_STATUSA_WSTATE0_BELOW (AC_STATUSA_WSTATE0_BELOW_Val << AC_STATUSA_WSTATE0_Pos) /**< (AC_STATUSA) Signal is below window Position */
#define AC_STATUSA_MASK _U_(0x33) /**< \deprecated (AC_STATUSA) Register MASK (Use AC_STATUSA_Msk instead) */
#define AC_STATUSA_Msk _U_(0x33) /**< (AC_STATUSA) Register Mask */
#define AC_STATUSA_STATE_Pos 0 /**< (AC_STATUSA Position) Comparator x Current State */
#define AC_STATUSA_STATE_Msk (_U_(0x3) << AC_STATUSA_STATE_Pos) /**< (AC_STATUSA Mask) STATE */
#define AC_STATUSA_STATE(value) (AC_STATUSA_STATE_Msk & ((value) << AC_STATUSA_STATE_Pos))
/* -------- AC_STATUSB : (AC Offset: 0x08) (R/ 8) Status B -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t READY0:1; /**< bit: 0 Comparator 0 Ready */
uint8_t READY1:1; /**< bit: 1 Comparator 1 Ready */
uint8_t :6; /**< bit: 2..7 Reserved */
} bit; /**< Structure used for bit access */
struct {
uint8_t READY:2; /**< bit: 0..1 Comparator x Ready */
uint8_t :6; /**< bit: 2..7 Reserved */
} vec; /**< Structure used for vec access */
uint8_t reg; /**< Type used for register access */
} AC_STATUSB_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define AC_STATUSB_OFFSET (0x08) /**< (AC_STATUSB) Status B Offset */
#define AC_STATUSB_RESETVALUE _U_(0x00) /**< (AC_STATUSB) Status B Reset Value */
#define AC_STATUSB_READY0_Pos 0 /**< (AC_STATUSB) Comparator 0 Ready Position */
#define AC_STATUSB_READY0_Msk (_U_(0x1) << AC_STATUSB_READY0_Pos) /**< (AC_STATUSB) Comparator 0 Ready Mask */
#define AC_STATUSB_READY0 AC_STATUSB_READY0_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use AC_STATUSB_READY0_Msk instead */
#define AC_STATUSB_READY1_Pos 1 /**< (AC_STATUSB) Comparator 1 Ready Position */
#define AC_STATUSB_READY1_Msk (_U_(0x1) << AC_STATUSB_READY1_Pos) /**< (AC_STATUSB) Comparator 1 Ready Mask */
#define AC_STATUSB_READY1 AC_STATUSB_READY1_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use AC_STATUSB_READY1_Msk instead */
#define AC_STATUSB_MASK _U_(0x03) /**< \deprecated (AC_STATUSB) Register MASK (Use AC_STATUSB_Msk instead) */
#define AC_STATUSB_Msk _U_(0x03) /**< (AC_STATUSB) Register Mask */
#define AC_STATUSB_READY_Pos 0 /**< (AC_STATUSB Position) Comparator x Ready */
#define AC_STATUSB_READY_Msk (_U_(0x3) << AC_STATUSB_READY_Pos) /**< (AC_STATUSB Mask) READY */
#define AC_STATUSB_READY(value) (AC_STATUSB_READY_Msk & ((value) << AC_STATUSB_READY_Pos))
/* -------- AC_DBGCTRL : (AC Offset: 0x09) (R/W 8) Debug Control -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t DBGRUN:1; /**< bit: 0 Debug Run */
uint8_t :7; /**< bit: 1..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} AC_DBGCTRL_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define AC_DBGCTRL_OFFSET (0x09) /**< (AC_DBGCTRL) Debug Control Offset */
#define AC_DBGCTRL_RESETVALUE _U_(0x00) /**< (AC_DBGCTRL) Debug Control Reset Value */
#define AC_DBGCTRL_DBGRUN_Pos 0 /**< (AC_DBGCTRL) Debug Run Position */
#define AC_DBGCTRL_DBGRUN_Msk (_U_(0x1) << AC_DBGCTRL_DBGRUN_Pos) /**< (AC_DBGCTRL) Debug Run Mask */
#define AC_DBGCTRL_DBGRUN AC_DBGCTRL_DBGRUN_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use AC_DBGCTRL_DBGRUN_Msk instead */
#define AC_DBGCTRL_MASK _U_(0x01) /**< \deprecated (AC_DBGCTRL) Register MASK (Use AC_DBGCTRL_Msk instead) */
#define AC_DBGCTRL_Msk _U_(0x01) /**< (AC_DBGCTRL) Register Mask */
/* -------- AC_WINCTRL : (AC Offset: 0x0a) (R/W 8) Window Control -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t WEN0:1; /**< bit: 0 Window 0 Mode Enable */
uint8_t WINTSEL0:2; /**< bit: 1..2 Window 0 Interrupt Selection */
uint8_t :5; /**< bit: 3..7 Reserved */
} bit; /**< Structure used for bit access */
struct {
uint8_t WEN:1; /**< bit: 0 Window x Mode Enable */
uint8_t :7; /**< bit: 1..7 Reserved */
} vec; /**< Structure used for vec access */
uint8_t reg; /**< Type used for register access */
} AC_WINCTRL_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define AC_WINCTRL_OFFSET (0x0A) /**< (AC_WINCTRL) Window Control Offset */
#define AC_WINCTRL_RESETVALUE _U_(0x00) /**< (AC_WINCTRL) Window Control Reset Value */
#define AC_WINCTRL_WEN0_Pos 0 /**< (AC_WINCTRL) Window 0 Mode Enable Position */
#define AC_WINCTRL_WEN0_Msk (_U_(0x1) << AC_WINCTRL_WEN0_Pos) /**< (AC_WINCTRL) Window 0 Mode Enable Mask */
#define AC_WINCTRL_WEN0 AC_WINCTRL_WEN0_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use AC_WINCTRL_WEN0_Msk instead */
#define AC_WINCTRL_WINTSEL0_Pos 1 /**< (AC_WINCTRL) Window 0 Interrupt Selection Position */
#define AC_WINCTRL_WINTSEL0_Msk (_U_(0x3) << AC_WINCTRL_WINTSEL0_Pos) /**< (AC_WINCTRL) Window 0 Interrupt Selection Mask */
#define AC_WINCTRL_WINTSEL0(value) (AC_WINCTRL_WINTSEL0_Msk & ((value) << AC_WINCTRL_WINTSEL0_Pos))
#define AC_WINCTRL_WINTSEL0_ABOVE_Val _U_(0x0) /**< (AC_WINCTRL) Interrupt on signal above window */
#define AC_WINCTRL_WINTSEL0_INSIDE_Val _U_(0x1) /**< (AC_WINCTRL) Interrupt on signal inside window */
#define AC_WINCTRL_WINTSEL0_BELOW_Val _U_(0x2) /**< (AC_WINCTRL) Interrupt on signal below window */
#define AC_WINCTRL_WINTSEL0_OUTSIDE_Val _U_(0x3) /**< (AC_WINCTRL) Interrupt on signal outside window */
#define AC_WINCTRL_WINTSEL0_ABOVE (AC_WINCTRL_WINTSEL0_ABOVE_Val << AC_WINCTRL_WINTSEL0_Pos) /**< (AC_WINCTRL) Interrupt on signal above window Position */
#define AC_WINCTRL_WINTSEL0_INSIDE (AC_WINCTRL_WINTSEL0_INSIDE_Val << AC_WINCTRL_WINTSEL0_Pos) /**< (AC_WINCTRL) Interrupt on signal inside window Position */
#define AC_WINCTRL_WINTSEL0_BELOW (AC_WINCTRL_WINTSEL0_BELOW_Val << AC_WINCTRL_WINTSEL0_Pos) /**< (AC_WINCTRL) Interrupt on signal below window Position */
#define AC_WINCTRL_WINTSEL0_OUTSIDE (AC_WINCTRL_WINTSEL0_OUTSIDE_Val << AC_WINCTRL_WINTSEL0_Pos) /**< (AC_WINCTRL) Interrupt on signal outside window Position */
#define AC_WINCTRL_MASK _U_(0x07) /**< \deprecated (AC_WINCTRL) Register MASK (Use AC_WINCTRL_Msk instead) */
#define AC_WINCTRL_Msk _U_(0x07) /**< (AC_WINCTRL) Register Mask */
#define AC_WINCTRL_WEN_Pos 0 /**< (AC_WINCTRL Position) Window x Mode Enable */
#define AC_WINCTRL_WEN_Msk (_U_(0x1) << AC_WINCTRL_WEN_Pos) /**< (AC_WINCTRL Mask) WEN */
#define AC_WINCTRL_WEN(value) (AC_WINCTRL_WEN_Msk & ((value) << AC_WINCTRL_WEN_Pos))
/* -------- AC_SCALER : (AC Offset: 0x0c) (R/W 8) Scaler n -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t VALUE:6; /**< bit: 0..5 Scaler Value */
uint8_t :2; /**< bit: 6..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} AC_SCALER_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define AC_SCALER_OFFSET (0x0C) /**< (AC_SCALER) Scaler n Offset */
#define AC_SCALER_RESETVALUE _U_(0x00) /**< (AC_SCALER) Scaler n Reset Value */
#define AC_SCALER_VALUE_Pos 0 /**< (AC_SCALER) Scaler Value Position */
#define AC_SCALER_VALUE_Msk (_U_(0x3F) << AC_SCALER_VALUE_Pos) /**< (AC_SCALER) Scaler Value Mask */
#define AC_SCALER_VALUE(value) (AC_SCALER_VALUE_Msk & ((value) << AC_SCALER_VALUE_Pos))
#define AC_SCALER_MASK _U_(0x3F) /**< \deprecated (AC_SCALER) Register MASK (Use AC_SCALER_Msk instead) */
#define AC_SCALER_Msk _U_(0x3F) /**< (AC_SCALER) Register Mask */
/* -------- AC_COMPCTRL : (AC Offset: 0x10) (R/W 32) Comparator Control n -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t :1; /**< bit: 0 Reserved */
uint32_t ENABLE:1; /**< bit: 1 Enable */
uint32_t SINGLE:1; /**< bit: 2 Single-Shot Mode */
uint32_t INTSEL:2; /**< bit: 3..4 Interrupt Selection */
uint32_t :1; /**< bit: 5 Reserved */
uint32_t RUNSTDBY:1; /**< bit: 6 Run in Standby */
uint32_t :1; /**< bit: 7 Reserved */
uint32_t MUXNEG:3; /**< bit: 8..10 Negative Input Mux Selection */
uint32_t :1; /**< bit: 11 Reserved */
uint32_t MUXPOS:3; /**< bit: 12..14 Positive Input Mux Selection */
uint32_t SWAP:1; /**< bit: 15 Swap Inputs and Invert */
uint32_t SPEED:2; /**< bit: 16..17 Speed Selection */
uint32_t :1; /**< bit: 18 Reserved */
uint32_t HYSTEN:1; /**< bit: 19 Hysteresis Enable */
uint32_t HYST:2; /**< bit: 20..21 Hysteresis Level */
uint32_t :2; /**< bit: 22..23 Reserved */
uint32_t FLEN:3; /**< bit: 24..26 Filter Length */
uint32_t :1; /**< bit: 27 Reserved */
uint32_t OUT:2; /**< bit: 28..29 Output */
uint32_t :2; /**< bit: 30..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} AC_COMPCTRL_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define AC_COMPCTRL_OFFSET (0x10) /**< (AC_COMPCTRL) Comparator Control n Offset */
#define AC_COMPCTRL_RESETVALUE _U_(0x00) /**< (AC_COMPCTRL) Comparator Control n Reset Value */
#define AC_COMPCTRL_ENABLE_Pos 1 /**< (AC_COMPCTRL) Enable Position */
#define AC_COMPCTRL_ENABLE_Msk (_U_(0x1) << AC_COMPCTRL_ENABLE_Pos) /**< (AC_COMPCTRL) Enable Mask */
#define AC_COMPCTRL_ENABLE AC_COMPCTRL_ENABLE_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use AC_COMPCTRL_ENABLE_Msk instead */
#define AC_COMPCTRL_SINGLE_Pos 2 /**< (AC_COMPCTRL) Single-Shot Mode Position */
#define AC_COMPCTRL_SINGLE_Msk (_U_(0x1) << AC_COMPCTRL_SINGLE_Pos) /**< (AC_COMPCTRL) Single-Shot Mode Mask */
#define AC_COMPCTRL_SINGLE AC_COMPCTRL_SINGLE_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use AC_COMPCTRL_SINGLE_Msk instead */
#define AC_COMPCTRL_INTSEL_Pos 3 /**< (AC_COMPCTRL) Interrupt Selection Position */
#define AC_COMPCTRL_INTSEL_Msk (_U_(0x3) << AC_COMPCTRL_INTSEL_Pos) /**< (AC_COMPCTRL) Interrupt Selection Mask */
#define AC_COMPCTRL_INTSEL(value) (AC_COMPCTRL_INTSEL_Msk & ((value) << AC_COMPCTRL_INTSEL_Pos))
#define AC_COMPCTRL_INTSEL_TOGGLE_Val _U_(0x0) /**< (AC_COMPCTRL) Interrupt on comparator output toggle */
#define AC_COMPCTRL_INTSEL_RISING_Val _U_(0x1) /**< (AC_COMPCTRL) Interrupt on comparator output rising */
#define AC_COMPCTRL_INTSEL_FALLING_Val _U_(0x2) /**< (AC_COMPCTRL) Interrupt on comparator output falling */
#define AC_COMPCTRL_INTSEL_EOC_Val _U_(0x3) /**< (AC_COMPCTRL) Interrupt on end of comparison (single-shot mode only) */
#define AC_COMPCTRL_INTSEL_TOGGLE (AC_COMPCTRL_INTSEL_TOGGLE_Val << AC_COMPCTRL_INTSEL_Pos) /**< (AC_COMPCTRL) Interrupt on comparator output toggle Position */
#define AC_COMPCTRL_INTSEL_RISING (AC_COMPCTRL_INTSEL_RISING_Val << AC_COMPCTRL_INTSEL_Pos) /**< (AC_COMPCTRL) Interrupt on comparator output rising Position */
#define AC_COMPCTRL_INTSEL_FALLING (AC_COMPCTRL_INTSEL_FALLING_Val << AC_COMPCTRL_INTSEL_Pos) /**< (AC_COMPCTRL) Interrupt on comparator output falling Position */
#define AC_COMPCTRL_INTSEL_EOC (AC_COMPCTRL_INTSEL_EOC_Val << AC_COMPCTRL_INTSEL_Pos) /**< (AC_COMPCTRL) Interrupt on end of comparison (single-shot mode only) Position */
#define AC_COMPCTRL_RUNSTDBY_Pos 6 /**< (AC_COMPCTRL) Run in Standby Position */
#define AC_COMPCTRL_RUNSTDBY_Msk (_U_(0x1) << AC_COMPCTRL_RUNSTDBY_Pos) /**< (AC_COMPCTRL) Run in Standby Mask */
#define AC_COMPCTRL_RUNSTDBY AC_COMPCTRL_RUNSTDBY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use AC_COMPCTRL_RUNSTDBY_Msk instead */
#define AC_COMPCTRL_MUXNEG_Pos 8 /**< (AC_COMPCTRL) Negative Input Mux Selection Position */
#define AC_COMPCTRL_MUXNEG_Msk (_U_(0x7) << AC_COMPCTRL_MUXNEG_Pos) /**< (AC_COMPCTRL) Negative Input Mux Selection Mask */
#define AC_COMPCTRL_MUXNEG(value) (AC_COMPCTRL_MUXNEG_Msk & ((value) << AC_COMPCTRL_MUXNEG_Pos))
#define AC_COMPCTRL_MUXNEG_PIN0_Val _U_(0x0) /**< (AC_COMPCTRL) I/O pin 0 */
#define AC_COMPCTRL_MUXNEG_PIN1_Val _U_(0x1) /**< (AC_COMPCTRL) I/O pin 1 */
#define AC_COMPCTRL_MUXNEG_PIN2_Val _U_(0x2) /**< (AC_COMPCTRL) I/O pin 2 */
#define AC_COMPCTRL_MUXNEG_PIN3_Val _U_(0x3) /**< (AC_COMPCTRL) I/O pin 3 */
#define AC_COMPCTRL_MUXNEG_GND_Val _U_(0x4) /**< (AC_COMPCTRL) Ground */
#define AC_COMPCTRL_MUXNEG_VSCALE_Val _U_(0x5) /**< (AC_COMPCTRL) VDD scaler */
#define AC_COMPCTRL_MUXNEG_BANDGAP_Val _U_(0x6) /**< (AC_COMPCTRL) Internal bandgap voltage */
#define AC_COMPCTRL_MUXNEG_OPAMP_Val _U_(0x7) /**< (AC_COMPCTRL) OPAMP output (on AC1) */
#define AC_COMPCTRL_MUXNEG_DAC_Val _U_(0x7) /**< (AC_COMPCTRL) DAC output (on AC0) */
#define AC_COMPCTRL_MUXNEG_PIN0 (AC_COMPCTRL_MUXNEG_PIN0_Val << AC_COMPCTRL_MUXNEG_Pos) /**< (AC_COMPCTRL) I/O pin 0 Position */
#define AC_COMPCTRL_MUXNEG_PIN1 (AC_COMPCTRL_MUXNEG_PIN1_Val << AC_COMPCTRL_MUXNEG_Pos) /**< (AC_COMPCTRL) I/O pin 1 Position */
#define AC_COMPCTRL_MUXNEG_PIN2 (AC_COMPCTRL_MUXNEG_PIN2_Val << AC_COMPCTRL_MUXNEG_Pos) /**< (AC_COMPCTRL) I/O pin 2 Position */
#define AC_COMPCTRL_MUXNEG_PIN3 (AC_COMPCTRL_MUXNEG_PIN3_Val << AC_COMPCTRL_MUXNEG_Pos) /**< (AC_COMPCTRL) I/O pin 3 Position */
#define AC_COMPCTRL_MUXNEG_GND (AC_COMPCTRL_MUXNEG_GND_Val << AC_COMPCTRL_MUXNEG_Pos) /**< (AC_COMPCTRL) Ground Position */
#define AC_COMPCTRL_MUXNEG_VSCALE (AC_COMPCTRL_MUXNEG_VSCALE_Val << AC_COMPCTRL_MUXNEG_Pos) /**< (AC_COMPCTRL) VDD scaler Position */
#define AC_COMPCTRL_MUXNEG_BANDGAP (AC_COMPCTRL_MUXNEG_BANDGAP_Val << AC_COMPCTRL_MUXNEG_Pos) /**< (AC_COMPCTRL) Internal bandgap voltage Position */
#define AC_COMPCTRL_MUXNEG_OPAMP (AC_COMPCTRL_MUXNEG_OPAMP_Val << AC_COMPCTRL_MUXNEG_Pos) /**< (AC_COMPCTRL) OPAMP output (on AC1) Position */
#define AC_COMPCTRL_MUXNEG_DAC (AC_COMPCTRL_MUXNEG_DAC_Val << AC_COMPCTRL_MUXNEG_Pos) /**< (AC_COMPCTRL) DAC output (on AC0) Position */
#define AC_COMPCTRL_MUXPOS_Pos 12 /**< (AC_COMPCTRL) Positive Input Mux Selection Position */
#define AC_COMPCTRL_MUXPOS_Msk (_U_(0x7) << AC_COMPCTRL_MUXPOS_Pos) /**< (AC_COMPCTRL) Positive Input Mux Selection Mask */
#define AC_COMPCTRL_MUXPOS(value) (AC_COMPCTRL_MUXPOS_Msk & ((value) << AC_COMPCTRL_MUXPOS_Pos))
#define AC_COMPCTRL_MUXPOS_PIN0_Val _U_(0x0) /**< (AC_COMPCTRL) I/O pin 0 */
#define AC_COMPCTRL_MUXPOS_PIN1_Val _U_(0x1) /**< (AC_COMPCTRL) I/O pin 1 */
#define AC_COMPCTRL_MUXPOS_PIN2_Val _U_(0x2) /**< (AC_COMPCTRL) I/O pin 2 */
#define AC_COMPCTRL_MUXPOS_PIN3_Val _U_(0x3) /**< (AC_COMPCTRL) I/O pin 3 */
#define AC_COMPCTRL_MUXPOS_VSCALE_Val _U_(0x4) /**< (AC_COMPCTRL) VDD Scaler */
#define AC_COMPCTRL_MUXPOS_PIN0 (AC_COMPCTRL_MUXPOS_PIN0_Val << AC_COMPCTRL_MUXPOS_Pos) /**< (AC_COMPCTRL) I/O pin 0 Position */
#define AC_COMPCTRL_MUXPOS_PIN1 (AC_COMPCTRL_MUXPOS_PIN1_Val << AC_COMPCTRL_MUXPOS_Pos) /**< (AC_COMPCTRL) I/O pin 1 Position */
#define AC_COMPCTRL_MUXPOS_PIN2 (AC_COMPCTRL_MUXPOS_PIN2_Val << AC_COMPCTRL_MUXPOS_Pos) /**< (AC_COMPCTRL) I/O pin 2 Position */
#define AC_COMPCTRL_MUXPOS_PIN3 (AC_COMPCTRL_MUXPOS_PIN3_Val << AC_COMPCTRL_MUXPOS_Pos) /**< (AC_COMPCTRL) I/O pin 3 Position */
#define AC_COMPCTRL_MUXPOS_VSCALE (AC_COMPCTRL_MUXPOS_VSCALE_Val << AC_COMPCTRL_MUXPOS_Pos) /**< (AC_COMPCTRL) VDD Scaler Position */
#define AC_COMPCTRL_SWAP_Pos 15 /**< (AC_COMPCTRL) Swap Inputs and Invert Position */
#define AC_COMPCTRL_SWAP_Msk (_U_(0x1) << AC_COMPCTRL_SWAP_Pos) /**< (AC_COMPCTRL) Swap Inputs and Invert Mask */
#define AC_COMPCTRL_SWAP AC_COMPCTRL_SWAP_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use AC_COMPCTRL_SWAP_Msk instead */
#define AC_COMPCTRL_SPEED_Pos 16 /**< (AC_COMPCTRL) Speed Selection Position */
#define AC_COMPCTRL_SPEED_Msk (_U_(0x3) << AC_COMPCTRL_SPEED_Pos) /**< (AC_COMPCTRL) Speed Selection Mask */
#define AC_COMPCTRL_SPEED(value) (AC_COMPCTRL_SPEED_Msk & ((value) << AC_COMPCTRL_SPEED_Pos))
#define AC_COMPCTRL_SPEED_LOW_Val _U_(0x0) /**< (AC_COMPCTRL) Low speed */
#define AC_COMPCTRL_SPEED_MEDLOW_Val _U_(0x1) /**< (AC_COMPCTRL) Medium low speed */
#define AC_COMPCTRL_SPEED_MEDHIGH_Val _U_(0x2) /**< (AC_COMPCTRL) Medium high speed */
#define AC_COMPCTRL_SPEED_HIGH_Val _U_(0x3) /**< (AC_COMPCTRL) High speed */
#define AC_COMPCTRL_SPEED_LOW (AC_COMPCTRL_SPEED_LOW_Val << AC_COMPCTRL_SPEED_Pos) /**< (AC_COMPCTRL) Low speed Position */
#define AC_COMPCTRL_SPEED_MEDLOW (AC_COMPCTRL_SPEED_MEDLOW_Val << AC_COMPCTRL_SPEED_Pos) /**< (AC_COMPCTRL) Medium low speed Position */
#define AC_COMPCTRL_SPEED_MEDHIGH (AC_COMPCTRL_SPEED_MEDHIGH_Val << AC_COMPCTRL_SPEED_Pos) /**< (AC_COMPCTRL) Medium high speed Position */
#define AC_COMPCTRL_SPEED_HIGH (AC_COMPCTRL_SPEED_HIGH_Val << AC_COMPCTRL_SPEED_Pos) /**< (AC_COMPCTRL) High speed Position */
#define AC_COMPCTRL_HYSTEN_Pos 19 /**< (AC_COMPCTRL) Hysteresis Enable Position */
#define AC_COMPCTRL_HYSTEN_Msk (_U_(0x1) << AC_COMPCTRL_HYSTEN_Pos) /**< (AC_COMPCTRL) Hysteresis Enable Mask */
#define AC_COMPCTRL_HYSTEN AC_COMPCTRL_HYSTEN_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use AC_COMPCTRL_HYSTEN_Msk instead */
#define AC_COMPCTRL_HYST_Pos 20 /**< (AC_COMPCTRL) Hysteresis Level Position */
#define AC_COMPCTRL_HYST_Msk (_U_(0x3) << AC_COMPCTRL_HYST_Pos) /**< (AC_COMPCTRL) Hysteresis Level Mask */
#define AC_COMPCTRL_HYST(value) (AC_COMPCTRL_HYST_Msk & ((value) << AC_COMPCTRL_HYST_Pos))
#define AC_COMPCTRL_HYST_HYST50_Val _U_(0x0) /**< (AC_COMPCTRL) 50mV */
#define AC_COMPCTRL_HYST_HYST70_Val _U_(0x1) /**< (AC_COMPCTRL) 70mV */
#define AC_COMPCTRL_HYST_HYST90_Val _U_(0x2) /**< (AC_COMPCTRL) 90mV */
#define AC_COMPCTRL_HYST_HYST110_Val _U_(0x3) /**< (AC_COMPCTRL) 110mV */
#define AC_COMPCTRL_HYST_HYST50 (AC_COMPCTRL_HYST_HYST50_Val << AC_COMPCTRL_HYST_Pos) /**< (AC_COMPCTRL) 50mV Position */
#define AC_COMPCTRL_HYST_HYST70 (AC_COMPCTRL_HYST_HYST70_Val << AC_COMPCTRL_HYST_Pos) /**< (AC_COMPCTRL) 70mV Position */
#define AC_COMPCTRL_HYST_HYST90 (AC_COMPCTRL_HYST_HYST90_Val << AC_COMPCTRL_HYST_Pos) /**< (AC_COMPCTRL) 90mV Position */
#define AC_COMPCTRL_HYST_HYST110 (AC_COMPCTRL_HYST_HYST110_Val << AC_COMPCTRL_HYST_Pos) /**< (AC_COMPCTRL) 110mV Position */
#define AC_COMPCTRL_FLEN_Pos 24 /**< (AC_COMPCTRL) Filter Length Position */
#define AC_COMPCTRL_FLEN_Msk (_U_(0x7) << AC_COMPCTRL_FLEN_Pos) /**< (AC_COMPCTRL) Filter Length Mask */
#define AC_COMPCTRL_FLEN(value) (AC_COMPCTRL_FLEN_Msk & ((value) << AC_COMPCTRL_FLEN_Pos))
#define AC_COMPCTRL_FLEN_OFF_Val _U_(0x0) /**< (AC_COMPCTRL) No filtering */
#define AC_COMPCTRL_FLEN_MAJ3_Val _U_(0x1) /**< (AC_COMPCTRL) 3-bit majority function (2 of 3) */
#define AC_COMPCTRL_FLEN_MAJ5_Val _U_(0x2) /**< (AC_COMPCTRL) 5-bit majority function (3 of 5) */
#define AC_COMPCTRL_FLEN_OFF (AC_COMPCTRL_FLEN_OFF_Val << AC_COMPCTRL_FLEN_Pos) /**< (AC_COMPCTRL) No filtering Position */
#define AC_COMPCTRL_FLEN_MAJ3 (AC_COMPCTRL_FLEN_MAJ3_Val << AC_COMPCTRL_FLEN_Pos) /**< (AC_COMPCTRL) 3-bit majority function (2 of 3) Position */
#define AC_COMPCTRL_FLEN_MAJ5 (AC_COMPCTRL_FLEN_MAJ5_Val << AC_COMPCTRL_FLEN_Pos) /**< (AC_COMPCTRL) 5-bit majority function (3 of 5) Position */
#define AC_COMPCTRL_OUT_Pos 28 /**< (AC_COMPCTRL) Output Position */
#define AC_COMPCTRL_OUT_Msk (_U_(0x3) << AC_COMPCTRL_OUT_Pos) /**< (AC_COMPCTRL) Output Mask */
#define AC_COMPCTRL_OUT(value) (AC_COMPCTRL_OUT_Msk & ((value) << AC_COMPCTRL_OUT_Pos))
#define AC_COMPCTRL_OUT_OFF_Val _U_(0x0) /**< (AC_COMPCTRL) The output of COMPn is not routed to the COMPn I/O port */
#define AC_COMPCTRL_OUT_ASYNC_Val _U_(0x1) /**< (AC_COMPCTRL) The asynchronous output of COMPn is routed to the COMPn I/O port */
#define AC_COMPCTRL_OUT_SYNC_Val _U_(0x2) /**< (AC_COMPCTRL) The synchronous output (including filtering) of COMPn is routed to the COMPn I/O port */
#define AC_COMPCTRL_OUT_OFF (AC_COMPCTRL_OUT_OFF_Val << AC_COMPCTRL_OUT_Pos) /**< (AC_COMPCTRL) The output of COMPn is not routed to the COMPn I/O port Position */
#define AC_COMPCTRL_OUT_ASYNC (AC_COMPCTRL_OUT_ASYNC_Val << AC_COMPCTRL_OUT_Pos) /**< (AC_COMPCTRL) The asynchronous output of COMPn is routed to the COMPn I/O port Position */
#define AC_COMPCTRL_OUT_SYNC (AC_COMPCTRL_OUT_SYNC_Val << AC_COMPCTRL_OUT_Pos) /**< (AC_COMPCTRL) The synchronous output (including filtering) of COMPn is routed to the COMPn I/O port Position */
#define AC_COMPCTRL_MASK _U_(0x373BF75E) /**< \deprecated (AC_COMPCTRL) Register MASK (Use AC_COMPCTRL_Msk instead) */
#define AC_COMPCTRL_Msk _U_(0x373BF75E) /**< (AC_COMPCTRL) Register Mask */
/* -------- AC_SYNCBUSY : (AC Offset: 0x20) (R/ 32) Synchronization Busy -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t SWRST:1; /**< bit: 0 Software Reset Synchronization Busy */
uint32_t ENABLE:1; /**< bit: 1 Enable Synchronization Busy */
uint32_t WINCTRL:1; /**< bit: 2 WINCTRL Synchronization Busy */
uint32_t COMPCTRL0:1; /**< bit: 3 COMPCTRL 0 Synchronization Busy */
uint32_t COMPCTRL1:1; /**< bit: 4 COMPCTRL 1 Synchronization Busy */
uint32_t :27; /**< bit: 5..31 Reserved */
} bit; /**< Structure used for bit access */
struct {
uint32_t :3; /**< bit: 0..2 Reserved */
uint32_t COMPCTRL:2; /**< bit: 3..4 COMPCTRL x Synchronization Busy */
uint32_t :27; /**< bit: 5..31 Reserved */
} vec; /**< Structure used for vec access */
uint32_t reg; /**< Type used for register access */
} AC_SYNCBUSY_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define AC_SYNCBUSY_OFFSET (0x20) /**< (AC_SYNCBUSY) Synchronization Busy Offset */
#define AC_SYNCBUSY_RESETVALUE _U_(0x00) /**< (AC_SYNCBUSY) Synchronization Busy Reset Value */
#define AC_SYNCBUSY_SWRST_Pos 0 /**< (AC_SYNCBUSY) Software Reset Synchronization Busy Position */
#define AC_SYNCBUSY_SWRST_Msk (_U_(0x1) << AC_SYNCBUSY_SWRST_Pos) /**< (AC_SYNCBUSY) Software Reset Synchronization Busy Mask */
#define AC_SYNCBUSY_SWRST AC_SYNCBUSY_SWRST_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use AC_SYNCBUSY_SWRST_Msk instead */
#define AC_SYNCBUSY_ENABLE_Pos 1 /**< (AC_SYNCBUSY) Enable Synchronization Busy Position */
#define AC_SYNCBUSY_ENABLE_Msk (_U_(0x1) << AC_SYNCBUSY_ENABLE_Pos) /**< (AC_SYNCBUSY) Enable Synchronization Busy Mask */
#define AC_SYNCBUSY_ENABLE AC_SYNCBUSY_ENABLE_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use AC_SYNCBUSY_ENABLE_Msk instead */
#define AC_SYNCBUSY_WINCTRL_Pos 2 /**< (AC_SYNCBUSY) WINCTRL Synchronization Busy Position */
#define AC_SYNCBUSY_WINCTRL_Msk (_U_(0x1) << AC_SYNCBUSY_WINCTRL_Pos) /**< (AC_SYNCBUSY) WINCTRL Synchronization Busy Mask */
#define AC_SYNCBUSY_WINCTRL AC_SYNCBUSY_WINCTRL_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use AC_SYNCBUSY_WINCTRL_Msk instead */
#define AC_SYNCBUSY_COMPCTRL0_Pos 3 /**< (AC_SYNCBUSY) COMPCTRL 0 Synchronization Busy Position */
#define AC_SYNCBUSY_COMPCTRL0_Msk (_U_(0x1) << AC_SYNCBUSY_COMPCTRL0_Pos) /**< (AC_SYNCBUSY) COMPCTRL 0 Synchronization Busy Mask */
#define AC_SYNCBUSY_COMPCTRL0 AC_SYNCBUSY_COMPCTRL0_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use AC_SYNCBUSY_COMPCTRL0_Msk instead */
#define AC_SYNCBUSY_COMPCTRL1_Pos 4 /**< (AC_SYNCBUSY) COMPCTRL 1 Synchronization Busy Position */
#define AC_SYNCBUSY_COMPCTRL1_Msk (_U_(0x1) << AC_SYNCBUSY_COMPCTRL1_Pos) /**< (AC_SYNCBUSY) COMPCTRL 1 Synchronization Busy Mask */
#define AC_SYNCBUSY_COMPCTRL1 AC_SYNCBUSY_COMPCTRL1_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use AC_SYNCBUSY_COMPCTRL1_Msk instead */
#define AC_SYNCBUSY_MASK _U_(0x1F) /**< \deprecated (AC_SYNCBUSY) Register MASK (Use AC_SYNCBUSY_Msk instead) */
#define AC_SYNCBUSY_Msk _U_(0x1F) /**< (AC_SYNCBUSY) Register Mask */
#define AC_SYNCBUSY_COMPCTRL_Pos 3 /**< (AC_SYNCBUSY Position) COMPCTRL x Synchronization Busy */
#define AC_SYNCBUSY_COMPCTRL_Msk (_U_(0x3) << AC_SYNCBUSY_COMPCTRL_Pos) /**< (AC_SYNCBUSY Mask) COMPCTRL */
#define AC_SYNCBUSY_COMPCTRL(value) (AC_SYNCBUSY_COMPCTRL_Msk & ((value) << AC_SYNCBUSY_COMPCTRL_Pos))
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
/** \brief AC hardware registers */
typedef struct { /* Analog Comparators */
__IO AC_CTRLA_Type CTRLA; /**< Offset: 0x00 (R/W 8) Control A */
__O AC_CTRLB_Type CTRLB; /**< Offset: 0x01 ( /W 8) Control B */
__IO AC_EVCTRL_Type EVCTRL; /**< Offset: 0x02 (R/W 16) Event Control */
__IO AC_INTENCLR_Type INTENCLR; /**< Offset: 0x04 (R/W 8) Interrupt Enable Clear */
__IO AC_INTENSET_Type INTENSET; /**< Offset: 0x05 (R/W 8) Interrupt Enable Set */
__IO AC_INTFLAG_Type INTFLAG; /**< Offset: 0x06 (R/W 8) Interrupt Flag Status and Clear */
__I AC_STATUSA_Type STATUSA; /**< Offset: 0x07 (R/ 8) Status A */
__I AC_STATUSB_Type STATUSB; /**< Offset: 0x08 (R/ 8) Status B */
__IO AC_DBGCTRL_Type DBGCTRL; /**< Offset: 0x09 (R/W 8) Debug Control */
__IO AC_WINCTRL_Type WINCTRL; /**< Offset: 0x0A (R/W 8) Window Control */
__I uint8_t Reserved1[1];
__IO AC_SCALER_Type SCALER[2]; /**< Offset: 0x0C (R/W 8) Scaler n */
__I uint8_t Reserved2[2];
__IO AC_COMPCTRL_Type COMPCTRL[2]; /**< Offset: 0x10 (R/W 32) Comparator Control n */
__I uint8_t Reserved3[8];
__I AC_SYNCBUSY_Type SYNCBUSY; /**< Offset: 0x20 (R/ 32) Synchronization Busy */
} Ac;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/** @} end of Analog Comparators */
#endif /* _SAML10_AC_COMPONENT_H_ */

View File

@ -0,0 +1,851 @@
/**
* \file
*
* \brief Component description for ADC
*
* Copyright (c) 2018 Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* 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
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
/* file generated from device description version 2018-08-31T13:51:50Z */
#ifndef _SAML10_ADC_COMPONENT_H_
#define _SAML10_ADC_COMPONENT_H_
#define _SAML10_ADC_COMPONENT_ /**< \deprecated Backward compatibility for ASF */
/** \addtogroup SAML_SAML10 Analog Digital Converter
* @{
*/
/* ========================================================================== */
/** SOFTWARE API DEFINITION FOR ADC */
/* ========================================================================== */
#define ADC_U2247 /**< (ADC) Module ID */
#define REV_ADC 0x240 /**< (ADC) Module revision */
/* -------- ADC_CTRLA : (ADC Offset: 0x00) (R/W 8) Control A -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t SWRST:1; /**< bit: 0 Software Reset */
uint8_t ENABLE:1; /**< bit: 1 Enable */
uint8_t :3; /**< bit: 2..4 Reserved */
uint8_t SLAVEEN:1; /**< bit: 5 Slave Enable */
uint8_t RUNSTDBY:1; /**< bit: 6 Run During Standby */
uint8_t ONDEMAND:1; /**< bit: 7 On Demand Control */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} ADC_CTRLA_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define ADC_CTRLA_OFFSET (0x00) /**< (ADC_CTRLA) Control A Offset */
#define ADC_CTRLA_RESETVALUE _U_(0x00) /**< (ADC_CTRLA) Control A Reset Value */
#define ADC_CTRLA_SWRST_Pos 0 /**< (ADC_CTRLA) Software Reset Position */
#define ADC_CTRLA_SWRST_Msk (_U_(0x1) << ADC_CTRLA_SWRST_Pos) /**< (ADC_CTRLA) Software Reset Mask */
#define ADC_CTRLA_SWRST ADC_CTRLA_SWRST_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use ADC_CTRLA_SWRST_Msk instead */
#define ADC_CTRLA_ENABLE_Pos 1 /**< (ADC_CTRLA) Enable Position */
#define ADC_CTRLA_ENABLE_Msk (_U_(0x1) << ADC_CTRLA_ENABLE_Pos) /**< (ADC_CTRLA) Enable Mask */
#define ADC_CTRLA_ENABLE ADC_CTRLA_ENABLE_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use ADC_CTRLA_ENABLE_Msk instead */
#define ADC_CTRLA_SLAVEEN_Pos 5 /**< (ADC_CTRLA) Slave Enable Position */
#define ADC_CTRLA_SLAVEEN_Msk (_U_(0x1) << ADC_CTRLA_SLAVEEN_Pos) /**< (ADC_CTRLA) Slave Enable Mask */
#define ADC_CTRLA_SLAVEEN ADC_CTRLA_SLAVEEN_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use ADC_CTRLA_SLAVEEN_Msk instead */
#define ADC_CTRLA_RUNSTDBY_Pos 6 /**< (ADC_CTRLA) Run During Standby Position */
#define ADC_CTRLA_RUNSTDBY_Msk (_U_(0x1) << ADC_CTRLA_RUNSTDBY_Pos) /**< (ADC_CTRLA) Run During Standby Mask */
#define ADC_CTRLA_RUNSTDBY ADC_CTRLA_RUNSTDBY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use ADC_CTRLA_RUNSTDBY_Msk instead */
#define ADC_CTRLA_ONDEMAND_Pos 7 /**< (ADC_CTRLA) On Demand Control Position */
#define ADC_CTRLA_ONDEMAND_Msk (_U_(0x1) << ADC_CTRLA_ONDEMAND_Pos) /**< (ADC_CTRLA) On Demand Control Mask */
#define ADC_CTRLA_ONDEMAND ADC_CTRLA_ONDEMAND_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use ADC_CTRLA_ONDEMAND_Msk instead */
#define ADC_CTRLA_MASK _U_(0xE3) /**< \deprecated (ADC_CTRLA) Register MASK (Use ADC_CTRLA_Msk instead) */
#define ADC_CTRLA_Msk _U_(0xE3) /**< (ADC_CTRLA) Register Mask */
/* -------- ADC_CTRLB : (ADC Offset: 0x01) (R/W 8) Control B -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t PRESCALER:3; /**< bit: 0..2 Prescaler Configuration */
uint8_t :5; /**< bit: 3..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} ADC_CTRLB_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define ADC_CTRLB_OFFSET (0x01) /**< (ADC_CTRLB) Control B Offset */
#define ADC_CTRLB_RESETVALUE _U_(0x00) /**< (ADC_CTRLB) Control B Reset Value */
#define ADC_CTRLB_PRESCALER_Pos 0 /**< (ADC_CTRLB) Prescaler Configuration Position */
#define ADC_CTRLB_PRESCALER_Msk (_U_(0x7) << ADC_CTRLB_PRESCALER_Pos) /**< (ADC_CTRLB) Prescaler Configuration Mask */
#define ADC_CTRLB_PRESCALER(value) (ADC_CTRLB_PRESCALER_Msk & ((value) << ADC_CTRLB_PRESCALER_Pos))
#define ADC_CTRLB_PRESCALER_DIV2_Val _U_(0x0) /**< (ADC_CTRLB) Peripheral clock divided by 2 */
#define ADC_CTRLB_PRESCALER_DIV4_Val _U_(0x1) /**< (ADC_CTRLB) Peripheral clock divided by 4 */
#define ADC_CTRLB_PRESCALER_DIV8_Val _U_(0x2) /**< (ADC_CTRLB) Peripheral clock divided by 8 */
#define ADC_CTRLB_PRESCALER_DIV16_Val _U_(0x3) /**< (ADC_CTRLB) Peripheral clock divided by 16 */
#define ADC_CTRLB_PRESCALER_DIV32_Val _U_(0x4) /**< (ADC_CTRLB) Peripheral clock divided by 32 */
#define ADC_CTRLB_PRESCALER_DIV64_Val _U_(0x5) /**< (ADC_CTRLB) Peripheral clock divided by 64 */
#define ADC_CTRLB_PRESCALER_DIV128_Val _U_(0x6) /**< (ADC_CTRLB) Peripheral clock divided by 128 */
#define ADC_CTRLB_PRESCALER_DIV256_Val _U_(0x7) /**< (ADC_CTRLB) Peripheral clock divided by 256 */
#define ADC_CTRLB_PRESCALER_DIV2 (ADC_CTRLB_PRESCALER_DIV2_Val << ADC_CTRLB_PRESCALER_Pos) /**< (ADC_CTRLB) Peripheral clock divided by 2 Position */
#define ADC_CTRLB_PRESCALER_DIV4 (ADC_CTRLB_PRESCALER_DIV4_Val << ADC_CTRLB_PRESCALER_Pos) /**< (ADC_CTRLB) Peripheral clock divided by 4 Position */
#define ADC_CTRLB_PRESCALER_DIV8 (ADC_CTRLB_PRESCALER_DIV8_Val << ADC_CTRLB_PRESCALER_Pos) /**< (ADC_CTRLB) Peripheral clock divided by 8 Position */
#define ADC_CTRLB_PRESCALER_DIV16 (ADC_CTRLB_PRESCALER_DIV16_Val << ADC_CTRLB_PRESCALER_Pos) /**< (ADC_CTRLB) Peripheral clock divided by 16 Position */
#define ADC_CTRLB_PRESCALER_DIV32 (ADC_CTRLB_PRESCALER_DIV32_Val << ADC_CTRLB_PRESCALER_Pos) /**< (ADC_CTRLB) Peripheral clock divided by 32 Position */
#define ADC_CTRLB_PRESCALER_DIV64 (ADC_CTRLB_PRESCALER_DIV64_Val << ADC_CTRLB_PRESCALER_Pos) /**< (ADC_CTRLB) Peripheral clock divided by 64 Position */
#define ADC_CTRLB_PRESCALER_DIV128 (ADC_CTRLB_PRESCALER_DIV128_Val << ADC_CTRLB_PRESCALER_Pos) /**< (ADC_CTRLB) Peripheral clock divided by 128 Position */
#define ADC_CTRLB_PRESCALER_DIV256 (ADC_CTRLB_PRESCALER_DIV256_Val << ADC_CTRLB_PRESCALER_Pos) /**< (ADC_CTRLB) Peripheral clock divided by 256 Position */
#define ADC_CTRLB_MASK _U_(0x07) /**< \deprecated (ADC_CTRLB) Register MASK (Use ADC_CTRLB_Msk instead) */
#define ADC_CTRLB_Msk _U_(0x07) /**< (ADC_CTRLB) Register Mask */
/* -------- ADC_REFCTRL : (ADC Offset: 0x02) (R/W 8) Reference Control -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t REFSEL:4; /**< bit: 0..3 Reference Selection */
uint8_t :3; /**< bit: 4..6 Reserved */
uint8_t REFCOMP:1; /**< bit: 7 Reference Buffer Offset Compensation Enable */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} ADC_REFCTRL_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define ADC_REFCTRL_OFFSET (0x02) /**< (ADC_REFCTRL) Reference Control Offset */
#define ADC_REFCTRL_RESETVALUE _U_(0x00) /**< (ADC_REFCTRL) Reference Control Reset Value */
#define ADC_REFCTRL_REFSEL_Pos 0 /**< (ADC_REFCTRL) Reference Selection Position */
#define ADC_REFCTRL_REFSEL_Msk (_U_(0xF) << ADC_REFCTRL_REFSEL_Pos) /**< (ADC_REFCTRL) Reference Selection Mask */
#define ADC_REFCTRL_REFSEL(value) (ADC_REFCTRL_REFSEL_Msk & ((value) << ADC_REFCTRL_REFSEL_Pos))
#define ADC_REFCTRL_REFSEL_INTREF_Val _U_(0x0) /**< (ADC_REFCTRL) Internal Bandgap Reference */
#define ADC_REFCTRL_REFSEL_INTVCC0_Val _U_(0x1) /**< (ADC_REFCTRL) 1/1.6 VDDANA */
#define ADC_REFCTRL_REFSEL_INTVCC1_Val _U_(0x2) /**< (ADC_REFCTRL) 1/2 VDDANA */
#define ADC_REFCTRL_REFSEL_AREFA_Val _U_(0x3) /**< (ADC_REFCTRL) External Reference */
#define ADC_REFCTRL_REFSEL_AREFB_Val _U_(0x4) /**< (ADC_REFCTRL) External Reference */
#define ADC_REFCTRL_REFSEL_INTVCC2_Val _U_(0x5) /**< (ADC_REFCTRL) VCCANA */
#define ADC_REFCTRL_REFSEL_INTREF (ADC_REFCTRL_REFSEL_INTREF_Val << ADC_REFCTRL_REFSEL_Pos) /**< (ADC_REFCTRL) Internal Bandgap Reference Position */
#define ADC_REFCTRL_REFSEL_INTVCC0 (ADC_REFCTRL_REFSEL_INTVCC0_Val << ADC_REFCTRL_REFSEL_Pos) /**< (ADC_REFCTRL) 1/1.6 VDDANA Position */
#define ADC_REFCTRL_REFSEL_INTVCC1 (ADC_REFCTRL_REFSEL_INTVCC1_Val << ADC_REFCTRL_REFSEL_Pos) /**< (ADC_REFCTRL) 1/2 VDDANA Position */
#define ADC_REFCTRL_REFSEL_AREFA (ADC_REFCTRL_REFSEL_AREFA_Val << ADC_REFCTRL_REFSEL_Pos) /**< (ADC_REFCTRL) External Reference Position */
#define ADC_REFCTRL_REFSEL_AREFB (ADC_REFCTRL_REFSEL_AREFB_Val << ADC_REFCTRL_REFSEL_Pos) /**< (ADC_REFCTRL) External Reference Position */
#define ADC_REFCTRL_REFSEL_INTVCC2 (ADC_REFCTRL_REFSEL_INTVCC2_Val << ADC_REFCTRL_REFSEL_Pos) /**< (ADC_REFCTRL) VCCANA Position */
#define ADC_REFCTRL_REFCOMP_Pos 7 /**< (ADC_REFCTRL) Reference Buffer Offset Compensation Enable Position */
#define ADC_REFCTRL_REFCOMP_Msk (_U_(0x1) << ADC_REFCTRL_REFCOMP_Pos) /**< (ADC_REFCTRL) Reference Buffer Offset Compensation Enable Mask */
#define ADC_REFCTRL_REFCOMP ADC_REFCTRL_REFCOMP_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use ADC_REFCTRL_REFCOMP_Msk instead */
#define ADC_REFCTRL_MASK _U_(0x8F) /**< \deprecated (ADC_REFCTRL) Register MASK (Use ADC_REFCTRL_Msk instead) */
#define ADC_REFCTRL_Msk _U_(0x8F) /**< (ADC_REFCTRL) Register Mask */
/* -------- ADC_EVCTRL : (ADC Offset: 0x03) (R/W 8) Event Control -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t FLUSHEI:1; /**< bit: 0 Flush Event Input Enable */
uint8_t STARTEI:1; /**< bit: 1 Start Conversion Event Input Enable */
uint8_t FLUSHINV:1; /**< bit: 2 Flush Event Invert Enable */
uint8_t STARTINV:1; /**< bit: 3 Satrt Event Invert Enable */
uint8_t RESRDYEO:1; /**< bit: 4 Result Ready Event Out */
uint8_t WINMONEO:1; /**< bit: 5 Window Monitor Event Out */
uint8_t :2; /**< bit: 6..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} ADC_EVCTRL_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define ADC_EVCTRL_OFFSET (0x03) /**< (ADC_EVCTRL) Event Control Offset */
#define ADC_EVCTRL_RESETVALUE _U_(0x00) /**< (ADC_EVCTRL) Event Control Reset Value */
#define ADC_EVCTRL_FLUSHEI_Pos 0 /**< (ADC_EVCTRL) Flush Event Input Enable Position */
#define ADC_EVCTRL_FLUSHEI_Msk (_U_(0x1) << ADC_EVCTRL_FLUSHEI_Pos) /**< (ADC_EVCTRL) Flush Event Input Enable Mask */
#define ADC_EVCTRL_FLUSHEI ADC_EVCTRL_FLUSHEI_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use ADC_EVCTRL_FLUSHEI_Msk instead */
#define ADC_EVCTRL_STARTEI_Pos 1 /**< (ADC_EVCTRL) Start Conversion Event Input Enable Position */
#define ADC_EVCTRL_STARTEI_Msk (_U_(0x1) << ADC_EVCTRL_STARTEI_Pos) /**< (ADC_EVCTRL) Start Conversion Event Input Enable Mask */
#define ADC_EVCTRL_STARTEI ADC_EVCTRL_STARTEI_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use ADC_EVCTRL_STARTEI_Msk instead */
#define ADC_EVCTRL_FLUSHINV_Pos 2 /**< (ADC_EVCTRL) Flush Event Invert Enable Position */
#define ADC_EVCTRL_FLUSHINV_Msk (_U_(0x1) << ADC_EVCTRL_FLUSHINV_Pos) /**< (ADC_EVCTRL) Flush Event Invert Enable Mask */
#define ADC_EVCTRL_FLUSHINV ADC_EVCTRL_FLUSHINV_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use ADC_EVCTRL_FLUSHINV_Msk instead */
#define ADC_EVCTRL_STARTINV_Pos 3 /**< (ADC_EVCTRL) Satrt Event Invert Enable Position */
#define ADC_EVCTRL_STARTINV_Msk (_U_(0x1) << ADC_EVCTRL_STARTINV_Pos) /**< (ADC_EVCTRL) Satrt Event Invert Enable Mask */
#define ADC_EVCTRL_STARTINV ADC_EVCTRL_STARTINV_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use ADC_EVCTRL_STARTINV_Msk instead */
#define ADC_EVCTRL_RESRDYEO_Pos 4 /**< (ADC_EVCTRL) Result Ready Event Out Position */
#define ADC_EVCTRL_RESRDYEO_Msk (_U_(0x1) << ADC_EVCTRL_RESRDYEO_Pos) /**< (ADC_EVCTRL) Result Ready Event Out Mask */
#define ADC_EVCTRL_RESRDYEO ADC_EVCTRL_RESRDYEO_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use ADC_EVCTRL_RESRDYEO_Msk instead */
#define ADC_EVCTRL_WINMONEO_Pos 5 /**< (ADC_EVCTRL) Window Monitor Event Out Position */
#define ADC_EVCTRL_WINMONEO_Msk (_U_(0x1) << ADC_EVCTRL_WINMONEO_Pos) /**< (ADC_EVCTRL) Window Monitor Event Out Mask */
#define ADC_EVCTRL_WINMONEO ADC_EVCTRL_WINMONEO_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use ADC_EVCTRL_WINMONEO_Msk instead */
#define ADC_EVCTRL_MASK _U_(0x3F) /**< \deprecated (ADC_EVCTRL) Register MASK (Use ADC_EVCTRL_Msk instead) */
#define ADC_EVCTRL_Msk _U_(0x3F) /**< (ADC_EVCTRL) Register Mask */
/* -------- ADC_INTENCLR : (ADC Offset: 0x04) (R/W 8) Interrupt Enable Clear -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t RESRDY:1; /**< bit: 0 Result Ready Interrupt Disable */
uint8_t OVERRUN:1; /**< bit: 1 Overrun Interrupt Disable */
uint8_t WINMON:1; /**< bit: 2 Window Monitor Interrupt Disable */
uint8_t :5; /**< bit: 3..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} ADC_INTENCLR_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define ADC_INTENCLR_OFFSET (0x04) /**< (ADC_INTENCLR) Interrupt Enable Clear Offset */
#define ADC_INTENCLR_RESETVALUE _U_(0x00) /**< (ADC_INTENCLR) Interrupt Enable Clear Reset Value */
#define ADC_INTENCLR_RESRDY_Pos 0 /**< (ADC_INTENCLR) Result Ready Interrupt Disable Position */
#define ADC_INTENCLR_RESRDY_Msk (_U_(0x1) << ADC_INTENCLR_RESRDY_Pos) /**< (ADC_INTENCLR) Result Ready Interrupt Disable Mask */
#define ADC_INTENCLR_RESRDY ADC_INTENCLR_RESRDY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use ADC_INTENCLR_RESRDY_Msk instead */
#define ADC_INTENCLR_OVERRUN_Pos 1 /**< (ADC_INTENCLR) Overrun Interrupt Disable Position */
#define ADC_INTENCLR_OVERRUN_Msk (_U_(0x1) << ADC_INTENCLR_OVERRUN_Pos) /**< (ADC_INTENCLR) Overrun Interrupt Disable Mask */
#define ADC_INTENCLR_OVERRUN ADC_INTENCLR_OVERRUN_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use ADC_INTENCLR_OVERRUN_Msk instead */
#define ADC_INTENCLR_WINMON_Pos 2 /**< (ADC_INTENCLR) Window Monitor Interrupt Disable Position */
#define ADC_INTENCLR_WINMON_Msk (_U_(0x1) << ADC_INTENCLR_WINMON_Pos) /**< (ADC_INTENCLR) Window Monitor Interrupt Disable Mask */
#define ADC_INTENCLR_WINMON ADC_INTENCLR_WINMON_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use ADC_INTENCLR_WINMON_Msk instead */
#define ADC_INTENCLR_MASK _U_(0x07) /**< \deprecated (ADC_INTENCLR) Register MASK (Use ADC_INTENCLR_Msk instead) */
#define ADC_INTENCLR_Msk _U_(0x07) /**< (ADC_INTENCLR) Register Mask */
/* -------- ADC_INTENSET : (ADC Offset: 0x05) (R/W 8) Interrupt Enable Set -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t RESRDY:1; /**< bit: 0 Result Ready Interrupt Enable */
uint8_t OVERRUN:1; /**< bit: 1 Overrun Interrupt Enable */
uint8_t WINMON:1; /**< bit: 2 Window Monitor Interrupt Enable */
uint8_t :5; /**< bit: 3..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} ADC_INTENSET_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define ADC_INTENSET_OFFSET (0x05) /**< (ADC_INTENSET) Interrupt Enable Set Offset */
#define ADC_INTENSET_RESETVALUE _U_(0x00) /**< (ADC_INTENSET) Interrupt Enable Set Reset Value */
#define ADC_INTENSET_RESRDY_Pos 0 /**< (ADC_INTENSET) Result Ready Interrupt Enable Position */
#define ADC_INTENSET_RESRDY_Msk (_U_(0x1) << ADC_INTENSET_RESRDY_Pos) /**< (ADC_INTENSET) Result Ready Interrupt Enable Mask */
#define ADC_INTENSET_RESRDY ADC_INTENSET_RESRDY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use ADC_INTENSET_RESRDY_Msk instead */
#define ADC_INTENSET_OVERRUN_Pos 1 /**< (ADC_INTENSET) Overrun Interrupt Enable Position */
#define ADC_INTENSET_OVERRUN_Msk (_U_(0x1) << ADC_INTENSET_OVERRUN_Pos) /**< (ADC_INTENSET) Overrun Interrupt Enable Mask */
#define ADC_INTENSET_OVERRUN ADC_INTENSET_OVERRUN_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use ADC_INTENSET_OVERRUN_Msk instead */
#define ADC_INTENSET_WINMON_Pos 2 /**< (ADC_INTENSET) Window Monitor Interrupt Enable Position */
#define ADC_INTENSET_WINMON_Msk (_U_(0x1) << ADC_INTENSET_WINMON_Pos) /**< (ADC_INTENSET) Window Monitor Interrupt Enable Mask */
#define ADC_INTENSET_WINMON ADC_INTENSET_WINMON_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use ADC_INTENSET_WINMON_Msk instead */
#define ADC_INTENSET_MASK _U_(0x07) /**< \deprecated (ADC_INTENSET) Register MASK (Use ADC_INTENSET_Msk instead) */
#define ADC_INTENSET_Msk _U_(0x07) /**< (ADC_INTENSET) Register Mask */
/* -------- ADC_INTFLAG : (ADC Offset: 0x06) (R/W 8) Interrupt Flag Status and Clear -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union { // __I to avoid read-modify-write on write-to-clear register
struct {
__I uint8_t RESRDY:1; /**< bit: 0 Result Ready Interrupt Flag */
__I uint8_t OVERRUN:1; /**< bit: 1 Overrun Interrupt Flag */
__I uint8_t WINMON:1; /**< bit: 2 Window Monitor Interrupt Flag */
__I uint8_t :5; /**< bit: 3..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} ADC_INTFLAG_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define ADC_INTFLAG_OFFSET (0x06) /**< (ADC_INTFLAG) Interrupt Flag Status and Clear Offset */
#define ADC_INTFLAG_RESETVALUE _U_(0x00) /**< (ADC_INTFLAG) Interrupt Flag Status and Clear Reset Value */
#define ADC_INTFLAG_RESRDY_Pos 0 /**< (ADC_INTFLAG) Result Ready Interrupt Flag Position */
#define ADC_INTFLAG_RESRDY_Msk (_U_(0x1) << ADC_INTFLAG_RESRDY_Pos) /**< (ADC_INTFLAG) Result Ready Interrupt Flag Mask */
#define ADC_INTFLAG_RESRDY ADC_INTFLAG_RESRDY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use ADC_INTFLAG_RESRDY_Msk instead */
#define ADC_INTFLAG_OVERRUN_Pos 1 /**< (ADC_INTFLAG) Overrun Interrupt Flag Position */
#define ADC_INTFLAG_OVERRUN_Msk (_U_(0x1) << ADC_INTFLAG_OVERRUN_Pos) /**< (ADC_INTFLAG) Overrun Interrupt Flag Mask */
#define ADC_INTFLAG_OVERRUN ADC_INTFLAG_OVERRUN_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use ADC_INTFLAG_OVERRUN_Msk instead */
#define ADC_INTFLAG_WINMON_Pos 2 /**< (ADC_INTFLAG) Window Monitor Interrupt Flag Position */
#define ADC_INTFLAG_WINMON_Msk (_U_(0x1) << ADC_INTFLAG_WINMON_Pos) /**< (ADC_INTFLAG) Window Monitor Interrupt Flag Mask */
#define ADC_INTFLAG_WINMON ADC_INTFLAG_WINMON_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use ADC_INTFLAG_WINMON_Msk instead */
#define ADC_INTFLAG_MASK _U_(0x07) /**< \deprecated (ADC_INTFLAG) Register MASK (Use ADC_INTFLAG_Msk instead) */
#define ADC_INTFLAG_Msk _U_(0x07) /**< (ADC_INTFLAG) Register Mask */
/* -------- ADC_SEQSTATUS : (ADC Offset: 0x07) (R/ 8) Sequence Status -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t SEQSTATE:5; /**< bit: 0..4 Sequence State */
uint8_t :2; /**< bit: 5..6 Reserved */
uint8_t SEQBUSY:1; /**< bit: 7 Sequence Busy */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} ADC_SEQSTATUS_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define ADC_SEQSTATUS_OFFSET (0x07) /**< (ADC_SEQSTATUS) Sequence Status Offset */
#define ADC_SEQSTATUS_RESETVALUE _U_(0x00) /**< (ADC_SEQSTATUS) Sequence Status Reset Value */
#define ADC_SEQSTATUS_SEQSTATE_Pos 0 /**< (ADC_SEQSTATUS) Sequence State Position */
#define ADC_SEQSTATUS_SEQSTATE_Msk (_U_(0x1F) << ADC_SEQSTATUS_SEQSTATE_Pos) /**< (ADC_SEQSTATUS) Sequence State Mask */
#define ADC_SEQSTATUS_SEQSTATE(value) (ADC_SEQSTATUS_SEQSTATE_Msk & ((value) << ADC_SEQSTATUS_SEQSTATE_Pos))
#define ADC_SEQSTATUS_SEQBUSY_Pos 7 /**< (ADC_SEQSTATUS) Sequence Busy Position */
#define ADC_SEQSTATUS_SEQBUSY_Msk (_U_(0x1) << ADC_SEQSTATUS_SEQBUSY_Pos) /**< (ADC_SEQSTATUS) Sequence Busy Mask */
#define ADC_SEQSTATUS_SEQBUSY ADC_SEQSTATUS_SEQBUSY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use ADC_SEQSTATUS_SEQBUSY_Msk instead */
#define ADC_SEQSTATUS_MASK _U_(0x9F) /**< \deprecated (ADC_SEQSTATUS) Register MASK (Use ADC_SEQSTATUS_Msk instead) */
#define ADC_SEQSTATUS_Msk _U_(0x9F) /**< (ADC_SEQSTATUS) Register Mask */
/* -------- ADC_INPUTCTRL : (ADC Offset: 0x08) (R/W 16) Input Control -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint16_t MUXPOS:5; /**< bit: 0..4 Positive Mux Input Selection */
uint16_t :3; /**< bit: 5..7 Reserved */
uint16_t MUXNEG:5; /**< bit: 8..12 Negative Mux Input Selection */
uint16_t :3; /**< bit: 13..15 Reserved */
} bit; /**< Structure used for bit access */
uint16_t reg; /**< Type used for register access */
} ADC_INPUTCTRL_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define ADC_INPUTCTRL_OFFSET (0x08) /**< (ADC_INPUTCTRL) Input Control Offset */
#define ADC_INPUTCTRL_RESETVALUE _U_(0x00) /**< (ADC_INPUTCTRL) Input Control Reset Value */
#define ADC_INPUTCTRL_MUXPOS_Pos 0 /**< (ADC_INPUTCTRL) Positive Mux Input Selection Position */
#define ADC_INPUTCTRL_MUXPOS_Msk (_U_(0x1F) << ADC_INPUTCTRL_MUXPOS_Pos) /**< (ADC_INPUTCTRL) Positive Mux Input Selection Mask */
#define ADC_INPUTCTRL_MUXPOS(value) (ADC_INPUTCTRL_MUXPOS_Msk & ((value) << ADC_INPUTCTRL_MUXPOS_Pos))
#define ADC_INPUTCTRL_MUXPOS_AIN0_Val _U_(0x0) /**< (ADC_INPUTCTRL) ADC AIN0 Pin */
#define ADC_INPUTCTRL_MUXPOS_AIN1_Val _U_(0x1) /**< (ADC_INPUTCTRL) ADC AIN1 Pin */
#define ADC_INPUTCTRL_MUXPOS_AIN2_Val _U_(0x2) /**< (ADC_INPUTCTRL) ADC AIN2 Pin */
#define ADC_INPUTCTRL_MUXPOS_AIN3_Val _U_(0x3) /**< (ADC_INPUTCTRL) ADC AIN3 Pin */
#define ADC_INPUTCTRL_MUXPOS_AIN4_Val _U_(0x4) /**< (ADC_INPUTCTRL) ADC AIN4 Pin */
#define ADC_INPUTCTRL_MUXPOS_AIN5_Val _U_(0x5) /**< (ADC_INPUTCTRL) ADC AIN5 Pin */
#define ADC_INPUTCTRL_MUXPOS_AIN6_Val _U_(0x6) /**< (ADC_INPUTCTRL) ADC AIN6 Pin */
#define ADC_INPUTCTRL_MUXPOS_AIN7_Val _U_(0x7) /**< (ADC_INPUTCTRL) ADC AIN7 Pin */
#define ADC_INPUTCTRL_MUXPOS_AIN8_Val _U_(0x8) /**< (ADC_INPUTCTRL) ADC AIN8 Pin */
#define ADC_INPUTCTRL_MUXPOS_AIN9_Val _U_(0x9) /**< (ADC_INPUTCTRL) ADC AIN9 Pin */
#define ADC_INPUTCTRL_MUXPOS_AIN10_Val _U_(0xA) /**< (ADC_INPUTCTRL) ADC AIN10 Pin */
#define ADC_INPUTCTRL_MUXPOS_AIN11_Val _U_(0xB) /**< (ADC_INPUTCTRL) ADC AIN11 Pin */
#define ADC_INPUTCTRL_MUXPOS_AIN12_Val _U_(0xC) /**< (ADC_INPUTCTRL) ADC AIN12 Pin */
#define ADC_INPUTCTRL_MUXPOS_AIN13_Val _U_(0xD) /**< (ADC_INPUTCTRL) ADC AIN13 Pin */
#define ADC_INPUTCTRL_MUXPOS_AIN14_Val _U_(0xE) /**< (ADC_INPUTCTRL) ADC AIN14 Pin */
#define ADC_INPUTCTRL_MUXPOS_AIN15_Val _U_(0xF) /**< (ADC_INPUTCTRL) ADC AIN15 Pin */
#define ADC_INPUTCTRL_MUXPOS_AIN16_Val _U_(0x10) /**< (ADC_INPUTCTRL) ADC AIN16 Pin */
#define ADC_INPUTCTRL_MUXPOS_AIN17_Val _U_(0x11) /**< (ADC_INPUTCTRL) ADC AIN17 Pin */
#define ADC_INPUTCTRL_MUXPOS_AIN18_Val _U_(0x12) /**< (ADC_INPUTCTRL) ADC AIN18 Pin */
#define ADC_INPUTCTRL_MUXPOS_AIN19_Val _U_(0x13) /**< (ADC_INPUTCTRL) ADC AIN19 Pin */
#define ADC_INPUTCTRL_MUXPOS_AIN20_Val _U_(0x14) /**< (ADC_INPUTCTRL) ADC AIN20 Pin */
#define ADC_INPUTCTRL_MUXPOS_AIN21_Val _U_(0x15) /**< (ADC_INPUTCTRL) ADC AIN21 Pin */
#define ADC_INPUTCTRL_MUXPOS_AIN22_Val _U_(0x16) /**< (ADC_INPUTCTRL) ADC AIN22 Pin */
#define ADC_INPUTCTRL_MUXPOS_AIN23_Val _U_(0x17) /**< (ADC_INPUTCTRL) ADC AIN23 Pin */
#define ADC_INPUTCTRL_MUXPOS_TEMP_Val _U_(0x18) /**< (ADC_INPUTCTRL) Temperature Sensor */
#define ADC_INPUTCTRL_MUXPOS_BANDGAP_Val _U_(0x19) /**< (ADC_INPUTCTRL) Bandgap Voltage */
#define ADC_INPUTCTRL_MUXPOS_SCALEDCOREVCC_Val _U_(0x1A) /**< (ADC_INPUTCTRL) 1/4 Scaled Core Supply */
#define ADC_INPUTCTRL_MUXPOS_SCALEDIOVCC_Val _U_(0x1B) /**< (ADC_INPUTCTRL) 1/4 Scaled I/O Supply */
#define ADC_INPUTCTRL_MUXPOS_DAC_Val _U_(0x1C) /**< (ADC_INPUTCTRL) DAC Output */
#define ADC_INPUTCTRL_MUXPOS_SCALEDVBAT_Val _U_(0x1D) /**< (ADC_INPUTCTRL) 1/4 Scaled VBAT Supply */
#define ADC_INPUTCTRL_MUXPOS_OPAMP01_Val _U_(0x1E) /**< (ADC_INPUTCTRL) OPAMP0 or OPAMP1 output */
#define ADC_INPUTCTRL_MUXPOS_OPAMP2_Val _U_(0x1F) /**< (ADC_INPUTCTRL) OPAMP2 output */
#define ADC_INPUTCTRL_MUXPOS_AIN0 (ADC_INPUTCTRL_MUXPOS_AIN0_Val << ADC_INPUTCTRL_MUXPOS_Pos) /**< (ADC_INPUTCTRL) ADC AIN0 Pin Position */
#define ADC_INPUTCTRL_MUXPOS_AIN1 (ADC_INPUTCTRL_MUXPOS_AIN1_Val << ADC_INPUTCTRL_MUXPOS_Pos) /**< (ADC_INPUTCTRL) ADC AIN1 Pin Position */
#define ADC_INPUTCTRL_MUXPOS_AIN2 (ADC_INPUTCTRL_MUXPOS_AIN2_Val << ADC_INPUTCTRL_MUXPOS_Pos) /**< (ADC_INPUTCTRL) ADC AIN2 Pin Position */
#define ADC_INPUTCTRL_MUXPOS_AIN3 (ADC_INPUTCTRL_MUXPOS_AIN3_Val << ADC_INPUTCTRL_MUXPOS_Pos) /**< (ADC_INPUTCTRL) ADC AIN3 Pin Position */
#define ADC_INPUTCTRL_MUXPOS_AIN4 (ADC_INPUTCTRL_MUXPOS_AIN4_Val << ADC_INPUTCTRL_MUXPOS_Pos) /**< (ADC_INPUTCTRL) ADC AIN4 Pin Position */
#define ADC_INPUTCTRL_MUXPOS_AIN5 (ADC_INPUTCTRL_MUXPOS_AIN5_Val << ADC_INPUTCTRL_MUXPOS_Pos) /**< (ADC_INPUTCTRL) ADC AIN5 Pin Position */
#define ADC_INPUTCTRL_MUXPOS_AIN6 (ADC_INPUTCTRL_MUXPOS_AIN6_Val << ADC_INPUTCTRL_MUXPOS_Pos) /**< (ADC_INPUTCTRL) ADC AIN6 Pin Position */
#define ADC_INPUTCTRL_MUXPOS_AIN7 (ADC_INPUTCTRL_MUXPOS_AIN7_Val << ADC_INPUTCTRL_MUXPOS_Pos) /**< (ADC_INPUTCTRL) ADC AIN7 Pin Position */
#define ADC_INPUTCTRL_MUXPOS_AIN8 (ADC_INPUTCTRL_MUXPOS_AIN8_Val << ADC_INPUTCTRL_MUXPOS_Pos) /**< (ADC_INPUTCTRL) ADC AIN8 Pin Position */
#define ADC_INPUTCTRL_MUXPOS_AIN9 (ADC_INPUTCTRL_MUXPOS_AIN9_Val << ADC_INPUTCTRL_MUXPOS_Pos) /**< (ADC_INPUTCTRL) ADC AIN9 Pin Position */
#define ADC_INPUTCTRL_MUXPOS_AIN10 (ADC_INPUTCTRL_MUXPOS_AIN10_Val << ADC_INPUTCTRL_MUXPOS_Pos) /**< (ADC_INPUTCTRL) ADC AIN10 Pin Position */
#define ADC_INPUTCTRL_MUXPOS_AIN11 (ADC_INPUTCTRL_MUXPOS_AIN11_Val << ADC_INPUTCTRL_MUXPOS_Pos) /**< (ADC_INPUTCTRL) ADC AIN11 Pin Position */
#define ADC_INPUTCTRL_MUXPOS_AIN12 (ADC_INPUTCTRL_MUXPOS_AIN12_Val << ADC_INPUTCTRL_MUXPOS_Pos) /**< (ADC_INPUTCTRL) ADC AIN12 Pin Position */
#define ADC_INPUTCTRL_MUXPOS_AIN13 (ADC_INPUTCTRL_MUXPOS_AIN13_Val << ADC_INPUTCTRL_MUXPOS_Pos) /**< (ADC_INPUTCTRL) ADC AIN13 Pin Position */
#define ADC_INPUTCTRL_MUXPOS_AIN14 (ADC_INPUTCTRL_MUXPOS_AIN14_Val << ADC_INPUTCTRL_MUXPOS_Pos) /**< (ADC_INPUTCTRL) ADC AIN14 Pin Position */
#define ADC_INPUTCTRL_MUXPOS_AIN15 (ADC_INPUTCTRL_MUXPOS_AIN15_Val << ADC_INPUTCTRL_MUXPOS_Pos) /**< (ADC_INPUTCTRL) ADC AIN15 Pin Position */
#define ADC_INPUTCTRL_MUXPOS_AIN16 (ADC_INPUTCTRL_MUXPOS_AIN16_Val << ADC_INPUTCTRL_MUXPOS_Pos) /**< (ADC_INPUTCTRL) ADC AIN16 Pin Position */
#define ADC_INPUTCTRL_MUXPOS_AIN17 (ADC_INPUTCTRL_MUXPOS_AIN17_Val << ADC_INPUTCTRL_MUXPOS_Pos) /**< (ADC_INPUTCTRL) ADC AIN17 Pin Position */
#define ADC_INPUTCTRL_MUXPOS_AIN18 (ADC_INPUTCTRL_MUXPOS_AIN18_Val << ADC_INPUTCTRL_MUXPOS_Pos) /**< (ADC_INPUTCTRL) ADC AIN18 Pin Position */
#define ADC_INPUTCTRL_MUXPOS_AIN19 (ADC_INPUTCTRL_MUXPOS_AIN19_Val << ADC_INPUTCTRL_MUXPOS_Pos) /**< (ADC_INPUTCTRL) ADC AIN19 Pin Position */
#define ADC_INPUTCTRL_MUXPOS_AIN20 (ADC_INPUTCTRL_MUXPOS_AIN20_Val << ADC_INPUTCTRL_MUXPOS_Pos) /**< (ADC_INPUTCTRL) ADC AIN20 Pin Position */
#define ADC_INPUTCTRL_MUXPOS_AIN21 (ADC_INPUTCTRL_MUXPOS_AIN21_Val << ADC_INPUTCTRL_MUXPOS_Pos) /**< (ADC_INPUTCTRL) ADC AIN21 Pin Position */
#define ADC_INPUTCTRL_MUXPOS_AIN22 (ADC_INPUTCTRL_MUXPOS_AIN22_Val << ADC_INPUTCTRL_MUXPOS_Pos) /**< (ADC_INPUTCTRL) ADC AIN22 Pin Position */
#define ADC_INPUTCTRL_MUXPOS_AIN23 (ADC_INPUTCTRL_MUXPOS_AIN23_Val << ADC_INPUTCTRL_MUXPOS_Pos) /**< (ADC_INPUTCTRL) ADC AIN23 Pin Position */
#define ADC_INPUTCTRL_MUXPOS_TEMP (ADC_INPUTCTRL_MUXPOS_TEMP_Val << ADC_INPUTCTRL_MUXPOS_Pos) /**< (ADC_INPUTCTRL) Temperature Sensor Position */
#define ADC_INPUTCTRL_MUXPOS_BANDGAP (ADC_INPUTCTRL_MUXPOS_BANDGAP_Val << ADC_INPUTCTRL_MUXPOS_Pos) /**< (ADC_INPUTCTRL) Bandgap Voltage Position */
#define ADC_INPUTCTRL_MUXPOS_SCALEDCOREVCC (ADC_INPUTCTRL_MUXPOS_SCALEDCOREVCC_Val << ADC_INPUTCTRL_MUXPOS_Pos) /**< (ADC_INPUTCTRL) 1/4 Scaled Core Supply Position */
#define ADC_INPUTCTRL_MUXPOS_SCALEDIOVCC (ADC_INPUTCTRL_MUXPOS_SCALEDIOVCC_Val << ADC_INPUTCTRL_MUXPOS_Pos) /**< (ADC_INPUTCTRL) 1/4 Scaled I/O Supply Position */
#define ADC_INPUTCTRL_MUXPOS_DAC (ADC_INPUTCTRL_MUXPOS_DAC_Val << ADC_INPUTCTRL_MUXPOS_Pos) /**< (ADC_INPUTCTRL) DAC Output Position */
#define ADC_INPUTCTRL_MUXPOS_SCALEDVBAT (ADC_INPUTCTRL_MUXPOS_SCALEDVBAT_Val << ADC_INPUTCTRL_MUXPOS_Pos) /**< (ADC_INPUTCTRL) 1/4 Scaled VBAT Supply Position */
#define ADC_INPUTCTRL_MUXPOS_OPAMP01 (ADC_INPUTCTRL_MUXPOS_OPAMP01_Val << ADC_INPUTCTRL_MUXPOS_Pos) /**< (ADC_INPUTCTRL) OPAMP0 or OPAMP1 output Position */
#define ADC_INPUTCTRL_MUXPOS_OPAMP2 (ADC_INPUTCTRL_MUXPOS_OPAMP2_Val << ADC_INPUTCTRL_MUXPOS_Pos) /**< (ADC_INPUTCTRL) OPAMP2 output Position */
#define ADC_INPUTCTRL_MUXNEG_Pos 8 /**< (ADC_INPUTCTRL) Negative Mux Input Selection Position */
#define ADC_INPUTCTRL_MUXNEG_Msk (_U_(0x1F) << ADC_INPUTCTRL_MUXNEG_Pos) /**< (ADC_INPUTCTRL) Negative Mux Input Selection Mask */
#define ADC_INPUTCTRL_MUXNEG(value) (ADC_INPUTCTRL_MUXNEG_Msk & ((value) << ADC_INPUTCTRL_MUXNEG_Pos))
#define ADC_INPUTCTRL_MUXNEG_AIN0_Val _U_(0x0) /**< (ADC_INPUTCTRL) ADC AIN0 Pin */
#define ADC_INPUTCTRL_MUXNEG_AIN1_Val _U_(0x1) /**< (ADC_INPUTCTRL) ADC AIN1 Pin */
#define ADC_INPUTCTRL_MUXNEG_AIN2_Val _U_(0x2) /**< (ADC_INPUTCTRL) ADC AIN2 Pin */
#define ADC_INPUTCTRL_MUXNEG_AIN3_Val _U_(0x3) /**< (ADC_INPUTCTRL) ADC AIN3 Pin */
#define ADC_INPUTCTRL_MUXNEG_AIN4_Val _U_(0x4) /**< (ADC_INPUTCTRL) ADC AIN4 Pin */
#define ADC_INPUTCTRL_MUXNEG_AIN5_Val _U_(0x5) /**< (ADC_INPUTCTRL) ADC AIN5 Pin */
#define ADC_INPUTCTRL_MUXNEG_AIN6_Val _U_(0x6) /**< (ADC_INPUTCTRL) ADC AIN6 Pin */
#define ADC_INPUTCTRL_MUXNEG_AIN7_Val _U_(0x7) /**< (ADC_INPUTCTRL) ADC AIN7 Pin */
#define ADC_INPUTCTRL_MUXNEG_AIN0 (ADC_INPUTCTRL_MUXNEG_AIN0_Val << ADC_INPUTCTRL_MUXNEG_Pos) /**< (ADC_INPUTCTRL) ADC AIN0 Pin Position */
#define ADC_INPUTCTRL_MUXNEG_AIN1 (ADC_INPUTCTRL_MUXNEG_AIN1_Val << ADC_INPUTCTRL_MUXNEG_Pos) /**< (ADC_INPUTCTRL) ADC AIN1 Pin Position */
#define ADC_INPUTCTRL_MUXNEG_AIN2 (ADC_INPUTCTRL_MUXNEG_AIN2_Val << ADC_INPUTCTRL_MUXNEG_Pos) /**< (ADC_INPUTCTRL) ADC AIN2 Pin Position */
#define ADC_INPUTCTRL_MUXNEG_AIN3 (ADC_INPUTCTRL_MUXNEG_AIN3_Val << ADC_INPUTCTRL_MUXNEG_Pos) /**< (ADC_INPUTCTRL) ADC AIN3 Pin Position */
#define ADC_INPUTCTRL_MUXNEG_AIN4 (ADC_INPUTCTRL_MUXNEG_AIN4_Val << ADC_INPUTCTRL_MUXNEG_Pos) /**< (ADC_INPUTCTRL) ADC AIN4 Pin Position */
#define ADC_INPUTCTRL_MUXNEG_AIN5 (ADC_INPUTCTRL_MUXNEG_AIN5_Val << ADC_INPUTCTRL_MUXNEG_Pos) /**< (ADC_INPUTCTRL) ADC AIN5 Pin Position */
#define ADC_INPUTCTRL_MUXNEG_AIN6 (ADC_INPUTCTRL_MUXNEG_AIN6_Val << ADC_INPUTCTRL_MUXNEG_Pos) /**< (ADC_INPUTCTRL) ADC AIN6 Pin Position */
#define ADC_INPUTCTRL_MUXNEG_AIN7 (ADC_INPUTCTRL_MUXNEG_AIN7_Val << ADC_INPUTCTRL_MUXNEG_Pos) /**< (ADC_INPUTCTRL) ADC AIN7 Pin Position */
#define ADC_INPUTCTRL_MASK _U_(0x1F1F) /**< \deprecated (ADC_INPUTCTRL) Register MASK (Use ADC_INPUTCTRL_Msk instead) */
#define ADC_INPUTCTRL_Msk _U_(0x1F1F) /**< (ADC_INPUTCTRL) Register Mask */
/* -------- ADC_CTRLC : (ADC Offset: 0x0a) (R/W 16) Control C -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint16_t DIFFMODE:1; /**< bit: 0 Differential Mode */
uint16_t LEFTADJ:1; /**< bit: 1 Left-Adjusted Result */
uint16_t FREERUN:1; /**< bit: 2 Free Running Mode */
uint16_t CORREN:1; /**< bit: 3 Digital Correction Logic Enable */
uint16_t RESSEL:2; /**< bit: 4..5 Conversion Result Resolution */
uint16_t :1; /**< bit: 6 Reserved */
uint16_t R2R:1; /**< bit: 7 Rail-to-Rail mode enable */
uint16_t WINMODE:3; /**< bit: 8..10 Window Monitor Mode */
uint16_t :1; /**< bit: 11 Reserved */
uint16_t DUALSEL:2; /**< bit: 12..13 Dual Mode Trigger Selection */
uint16_t :2; /**< bit: 14..15 Reserved */
} bit; /**< Structure used for bit access */
uint16_t reg; /**< Type used for register access */
} ADC_CTRLC_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define ADC_CTRLC_OFFSET (0x0A) /**< (ADC_CTRLC) Control C Offset */
#define ADC_CTRLC_RESETVALUE _U_(0x00) /**< (ADC_CTRLC) Control C Reset Value */
#define ADC_CTRLC_DIFFMODE_Pos 0 /**< (ADC_CTRLC) Differential Mode Position */
#define ADC_CTRLC_DIFFMODE_Msk (_U_(0x1) << ADC_CTRLC_DIFFMODE_Pos) /**< (ADC_CTRLC) Differential Mode Mask */
#define ADC_CTRLC_DIFFMODE ADC_CTRLC_DIFFMODE_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use ADC_CTRLC_DIFFMODE_Msk instead */
#define ADC_CTRLC_LEFTADJ_Pos 1 /**< (ADC_CTRLC) Left-Adjusted Result Position */
#define ADC_CTRLC_LEFTADJ_Msk (_U_(0x1) << ADC_CTRLC_LEFTADJ_Pos) /**< (ADC_CTRLC) Left-Adjusted Result Mask */
#define ADC_CTRLC_LEFTADJ ADC_CTRLC_LEFTADJ_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use ADC_CTRLC_LEFTADJ_Msk instead */
#define ADC_CTRLC_FREERUN_Pos 2 /**< (ADC_CTRLC) Free Running Mode Position */
#define ADC_CTRLC_FREERUN_Msk (_U_(0x1) << ADC_CTRLC_FREERUN_Pos) /**< (ADC_CTRLC) Free Running Mode Mask */
#define ADC_CTRLC_FREERUN ADC_CTRLC_FREERUN_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use ADC_CTRLC_FREERUN_Msk instead */
#define ADC_CTRLC_CORREN_Pos 3 /**< (ADC_CTRLC) Digital Correction Logic Enable Position */
#define ADC_CTRLC_CORREN_Msk (_U_(0x1) << ADC_CTRLC_CORREN_Pos) /**< (ADC_CTRLC) Digital Correction Logic Enable Mask */
#define ADC_CTRLC_CORREN ADC_CTRLC_CORREN_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use ADC_CTRLC_CORREN_Msk instead */
#define ADC_CTRLC_RESSEL_Pos 4 /**< (ADC_CTRLC) Conversion Result Resolution Position */
#define ADC_CTRLC_RESSEL_Msk (_U_(0x3) << ADC_CTRLC_RESSEL_Pos) /**< (ADC_CTRLC) Conversion Result Resolution Mask */
#define ADC_CTRLC_RESSEL(value) (ADC_CTRLC_RESSEL_Msk & ((value) << ADC_CTRLC_RESSEL_Pos))
#define ADC_CTRLC_RESSEL_12BIT_Val _U_(0x0) /**< (ADC_CTRLC) 12-bit result */
#define ADC_CTRLC_RESSEL_16BIT_Val _U_(0x1) /**< (ADC_CTRLC) For averaging mode output */
#define ADC_CTRLC_RESSEL_10BIT_Val _U_(0x2) /**< (ADC_CTRLC) 10-bit result */
#define ADC_CTRLC_RESSEL_8BIT_Val _U_(0x3) /**< (ADC_CTRLC) 8-bit result */
#define ADC_CTRLC_RESSEL_12BIT (ADC_CTRLC_RESSEL_12BIT_Val << ADC_CTRLC_RESSEL_Pos) /**< (ADC_CTRLC) 12-bit result Position */
#define ADC_CTRLC_RESSEL_16BIT (ADC_CTRLC_RESSEL_16BIT_Val << ADC_CTRLC_RESSEL_Pos) /**< (ADC_CTRLC) For averaging mode output Position */
#define ADC_CTRLC_RESSEL_10BIT (ADC_CTRLC_RESSEL_10BIT_Val << ADC_CTRLC_RESSEL_Pos) /**< (ADC_CTRLC) 10-bit result Position */
#define ADC_CTRLC_RESSEL_8BIT (ADC_CTRLC_RESSEL_8BIT_Val << ADC_CTRLC_RESSEL_Pos) /**< (ADC_CTRLC) 8-bit result Position */
#define ADC_CTRLC_R2R_Pos 7 /**< (ADC_CTRLC) Rail-to-Rail mode enable Position */
#define ADC_CTRLC_R2R_Msk (_U_(0x1) << ADC_CTRLC_R2R_Pos) /**< (ADC_CTRLC) Rail-to-Rail mode enable Mask */
#define ADC_CTRLC_R2R ADC_CTRLC_R2R_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use ADC_CTRLC_R2R_Msk instead */
#define ADC_CTRLC_WINMODE_Pos 8 /**< (ADC_CTRLC) Window Monitor Mode Position */
#define ADC_CTRLC_WINMODE_Msk (_U_(0x7) << ADC_CTRLC_WINMODE_Pos) /**< (ADC_CTRLC) Window Monitor Mode Mask */
#define ADC_CTRLC_WINMODE(value) (ADC_CTRLC_WINMODE_Msk & ((value) << ADC_CTRLC_WINMODE_Pos))
#define ADC_CTRLC_WINMODE_DISABLE_Val _U_(0x0) /**< (ADC_CTRLC) No window mode (default) */
#define ADC_CTRLC_WINMODE_MODE1_Val _U_(0x1) /**< (ADC_CTRLC) RESULT > WINLT */
#define ADC_CTRLC_WINMODE_MODE2_Val _U_(0x2) /**< (ADC_CTRLC) RESULT < WINUT */
#define ADC_CTRLC_WINMODE_MODE3_Val _U_(0x3) /**< (ADC_CTRLC) WINLT < RESULT < WINUT */
#define ADC_CTRLC_WINMODE_MODE4_Val _U_(0x4) /**< (ADC_CTRLC) !(WINLT < RESULT < WINUT) */
#define ADC_CTRLC_WINMODE_DISABLE (ADC_CTRLC_WINMODE_DISABLE_Val << ADC_CTRLC_WINMODE_Pos) /**< (ADC_CTRLC) No window mode (default) Position */
#define ADC_CTRLC_WINMODE_MODE1 (ADC_CTRLC_WINMODE_MODE1_Val << ADC_CTRLC_WINMODE_Pos) /**< (ADC_CTRLC) RESULT > WINLT Position */
#define ADC_CTRLC_WINMODE_MODE2 (ADC_CTRLC_WINMODE_MODE2_Val << ADC_CTRLC_WINMODE_Pos) /**< (ADC_CTRLC) RESULT < WINUT Position */
#define ADC_CTRLC_WINMODE_MODE3 (ADC_CTRLC_WINMODE_MODE3_Val << ADC_CTRLC_WINMODE_Pos) /**< (ADC_CTRLC) WINLT < RESULT < WINUT Position */
#define ADC_CTRLC_WINMODE_MODE4 (ADC_CTRLC_WINMODE_MODE4_Val << ADC_CTRLC_WINMODE_Pos) /**< (ADC_CTRLC) !(WINLT < RESULT < WINUT) Position */
#define ADC_CTRLC_DUALSEL_Pos 12 /**< (ADC_CTRLC) Dual Mode Trigger Selection Position */
#define ADC_CTRLC_DUALSEL_Msk (_U_(0x3) << ADC_CTRLC_DUALSEL_Pos) /**< (ADC_CTRLC) Dual Mode Trigger Selection Mask */
#define ADC_CTRLC_DUALSEL(value) (ADC_CTRLC_DUALSEL_Msk & ((value) << ADC_CTRLC_DUALSEL_Pos))
#define ADC_CTRLC_DUALSEL_BOTH_Val _U_(0x0) /**< (ADC_CTRLC) Start event or software trigger will start a conversion on both ADCs */
#define ADC_CTRLC_DUALSEL_INTERLEAVE_Val _U_(0x1) /**< (ADC_CTRLC) START event or software trigger will alternatingly start a conversion on ADC0 and ADC1 */
#define ADC_CTRLC_DUALSEL_BOTH (ADC_CTRLC_DUALSEL_BOTH_Val << ADC_CTRLC_DUALSEL_Pos) /**< (ADC_CTRLC) Start event or software trigger will start a conversion on both ADCs Position */
#define ADC_CTRLC_DUALSEL_INTERLEAVE (ADC_CTRLC_DUALSEL_INTERLEAVE_Val << ADC_CTRLC_DUALSEL_Pos) /**< (ADC_CTRLC) START event or software trigger will alternatingly start a conversion on ADC0 and ADC1 Position */
#define ADC_CTRLC_MASK _U_(0x37BF) /**< \deprecated (ADC_CTRLC) Register MASK (Use ADC_CTRLC_Msk instead) */
#define ADC_CTRLC_Msk _U_(0x37BF) /**< (ADC_CTRLC) Register Mask */
/* -------- ADC_AVGCTRL : (ADC Offset: 0x0c) (R/W 8) Average Control -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t SAMPLENUM:4; /**< bit: 0..3 Number of Samples to be Collected */
uint8_t ADJRES:3; /**< bit: 4..6 Adjusting Result / Division Coefficient */
uint8_t :1; /**< bit: 7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} ADC_AVGCTRL_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define ADC_AVGCTRL_OFFSET (0x0C) /**< (ADC_AVGCTRL) Average Control Offset */
#define ADC_AVGCTRL_RESETVALUE _U_(0x00) /**< (ADC_AVGCTRL) Average Control Reset Value */
#define ADC_AVGCTRL_SAMPLENUM_Pos 0 /**< (ADC_AVGCTRL) Number of Samples to be Collected Position */
#define ADC_AVGCTRL_SAMPLENUM_Msk (_U_(0xF) << ADC_AVGCTRL_SAMPLENUM_Pos) /**< (ADC_AVGCTRL) Number of Samples to be Collected Mask */
#define ADC_AVGCTRL_SAMPLENUM(value) (ADC_AVGCTRL_SAMPLENUM_Msk & ((value) << ADC_AVGCTRL_SAMPLENUM_Pos))
#define ADC_AVGCTRL_SAMPLENUM_1_Val _U_(0x0) /**< (ADC_AVGCTRL) 1 sample */
#define ADC_AVGCTRL_SAMPLENUM_2_Val _U_(0x1) /**< (ADC_AVGCTRL) 2 samples */
#define ADC_AVGCTRL_SAMPLENUM_4_Val _U_(0x2) /**< (ADC_AVGCTRL) 4 samples */
#define ADC_AVGCTRL_SAMPLENUM_8_Val _U_(0x3) /**< (ADC_AVGCTRL) 8 samples */
#define ADC_AVGCTRL_SAMPLENUM_16_Val _U_(0x4) /**< (ADC_AVGCTRL) 16 samples */
#define ADC_AVGCTRL_SAMPLENUM_32_Val _U_(0x5) /**< (ADC_AVGCTRL) 32 samples */
#define ADC_AVGCTRL_SAMPLENUM_64_Val _U_(0x6) /**< (ADC_AVGCTRL) 64 samples */
#define ADC_AVGCTRL_SAMPLENUM_128_Val _U_(0x7) /**< (ADC_AVGCTRL) 128 samples */
#define ADC_AVGCTRL_SAMPLENUM_256_Val _U_(0x8) /**< (ADC_AVGCTRL) 256 samples */
#define ADC_AVGCTRL_SAMPLENUM_512_Val _U_(0x9) /**< (ADC_AVGCTRL) 512 samples */
#define ADC_AVGCTRL_SAMPLENUM_1024_Val _U_(0xA) /**< (ADC_AVGCTRL) 1024 samples */
#define ADC_AVGCTRL_SAMPLENUM_1 (ADC_AVGCTRL_SAMPLENUM_1_Val << ADC_AVGCTRL_SAMPLENUM_Pos) /**< (ADC_AVGCTRL) 1 sample Position */
#define ADC_AVGCTRL_SAMPLENUM_2 (ADC_AVGCTRL_SAMPLENUM_2_Val << ADC_AVGCTRL_SAMPLENUM_Pos) /**< (ADC_AVGCTRL) 2 samples Position */
#define ADC_AVGCTRL_SAMPLENUM_4 (ADC_AVGCTRL_SAMPLENUM_4_Val << ADC_AVGCTRL_SAMPLENUM_Pos) /**< (ADC_AVGCTRL) 4 samples Position */
#define ADC_AVGCTRL_SAMPLENUM_8 (ADC_AVGCTRL_SAMPLENUM_8_Val << ADC_AVGCTRL_SAMPLENUM_Pos) /**< (ADC_AVGCTRL) 8 samples Position */
#define ADC_AVGCTRL_SAMPLENUM_16 (ADC_AVGCTRL_SAMPLENUM_16_Val << ADC_AVGCTRL_SAMPLENUM_Pos) /**< (ADC_AVGCTRL) 16 samples Position */
#define ADC_AVGCTRL_SAMPLENUM_32 (ADC_AVGCTRL_SAMPLENUM_32_Val << ADC_AVGCTRL_SAMPLENUM_Pos) /**< (ADC_AVGCTRL) 32 samples Position */
#define ADC_AVGCTRL_SAMPLENUM_64 (ADC_AVGCTRL_SAMPLENUM_64_Val << ADC_AVGCTRL_SAMPLENUM_Pos) /**< (ADC_AVGCTRL) 64 samples Position */
#define ADC_AVGCTRL_SAMPLENUM_128 (ADC_AVGCTRL_SAMPLENUM_128_Val << ADC_AVGCTRL_SAMPLENUM_Pos) /**< (ADC_AVGCTRL) 128 samples Position */
#define ADC_AVGCTRL_SAMPLENUM_256 (ADC_AVGCTRL_SAMPLENUM_256_Val << ADC_AVGCTRL_SAMPLENUM_Pos) /**< (ADC_AVGCTRL) 256 samples Position */
#define ADC_AVGCTRL_SAMPLENUM_512 (ADC_AVGCTRL_SAMPLENUM_512_Val << ADC_AVGCTRL_SAMPLENUM_Pos) /**< (ADC_AVGCTRL) 512 samples Position */
#define ADC_AVGCTRL_SAMPLENUM_1024 (ADC_AVGCTRL_SAMPLENUM_1024_Val << ADC_AVGCTRL_SAMPLENUM_Pos) /**< (ADC_AVGCTRL) 1024 samples Position */
#define ADC_AVGCTRL_ADJRES_Pos 4 /**< (ADC_AVGCTRL) Adjusting Result / Division Coefficient Position */
#define ADC_AVGCTRL_ADJRES_Msk (_U_(0x7) << ADC_AVGCTRL_ADJRES_Pos) /**< (ADC_AVGCTRL) Adjusting Result / Division Coefficient Mask */
#define ADC_AVGCTRL_ADJRES(value) (ADC_AVGCTRL_ADJRES_Msk & ((value) << ADC_AVGCTRL_ADJRES_Pos))
#define ADC_AVGCTRL_MASK _U_(0x7F) /**< \deprecated (ADC_AVGCTRL) Register MASK (Use ADC_AVGCTRL_Msk instead) */
#define ADC_AVGCTRL_Msk _U_(0x7F) /**< (ADC_AVGCTRL) Register Mask */
/* -------- ADC_SAMPCTRL : (ADC Offset: 0x0d) (R/W 8) Sample Time Control -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t SAMPLEN:6; /**< bit: 0..5 Sampling Time Length */
uint8_t :1; /**< bit: 6 Reserved */
uint8_t OFFCOMP:1; /**< bit: 7 Comparator Offset Compensation Enable */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} ADC_SAMPCTRL_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define ADC_SAMPCTRL_OFFSET (0x0D) /**< (ADC_SAMPCTRL) Sample Time Control Offset */
#define ADC_SAMPCTRL_RESETVALUE _U_(0x00) /**< (ADC_SAMPCTRL) Sample Time Control Reset Value */
#define ADC_SAMPCTRL_SAMPLEN_Pos 0 /**< (ADC_SAMPCTRL) Sampling Time Length Position */
#define ADC_SAMPCTRL_SAMPLEN_Msk (_U_(0x3F) << ADC_SAMPCTRL_SAMPLEN_Pos) /**< (ADC_SAMPCTRL) Sampling Time Length Mask */
#define ADC_SAMPCTRL_SAMPLEN(value) (ADC_SAMPCTRL_SAMPLEN_Msk & ((value) << ADC_SAMPCTRL_SAMPLEN_Pos))
#define ADC_SAMPCTRL_OFFCOMP_Pos 7 /**< (ADC_SAMPCTRL) Comparator Offset Compensation Enable Position */
#define ADC_SAMPCTRL_OFFCOMP_Msk (_U_(0x1) << ADC_SAMPCTRL_OFFCOMP_Pos) /**< (ADC_SAMPCTRL) Comparator Offset Compensation Enable Mask */
#define ADC_SAMPCTRL_OFFCOMP ADC_SAMPCTRL_OFFCOMP_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use ADC_SAMPCTRL_OFFCOMP_Msk instead */
#define ADC_SAMPCTRL_MASK _U_(0xBF) /**< \deprecated (ADC_SAMPCTRL) Register MASK (Use ADC_SAMPCTRL_Msk instead) */
#define ADC_SAMPCTRL_Msk _U_(0xBF) /**< (ADC_SAMPCTRL) Register Mask */
/* -------- ADC_WINLT : (ADC Offset: 0x0e) (R/W 16) Window Monitor Lower Threshold -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint16_t WINLT:16; /**< bit: 0..15 Window Lower Threshold */
} bit; /**< Structure used for bit access */
uint16_t reg; /**< Type used for register access */
} ADC_WINLT_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define ADC_WINLT_OFFSET (0x0E) /**< (ADC_WINLT) Window Monitor Lower Threshold Offset */
#define ADC_WINLT_RESETVALUE _U_(0x00) /**< (ADC_WINLT) Window Monitor Lower Threshold Reset Value */
#define ADC_WINLT_WINLT_Pos 0 /**< (ADC_WINLT) Window Lower Threshold Position */
#define ADC_WINLT_WINLT_Msk (_U_(0xFFFF) << ADC_WINLT_WINLT_Pos) /**< (ADC_WINLT) Window Lower Threshold Mask */
#define ADC_WINLT_WINLT(value) (ADC_WINLT_WINLT_Msk & ((value) << ADC_WINLT_WINLT_Pos))
#define ADC_WINLT_MASK _U_(0xFFFF) /**< \deprecated (ADC_WINLT) Register MASK (Use ADC_WINLT_Msk instead) */
#define ADC_WINLT_Msk _U_(0xFFFF) /**< (ADC_WINLT) Register Mask */
/* -------- ADC_WINUT : (ADC Offset: 0x10) (R/W 16) Window Monitor Upper Threshold -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint16_t WINUT:16; /**< bit: 0..15 Window Upper Threshold */
} bit; /**< Structure used for bit access */
uint16_t reg; /**< Type used for register access */
} ADC_WINUT_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define ADC_WINUT_OFFSET (0x10) /**< (ADC_WINUT) Window Monitor Upper Threshold Offset */
#define ADC_WINUT_RESETVALUE _U_(0x00) /**< (ADC_WINUT) Window Monitor Upper Threshold Reset Value */
#define ADC_WINUT_WINUT_Pos 0 /**< (ADC_WINUT) Window Upper Threshold Position */
#define ADC_WINUT_WINUT_Msk (_U_(0xFFFF) << ADC_WINUT_WINUT_Pos) /**< (ADC_WINUT) Window Upper Threshold Mask */
#define ADC_WINUT_WINUT(value) (ADC_WINUT_WINUT_Msk & ((value) << ADC_WINUT_WINUT_Pos))
#define ADC_WINUT_MASK _U_(0xFFFF) /**< \deprecated (ADC_WINUT) Register MASK (Use ADC_WINUT_Msk instead) */
#define ADC_WINUT_Msk _U_(0xFFFF) /**< (ADC_WINUT) Register Mask */
/* -------- ADC_GAINCORR : (ADC Offset: 0x12) (R/W 16) Gain Correction -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint16_t GAINCORR:12; /**< bit: 0..11 Gain Correction Value */
uint16_t :4; /**< bit: 12..15 Reserved */
} bit; /**< Structure used for bit access */
uint16_t reg; /**< Type used for register access */
} ADC_GAINCORR_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define ADC_GAINCORR_OFFSET (0x12) /**< (ADC_GAINCORR) Gain Correction Offset */
#define ADC_GAINCORR_RESETVALUE _U_(0x00) /**< (ADC_GAINCORR) Gain Correction Reset Value */
#define ADC_GAINCORR_GAINCORR_Pos 0 /**< (ADC_GAINCORR) Gain Correction Value Position */
#define ADC_GAINCORR_GAINCORR_Msk (_U_(0xFFF) << ADC_GAINCORR_GAINCORR_Pos) /**< (ADC_GAINCORR) Gain Correction Value Mask */
#define ADC_GAINCORR_GAINCORR(value) (ADC_GAINCORR_GAINCORR_Msk & ((value) << ADC_GAINCORR_GAINCORR_Pos))
#define ADC_GAINCORR_MASK _U_(0xFFF) /**< \deprecated (ADC_GAINCORR) Register MASK (Use ADC_GAINCORR_Msk instead) */
#define ADC_GAINCORR_Msk _U_(0xFFF) /**< (ADC_GAINCORR) Register Mask */
/* -------- ADC_OFFSETCORR : (ADC Offset: 0x14) (R/W 16) Offset Correction -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint16_t OFFSETCORR:12; /**< bit: 0..11 Offset Correction Value */
uint16_t :4; /**< bit: 12..15 Reserved */
} bit; /**< Structure used for bit access */
uint16_t reg; /**< Type used for register access */
} ADC_OFFSETCORR_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define ADC_OFFSETCORR_OFFSET (0x14) /**< (ADC_OFFSETCORR) Offset Correction Offset */
#define ADC_OFFSETCORR_RESETVALUE _U_(0x00) /**< (ADC_OFFSETCORR) Offset Correction Reset Value */
#define ADC_OFFSETCORR_OFFSETCORR_Pos 0 /**< (ADC_OFFSETCORR) Offset Correction Value Position */
#define ADC_OFFSETCORR_OFFSETCORR_Msk (_U_(0xFFF) << ADC_OFFSETCORR_OFFSETCORR_Pos) /**< (ADC_OFFSETCORR) Offset Correction Value Mask */
#define ADC_OFFSETCORR_OFFSETCORR(value) (ADC_OFFSETCORR_OFFSETCORR_Msk & ((value) << ADC_OFFSETCORR_OFFSETCORR_Pos))
#define ADC_OFFSETCORR_MASK _U_(0xFFF) /**< \deprecated (ADC_OFFSETCORR) Register MASK (Use ADC_OFFSETCORR_Msk instead) */
#define ADC_OFFSETCORR_Msk _U_(0xFFF) /**< (ADC_OFFSETCORR) Register Mask */
/* -------- ADC_SWTRIG : (ADC Offset: 0x18) (R/W 8) Software Trigger -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t FLUSH:1; /**< bit: 0 ADC Flush */
uint8_t START:1; /**< bit: 1 Start ADC Conversion */
uint8_t :6; /**< bit: 2..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} ADC_SWTRIG_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define ADC_SWTRIG_OFFSET (0x18) /**< (ADC_SWTRIG) Software Trigger Offset */
#define ADC_SWTRIG_RESETVALUE _U_(0x00) /**< (ADC_SWTRIG) Software Trigger Reset Value */
#define ADC_SWTRIG_FLUSH_Pos 0 /**< (ADC_SWTRIG) ADC Flush Position */
#define ADC_SWTRIG_FLUSH_Msk (_U_(0x1) << ADC_SWTRIG_FLUSH_Pos) /**< (ADC_SWTRIG) ADC Flush Mask */
#define ADC_SWTRIG_FLUSH ADC_SWTRIG_FLUSH_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use ADC_SWTRIG_FLUSH_Msk instead */
#define ADC_SWTRIG_START_Pos 1 /**< (ADC_SWTRIG) Start ADC Conversion Position */
#define ADC_SWTRIG_START_Msk (_U_(0x1) << ADC_SWTRIG_START_Pos) /**< (ADC_SWTRIG) Start ADC Conversion Mask */
#define ADC_SWTRIG_START ADC_SWTRIG_START_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use ADC_SWTRIG_START_Msk instead */
#define ADC_SWTRIG_MASK _U_(0x03) /**< \deprecated (ADC_SWTRIG) Register MASK (Use ADC_SWTRIG_Msk instead) */
#define ADC_SWTRIG_Msk _U_(0x03) /**< (ADC_SWTRIG) Register Mask */
/* -------- ADC_DBGCTRL : (ADC Offset: 0x1c) (R/W 8) Debug Control -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t DBGRUN:1; /**< bit: 0 Debug Run */
uint8_t :7; /**< bit: 1..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} ADC_DBGCTRL_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define ADC_DBGCTRL_OFFSET (0x1C) /**< (ADC_DBGCTRL) Debug Control Offset */
#define ADC_DBGCTRL_RESETVALUE _U_(0x00) /**< (ADC_DBGCTRL) Debug Control Reset Value */
#define ADC_DBGCTRL_DBGRUN_Pos 0 /**< (ADC_DBGCTRL) Debug Run Position */
#define ADC_DBGCTRL_DBGRUN_Msk (_U_(0x1) << ADC_DBGCTRL_DBGRUN_Pos) /**< (ADC_DBGCTRL) Debug Run Mask */
#define ADC_DBGCTRL_DBGRUN ADC_DBGCTRL_DBGRUN_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use ADC_DBGCTRL_DBGRUN_Msk instead */
#define ADC_DBGCTRL_MASK _U_(0x01) /**< \deprecated (ADC_DBGCTRL) Register MASK (Use ADC_DBGCTRL_Msk instead) */
#define ADC_DBGCTRL_Msk _U_(0x01) /**< (ADC_DBGCTRL) Register Mask */
/* -------- ADC_SYNCBUSY : (ADC Offset: 0x20) (R/ 16) Synchronization Busy -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint16_t SWRST:1; /**< bit: 0 SWRST Synchronization Busy */
uint16_t ENABLE:1; /**< bit: 1 ENABLE Synchronization Busy */
uint16_t INPUTCTRL:1; /**< bit: 2 INPUTCTRL Synchronization Busy */
uint16_t CTRLC:1; /**< bit: 3 CTRLC Synchronization Busy */
uint16_t AVGCTRL:1; /**< bit: 4 AVGCTRL Synchronization Busy */
uint16_t SAMPCTRL:1; /**< bit: 5 SAMPCTRL Synchronization Busy */
uint16_t WINLT:1; /**< bit: 6 WINLT Synchronization Busy */
uint16_t WINUT:1; /**< bit: 7 WINUT Synchronization Busy */
uint16_t GAINCORR:1; /**< bit: 8 GAINCORR Synchronization Busy */
uint16_t OFFSETCORR:1; /**< bit: 9 OFFSETCTRL Synchronization Busy */
uint16_t SWTRIG:1; /**< bit: 10 SWTRG Synchronization Busy */
uint16_t :5; /**< bit: 11..15 Reserved */
} bit; /**< Structure used for bit access */
uint16_t reg; /**< Type used for register access */
} ADC_SYNCBUSY_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define ADC_SYNCBUSY_OFFSET (0x20) /**< (ADC_SYNCBUSY) Synchronization Busy Offset */
#define ADC_SYNCBUSY_RESETVALUE _U_(0x00) /**< (ADC_SYNCBUSY) Synchronization Busy Reset Value */
#define ADC_SYNCBUSY_SWRST_Pos 0 /**< (ADC_SYNCBUSY) SWRST Synchronization Busy Position */
#define ADC_SYNCBUSY_SWRST_Msk (_U_(0x1) << ADC_SYNCBUSY_SWRST_Pos) /**< (ADC_SYNCBUSY) SWRST Synchronization Busy Mask */
#define ADC_SYNCBUSY_SWRST ADC_SYNCBUSY_SWRST_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use ADC_SYNCBUSY_SWRST_Msk instead */
#define ADC_SYNCBUSY_ENABLE_Pos 1 /**< (ADC_SYNCBUSY) ENABLE Synchronization Busy Position */
#define ADC_SYNCBUSY_ENABLE_Msk (_U_(0x1) << ADC_SYNCBUSY_ENABLE_Pos) /**< (ADC_SYNCBUSY) ENABLE Synchronization Busy Mask */
#define ADC_SYNCBUSY_ENABLE ADC_SYNCBUSY_ENABLE_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use ADC_SYNCBUSY_ENABLE_Msk instead */
#define ADC_SYNCBUSY_INPUTCTRL_Pos 2 /**< (ADC_SYNCBUSY) INPUTCTRL Synchronization Busy Position */
#define ADC_SYNCBUSY_INPUTCTRL_Msk (_U_(0x1) << ADC_SYNCBUSY_INPUTCTRL_Pos) /**< (ADC_SYNCBUSY) INPUTCTRL Synchronization Busy Mask */
#define ADC_SYNCBUSY_INPUTCTRL ADC_SYNCBUSY_INPUTCTRL_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use ADC_SYNCBUSY_INPUTCTRL_Msk instead */
#define ADC_SYNCBUSY_CTRLC_Pos 3 /**< (ADC_SYNCBUSY) CTRLC Synchronization Busy Position */
#define ADC_SYNCBUSY_CTRLC_Msk (_U_(0x1) << ADC_SYNCBUSY_CTRLC_Pos) /**< (ADC_SYNCBUSY) CTRLC Synchronization Busy Mask */
#define ADC_SYNCBUSY_CTRLC ADC_SYNCBUSY_CTRLC_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use ADC_SYNCBUSY_CTRLC_Msk instead */
#define ADC_SYNCBUSY_AVGCTRL_Pos 4 /**< (ADC_SYNCBUSY) AVGCTRL Synchronization Busy Position */
#define ADC_SYNCBUSY_AVGCTRL_Msk (_U_(0x1) << ADC_SYNCBUSY_AVGCTRL_Pos) /**< (ADC_SYNCBUSY) AVGCTRL Synchronization Busy Mask */
#define ADC_SYNCBUSY_AVGCTRL ADC_SYNCBUSY_AVGCTRL_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use ADC_SYNCBUSY_AVGCTRL_Msk instead */
#define ADC_SYNCBUSY_SAMPCTRL_Pos 5 /**< (ADC_SYNCBUSY) SAMPCTRL Synchronization Busy Position */
#define ADC_SYNCBUSY_SAMPCTRL_Msk (_U_(0x1) << ADC_SYNCBUSY_SAMPCTRL_Pos) /**< (ADC_SYNCBUSY) SAMPCTRL Synchronization Busy Mask */
#define ADC_SYNCBUSY_SAMPCTRL ADC_SYNCBUSY_SAMPCTRL_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use ADC_SYNCBUSY_SAMPCTRL_Msk instead */
#define ADC_SYNCBUSY_WINLT_Pos 6 /**< (ADC_SYNCBUSY) WINLT Synchronization Busy Position */
#define ADC_SYNCBUSY_WINLT_Msk (_U_(0x1) << ADC_SYNCBUSY_WINLT_Pos) /**< (ADC_SYNCBUSY) WINLT Synchronization Busy Mask */
#define ADC_SYNCBUSY_WINLT ADC_SYNCBUSY_WINLT_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use ADC_SYNCBUSY_WINLT_Msk instead */
#define ADC_SYNCBUSY_WINUT_Pos 7 /**< (ADC_SYNCBUSY) WINUT Synchronization Busy Position */
#define ADC_SYNCBUSY_WINUT_Msk (_U_(0x1) << ADC_SYNCBUSY_WINUT_Pos) /**< (ADC_SYNCBUSY) WINUT Synchronization Busy Mask */
#define ADC_SYNCBUSY_WINUT ADC_SYNCBUSY_WINUT_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use ADC_SYNCBUSY_WINUT_Msk instead */
#define ADC_SYNCBUSY_GAINCORR_Pos 8 /**< (ADC_SYNCBUSY) GAINCORR Synchronization Busy Position */
#define ADC_SYNCBUSY_GAINCORR_Msk (_U_(0x1) << ADC_SYNCBUSY_GAINCORR_Pos) /**< (ADC_SYNCBUSY) GAINCORR Synchronization Busy Mask */
#define ADC_SYNCBUSY_GAINCORR ADC_SYNCBUSY_GAINCORR_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use ADC_SYNCBUSY_GAINCORR_Msk instead */
#define ADC_SYNCBUSY_OFFSETCORR_Pos 9 /**< (ADC_SYNCBUSY) OFFSETCTRL Synchronization Busy Position */
#define ADC_SYNCBUSY_OFFSETCORR_Msk (_U_(0x1) << ADC_SYNCBUSY_OFFSETCORR_Pos) /**< (ADC_SYNCBUSY) OFFSETCTRL Synchronization Busy Mask */
#define ADC_SYNCBUSY_OFFSETCORR ADC_SYNCBUSY_OFFSETCORR_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use ADC_SYNCBUSY_OFFSETCORR_Msk instead */
#define ADC_SYNCBUSY_SWTRIG_Pos 10 /**< (ADC_SYNCBUSY) SWTRG Synchronization Busy Position */
#define ADC_SYNCBUSY_SWTRIG_Msk (_U_(0x1) << ADC_SYNCBUSY_SWTRIG_Pos) /**< (ADC_SYNCBUSY) SWTRG Synchronization Busy Mask */
#define ADC_SYNCBUSY_SWTRIG ADC_SYNCBUSY_SWTRIG_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use ADC_SYNCBUSY_SWTRIG_Msk instead */
#define ADC_SYNCBUSY_MASK _U_(0x7FF) /**< \deprecated (ADC_SYNCBUSY) Register MASK (Use ADC_SYNCBUSY_Msk instead) */
#define ADC_SYNCBUSY_Msk _U_(0x7FF) /**< (ADC_SYNCBUSY) Register Mask */
/* -------- ADC_RESULT : (ADC Offset: 0x24) (R/ 16) Result -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint16_t RESULT:16; /**< bit: 0..15 Result Value */
} bit; /**< Structure used for bit access */
uint16_t reg; /**< Type used for register access */
} ADC_RESULT_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define ADC_RESULT_OFFSET (0x24) /**< (ADC_RESULT) Result Offset */
#define ADC_RESULT_RESETVALUE _U_(0x00) /**< (ADC_RESULT) Result Reset Value */
#define ADC_RESULT_RESULT_Pos 0 /**< (ADC_RESULT) Result Value Position */
#define ADC_RESULT_RESULT_Msk (_U_(0xFFFF) << ADC_RESULT_RESULT_Pos) /**< (ADC_RESULT) Result Value Mask */
#define ADC_RESULT_RESULT(value) (ADC_RESULT_RESULT_Msk & ((value) << ADC_RESULT_RESULT_Pos))
#define ADC_RESULT_MASK _U_(0xFFFF) /**< \deprecated (ADC_RESULT) Register MASK (Use ADC_RESULT_Msk instead) */
#define ADC_RESULT_Msk _U_(0xFFFF) /**< (ADC_RESULT) Register Mask */
/* -------- ADC_SEQCTRL : (ADC Offset: 0x28) (R/W 32) Sequence Control -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t SEQEN:32; /**< bit: 0..31 Enable Positive Input in the Sequence */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} ADC_SEQCTRL_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define ADC_SEQCTRL_OFFSET (0x28) /**< (ADC_SEQCTRL) Sequence Control Offset */
#define ADC_SEQCTRL_RESETVALUE _U_(0x00) /**< (ADC_SEQCTRL) Sequence Control Reset Value */
#define ADC_SEQCTRL_SEQEN_Pos 0 /**< (ADC_SEQCTRL) Enable Positive Input in the Sequence Position */
#define ADC_SEQCTRL_SEQEN_Msk (_U_(0xFFFFFFFF) << ADC_SEQCTRL_SEQEN_Pos) /**< (ADC_SEQCTRL) Enable Positive Input in the Sequence Mask */
#define ADC_SEQCTRL_SEQEN(value) (ADC_SEQCTRL_SEQEN_Msk & ((value) << ADC_SEQCTRL_SEQEN_Pos))
#define ADC_SEQCTRL_MASK _U_(0xFFFFFFFF) /**< \deprecated (ADC_SEQCTRL) Register MASK (Use ADC_SEQCTRL_Msk instead) */
#define ADC_SEQCTRL_Msk _U_(0xFFFFFFFF) /**< (ADC_SEQCTRL) Register Mask */
/* -------- ADC_CALIB : (ADC Offset: 0x2c) (R/W 16) Calibration -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint16_t BIASCOMP:3; /**< bit: 0..2 Bias Comparator Scaling */
uint16_t :5; /**< bit: 3..7 Reserved */
uint16_t BIASREFBUF:3; /**< bit: 8..10 Bias Reference Buffer Scaling */
uint16_t :5; /**< bit: 11..15 Reserved */
} bit; /**< Structure used for bit access */
uint16_t reg; /**< Type used for register access */
} ADC_CALIB_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define ADC_CALIB_OFFSET (0x2C) /**< (ADC_CALIB) Calibration Offset */
#define ADC_CALIB_RESETVALUE _U_(0x00) /**< (ADC_CALIB) Calibration Reset Value */
#define ADC_CALIB_BIASCOMP_Pos 0 /**< (ADC_CALIB) Bias Comparator Scaling Position */
#define ADC_CALIB_BIASCOMP_Msk (_U_(0x7) << ADC_CALIB_BIASCOMP_Pos) /**< (ADC_CALIB) Bias Comparator Scaling Mask */
#define ADC_CALIB_BIASCOMP(value) (ADC_CALIB_BIASCOMP_Msk & ((value) << ADC_CALIB_BIASCOMP_Pos))
#define ADC_CALIB_BIASREFBUF_Pos 8 /**< (ADC_CALIB) Bias Reference Buffer Scaling Position */
#define ADC_CALIB_BIASREFBUF_Msk (_U_(0x7) << ADC_CALIB_BIASREFBUF_Pos) /**< (ADC_CALIB) Bias Reference Buffer Scaling Mask */
#define ADC_CALIB_BIASREFBUF(value) (ADC_CALIB_BIASREFBUF_Msk & ((value) << ADC_CALIB_BIASREFBUF_Pos))
#define ADC_CALIB_MASK _U_(0x707) /**< \deprecated (ADC_CALIB) Register MASK (Use ADC_CALIB_Msk instead) */
#define ADC_CALIB_Msk _U_(0x707) /**< (ADC_CALIB) Register Mask */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
/** \brief ADC hardware registers */
typedef struct { /* Analog Digital Converter */
__IO ADC_CTRLA_Type CTRLA; /**< Offset: 0x00 (R/W 8) Control A */
__IO ADC_CTRLB_Type CTRLB; /**< Offset: 0x01 (R/W 8) Control B */
__IO ADC_REFCTRL_Type REFCTRL; /**< Offset: 0x02 (R/W 8) Reference Control */
__IO ADC_EVCTRL_Type EVCTRL; /**< Offset: 0x03 (R/W 8) Event Control */
__IO ADC_INTENCLR_Type INTENCLR; /**< Offset: 0x04 (R/W 8) Interrupt Enable Clear */
__IO ADC_INTENSET_Type INTENSET; /**< Offset: 0x05 (R/W 8) Interrupt Enable Set */
__IO ADC_INTFLAG_Type INTFLAG; /**< Offset: 0x06 (R/W 8) Interrupt Flag Status and Clear */
__I ADC_SEQSTATUS_Type SEQSTATUS; /**< Offset: 0x07 (R/ 8) Sequence Status */
__IO ADC_INPUTCTRL_Type INPUTCTRL; /**< Offset: 0x08 (R/W 16) Input Control */
__IO ADC_CTRLC_Type CTRLC; /**< Offset: 0x0A (R/W 16) Control C */
__IO ADC_AVGCTRL_Type AVGCTRL; /**< Offset: 0x0C (R/W 8) Average Control */
__IO ADC_SAMPCTRL_Type SAMPCTRL; /**< Offset: 0x0D (R/W 8) Sample Time Control */
__IO ADC_WINLT_Type WINLT; /**< Offset: 0x0E (R/W 16) Window Monitor Lower Threshold */
__IO ADC_WINUT_Type WINUT; /**< Offset: 0x10 (R/W 16) Window Monitor Upper Threshold */
__IO ADC_GAINCORR_Type GAINCORR; /**< Offset: 0x12 (R/W 16) Gain Correction */
__IO ADC_OFFSETCORR_Type OFFSETCORR; /**< Offset: 0x14 (R/W 16) Offset Correction */
__I uint8_t Reserved1[2];
__IO ADC_SWTRIG_Type SWTRIG; /**< Offset: 0x18 (R/W 8) Software Trigger */
__I uint8_t Reserved2[3];
__IO ADC_DBGCTRL_Type DBGCTRL; /**< Offset: 0x1C (R/W 8) Debug Control */
__I uint8_t Reserved3[3];
__I ADC_SYNCBUSY_Type SYNCBUSY; /**< Offset: 0x20 (R/ 16) Synchronization Busy */
__I uint8_t Reserved4[2];
__I ADC_RESULT_Type RESULT; /**< Offset: 0x24 (R/ 16) Result */
__I uint8_t Reserved5[2];
__IO ADC_SEQCTRL_Type SEQCTRL; /**< Offset: 0x28 (R/W 32) Sequence Control */
__IO ADC_CALIB_Type CALIB; /**< Offset: 0x2C (R/W 16) Calibration */
} Adc;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/** @} end of Analog Digital Converter */
#endif /* _SAML10_ADC_COMPONENT_H_ */

View File

@ -0,0 +1,258 @@
/**
* \file
*
* \brief Component description for CCL
*
* Copyright (c) 2018 Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* 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
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
/* file generated from device description version 2018-08-31T13:51:50Z */
#ifndef _SAML10_CCL_COMPONENT_H_
#define _SAML10_CCL_COMPONENT_H_
#define _SAML10_CCL_COMPONENT_ /**< \deprecated Backward compatibility for ASF */
/** \addtogroup SAML_SAML10 Configurable Custom Logic
* @{
*/
/* ========================================================================== */
/** SOFTWARE API DEFINITION FOR CCL */
/* ========================================================================== */
#define CCL_U2225 /**< (CCL) Module ID */
#define REV_CCL 0x200 /**< (CCL) Module revision */
/* -------- CCL_CTRL : (CCL Offset: 0x00) (R/W 8) Control -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t SWRST:1; /**< bit: 0 Software Reset */
uint8_t ENABLE:1; /**< bit: 1 Enable */
uint8_t :4; /**< bit: 2..5 Reserved */
uint8_t RUNSTDBY:1; /**< bit: 6 Run in Standby */
uint8_t :1; /**< bit: 7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} CCL_CTRL_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define CCL_CTRL_OFFSET (0x00) /**< (CCL_CTRL) Control Offset */
#define CCL_CTRL_RESETVALUE _U_(0x00) /**< (CCL_CTRL) Control Reset Value */
#define CCL_CTRL_SWRST_Pos 0 /**< (CCL_CTRL) Software Reset Position */
#define CCL_CTRL_SWRST_Msk (_U_(0x1) << CCL_CTRL_SWRST_Pos) /**< (CCL_CTRL) Software Reset Mask */
#define CCL_CTRL_SWRST CCL_CTRL_SWRST_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use CCL_CTRL_SWRST_Msk instead */
#define CCL_CTRL_ENABLE_Pos 1 /**< (CCL_CTRL) Enable Position */
#define CCL_CTRL_ENABLE_Msk (_U_(0x1) << CCL_CTRL_ENABLE_Pos) /**< (CCL_CTRL) Enable Mask */
#define CCL_CTRL_ENABLE CCL_CTRL_ENABLE_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use CCL_CTRL_ENABLE_Msk instead */
#define CCL_CTRL_RUNSTDBY_Pos 6 /**< (CCL_CTRL) Run in Standby Position */
#define CCL_CTRL_RUNSTDBY_Msk (_U_(0x1) << CCL_CTRL_RUNSTDBY_Pos) /**< (CCL_CTRL) Run in Standby Mask */
#define CCL_CTRL_RUNSTDBY CCL_CTRL_RUNSTDBY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use CCL_CTRL_RUNSTDBY_Msk instead */
#define CCL_CTRL_MASK _U_(0x43) /**< \deprecated (CCL_CTRL) Register MASK (Use CCL_CTRL_Msk instead) */
#define CCL_CTRL_Msk _U_(0x43) /**< (CCL_CTRL) Register Mask */
/* -------- CCL_SEQCTRL : (CCL Offset: 0x04) (R/W 8) SEQ Control x -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t SEQSEL:4; /**< bit: 0..3 Sequential Selection */
uint8_t :4; /**< bit: 4..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} CCL_SEQCTRL_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define CCL_SEQCTRL_OFFSET (0x04) /**< (CCL_SEQCTRL) SEQ Control x Offset */
#define CCL_SEQCTRL_RESETVALUE _U_(0x00) /**< (CCL_SEQCTRL) SEQ Control x Reset Value */
#define CCL_SEQCTRL_SEQSEL_Pos 0 /**< (CCL_SEQCTRL) Sequential Selection Position */
#define CCL_SEQCTRL_SEQSEL_Msk (_U_(0xF) << CCL_SEQCTRL_SEQSEL_Pos) /**< (CCL_SEQCTRL) Sequential Selection Mask */
#define CCL_SEQCTRL_SEQSEL(value) (CCL_SEQCTRL_SEQSEL_Msk & ((value) << CCL_SEQCTRL_SEQSEL_Pos))
#define CCL_SEQCTRL_SEQSEL_DISABLE_Val _U_(0x0) /**< (CCL_SEQCTRL) Sequential logic is disabled */
#define CCL_SEQCTRL_SEQSEL_DFF_Val _U_(0x1) /**< (CCL_SEQCTRL) D flip flop */
#define CCL_SEQCTRL_SEQSEL_JK_Val _U_(0x2) /**< (CCL_SEQCTRL) JK flip flop */
#define CCL_SEQCTRL_SEQSEL_LATCH_Val _U_(0x3) /**< (CCL_SEQCTRL) D latch */
#define CCL_SEQCTRL_SEQSEL_RS_Val _U_(0x4) /**< (CCL_SEQCTRL) RS latch */
#define CCL_SEQCTRL_SEQSEL_DISABLE (CCL_SEQCTRL_SEQSEL_DISABLE_Val << CCL_SEQCTRL_SEQSEL_Pos) /**< (CCL_SEQCTRL) Sequential logic is disabled Position */
#define CCL_SEQCTRL_SEQSEL_DFF (CCL_SEQCTRL_SEQSEL_DFF_Val << CCL_SEQCTRL_SEQSEL_Pos) /**< (CCL_SEQCTRL) D flip flop Position */
#define CCL_SEQCTRL_SEQSEL_JK (CCL_SEQCTRL_SEQSEL_JK_Val << CCL_SEQCTRL_SEQSEL_Pos) /**< (CCL_SEQCTRL) JK flip flop Position */
#define CCL_SEQCTRL_SEQSEL_LATCH (CCL_SEQCTRL_SEQSEL_LATCH_Val << CCL_SEQCTRL_SEQSEL_Pos) /**< (CCL_SEQCTRL) D latch Position */
#define CCL_SEQCTRL_SEQSEL_RS (CCL_SEQCTRL_SEQSEL_RS_Val << CCL_SEQCTRL_SEQSEL_Pos) /**< (CCL_SEQCTRL) RS latch Position */
#define CCL_SEQCTRL_MASK _U_(0x0F) /**< \deprecated (CCL_SEQCTRL) Register MASK (Use CCL_SEQCTRL_Msk instead) */
#define CCL_SEQCTRL_Msk _U_(0x0F) /**< (CCL_SEQCTRL) Register Mask */
/* -------- CCL_LUTCTRL : (CCL Offset: 0x08) (R/W 32) LUT Control x -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t :1; /**< bit: 0 Reserved */
uint32_t ENABLE:1; /**< bit: 1 LUT Enable */
uint32_t :2; /**< bit: 2..3 Reserved */
uint32_t FILTSEL:2; /**< bit: 4..5 Filter Selection */
uint32_t :1; /**< bit: 6 Reserved */
uint32_t EDGESEL:1; /**< bit: 7 Edge Selection */
uint32_t INSEL0:4; /**< bit: 8..11 Input Selection 0 */
uint32_t INSEL1:4; /**< bit: 12..15 Input Selection 1 */
uint32_t INSEL2:4; /**< bit: 16..19 Input Selection 2 */
uint32_t INVEI:1; /**< bit: 20 Inverted Event Input Enable */
uint32_t LUTEI:1; /**< bit: 21 LUT Event Input Enable */
uint32_t LUTEO:1; /**< bit: 22 LUT Event Output Enable */
uint32_t :1; /**< bit: 23 Reserved */
uint32_t TRUTH:8; /**< bit: 24..31 Truth Value */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} CCL_LUTCTRL_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define CCL_LUTCTRL_OFFSET (0x08) /**< (CCL_LUTCTRL) LUT Control x Offset */
#define CCL_LUTCTRL_RESETVALUE _U_(0x00) /**< (CCL_LUTCTRL) LUT Control x Reset Value */
#define CCL_LUTCTRL_ENABLE_Pos 1 /**< (CCL_LUTCTRL) LUT Enable Position */
#define CCL_LUTCTRL_ENABLE_Msk (_U_(0x1) << CCL_LUTCTRL_ENABLE_Pos) /**< (CCL_LUTCTRL) LUT Enable Mask */
#define CCL_LUTCTRL_ENABLE CCL_LUTCTRL_ENABLE_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use CCL_LUTCTRL_ENABLE_Msk instead */
#define CCL_LUTCTRL_FILTSEL_Pos 4 /**< (CCL_LUTCTRL) Filter Selection Position */
#define CCL_LUTCTRL_FILTSEL_Msk (_U_(0x3) << CCL_LUTCTRL_FILTSEL_Pos) /**< (CCL_LUTCTRL) Filter Selection Mask */
#define CCL_LUTCTRL_FILTSEL(value) (CCL_LUTCTRL_FILTSEL_Msk & ((value) << CCL_LUTCTRL_FILTSEL_Pos))
#define CCL_LUTCTRL_FILTSEL_DISABLE_Val _U_(0x0) /**< (CCL_LUTCTRL) Filter disabled */
#define CCL_LUTCTRL_FILTSEL_SYNCH_Val _U_(0x1) /**< (CCL_LUTCTRL) Synchronizer enabled */
#define CCL_LUTCTRL_FILTSEL_FILTER_Val _U_(0x2) /**< (CCL_LUTCTRL) Filter enabled */
#define CCL_LUTCTRL_FILTSEL_DISABLE (CCL_LUTCTRL_FILTSEL_DISABLE_Val << CCL_LUTCTRL_FILTSEL_Pos) /**< (CCL_LUTCTRL) Filter disabled Position */
#define CCL_LUTCTRL_FILTSEL_SYNCH (CCL_LUTCTRL_FILTSEL_SYNCH_Val << CCL_LUTCTRL_FILTSEL_Pos) /**< (CCL_LUTCTRL) Synchronizer enabled Position */
#define CCL_LUTCTRL_FILTSEL_FILTER (CCL_LUTCTRL_FILTSEL_FILTER_Val << CCL_LUTCTRL_FILTSEL_Pos) /**< (CCL_LUTCTRL) Filter enabled Position */
#define CCL_LUTCTRL_EDGESEL_Pos 7 /**< (CCL_LUTCTRL) Edge Selection Position */
#define CCL_LUTCTRL_EDGESEL_Msk (_U_(0x1) << CCL_LUTCTRL_EDGESEL_Pos) /**< (CCL_LUTCTRL) Edge Selection Mask */
#define CCL_LUTCTRL_EDGESEL CCL_LUTCTRL_EDGESEL_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use CCL_LUTCTRL_EDGESEL_Msk instead */
#define CCL_LUTCTRL_INSEL0_Pos 8 /**< (CCL_LUTCTRL) Input Selection 0 Position */
#define CCL_LUTCTRL_INSEL0_Msk (_U_(0xF) << CCL_LUTCTRL_INSEL0_Pos) /**< (CCL_LUTCTRL) Input Selection 0 Mask */
#define CCL_LUTCTRL_INSEL0(value) (CCL_LUTCTRL_INSEL0_Msk & ((value) << CCL_LUTCTRL_INSEL0_Pos))
#define CCL_LUTCTRL_INSEL0_MASK_Val _U_(0x0) /**< (CCL_LUTCTRL) Masked input */
#define CCL_LUTCTRL_INSEL0_FEEDBACK_Val _U_(0x1) /**< (CCL_LUTCTRL) Feedback input source */
#define CCL_LUTCTRL_INSEL0_LINK_Val _U_(0x2) /**< (CCL_LUTCTRL) Linked LUT input source */
#define CCL_LUTCTRL_INSEL0_EVENT_Val _U_(0x3) /**< (CCL_LUTCTRL) Event input source */
#define CCL_LUTCTRL_INSEL0_IO_Val _U_(0x4) /**< (CCL_LUTCTRL) I/O pin input source */
#define CCL_LUTCTRL_INSEL0_AC_Val _U_(0x5) /**< (CCL_LUTCTRL) AC input source */
#define CCL_LUTCTRL_INSEL0_TC_Val _U_(0x6) /**< (CCL_LUTCTRL) TC input source */
#define CCL_LUTCTRL_INSEL0_ALTTC_Val _U_(0x7) /**< (CCL_LUTCTRL) Alternate TC input source */
#define CCL_LUTCTRL_INSEL0_TCC_Val _U_(0x8) /**< (CCL_LUTCTRL) TCC input source */
#define CCL_LUTCTRL_INSEL0_SERCOM_Val _U_(0x9) /**< (CCL_LUTCTRL) SERCOM input source */
#define CCL_LUTCTRL_INSEL0_ALT2TC_Val _U_(0xA) /**< (CCL_LUTCTRL) Alternate 2 TC input source */
#define CCL_LUTCTRL_INSEL0_ASYNCEVENT_Val _U_(0xB) /**< (CCL_LUTCTRL) Asynchronous event input source. The EVENT input will bypass edge detection logic. */
#define CCL_LUTCTRL_INSEL0_MASK (CCL_LUTCTRL_INSEL0_MASK_Val << CCL_LUTCTRL_INSEL0_Pos) /**< (CCL_LUTCTRL) Masked input Position */
#define CCL_LUTCTRL_INSEL0_FEEDBACK (CCL_LUTCTRL_INSEL0_FEEDBACK_Val << CCL_LUTCTRL_INSEL0_Pos) /**< (CCL_LUTCTRL) Feedback input source Position */
#define CCL_LUTCTRL_INSEL0_LINK (CCL_LUTCTRL_INSEL0_LINK_Val << CCL_LUTCTRL_INSEL0_Pos) /**< (CCL_LUTCTRL) Linked LUT input source Position */
#define CCL_LUTCTRL_INSEL0_EVENT (CCL_LUTCTRL_INSEL0_EVENT_Val << CCL_LUTCTRL_INSEL0_Pos) /**< (CCL_LUTCTRL) Event input source Position */
#define CCL_LUTCTRL_INSEL0_IO (CCL_LUTCTRL_INSEL0_IO_Val << CCL_LUTCTRL_INSEL0_Pos) /**< (CCL_LUTCTRL) I/O pin input source Position */
#define CCL_LUTCTRL_INSEL0_AC (CCL_LUTCTRL_INSEL0_AC_Val << CCL_LUTCTRL_INSEL0_Pos) /**< (CCL_LUTCTRL) AC input source Position */
#define CCL_LUTCTRL_INSEL0_TC (CCL_LUTCTRL_INSEL0_TC_Val << CCL_LUTCTRL_INSEL0_Pos) /**< (CCL_LUTCTRL) TC input source Position */
#define CCL_LUTCTRL_INSEL0_ALTTC (CCL_LUTCTRL_INSEL0_ALTTC_Val << CCL_LUTCTRL_INSEL0_Pos) /**< (CCL_LUTCTRL) Alternate TC input source Position */
#define CCL_LUTCTRL_INSEL0_TCC (CCL_LUTCTRL_INSEL0_TCC_Val << CCL_LUTCTRL_INSEL0_Pos) /**< (CCL_LUTCTRL) TCC input source Position */
#define CCL_LUTCTRL_INSEL0_SERCOM (CCL_LUTCTRL_INSEL0_SERCOM_Val << CCL_LUTCTRL_INSEL0_Pos) /**< (CCL_LUTCTRL) SERCOM input source Position */
#define CCL_LUTCTRL_INSEL0_ALT2TC (CCL_LUTCTRL_INSEL0_ALT2TC_Val << CCL_LUTCTRL_INSEL0_Pos) /**< (CCL_LUTCTRL) Alternate 2 TC input source Position */
#define CCL_LUTCTRL_INSEL0_ASYNCEVENT (CCL_LUTCTRL_INSEL0_ASYNCEVENT_Val << CCL_LUTCTRL_INSEL0_Pos) /**< (CCL_LUTCTRL) Asynchronous event input source. The EVENT input will bypass edge detection logic. Position */
#define CCL_LUTCTRL_INSEL1_Pos 12 /**< (CCL_LUTCTRL) Input Selection 1 Position */
#define CCL_LUTCTRL_INSEL1_Msk (_U_(0xF) << CCL_LUTCTRL_INSEL1_Pos) /**< (CCL_LUTCTRL) Input Selection 1 Mask */
#define CCL_LUTCTRL_INSEL1(value) (CCL_LUTCTRL_INSEL1_Msk & ((value) << CCL_LUTCTRL_INSEL1_Pos))
#define CCL_LUTCTRL_INSEL1_MASK_Val _U_(0x0) /**< (CCL_LUTCTRL) Masked input */
#define CCL_LUTCTRL_INSEL1_FEEDBACK_Val _U_(0x1) /**< (CCL_LUTCTRL) Feedback input source */
#define CCL_LUTCTRL_INSEL1_LINK_Val _U_(0x2) /**< (CCL_LUTCTRL) Linked LUT input source */
#define CCL_LUTCTRL_INSEL1_EVENT_Val _U_(0x3) /**< (CCL_LUTCTRL) Event input source */
#define CCL_LUTCTRL_INSEL1_IO_Val _U_(0x4) /**< (CCL_LUTCTRL) I/O pin input source */
#define CCL_LUTCTRL_INSEL1_AC_Val _U_(0x5) /**< (CCL_LUTCTRL) AC input source */
#define CCL_LUTCTRL_INSEL1_TC_Val _U_(0x6) /**< (CCL_LUTCTRL) TC input source */
#define CCL_LUTCTRL_INSEL1_ALTTC_Val _U_(0x7) /**< (CCL_LUTCTRL) Alternate TC input source */
#define CCL_LUTCTRL_INSEL1_TCC_Val _U_(0x8) /**< (CCL_LUTCTRL) TCC input source */
#define CCL_LUTCTRL_INSEL1_SERCOM_Val _U_(0x9) /**< (CCL_LUTCTRL) SERCOM input source */
#define CCL_LUTCTRL_INSEL1_ALT2TC_Val _U_(0xA) /**< (CCL_LUTCTRL) Alternate 2 TC input source */
#define CCL_LUTCTRL_INSEL1_ASYNCEVENT_Val _U_(0xB) /**< (CCL_LUTCTRL) Asynchronous event input source. The EVENT input will bypass edge detection logic. */
#define CCL_LUTCTRL_INSEL1_MASK (CCL_LUTCTRL_INSEL1_MASK_Val << CCL_LUTCTRL_INSEL1_Pos) /**< (CCL_LUTCTRL) Masked input Position */
#define CCL_LUTCTRL_INSEL1_FEEDBACK (CCL_LUTCTRL_INSEL1_FEEDBACK_Val << CCL_LUTCTRL_INSEL1_Pos) /**< (CCL_LUTCTRL) Feedback input source Position */
#define CCL_LUTCTRL_INSEL1_LINK (CCL_LUTCTRL_INSEL1_LINK_Val << CCL_LUTCTRL_INSEL1_Pos) /**< (CCL_LUTCTRL) Linked LUT input source Position */
#define CCL_LUTCTRL_INSEL1_EVENT (CCL_LUTCTRL_INSEL1_EVENT_Val << CCL_LUTCTRL_INSEL1_Pos) /**< (CCL_LUTCTRL) Event input source Position */
#define CCL_LUTCTRL_INSEL1_IO (CCL_LUTCTRL_INSEL1_IO_Val << CCL_LUTCTRL_INSEL1_Pos) /**< (CCL_LUTCTRL) I/O pin input source Position */
#define CCL_LUTCTRL_INSEL1_AC (CCL_LUTCTRL_INSEL1_AC_Val << CCL_LUTCTRL_INSEL1_Pos) /**< (CCL_LUTCTRL) AC input source Position */
#define CCL_LUTCTRL_INSEL1_TC (CCL_LUTCTRL_INSEL1_TC_Val << CCL_LUTCTRL_INSEL1_Pos) /**< (CCL_LUTCTRL) TC input source Position */
#define CCL_LUTCTRL_INSEL1_ALTTC (CCL_LUTCTRL_INSEL1_ALTTC_Val << CCL_LUTCTRL_INSEL1_Pos) /**< (CCL_LUTCTRL) Alternate TC input source Position */
#define CCL_LUTCTRL_INSEL1_TCC (CCL_LUTCTRL_INSEL1_TCC_Val << CCL_LUTCTRL_INSEL1_Pos) /**< (CCL_LUTCTRL) TCC input source Position */
#define CCL_LUTCTRL_INSEL1_SERCOM (CCL_LUTCTRL_INSEL1_SERCOM_Val << CCL_LUTCTRL_INSEL1_Pos) /**< (CCL_LUTCTRL) SERCOM input source Position */
#define CCL_LUTCTRL_INSEL1_ALT2TC (CCL_LUTCTRL_INSEL1_ALT2TC_Val << CCL_LUTCTRL_INSEL1_Pos) /**< (CCL_LUTCTRL) Alternate 2 TC input source Position */
#define CCL_LUTCTRL_INSEL1_ASYNCEVENT (CCL_LUTCTRL_INSEL1_ASYNCEVENT_Val << CCL_LUTCTRL_INSEL1_Pos) /**< (CCL_LUTCTRL) Asynchronous event input source. The EVENT input will bypass edge detection logic. Position */
#define CCL_LUTCTRL_INSEL2_Pos 16 /**< (CCL_LUTCTRL) Input Selection 2 Position */
#define CCL_LUTCTRL_INSEL2_Msk (_U_(0xF) << CCL_LUTCTRL_INSEL2_Pos) /**< (CCL_LUTCTRL) Input Selection 2 Mask */
#define CCL_LUTCTRL_INSEL2(value) (CCL_LUTCTRL_INSEL2_Msk & ((value) << CCL_LUTCTRL_INSEL2_Pos))
#define CCL_LUTCTRL_INSEL2_MASK_Val _U_(0x0) /**< (CCL_LUTCTRL) Masked input */
#define CCL_LUTCTRL_INSEL2_FEEDBACK_Val _U_(0x1) /**< (CCL_LUTCTRL) Feedback input source */
#define CCL_LUTCTRL_INSEL2_LINK_Val _U_(0x2) /**< (CCL_LUTCTRL) Linked LUT input source */
#define CCL_LUTCTRL_INSEL2_EVENT_Val _U_(0x3) /**< (CCL_LUTCTRL) Event input source */
#define CCL_LUTCTRL_INSEL2_IO_Val _U_(0x4) /**< (CCL_LUTCTRL) I/O pin input source */
#define CCL_LUTCTRL_INSEL2_AC_Val _U_(0x5) /**< (CCL_LUTCTRL) AC input source */
#define CCL_LUTCTRL_INSEL2_TC_Val _U_(0x6) /**< (CCL_LUTCTRL) TC input source */
#define CCL_LUTCTRL_INSEL2_ALTTC_Val _U_(0x7) /**< (CCL_LUTCTRL) Alternate TC input source */
#define CCL_LUTCTRL_INSEL2_TCC_Val _U_(0x8) /**< (CCL_LUTCTRL) TCC input source */
#define CCL_LUTCTRL_INSEL2_SERCOM_Val _U_(0x9) /**< (CCL_LUTCTRL) SERCOM input source */
#define CCL_LUTCTRL_INSEL2_ALT2TC_Val _U_(0xA) /**< (CCL_LUTCTRL) Alternate 2 TC input source */
#define CCL_LUTCTRL_INSEL2_ASYNCEVENT_Val _U_(0xB) /**< (CCL_LUTCTRL) Asynchronous event input source. The EVENT input will bypass edge detection logic. */
#define CCL_LUTCTRL_INSEL2_MASK (CCL_LUTCTRL_INSEL2_MASK_Val << CCL_LUTCTRL_INSEL2_Pos) /**< (CCL_LUTCTRL) Masked input Position */
#define CCL_LUTCTRL_INSEL2_FEEDBACK (CCL_LUTCTRL_INSEL2_FEEDBACK_Val << CCL_LUTCTRL_INSEL2_Pos) /**< (CCL_LUTCTRL) Feedback input source Position */
#define CCL_LUTCTRL_INSEL2_LINK (CCL_LUTCTRL_INSEL2_LINK_Val << CCL_LUTCTRL_INSEL2_Pos) /**< (CCL_LUTCTRL) Linked LUT input source Position */
#define CCL_LUTCTRL_INSEL2_EVENT (CCL_LUTCTRL_INSEL2_EVENT_Val << CCL_LUTCTRL_INSEL2_Pos) /**< (CCL_LUTCTRL) Event input source Position */
#define CCL_LUTCTRL_INSEL2_IO (CCL_LUTCTRL_INSEL2_IO_Val << CCL_LUTCTRL_INSEL2_Pos) /**< (CCL_LUTCTRL) I/O pin input source Position */
#define CCL_LUTCTRL_INSEL2_AC (CCL_LUTCTRL_INSEL2_AC_Val << CCL_LUTCTRL_INSEL2_Pos) /**< (CCL_LUTCTRL) AC input source Position */
#define CCL_LUTCTRL_INSEL2_TC (CCL_LUTCTRL_INSEL2_TC_Val << CCL_LUTCTRL_INSEL2_Pos) /**< (CCL_LUTCTRL) TC input source Position */
#define CCL_LUTCTRL_INSEL2_ALTTC (CCL_LUTCTRL_INSEL2_ALTTC_Val << CCL_LUTCTRL_INSEL2_Pos) /**< (CCL_LUTCTRL) Alternate TC input source Position */
#define CCL_LUTCTRL_INSEL2_TCC (CCL_LUTCTRL_INSEL2_TCC_Val << CCL_LUTCTRL_INSEL2_Pos) /**< (CCL_LUTCTRL) TCC input source Position */
#define CCL_LUTCTRL_INSEL2_SERCOM (CCL_LUTCTRL_INSEL2_SERCOM_Val << CCL_LUTCTRL_INSEL2_Pos) /**< (CCL_LUTCTRL) SERCOM input source Position */
#define CCL_LUTCTRL_INSEL2_ALT2TC (CCL_LUTCTRL_INSEL2_ALT2TC_Val << CCL_LUTCTRL_INSEL2_Pos) /**< (CCL_LUTCTRL) Alternate 2 TC input source Position */
#define CCL_LUTCTRL_INSEL2_ASYNCEVENT (CCL_LUTCTRL_INSEL2_ASYNCEVENT_Val << CCL_LUTCTRL_INSEL2_Pos) /**< (CCL_LUTCTRL) Asynchronous event input source. The EVENT input will bypass edge detection logic. Position */
#define CCL_LUTCTRL_INVEI_Pos 20 /**< (CCL_LUTCTRL) Inverted Event Input Enable Position */
#define CCL_LUTCTRL_INVEI_Msk (_U_(0x1) << CCL_LUTCTRL_INVEI_Pos) /**< (CCL_LUTCTRL) Inverted Event Input Enable Mask */
#define CCL_LUTCTRL_INVEI CCL_LUTCTRL_INVEI_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use CCL_LUTCTRL_INVEI_Msk instead */
#define CCL_LUTCTRL_LUTEI_Pos 21 /**< (CCL_LUTCTRL) LUT Event Input Enable Position */
#define CCL_LUTCTRL_LUTEI_Msk (_U_(0x1) << CCL_LUTCTRL_LUTEI_Pos) /**< (CCL_LUTCTRL) LUT Event Input Enable Mask */
#define CCL_LUTCTRL_LUTEI CCL_LUTCTRL_LUTEI_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use CCL_LUTCTRL_LUTEI_Msk instead */
#define CCL_LUTCTRL_LUTEO_Pos 22 /**< (CCL_LUTCTRL) LUT Event Output Enable Position */
#define CCL_LUTCTRL_LUTEO_Msk (_U_(0x1) << CCL_LUTCTRL_LUTEO_Pos) /**< (CCL_LUTCTRL) LUT Event Output Enable Mask */
#define CCL_LUTCTRL_LUTEO CCL_LUTCTRL_LUTEO_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use CCL_LUTCTRL_LUTEO_Msk instead */
#define CCL_LUTCTRL_TRUTH_Pos 24 /**< (CCL_LUTCTRL) Truth Value Position */
#define CCL_LUTCTRL_TRUTH_Msk (_U_(0xFF) << CCL_LUTCTRL_TRUTH_Pos) /**< (CCL_LUTCTRL) Truth Value Mask */
#define CCL_LUTCTRL_TRUTH(value) (CCL_LUTCTRL_TRUTH_Msk & ((value) << CCL_LUTCTRL_TRUTH_Pos))
#define CCL_LUTCTRL_MASK _U_(0xFF7FFFB2) /**< \deprecated (CCL_LUTCTRL) Register MASK (Use CCL_LUTCTRL_Msk instead) */
#define CCL_LUTCTRL_Msk _U_(0xFF7FFFB2) /**< (CCL_LUTCTRL) Register Mask */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
/** \brief CCL hardware registers */
typedef struct { /* Configurable Custom Logic */
__IO CCL_CTRL_Type CTRL; /**< Offset: 0x00 (R/W 8) Control */
__I uint8_t Reserved1[3];
__IO CCL_SEQCTRL_Type SEQCTRL[1]; /**< Offset: 0x04 (R/W 8) SEQ Control x */
__I uint8_t Reserved2[3];
__IO CCL_LUTCTRL_Type LUTCTRL[2]; /**< Offset: 0x08 (R/W 32) LUT Control x */
} Ccl;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/** @} end of Configurable Custom Logic */
#endif /* _SAML10_CCL_COMPONENT_H_ */

View File

@ -0,0 +1,364 @@
/**
* \file
*
* \brief Component description for DAC
*
* Copyright (c) 2018 Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* 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
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
/* file generated from device description version 2018-08-31T13:51:50Z */
#ifndef _SAML10_DAC_COMPONENT_H_
#define _SAML10_DAC_COMPONENT_H_
#define _SAML10_DAC_COMPONENT_ /**< \deprecated Backward compatibility for ASF */
/** \addtogroup SAML_SAML10 Digital Analog Converter
* @{
*/
/* ========================================================================== */
/** SOFTWARE API DEFINITION FOR DAC */
/* ========================================================================== */
#define DAC_U2214 /**< (DAC) Module ID */
#define REV_DAC 0x210 /**< (DAC) Module revision */
/* -------- DAC_CTRLA : (DAC Offset: 0x00) (R/W 8) Control A -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t SWRST:1; /**< bit: 0 Software Reset */
uint8_t ENABLE:1; /**< bit: 1 Enable */
uint8_t :4; /**< bit: 2..5 Reserved */
uint8_t RUNSTDBY:1; /**< bit: 6 Run in Standby */
uint8_t :1; /**< bit: 7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} DAC_CTRLA_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define DAC_CTRLA_OFFSET (0x00) /**< (DAC_CTRLA) Control A Offset */
#define DAC_CTRLA_RESETVALUE _U_(0x00) /**< (DAC_CTRLA) Control A Reset Value */
#define DAC_CTRLA_SWRST_Pos 0 /**< (DAC_CTRLA) Software Reset Position */
#define DAC_CTRLA_SWRST_Msk (_U_(0x1) << DAC_CTRLA_SWRST_Pos) /**< (DAC_CTRLA) Software Reset Mask */
#define DAC_CTRLA_SWRST DAC_CTRLA_SWRST_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use DAC_CTRLA_SWRST_Msk instead */
#define DAC_CTRLA_ENABLE_Pos 1 /**< (DAC_CTRLA) Enable Position */
#define DAC_CTRLA_ENABLE_Msk (_U_(0x1) << DAC_CTRLA_ENABLE_Pos) /**< (DAC_CTRLA) Enable Mask */
#define DAC_CTRLA_ENABLE DAC_CTRLA_ENABLE_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use DAC_CTRLA_ENABLE_Msk instead */
#define DAC_CTRLA_RUNSTDBY_Pos 6 /**< (DAC_CTRLA) Run in Standby Position */
#define DAC_CTRLA_RUNSTDBY_Msk (_U_(0x1) << DAC_CTRLA_RUNSTDBY_Pos) /**< (DAC_CTRLA) Run in Standby Mask */
#define DAC_CTRLA_RUNSTDBY DAC_CTRLA_RUNSTDBY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use DAC_CTRLA_RUNSTDBY_Msk instead */
#define DAC_CTRLA_MASK _U_(0x43) /**< \deprecated (DAC_CTRLA) Register MASK (Use DAC_CTRLA_Msk instead) */
#define DAC_CTRLA_Msk _U_(0x43) /**< (DAC_CTRLA) Register Mask */
/* -------- DAC_CTRLB : (DAC Offset: 0x01) (R/W 8) Control B -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t EOEN:1; /**< bit: 0 External Output Enable */
uint8_t IOEN:1; /**< bit: 1 Internal Output Enable */
uint8_t LEFTADJ:1; /**< bit: 2 Left Adjusted Data */
uint8_t VPD:1; /**< bit: 3 Voltage Pump Disable */
uint8_t :1; /**< bit: 4 Reserved */
uint8_t DITHER:1; /**< bit: 5 Dither Enable */
uint8_t REFSEL:2; /**< bit: 6..7 Reference Selection */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} DAC_CTRLB_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define DAC_CTRLB_OFFSET (0x01) /**< (DAC_CTRLB) Control B Offset */
#define DAC_CTRLB_RESETVALUE _U_(0x00) /**< (DAC_CTRLB) Control B Reset Value */
#define DAC_CTRLB_EOEN_Pos 0 /**< (DAC_CTRLB) External Output Enable Position */
#define DAC_CTRLB_EOEN_Msk (_U_(0x1) << DAC_CTRLB_EOEN_Pos) /**< (DAC_CTRLB) External Output Enable Mask */
#define DAC_CTRLB_EOEN DAC_CTRLB_EOEN_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use DAC_CTRLB_EOEN_Msk instead */
#define DAC_CTRLB_IOEN_Pos 1 /**< (DAC_CTRLB) Internal Output Enable Position */
#define DAC_CTRLB_IOEN_Msk (_U_(0x1) << DAC_CTRLB_IOEN_Pos) /**< (DAC_CTRLB) Internal Output Enable Mask */
#define DAC_CTRLB_IOEN DAC_CTRLB_IOEN_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use DAC_CTRLB_IOEN_Msk instead */
#define DAC_CTRLB_LEFTADJ_Pos 2 /**< (DAC_CTRLB) Left Adjusted Data Position */
#define DAC_CTRLB_LEFTADJ_Msk (_U_(0x1) << DAC_CTRLB_LEFTADJ_Pos) /**< (DAC_CTRLB) Left Adjusted Data Mask */
#define DAC_CTRLB_LEFTADJ DAC_CTRLB_LEFTADJ_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use DAC_CTRLB_LEFTADJ_Msk instead */
#define DAC_CTRLB_VPD_Pos 3 /**< (DAC_CTRLB) Voltage Pump Disable Position */
#define DAC_CTRLB_VPD_Msk (_U_(0x1) << DAC_CTRLB_VPD_Pos) /**< (DAC_CTRLB) Voltage Pump Disable Mask */
#define DAC_CTRLB_VPD DAC_CTRLB_VPD_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use DAC_CTRLB_VPD_Msk instead */
#define DAC_CTRLB_DITHER_Pos 5 /**< (DAC_CTRLB) Dither Enable Position */
#define DAC_CTRLB_DITHER_Msk (_U_(0x1) << DAC_CTRLB_DITHER_Pos) /**< (DAC_CTRLB) Dither Enable Mask */
#define DAC_CTRLB_DITHER DAC_CTRLB_DITHER_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use DAC_CTRLB_DITHER_Msk instead */
#define DAC_CTRLB_REFSEL_Pos 6 /**< (DAC_CTRLB) Reference Selection Position */
#define DAC_CTRLB_REFSEL_Msk (_U_(0x3) << DAC_CTRLB_REFSEL_Pos) /**< (DAC_CTRLB) Reference Selection Mask */
#define DAC_CTRLB_REFSEL(value) (DAC_CTRLB_REFSEL_Msk & ((value) << DAC_CTRLB_REFSEL_Pos))
#define DAC_CTRLB_REFSEL_INT1V_Val _U_(0x0) /**< (DAC_CTRLB) Internal 1.0V reference */
#define DAC_CTRLB_REFSEL_AVCC_Val _U_(0x1) /**< (DAC_CTRLB) AVCC */
#define DAC_CTRLB_REFSEL_VREFP_Val _U_(0x2) /**< (DAC_CTRLB) External reference */
#define DAC_CTRLB_REFSEL_INT1V (DAC_CTRLB_REFSEL_INT1V_Val << DAC_CTRLB_REFSEL_Pos) /**< (DAC_CTRLB) Internal 1.0V reference Position */
#define DAC_CTRLB_REFSEL_AVCC (DAC_CTRLB_REFSEL_AVCC_Val << DAC_CTRLB_REFSEL_Pos) /**< (DAC_CTRLB) AVCC Position */
#define DAC_CTRLB_REFSEL_VREFP (DAC_CTRLB_REFSEL_VREFP_Val << DAC_CTRLB_REFSEL_Pos) /**< (DAC_CTRLB) External reference Position */
#define DAC_CTRLB_MASK _U_(0xEF) /**< \deprecated (DAC_CTRLB) Register MASK (Use DAC_CTRLB_Msk instead) */
#define DAC_CTRLB_Msk _U_(0xEF) /**< (DAC_CTRLB) Register Mask */
/* -------- DAC_EVCTRL : (DAC Offset: 0x02) (R/W 8) Event Control -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t STARTEI:1; /**< bit: 0 Start Conversion Event Input */
uint8_t EMPTYEO:1; /**< bit: 1 Data Buffer Empty Event Output */
uint8_t INVEI:1; /**< bit: 2 Invert Event Input */
uint8_t :5; /**< bit: 3..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} DAC_EVCTRL_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define DAC_EVCTRL_OFFSET (0x02) /**< (DAC_EVCTRL) Event Control Offset */
#define DAC_EVCTRL_RESETVALUE _U_(0x00) /**< (DAC_EVCTRL) Event Control Reset Value */
#define DAC_EVCTRL_STARTEI_Pos 0 /**< (DAC_EVCTRL) Start Conversion Event Input Position */
#define DAC_EVCTRL_STARTEI_Msk (_U_(0x1) << DAC_EVCTRL_STARTEI_Pos) /**< (DAC_EVCTRL) Start Conversion Event Input Mask */
#define DAC_EVCTRL_STARTEI DAC_EVCTRL_STARTEI_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use DAC_EVCTRL_STARTEI_Msk instead */
#define DAC_EVCTRL_EMPTYEO_Pos 1 /**< (DAC_EVCTRL) Data Buffer Empty Event Output Position */
#define DAC_EVCTRL_EMPTYEO_Msk (_U_(0x1) << DAC_EVCTRL_EMPTYEO_Pos) /**< (DAC_EVCTRL) Data Buffer Empty Event Output Mask */
#define DAC_EVCTRL_EMPTYEO DAC_EVCTRL_EMPTYEO_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use DAC_EVCTRL_EMPTYEO_Msk instead */
#define DAC_EVCTRL_INVEI_Pos 2 /**< (DAC_EVCTRL) Invert Event Input Position */
#define DAC_EVCTRL_INVEI_Msk (_U_(0x1) << DAC_EVCTRL_INVEI_Pos) /**< (DAC_EVCTRL) Invert Event Input Mask */
#define DAC_EVCTRL_INVEI DAC_EVCTRL_INVEI_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use DAC_EVCTRL_INVEI_Msk instead */
#define DAC_EVCTRL_MASK _U_(0x07) /**< \deprecated (DAC_EVCTRL) Register MASK (Use DAC_EVCTRL_Msk instead) */
#define DAC_EVCTRL_Msk _U_(0x07) /**< (DAC_EVCTRL) Register Mask */
/* -------- DAC_INTENCLR : (DAC Offset: 0x04) (R/W 8) Interrupt Enable Clear -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t UNDERRUN:1; /**< bit: 0 Underrun Interrupt Enable */
uint8_t EMPTY:1; /**< bit: 1 Data Buffer Empty Interrupt Enable */
uint8_t :6; /**< bit: 2..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} DAC_INTENCLR_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define DAC_INTENCLR_OFFSET (0x04) /**< (DAC_INTENCLR) Interrupt Enable Clear Offset */
#define DAC_INTENCLR_RESETVALUE _U_(0x00) /**< (DAC_INTENCLR) Interrupt Enable Clear Reset Value */
#define DAC_INTENCLR_UNDERRUN_Pos 0 /**< (DAC_INTENCLR) Underrun Interrupt Enable Position */
#define DAC_INTENCLR_UNDERRUN_Msk (_U_(0x1) << DAC_INTENCLR_UNDERRUN_Pos) /**< (DAC_INTENCLR) Underrun Interrupt Enable Mask */
#define DAC_INTENCLR_UNDERRUN DAC_INTENCLR_UNDERRUN_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use DAC_INTENCLR_UNDERRUN_Msk instead */
#define DAC_INTENCLR_EMPTY_Pos 1 /**< (DAC_INTENCLR) Data Buffer Empty Interrupt Enable Position */
#define DAC_INTENCLR_EMPTY_Msk (_U_(0x1) << DAC_INTENCLR_EMPTY_Pos) /**< (DAC_INTENCLR) Data Buffer Empty Interrupt Enable Mask */
#define DAC_INTENCLR_EMPTY DAC_INTENCLR_EMPTY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use DAC_INTENCLR_EMPTY_Msk instead */
#define DAC_INTENCLR_MASK _U_(0x03) /**< \deprecated (DAC_INTENCLR) Register MASK (Use DAC_INTENCLR_Msk instead) */
#define DAC_INTENCLR_Msk _U_(0x03) /**< (DAC_INTENCLR) Register Mask */
/* -------- DAC_INTENSET : (DAC Offset: 0x05) (R/W 8) Interrupt Enable Set -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t UNDERRUN:1; /**< bit: 0 Underrun Interrupt Enable */
uint8_t EMPTY:1; /**< bit: 1 Data Buffer Empty Interrupt Enable */
uint8_t :6; /**< bit: 2..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} DAC_INTENSET_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define DAC_INTENSET_OFFSET (0x05) /**< (DAC_INTENSET) Interrupt Enable Set Offset */
#define DAC_INTENSET_RESETVALUE _U_(0x00) /**< (DAC_INTENSET) Interrupt Enable Set Reset Value */
#define DAC_INTENSET_UNDERRUN_Pos 0 /**< (DAC_INTENSET) Underrun Interrupt Enable Position */
#define DAC_INTENSET_UNDERRUN_Msk (_U_(0x1) << DAC_INTENSET_UNDERRUN_Pos) /**< (DAC_INTENSET) Underrun Interrupt Enable Mask */
#define DAC_INTENSET_UNDERRUN DAC_INTENSET_UNDERRUN_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use DAC_INTENSET_UNDERRUN_Msk instead */
#define DAC_INTENSET_EMPTY_Pos 1 /**< (DAC_INTENSET) Data Buffer Empty Interrupt Enable Position */
#define DAC_INTENSET_EMPTY_Msk (_U_(0x1) << DAC_INTENSET_EMPTY_Pos) /**< (DAC_INTENSET) Data Buffer Empty Interrupt Enable Mask */
#define DAC_INTENSET_EMPTY DAC_INTENSET_EMPTY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use DAC_INTENSET_EMPTY_Msk instead */
#define DAC_INTENSET_MASK _U_(0x03) /**< \deprecated (DAC_INTENSET) Register MASK (Use DAC_INTENSET_Msk instead) */
#define DAC_INTENSET_Msk _U_(0x03) /**< (DAC_INTENSET) Register Mask */
/* -------- DAC_INTFLAG : (DAC Offset: 0x06) (R/W 8) Interrupt Flag Status and Clear -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union { // __I to avoid read-modify-write on write-to-clear register
struct {
__I uint8_t UNDERRUN:1; /**< bit: 0 Underrun */
__I uint8_t EMPTY:1; /**< bit: 1 Data Buffer Empty */
__I uint8_t :6; /**< bit: 2..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} DAC_INTFLAG_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define DAC_INTFLAG_OFFSET (0x06) /**< (DAC_INTFLAG) Interrupt Flag Status and Clear Offset */
#define DAC_INTFLAG_RESETVALUE _U_(0x00) /**< (DAC_INTFLAG) Interrupt Flag Status and Clear Reset Value */
#define DAC_INTFLAG_UNDERRUN_Pos 0 /**< (DAC_INTFLAG) Underrun Position */
#define DAC_INTFLAG_UNDERRUN_Msk (_U_(0x1) << DAC_INTFLAG_UNDERRUN_Pos) /**< (DAC_INTFLAG) Underrun Mask */
#define DAC_INTFLAG_UNDERRUN DAC_INTFLAG_UNDERRUN_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use DAC_INTFLAG_UNDERRUN_Msk instead */
#define DAC_INTFLAG_EMPTY_Pos 1 /**< (DAC_INTFLAG) Data Buffer Empty Position */
#define DAC_INTFLAG_EMPTY_Msk (_U_(0x1) << DAC_INTFLAG_EMPTY_Pos) /**< (DAC_INTFLAG) Data Buffer Empty Mask */
#define DAC_INTFLAG_EMPTY DAC_INTFLAG_EMPTY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use DAC_INTFLAG_EMPTY_Msk instead */
#define DAC_INTFLAG_MASK _U_(0x03) /**< \deprecated (DAC_INTFLAG) Register MASK (Use DAC_INTFLAG_Msk instead) */
#define DAC_INTFLAG_Msk _U_(0x03) /**< (DAC_INTFLAG) Register Mask */
/* -------- DAC_STATUS : (DAC Offset: 0x07) (R/ 8) Status -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t READY:1; /**< bit: 0 Ready */
uint8_t :7; /**< bit: 1..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} DAC_STATUS_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define DAC_STATUS_OFFSET (0x07) /**< (DAC_STATUS) Status Offset */
#define DAC_STATUS_RESETVALUE _U_(0x00) /**< (DAC_STATUS) Status Reset Value */
#define DAC_STATUS_READY_Pos 0 /**< (DAC_STATUS) Ready Position */
#define DAC_STATUS_READY_Msk (_U_(0x1) << DAC_STATUS_READY_Pos) /**< (DAC_STATUS) Ready Mask */
#define DAC_STATUS_READY DAC_STATUS_READY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use DAC_STATUS_READY_Msk instead */
#define DAC_STATUS_MASK _U_(0x01) /**< \deprecated (DAC_STATUS) Register MASK (Use DAC_STATUS_Msk instead) */
#define DAC_STATUS_Msk _U_(0x01) /**< (DAC_STATUS) Register Mask */
/* -------- DAC_DATA : (DAC Offset: 0x08) (/W 16) Data -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint16_t DATA:16; /**< bit: 0..15 Data value to be converted */
} bit; /**< Structure used for bit access */
uint16_t reg; /**< Type used for register access */
} DAC_DATA_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define DAC_DATA_OFFSET (0x08) /**< (DAC_DATA) Data Offset */
#define DAC_DATA_RESETVALUE _U_(0x00) /**< (DAC_DATA) Data Reset Value */
#define DAC_DATA_DATA_Pos 0 /**< (DAC_DATA) Data value to be converted Position */
#define DAC_DATA_DATA_Msk (_U_(0xFFFF) << DAC_DATA_DATA_Pos) /**< (DAC_DATA) Data value to be converted Mask */
#define DAC_DATA_DATA(value) (DAC_DATA_DATA_Msk & ((value) << DAC_DATA_DATA_Pos))
#define DAC_DATA_MASK _U_(0xFFFF) /**< \deprecated (DAC_DATA) Register MASK (Use DAC_DATA_Msk instead) */
#define DAC_DATA_Msk _U_(0xFFFF) /**< (DAC_DATA) Register Mask */
/* -------- DAC_DATABUF : (DAC Offset: 0x0c) (/W 16) Data Buffer -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint16_t DATABUF:16; /**< bit: 0..15 Data Buffer */
} bit; /**< Structure used for bit access */
uint16_t reg; /**< Type used for register access */
} DAC_DATABUF_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define DAC_DATABUF_OFFSET (0x0C) /**< (DAC_DATABUF) Data Buffer Offset */
#define DAC_DATABUF_RESETVALUE _U_(0x00) /**< (DAC_DATABUF) Data Buffer Reset Value */
#define DAC_DATABUF_DATABUF_Pos 0 /**< (DAC_DATABUF) Data Buffer Position */
#define DAC_DATABUF_DATABUF_Msk (_U_(0xFFFF) << DAC_DATABUF_DATABUF_Pos) /**< (DAC_DATABUF) Data Buffer Mask */
#define DAC_DATABUF_DATABUF(value) (DAC_DATABUF_DATABUF_Msk & ((value) << DAC_DATABUF_DATABUF_Pos))
#define DAC_DATABUF_MASK _U_(0xFFFF) /**< \deprecated (DAC_DATABUF) Register MASK (Use DAC_DATABUF_Msk instead) */
#define DAC_DATABUF_Msk _U_(0xFFFF) /**< (DAC_DATABUF) Register Mask */
/* -------- DAC_SYNCBUSY : (DAC Offset: 0x10) (R/ 32) Synchronization Busy -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t SWRST:1; /**< bit: 0 Software Reset */
uint32_t ENABLE:1; /**< bit: 1 Enable */
uint32_t DATA:1; /**< bit: 2 Data */
uint32_t DATABUF:1; /**< bit: 3 Data Buffer */
uint32_t :28; /**< bit: 4..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} DAC_SYNCBUSY_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define DAC_SYNCBUSY_OFFSET (0x10) /**< (DAC_SYNCBUSY) Synchronization Busy Offset */
#define DAC_SYNCBUSY_RESETVALUE _U_(0x00) /**< (DAC_SYNCBUSY) Synchronization Busy Reset Value */
#define DAC_SYNCBUSY_SWRST_Pos 0 /**< (DAC_SYNCBUSY) Software Reset Position */
#define DAC_SYNCBUSY_SWRST_Msk (_U_(0x1) << DAC_SYNCBUSY_SWRST_Pos) /**< (DAC_SYNCBUSY) Software Reset Mask */
#define DAC_SYNCBUSY_SWRST DAC_SYNCBUSY_SWRST_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use DAC_SYNCBUSY_SWRST_Msk instead */
#define DAC_SYNCBUSY_ENABLE_Pos 1 /**< (DAC_SYNCBUSY) Enable Position */
#define DAC_SYNCBUSY_ENABLE_Msk (_U_(0x1) << DAC_SYNCBUSY_ENABLE_Pos) /**< (DAC_SYNCBUSY) Enable Mask */
#define DAC_SYNCBUSY_ENABLE DAC_SYNCBUSY_ENABLE_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use DAC_SYNCBUSY_ENABLE_Msk instead */
#define DAC_SYNCBUSY_DATA_Pos 2 /**< (DAC_SYNCBUSY) Data Position */
#define DAC_SYNCBUSY_DATA_Msk (_U_(0x1) << DAC_SYNCBUSY_DATA_Pos) /**< (DAC_SYNCBUSY) Data Mask */
#define DAC_SYNCBUSY_DATA DAC_SYNCBUSY_DATA_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use DAC_SYNCBUSY_DATA_Msk instead */
#define DAC_SYNCBUSY_DATABUF_Pos 3 /**< (DAC_SYNCBUSY) Data Buffer Position */
#define DAC_SYNCBUSY_DATABUF_Msk (_U_(0x1) << DAC_SYNCBUSY_DATABUF_Pos) /**< (DAC_SYNCBUSY) Data Buffer Mask */
#define DAC_SYNCBUSY_DATABUF DAC_SYNCBUSY_DATABUF_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use DAC_SYNCBUSY_DATABUF_Msk instead */
#define DAC_SYNCBUSY_MASK _U_(0x0F) /**< \deprecated (DAC_SYNCBUSY) Register MASK (Use DAC_SYNCBUSY_Msk instead) */
#define DAC_SYNCBUSY_Msk _U_(0x0F) /**< (DAC_SYNCBUSY) Register Mask */
/* -------- DAC_DBGCTRL : (DAC Offset: 0x14) (R/W 8) Debug Control -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t DBGRUN:1; /**< bit: 0 Debug Run */
uint8_t :7; /**< bit: 1..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} DAC_DBGCTRL_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define DAC_DBGCTRL_OFFSET (0x14) /**< (DAC_DBGCTRL) Debug Control Offset */
#define DAC_DBGCTRL_RESETVALUE _U_(0x00) /**< (DAC_DBGCTRL) Debug Control Reset Value */
#define DAC_DBGCTRL_DBGRUN_Pos 0 /**< (DAC_DBGCTRL) Debug Run Position */
#define DAC_DBGCTRL_DBGRUN_Msk (_U_(0x1) << DAC_DBGCTRL_DBGRUN_Pos) /**< (DAC_DBGCTRL) Debug Run Mask */
#define DAC_DBGCTRL_DBGRUN DAC_DBGCTRL_DBGRUN_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use DAC_DBGCTRL_DBGRUN_Msk instead */
#define DAC_DBGCTRL_MASK _U_(0x01) /**< \deprecated (DAC_DBGCTRL) Register MASK (Use DAC_DBGCTRL_Msk instead) */
#define DAC_DBGCTRL_Msk _U_(0x01) /**< (DAC_DBGCTRL) Register Mask */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
/** \brief DAC hardware registers */
typedef struct { /* Digital Analog Converter */
__IO DAC_CTRLA_Type CTRLA; /**< Offset: 0x00 (R/W 8) Control A */
__IO DAC_CTRLB_Type CTRLB; /**< Offset: 0x01 (R/W 8) Control B */
__IO DAC_EVCTRL_Type EVCTRL; /**< Offset: 0x02 (R/W 8) Event Control */
__I uint8_t Reserved1[1];
__IO DAC_INTENCLR_Type INTENCLR; /**< Offset: 0x04 (R/W 8) Interrupt Enable Clear */
__IO DAC_INTENSET_Type INTENSET; /**< Offset: 0x05 (R/W 8) Interrupt Enable Set */
__IO DAC_INTFLAG_Type INTFLAG; /**< Offset: 0x06 (R/W 8) Interrupt Flag Status and Clear */
__I DAC_STATUS_Type STATUS; /**< Offset: 0x07 (R/ 8) Status */
__O DAC_DATA_Type DATA; /**< Offset: 0x08 ( /W 16) Data */
__I uint8_t Reserved2[2];
__O DAC_DATABUF_Type DATABUF; /**< Offset: 0x0C ( /W 16) Data Buffer */
__I uint8_t Reserved3[2];
__I DAC_SYNCBUSY_Type SYNCBUSY; /**< Offset: 0x10 (R/ 32) Synchronization Busy */
__IO DAC_DBGCTRL_Type DBGCTRL; /**< Offset: 0x14 (R/W 8) Debug Control */
} Dac;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/** @} end of Digital Analog Converter */
#endif /* _SAML10_DAC_COMPONENT_H_ */

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,785 @@
/**
* \file
*
* \brief Component description for DSU
*
* Copyright (c) 2018 Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* 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
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
/* file generated from device description version 2018-08-31T13:51:50Z */
#ifndef _SAML10_DSU_COMPONENT_H_
#define _SAML10_DSU_COMPONENT_H_
#define _SAML10_DSU_COMPONENT_ /**< \deprecated Backward compatibility for ASF */
/** \addtogroup SAML_SAML10 Device Service Unit
* @{
*/
/* ========================================================================== */
/** SOFTWARE API DEFINITION FOR DSU */
/* ========================================================================== */
#define DSU_U2810 /**< (DSU) Module ID */
#define REV_DSU 0x100 /**< (DSU) Module revision */
/* -------- DSU_CTRL : (DSU Offset: 0x00) (/W 8) Control -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t SWRST:1; /**< bit: 0 Software Reset */
uint8_t :1; /**< bit: 1 Reserved */
uint8_t CRC:1; /**< bit: 2 32-bit Cyclic Redundancy Code */
uint8_t MBIST:1; /**< bit: 3 Memory built-in self-test */
uint8_t :4; /**< bit: 4..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} DSU_CTRL_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define DSU_CTRL_OFFSET (0x00) /**< (DSU_CTRL) Control Offset */
#define DSU_CTRL_RESETVALUE _U_(0x00) /**< (DSU_CTRL) Control Reset Value */
#define DSU_CTRL_SWRST_Pos 0 /**< (DSU_CTRL) Software Reset Position */
#define DSU_CTRL_SWRST_Msk (_U_(0x1) << DSU_CTRL_SWRST_Pos) /**< (DSU_CTRL) Software Reset Mask */
#define DSU_CTRL_SWRST DSU_CTRL_SWRST_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use DSU_CTRL_SWRST_Msk instead */
#define DSU_CTRL_CRC_Pos 2 /**< (DSU_CTRL) 32-bit Cyclic Redundancy Code Position */
#define DSU_CTRL_CRC_Msk (_U_(0x1) << DSU_CTRL_CRC_Pos) /**< (DSU_CTRL) 32-bit Cyclic Redundancy Code Mask */
#define DSU_CTRL_CRC DSU_CTRL_CRC_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use DSU_CTRL_CRC_Msk instead */
#define DSU_CTRL_MBIST_Pos 3 /**< (DSU_CTRL) Memory built-in self-test Position */
#define DSU_CTRL_MBIST_Msk (_U_(0x1) << DSU_CTRL_MBIST_Pos) /**< (DSU_CTRL) Memory built-in self-test Mask */
#define DSU_CTRL_MBIST DSU_CTRL_MBIST_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use DSU_CTRL_MBIST_Msk instead */
#define DSU_CTRL_MASK _U_(0x0D) /**< \deprecated (DSU_CTRL) Register MASK (Use DSU_CTRL_Msk instead) */
#define DSU_CTRL_Msk _U_(0x0D) /**< (DSU_CTRL) Register Mask */
/* -------- DSU_STATUSA : (DSU Offset: 0x01) (R/W 8) Status A -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t DONE:1; /**< bit: 0 Done */
uint8_t CRSTEXT:1; /**< bit: 1 CPU Reset Phase Extension */
uint8_t BERR:1; /**< bit: 2 Bus Error */
uint8_t FAIL:1; /**< bit: 3 Failure */
uint8_t PERR:1; /**< bit: 4 Protection Error Detected by the State Machine */
uint8_t BREXT:1; /**< bit: 5 BootRom Phase Extension */
uint8_t :2; /**< bit: 6..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} DSU_STATUSA_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define DSU_STATUSA_OFFSET (0x01) /**< (DSU_STATUSA) Status A Offset */
#define DSU_STATUSA_RESETVALUE _U_(0x00) /**< (DSU_STATUSA) Status A Reset Value */
#define DSU_STATUSA_DONE_Pos 0 /**< (DSU_STATUSA) Done Position */
#define DSU_STATUSA_DONE_Msk (_U_(0x1) << DSU_STATUSA_DONE_Pos) /**< (DSU_STATUSA) Done Mask */
#define DSU_STATUSA_DONE DSU_STATUSA_DONE_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use DSU_STATUSA_DONE_Msk instead */
#define DSU_STATUSA_CRSTEXT_Pos 1 /**< (DSU_STATUSA) CPU Reset Phase Extension Position */
#define DSU_STATUSA_CRSTEXT_Msk (_U_(0x1) << DSU_STATUSA_CRSTEXT_Pos) /**< (DSU_STATUSA) CPU Reset Phase Extension Mask */
#define DSU_STATUSA_CRSTEXT DSU_STATUSA_CRSTEXT_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use DSU_STATUSA_CRSTEXT_Msk instead */
#define DSU_STATUSA_BERR_Pos 2 /**< (DSU_STATUSA) Bus Error Position */
#define DSU_STATUSA_BERR_Msk (_U_(0x1) << DSU_STATUSA_BERR_Pos) /**< (DSU_STATUSA) Bus Error Mask */
#define DSU_STATUSA_BERR DSU_STATUSA_BERR_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use DSU_STATUSA_BERR_Msk instead */
#define DSU_STATUSA_FAIL_Pos 3 /**< (DSU_STATUSA) Failure Position */
#define DSU_STATUSA_FAIL_Msk (_U_(0x1) << DSU_STATUSA_FAIL_Pos) /**< (DSU_STATUSA) Failure Mask */
#define DSU_STATUSA_FAIL DSU_STATUSA_FAIL_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use DSU_STATUSA_FAIL_Msk instead */
#define DSU_STATUSA_PERR_Pos 4 /**< (DSU_STATUSA) Protection Error Detected by the State Machine Position */
#define DSU_STATUSA_PERR_Msk (_U_(0x1) << DSU_STATUSA_PERR_Pos) /**< (DSU_STATUSA) Protection Error Detected by the State Machine Mask */
#define DSU_STATUSA_PERR DSU_STATUSA_PERR_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use DSU_STATUSA_PERR_Msk instead */
#define DSU_STATUSA_BREXT_Pos 5 /**< (DSU_STATUSA) BootRom Phase Extension Position */
#define DSU_STATUSA_BREXT_Msk (_U_(0x1) << DSU_STATUSA_BREXT_Pos) /**< (DSU_STATUSA) BootRom Phase Extension Mask */
#define DSU_STATUSA_BREXT DSU_STATUSA_BREXT_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use DSU_STATUSA_BREXT_Msk instead */
#define DSU_STATUSA_MASK _U_(0x3F) /**< \deprecated (DSU_STATUSA) Register MASK (Use DSU_STATUSA_Msk instead) */
#define DSU_STATUSA_Msk _U_(0x3F) /**< (DSU_STATUSA) Register Mask */
/* -------- DSU_STATUSB : (DSU Offset: 0x02) (R/ 8) Status B -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t DAL:2; /**< bit: 0..1 Debugger Access Level */
uint8_t DBGPRES:1; /**< bit: 2 Debugger Present */
uint8_t HPE:1; /**< bit: 3 Hot-Plugging Enable */
uint8_t DCCD0:1; /**< bit: 4 Debug Communication Channel 0 Dirty */
uint8_t DCCD1:1; /**< bit: 5 Debug Communication Channel 1 Dirty */
uint8_t BCCD0:1; /**< bit: 6 Boot ROM Communication Channel 0 Dirty */
uint8_t BCCD1:1; /**< bit: 7 Boot ROM Communication Channel 1 Dirty */
} bit; /**< Structure used for bit access */
struct {
uint8_t :4; /**< bit: 0..3 Reserved */
uint8_t DCCD:2; /**< bit: 4..5 Debug Communication Channel x Dirty */
uint8_t BCCD:2; /**< bit: 6..7 Boot ROM Communication Channel x Dirty */
} vec; /**< Structure used for vec access */
uint8_t reg; /**< Type used for register access */
} DSU_STATUSB_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define DSU_STATUSB_OFFSET (0x02) /**< (DSU_STATUSB) Status B Offset */
#define DSU_STATUSB_RESETVALUE _U_(0x00) /**< (DSU_STATUSB) Status B Reset Value */
#define DSU_STATUSB_DAL_Pos 0 /**< (DSU_STATUSB) Debugger Access Level Position */
#define DSU_STATUSB_DAL_Msk (_U_(0x3) << DSU_STATUSB_DAL_Pos) /**< (DSU_STATUSB) Debugger Access Level Mask */
#define DSU_STATUSB_DAL(value) (DSU_STATUSB_DAL_Msk & ((value) << DSU_STATUSB_DAL_Pos))
#define DSU_STATUSB_DAL_SECURED_Val _U_(0x0) /**< (DSU_STATUSB) */
#define DSU_STATUSB_DAL_NS_DEBUG_Val _U_(0x1) /**< (DSU_STATUSB) */
#define DSU_STATUSB_DAL_FULL_DEBUG_Val _U_(0x2) /**< (DSU_STATUSB) */
#define DSU_STATUSB_DAL_SECURED (DSU_STATUSB_DAL_SECURED_Val << DSU_STATUSB_DAL_Pos) /**< (DSU_STATUSB) Position */
#define DSU_STATUSB_DAL_NS_DEBUG (DSU_STATUSB_DAL_NS_DEBUG_Val << DSU_STATUSB_DAL_Pos) /**< (DSU_STATUSB) Position */
#define DSU_STATUSB_DAL_FULL_DEBUG (DSU_STATUSB_DAL_FULL_DEBUG_Val << DSU_STATUSB_DAL_Pos) /**< (DSU_STATUSB) Position */
#define DSU_STATUSB_DBGPRES_Pos 2 /**< (DSU_STATUSB) Debugger Present Position */
#define DSU_STATUSB_DBGPRES_Msk (_U_(0x1) << DSU_STATUSB_DBGPRES_Pos) /**< (DSU_STATUSB) Debugger Present Mask */
#define DSU_STATUSB_DBGPRES DSU_STATUSB_DBGPRES_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use DSU_STATUSB_DBGPRES_Msk instead */
#define DSU_STATUSB_HPE_Pos 3 /**< (DSU_STATUSB) Hot-Plugging Enable Position */
#define DSU_STATUSB_HPE_Msk (_U_(0x1) << DSU_STATUSB_HPE_Pos) /**< (DSU_STATUSB) Hot-Plugging Enable Mask */
#define DSU_STATUSB_HPE DSU_STATUSB_HPE_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use DSU_STATUSB_HPE_Msk instead */
#define DSU_STATUSB_DCCD0_Pos 4 /**< (DSU_STATUSB) Debug Communication Channel 0 Dirty Position */
#define DSU_STATUSB_DCCD0_Msk (_U_(0x1) << DSU_STATUSB_DCCD0_Pos) /**< (DSU_STATUSB) Debug Communication Channel 0 Dirty Mask */
#define DSU_STATUSB_DCCD0 DSU_STATUSB_DCCD0_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use DSU_STATUSB_DCCD0_Msk instead */
#define DSU_STATUSB_DCCD1_Pos 5 /**< (DSU_STATUSB) Debug Communication Channel 1 Dirty Position */
#define DSU_STATUSB_DCCD1_Msk (_U_(0x1) << DSU_STATUSB_DCCD1_Pos) /**< (DSU_STATUSB) Debug Communication Channel 1 Dirty Mask */
#define DSU_STATUSB_DCCD1 DSU_STATUSB_DCCD1_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use DSU_STATUSB_DCCD1_Msk instead */
#define DSU_STATUSB_BCCD0_Pos 6 /**< (DSU_STATUSB) Boot ROM Communication Channel 0 Dirty Position */
#define DSU_STATUSB_BCCD0_Msk (_U_(0x1) << DSU_STATUSB_BCCD0_Pos) /**< (DSU_STATUSB) Boot ROM Communication Channel 0 Dirty Mask */
#define DSU_STATUSB_BCCD0 DSU_STATUSB_BCCD0_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use DSU_STATUSB_BCCD0_Msk instead */
#define DSU_STATUSB_BCCD1_Pos 7 /**< (DSU_STATUSB) Boot ROM Communication Channel 1 Dirty Position */
#define DSU_STATUSB_BCCD1_Msk (_U_(0x1) << DSU_STATUSB_BCCD1_Pos) /**< (DSU_STATUSB) Boot ROM Communication Channel 1 Dirty Mask */
#define DSU_STATUSB_BCCD1 DSU_STATUSB_BCCD1_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use DSU_STATUSB_BCCD1_Msk instead */
#define DSU_STATUSB_MASK _U_(0xFF) /**< \deprecated (DSU_STATUSB) Register MASK (Use DSU_STATUSB_Msk instead) */
#define DSU_STATUSB_Msk _U_(0xFF) /**< (DSU_STATUSB) Register Mask */
#define DSU_STATUSB_DCCD_Pos 4 /**< (DSU_STATUSB Position) Debug Communication Channel x Dirty */
#define DSU_STATUSB_DCCD_Msk (_U_(0x3) << DSU_STATUSB_DCCD_Pos) /**< (DSU_STATUSB Mask) DCCD */
#define DSU_STATUSB_DCCD(value) (DSU_STATUSB_DCCD_Msk & ((value) << DSU_STATUSB_DCCD_Pos))
#define DSU_STATUSB_BCCD_Pos 6 /**< (DSU_STATUSB Position) Boot ROM Communication Channel x Dirty */
#define DSU_STATUSB_BCCD_Msk (_U_(0x3) << DSU_STATUSB_BCCD_Pos) /**< (DSU_STATUSB Mask) BCCD */
#define DSU_STATUSB_BCCD(value) (DSU_STATUSB_BCCD_Msk & ((value) << DSU_STATUSB_BCCD_Pos))
/* -------- DSU_STATUSC : (DSU Offset: 0x03) (R/ 8) Status C -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
uint8_t reg; /**< Type used for register access */
} DSU_STATUSC_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define DSU_STATUSC_OFFSET (0x03) /**< (DSU_STATUSC) Status C Offset */
#define DSU_STATUSC_RESETVALUE _U_(0x00) /**< (DSU_STATUSC) Status C Reset Value */
#define DSU_STATUSC_MASK _U_(0x00) /**< \deprecated (DSU_STATUSC) Register MASK (Use DSU_STATUSC_Msk instead) */
#define DSU_STATUSC_Msk _U_(0x00) /**< (DSU_STATUSC) Register Mask */
/* -------- DSU_ADDR : (DSU Offset: 0x04) (R/W 32) Address -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t AMOD:2; /**< bit: 0..1 Access Mode */
uint32_t ADDR:30; /**< bit: 2..31 Address */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} DSU_ADDR_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define DSU_ADDR_OFFSET (0x04) /**< (DSU_ADDR) Address Offset */
#define DSU_ADDR_RESETVALUE _U_(0x00) /**< (DSU_ADDR) Address Reset Value */
#define DSU_ADDR_AMOD_Pos 0 /**< (DSU_ADDR) Access Mode Position */
#define DSU_ADDR_AMOD_Msk (_U_(0x3) << DSU_ADDR_AMOD_Pos) /**< (DSU_ADDR) Access Mode Mask */
#define DSU_ADDR_AMOD(value) (DSU_ADDR_AMOD_Msk & ((value) << DSU_ADDR_AMOD_Pos))
#define DSU_ADDR_ADDR_Pos 2 /**< (DSU_ADDR) Address Position */
#define DSU_ADDR_ADDR_Msk (_U_(0x3FFFFFFF) << DSU_ADDR_ADDR_Pos) /**< (DSU_ADDR) Address Mask */
#define DSU_ADDR_ADDR(value) (DSU_ADDR_ADDR_Msk & ((value) << DSU_ADDR_ADDR_Pos))
#define DSU_ADDR_MASK _U_(0xFFFFFFFF) /**< \deprecated (DSU_ADDR) Register MASK (Use DSU_ADDR_Msk instead) */
#define DSU_ADDR_Msk _U_(0xFFFFFFFF) /**< (DSU_ADDR) Register Mask */
/* -------- DSU_LENGTH : (DSU Offset: 0x08) (R/W 32) Length -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t :2; /**< bit: 0..1 Reserved */
uint32_t LENGTH:30; /**< bit: 2..31 Length */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} DSU_LENGTH_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define DSU_LENGTH_OFFSET (0x08) /**< (DSU_LENGTH) Length Offset */
#define DSU_LENGTH_RESETVALUE _U_(0x00) /**< (DSU_LENGTH) Length Reset Value */
#define DSU_LENGTH_LENGTH_Pos 2 /**< (DSU_LENGTH) Length Position */
#define DSU_LENGTH_LENGTH_Msk (_U_(0x3FFFFFFF) << DSU_LENGTH_LENGTH_Pos) /**< (DSU_LENGTH) Length Mask */
#define DSU_LENGTH_LENGTH(value) (DSU_LENGTH_LENGTH_Msk & ((value) << DSU_LENGTH_LENGTH_Pos))
#define DSU_LENGTH_MASK _U_(0xFFFFFFFC) /**< \deprecated (DSU_LENGTH) Register MASK (Use DSU_LENGTH_Msk instead) */
#define DSU_LENGTH_Msk _U_(0xFFFFFFFC) /**< (DSU_LENGTH) Register Mask */
/* -------- DSU_DATA : (DSU Offset: 0x0c) (R/W 32) Data -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t DATA:32; /**< bit: 0..31 Data */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} DSU_DATA_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define DSU_DATA_OFFSET (0x0C) /**< (DSU_DATA) Data Offset */
#define DSU_DATA_RESETVALUE _U_(0x00) /**< (DSU_DATA) Data Reset Value */
#define DSU_DATA_DATA_Pos 0 /**< (DSU_DATA) Data Position */
#define DSU_DATA_DATA_Msk (_U_(0xFFFFFFFF) << DSU_DATA_DATA_Pos) /**< (DSU_DATA) Data Mask */
#define DSU_DATA_DATA(value) (DSU_DATA_DATA_Msk & ((value) << DSU_DATA_DATA_Pos))
#define DSU_DATA_MASK _U_(0xFFFFFFFF) /**< \deprecated (DSU_DATA) Register MASK (Use DSU_DATA_Msk instead) */
#define DSU_DATA_Msk _U_(0xFFFFFFFF) /**< (DSU_DATA) Register Mask */
/* -------- DSU_DCC : (DSU Offset: 0x10) (R/W 32) Debug Communication Channel n -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t DATA:32; /**< bit: 0..31 Data */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} DSU_DCC_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define DSU_DCC_OFFSET (0x10) /**< (DSU_DCC) Debug Communication Channel n Offset */
#define DSU_DCC_RESETVALUE _U_(0x00) /**< (DSU_DCC) Debug Communication Channel n Reset Value */
#define DSU_DCC_DATA_Pos 0 /**< (DSU_DCC) Data Position */
#define DSU_DCC_DATA_Msk (_U_(0xFFFFFFFF) << DSU_DCC_DATA_Pos) /**< (DSU_DCC) Data Mask */
#define DSU_DCC_DATA(value) (DSU_DCC_DATA_Msk & ((value) << DSU_DCC_DATA_Pos))
#define DSU_DCC_MASK _U_(0xFFFFFFFF) /**< \deprecated (DSU_DCC) Register MASK (Use DSU_DCC_Msk instead) */
#define DSU_DCC_Msk _U_(0xFFFFFFFF) /**< (DSU_DCC) Register Mask */
/* -------- DSU_DID : (DSU Offset: 0x18) (R/ 32) Device Identification -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t DEVSEL:8; /**< bit: 0..7 Device Select */
uint32_t REVISION:4; /**< bit: 8..11 Revision Number */
uint32_t DIE:4; /**< bit: 12..15 Die Number */
uint32_t SERIES:6; /**< bit: 16..21 Series */
uint32_t :1; /**< bit: 22 Reserved */
uint32_t FAMILY:5; /**< bit: 23..27 Family */
uint32_t PROCESSOR:4; /**< bit: 28..31 Processor */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} DSU_DID_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define DSU_DID_OFFSET (0x18) /**< (DSU_DID) Device Identification Offset */
#define DSU_DID_RESETVALUE _U_(0x20840000) /**< (DSU_DID) Device Identification Reset Value */
#define DSU_DID_DEVSEL_Pos 0 /**< (DSU_DID) Device Select Position */
#define DSU_DID_DEVSEL_Msk (_U_(0xFF) << DSU_DID_DEVSEL_Pos) /**< (DSU_DID) Device Select Mask */
#define DSU_DID_DEVSEL(value) (DSU_DID_DEVSEL_Msk & ((value) << DSU_DID_DEVSEL_Pos))
#define DSU_DID_REVISION_Pos 8 /**< (DSU_DID) Revision Number Position */
#define DSU_DID_REVISION_Msk (_U_(0xF) << DSU_DID_REVISION_Pos) /**< (DSU_DID) Revision Number Mask */
#define DSU_DID_REVISION(value) (DSU_DID_REVISION_Msk & ((value) << DSU_DID_REVISION_Pos))
#define DSU_DID_DIE_Pos 12 /**< (DSU_DID) Die Number Position */
#define DSU_DID_DIE_Msk (_U_(0xF) << DSU_DID_DIE_Pos) /**< (DSU_DID) Die Number Mask */
#define DSU_DID_DIE(value) (DSU_DID_DIE_Msk & ((value) << DSU_DID_DIE_Pos))
#define DSU_DID_SERIES_Pos 16 /**< (DSU_DID) Series Position */
#define DSU_DID_SERIES_Msk (_U_(0x3F) << DSU_DID_SERIES_Pos) /**< (DSU_DID) Series Mask */
#define DSU_DID_SERIES(value) (DSU_DID_SERIES_Msk & ((value) << DSU_DID_SERIES_Pos))
#define DSU_DID_SERIES_0_Val _U_(0x0) /**< (DSU_DID) Cortex-M0+ processor, basic feature set */
#define DSU_DID_SERIES_1_Val _U_(0x1) /**< (DSU_DID) Cortex-M0+ processor, USB */
#define DSU_DID_SERIES_0 (DSU_DID_SERIES_0_Val << DSU_DID_SERIES_Pos) /**< (DSU_DID) Cortex-M0+ processor, basic feature set Position */
#define DSU_DID_SERIES_1 (DSU_DID_SERIES_1_Val << DSU_DID_SERIES_Pos) /**< (DSU_DID) Cortex-M0+ processor, USB Position */
#define DSU_DID_FAMILY_Pos 23 /**< (DSU_DID) Family Position */
#define DSU_DID_FAMILY_Msk (_U_(0x1F) << DSU_DID_FAMILY_Pos) /**< (DSU_DID) Family Mask */
#define DSU_DID_FAMILY(value) (DSU_DID_FAMILY_Msk & ((value) << DSU_DID_FAMILY_Pos))
#define DSU_DID_FAMILY_0_Val _U_(0x0) /**< (DSU_DID) General purpose microcontroller */
#define DSU_DID_FAMILY_1_Val _U_(0x1) /**< (DSU_DID) PicoPower */
#define DSU_DID_FAMILY_0 (DSU_DID_FAMILY_0_Val << DSU_DID_FAMILY_Pos) /**< (DSU_DID) General purpose microcontroller Position */
#define DSU_DID_FAMILY_1 (DSU_DID_FAMILY_1_Val << DSU_DID_FAMILY_Pos) /**< (DSU_DID) PicoPower Position */
#define DSU_DID_PROCESSOR_Pos 28 /**< (DSU_DID) Processor Position */
#define DSU_DID_PROCESSOR_Msk (_U_(0xF) << DSU_DID_PROCESSOR_Pos) /**< (DSU_DID) Processor Mask */
#define DSU_DID_PROCESSOR(value) (DSU_DID_PROCESSOR_Msk & ((value) << DSU_DID_PROCESSOR_Pos))
#define DSU_DID_PROCESSOR_CM0P_Val _U_(0x1) /**< (DSU_DID) Cortex-M0+ */
#define DSU_DID_PROCESSOR_CM23_Val _U_(0x2) /**< (DSU_DID) Cortex-M23 */
#define DSU_DID_PROCESSOR_CM3_Val _U_(0x3) /**< (DSU_DID) Cortex-M3 */
#define DSU_DID_PROCESSOR_CM4_Val _U_(0x5) /**< (DSU_DID) Cortex-M4 */
#define DSU_DID_PROCESSOR_CM4F_Val _U_(0x6) /**< (DSU_DID) Cortex-M4 with FPU */
#define DSU_DID_PROCESSOR_CM33_Val _U_(0x7) /**< (DSU_DID) Cortex-M33 */
#define DSU_DID_PROCESSOR_CM0P (DSU_DID_PROCESSOR_CM0P_Val << DSU_DID_PROCESSOR_Pos) /**< (DSU_DID) Cortex-M0+ Position */
#define DSU_DID_PROCESSOR_CM23 (DSU_DID_PROCESSOR_CM23_Val << DSU_DID_PROCESSOR_Pos) /**< (DSU_DID) Cortex-M23 Position */
#define DSU_DID_PROCESSOR_CM3 (DSU_DID_PROCESSOR_CM3_Val << DSU_DID_PROCESSOR_Pos) /**< (DSU_DID) Cortex-M3 Position */
#define DSU_DID_PROCESSOR_CM4 (DSU_DID_PROCESSOR_CM4_Val << DSU_DID_PROCESSOR_Pos) /**< (DSU_DID) Cortex-M4 Position */
#define DSU_DID_PROCESSOR_CM4F (DSU_DID_PROCESSOR_CM4F_Val << DSU_DID_PROCESSOR_Pos) /**< (DSU_DID) Cortex-M4 with FPU Position */
#define DSU_DID_PROCESSOR_CM33 (DSU_DID_PROCESSOR_CM33_Val << DSU_DID_PROCESSOR_Pos) /**< (DSU_DID) Cortex-M33 Position */
#define DSU_DID_MASK _U_(0xFFBFFFFF) /**< \deprecated (DSU_DID) Register MASK (Use DSU_DID_Msk instead) */
#define DSU_DID_Msk _U_(0xFFBFFFFF) /**< (DSU_DID) Register Mask */
/* -------- DSU_CFG : (DSU Offset: 0x1c) (R/W 32) Configuration -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t LQOS:2; /**< bit: 0..1 Latency Quality Of Service */
uint32_t DCCDMALEVEL:2; /**< bit: 2..3 DMA Trigger Level */
uint32_t :28; /**< bit: 4..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} DSU_CFG_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define DSU_CFG_OFFSET (0x1C) /**< (DSU_CFG) Configuration Offset */
#define DSU_CFG_RESETVALUE _U_(0x02) /**< (DSU_CFG) Configuration Reset Value */
#define DSU_CFG_LQOS_Pos 0 /**< (DSU_CFG) Latency Quality Of Service Position */
#define DSU_CFG_LQOS_Msk (_U_(0x3) << DSU_CFG_LQOS_Pos) /**< (DSU_CFG) Latency Quality Of Service Mask */
#define DSU_CFG_LQOS(value) (DSU_CFG_LQOS_Msk & ((value) << DSU_CFG_LQOS_Pos))
#define DSU_CFG_DCCDMALEVEL_Pos 2 /**< (DSU_CFG) DMA Trigger Level Position */
#define DSU_CFG_DCCDMALEVEL_Msk (_U_(0x3) << DSU_CFG_DCCDMALEVEL_Pos) /**< (DSU_CFG) DMA Trigger Level Mask */
#define DSU_CFG_DCCDMALEVEL(value) (DSU_CFG_DCCDMALEVEL_Msk & ((value) << DSU_CFG_DCCDMALEVEL_Pos))
#define DSU_CFG_DCCDMALEVEL_EMPTY_Val _U_(0x0) /**< (DSU_CFG) Trigger rises when DCC is empty */
#define DSU_CFG_DCCDMALEVEL_FULL_Val _U_(0x1) /**< (DSU_CFG) Trigger rises when DCC is full */
#define DSU_CFG_DCCDMALEVEL_EMPTY (DSU_CFG_DCCDMALEVEL_EMPTY_Val << DSU_CFG_DCCDMALEVEL_Pos) /**< (DSU_CFG) Trigger rises when DCC is empty Position */
#define DSU_CFG_DCCDMALEVEL_FULL (DSU_CFG_DCCDMALEVEL_FULL_Val << DSU_CFG_DCCDMALEVEL_Pos) /**< (DSU_CFG) Trigger rises when DCC is full Position */
#define DSU_CFG_MASK _U_(0x0F) /**< \deprecated (DSU_CFG) Register MASK (Use DSU_CFG_Msk instead) */
#define DSU_CFG_Msk _U_(0x0F) /**< (DSU_CFG) Register Mask */
/* -------- DSU_BCC : (DSU Offset: 0x20) (R/W 32) Boot ROM Communication Channel n -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t DATA:32; /**< bit: 0..31 Data */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} DSU_BCC_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define DSU_BCC_OFFSET (0x20) /**< (DSU_BCC) Boot ROM Communication Channel n Offset */
#define DSU_BCC_RESETVALUE _U_(0x00) /**< (DSU_BCC) Boot ROM Communication Channel n Reset Value */
#define DSU_BCC_DATA_Pos 0 /**< (DSU_BCC) Data Position */
#define DSU_BCC_DATA_Msk (_U_(0xFFFFFFFF) << DSU_BCC_DATA_Pos) /**< (DSU_BCC) Data Mask */
#define DSU_BCC_DATA(value) (DSU_BCC_DATA_Msk & ((value) << DSU_BCC_DATA_Pos))
#define DSU_BCC_MASK _U_(0xFFFFFFFF) /**< \deprecated (DSU_BCC) Register MASK (Use DSU_BCC_Msk instead) */
#define DSU_BCC_Msk _U_(0xFFFFFFFF) /**< (DSU_BCC) Register Mask */
/* -------- DSU_DCFG : (DSU Offset: 0xf0) (R/W 32) Device Configuration -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t DCFG:32; /**< bit: 0..31 Device Configuration */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} DSU_DCFG_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define DSU_DCFG_OFFSET (0xF0) /**< (DSU_DCFG) Device Configuration Offset */
#define DSU_DCFG_RESETVALUE _U_(0x00) /**< (DSU_DCFG) Device Configuration Reset Value */
#define DSU_DCFG_DCFG_Pos 0 /**< (DSU_DCFG) Device Configuration Position */
#define DSU_DCFG_DCFG_Msk (_U_(0xFFFFFFFF) << DSU_DCFG_DCFG_Pos) /**< (DSU_DCFG) Device Configuration Mask */
#define DSU_DCFG_DCFG(value) (DSU_DCFG_DCFG_Msk & ((value) << DSU_DCFG_DCFG_Pos))
#define DSU_DCFG_MASK _U_(0xFFFFFFFF) /**< \deprecated (DSU_DCFG) Register MASK (Use DSU_DCFG_Msk instead) */
#define DSU_DCFG_Msk _U_(0xFFFFFFFF) /**< (DSU_DCFG) Register Mask */
/* -------- DSU_ENTRY0 : (DSU Offset: 0x1000) (R/ 32) CoreSight ROM Table Entry 0 -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t EPRES:1; /**< bit: 0 Entry Present */
uint32_t FMT:1; /**< bit: 1 Format */
uint32_t :10; /**< bit: 2..11 Reserved */
uint32_t ADDOFF:20; /**< bit: 12..31 Address Offset */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} DSU_ENTRY0_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define DSU_ENTRY0_OFFSET (0x1000) /**< (DSU_ENTRY0) CoreSight ROM Table Entry 0 Offset */
#define DSU_ENTRY0_RESETVALUE _U_(0x9F0FC002) /**< (DSU_ENTRY0) CoreSight ROM Table Entry 0 Reset Value */
#define DSU_ENTRY0_EPRES_Pos 0 /**< (DSU_ENTRY0) Entry Present Position */
#define DSU_ENTRY0_EPRES_Msk (_U_(0x1) << DSU_ENTRY0_EPRES_Pos) /**< (DSU_ENTRY0) Entry Present Mask */
#define DSU_ENTRY0_EPRES DSU_ENTRY0_EPRES_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use DSU_ENTRY0_EPRES_Msk instead */
#define DSU_ENTRY0_FMT_Pos 1 /**< (DSU_ENTRY0) Format Position */
#define DSU_ENTRY0_FMT_Msk (_U_(0x1) << DSU_ENTRY0_FMT_Pos) /**< (DSU_ENTRY0) Format Mask */
#define DSU_ENTRY0_FMT DSU_ENTRY0_FMT_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use DSU_ENTRY0_FMT_Msk instead */
#define DSU_ENTRY0_ADDOFF_Pos 12 /**< (DSU_ENTRY0) Address Offset Position */
#define DSU_ENTRY0_ADDOFF_Msk (_U_(0xFFFFF) << DSU_ENTRY0_ADDOFF_Pos) /**< (DSU_ENTRY0) Address Offset Mask */
#define DSU_ENTRY0_ADDOFF(value) (DSU_ENTRY0_ADDOFF_Msk & ((value) << DSU_ENTRY0_ADDOFF_Pos))
#define DSU_ENTRY0_MASK _U_(0xFFFFF003) /**< \deprecated (DSU_ENTRY0) Register MASK (Use DSU_ENTRY0_Msk instead) */
#define DSU_ENTRY0_Msk _U_(0xFFFFF003) /**< (DSU_ENTRY0) Register Mask */
/* -------- DSU_ENTRY1 : (DSU Offset: 0x1004) (R/ 32) CoreSight ROM Table Entry 1 -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
uint32_t reg; /**< Type used for register access */
} DSU_ENTRY1_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define DSU_ENTRY1_OFFSET (0x1004) /**< (DSU_ENTRY1) CoreSight ROM Table Entry 1 Offset */
#define DSU_ENTRY1_RESETVALUE _U_(0x00) /**< (DSU_ENTRY1) CoreSight ROM Table Entry 1 Reset Value */
#define DSU_ENTRY1_MASK _U_(0x00) /**< \deprecated (DSU_ENTRY1) Register MASK (Use DSU_ENTRY1_Msk instead) */
#define DSU_ENTRY1_Msk _U_(0x00) /**< (DSU_ENTRY1) Register Mask */
/* -------- DSU_END : (DSU Offset: 0x1008) (R/ 32) CoreSight ROM Table End -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t END:32; /**< bit: 0..31 End Marker */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} DSU_END_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define DSU_END_OFFSET (0x1008) /**< (DSU_END) CoreSight ROM Table End Offset */
#define DSU_END_RESETVALUE _U_(0x00) /**< (DSU_END) CoreSight ROM Table End Reset Value */
#define DSU_END_END_Pos 0 /**< (DSU_END) End Marker Position */
#define DSU_END_END_Msk (_U_(0xFFFFFFFF) << DSU_END_END_Pos) /**< (DSU_END) End Marker Mask */
#define DSU_END_END(value) (DSU_END_END_Msk & ((value) << DSU_END_END_Pos))
#define DSU_END_MASK _U_(0xFFFFFFFF) /**< \deprecated (DSU_END) Register MASK (Use DSU_END_Msk instead) */
#define DSU_END_Msk _U_(0xFFFFFFFF) /**< (DSU_END) Register Mask */
/* -------- DSU_MEMTYPE : (DSU Offset: 0x1fcc) (R/ 32) CoreSight ROM Table Memory Type -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t SMEMP:1; /**< bit: 0 System Memory Present */
uint32_t :31; /**< bit: 1..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} DSU_MEMTYPE_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define DSU_MEMTYPE_OFFSET (0x1FCC) /**< (DSU_MEMTYPE) CoreSight ROM Table Memory Type Offset */
#define DSU_MEMTYPE_RESETVALUE _U_(0x00) /**< (DSU_MEMTYPE) CoreSight ROM Table Memory Type Reset Value */
#define DSU_MEMTYPE_SMEMP_Pos 0 /**< (DSU_MEMTYPE) System Memory Present Position */
#define DSU_MEMTYPE_SMEMP_Msk (_U_(0x1) << DSU_MEMTYPE_SMEMP_Pos) /**< (DSU_MEMTYPE) System Memory Present Mask */
#define DSU_MEMTYPE_SMEMP DSU_MEMTYPE_SMEMP_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use DSU_MEMTYPE_SMEMP_Msk instead */
#define DSU_MEMTYPE_MASK _U_(0x01) /**< \deprecated (DSU_MEMTYPE) Register MASK (Use DSU_MEMTYPE_Msk instead) */
#define DSU_MEMTYPE_Msk _U_(0x01) /**< (DSU_MEMTYPE) Register Mask */
/* -------- DSU_PID4 : (DSU Offset: 0x1fd0) (R/ 32) Peripheral Identification 4 -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t JEPCC:4; /**< bit: 0..3 JEP-106 Continuation Code */
uint32_t FKBC:4; /**< bit: 4..7 4KB count */
uint32_t :24; /**< bit: 8..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} DSU_PID4_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define DSU_PID4_OFFSET (0x1FD0) /**< (DSU_PID4) Peripheral Identification 4 Offset */
#define DSU_PID4_RESETVALUE _U_(0x00) /**< (DSU_PID4) Peripheral Identification 4 Reset Value */
#define DSU_PID4_JEPCC_Pos 0 /**< (DSU_PID4) JEP-106 Continuation Code Position */
#define DSU_PID4_JEPCC_Msk (_U_(0xF) << DSU_PID4_JEPCC_Pos) /**< (DSU_PID4) JEP-106 Continuation Code Mask */
#define DSU_PID4_JEPCC(value) (DSU_PID4_JEPCC_Msk & ((value) << DSU_PID4_JEPCC_Pos))
#define DSU_PID4_FKBC_Pos 4 /**< (DSU_PID4) 4KB count Position */
#define DSU_PID4_FKBC_Msk (_U_(0xF) << DSU_PID4_FKBC_Pos) /**< (DSU_PID4) 4KB count Mask */
#define DSU_PID4_FKBC(value) (DSU_PID4_FKBC_Msk & ((value) << DSU_PID4_FKBC_Pos))
#define DSU_PID4_MASK _U_(0xFF) /**< \deprecated (DSU_PID4) Register MASK (Use DSU_PID4_Msk instead) */
#define DSU_PID4_Msk _U_(0xFF) /**< (DSU_PID4) Register Mask */
/* -------- DSU_PID5 : (DSU Offset: 0x1fd4) (R/ 32) Peripheral Identification 5 -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
uint32_t reg; /**< Type used for register access */
} DSU_PID5_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define DSU_PID5_OFFSET (0x1FD4) /**< (DSU_PID5) Peripheral Identification 5 Offset */
#define DSU_PID5_RESETVALUE _U_(0x00) /**< (DSU_PID5) Peripheral Identification 5 Reset Value */
#define DSU_PID5_MASK _U_(0x00) /**< \deprecated (DSU_PID5) Register MASK (Use DSU_PID5_Msk instead) */
#define DSU_PID5_Msk _U_(0x00) /**< (DSU_PID5) Register Mask */
/* -------- DSU_PID6 : (DSU Offset: 0x1fd8) (R/ 32) Peripheral Identification 6 -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
uint32_t reg; /**< Type used for register access */
} DSU_PID6_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define DSU_PID6_OFFSET (0x1FD8) /**< (DSU_PID6) Peripheral Identification 6 Offset */
#define DSU_PID6_RESETVALUE _U_(0x00) /**< (DSU_PID6) Peripheral Identification 6 Reset Value */
#define DSU_PID6_MASK _U_(0x00) /**< \deprecated (DSU_PID6) Register MASK (Use DSU_PID6_Msk instead) */
#define DSU_PID6_Msk _U_(0x00) /**< (DSU_PID6) Register Mask */
/* -------- DSU_PID7 : (DSU Offset: 0x1fdc) (R/ 32) Peripheral Identification 7 -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
uint32_t reg; /**< Type used for register access */
} DSU_PID7_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define DSU_PID7_OFFSET (0x1FDC) /**< (DSU_PID7) Peripheral Identification 7 Offset */
#define DSU_PID7_RESETVALUE _U_(0x00) /**< (DSU_PID7) Peripheral Identification 7 Reset Value */
#define DSU_PID7_MASK _U_(0x00) /**< \deprecated (DSU_PID7) Register MASK (Use DSU_PID7_Msk instead) */
#define DSU_PID7_Msk _U_(0x00) /**< (DSU_PID7) Register Mask */
/* -------- DSU_PID0 : (DSU Offset: 0x1fe0) (R/ 32) Peripheral Identification 0 -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t PARTNBL:8; /**< bit: 0..7 Part Number Low */
uint32_t :24; /**< bit: 8..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} DSU_PID0_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define DSU_PID0_OFFSET (0x1FE0) /**< (DSU_PID0) Peripheral Identification 0 Offset */
#define DSU_PID0_RESETVALUE _U_(0xD0) /**< (DSU_PID0) Peripheral Identification 0 Reset Value */
#define DSU_PID0_PARTNBL_Pos 0 /**< (DSU_PID0) Part Number Low Position */
#define DSU_PID0_PARTNBL_Msk (_U_(0xFF) << DSU_PID0_PARTNBL_Pos) /**< (DSU_PID0) Part Number Low Mask */
#define DSU_PID0_PARTNBL(value) (DSU_PID0_PARTNBL_Msk & ((value) << DSU_PID0_PARTNBL_Pos))
#define DSU_PID0_MASK _U_(0xFF) /**< \deprecated (DSU_PID0) Register MASK (Use DSU_PID0_Msk instead) */
#define DSU_PID0_Msk _U_(0xFF) /**< (DSU_PID0) Register Mask */
/* -------- DSU_PID1 : (DSU Offset: 0x1fe4) (R/ 32) Peripheral Identification 1 -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t PARTNBH:4; /**< bit: 0..3 Part Number High */
uint32_t JEPIDCL:4; /**< bit: 4..7 Low part of the JEP-106 Identity Code */
uint32_t :24; /**< bit: 8..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} DSU_PID1_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define DSU_PID1_OFFSET (0x1FE4) /**< (DSU_PID1) Peripheral Identification 1 Offset */
#define DSU_PID1_RESETVALUE _U_(0xFC) /**< (DSU_PID1) Peripheral Identification 1 Reset Value */
#define DSU_PID1_PARTNBH_Pos 0 /**< (DSU_PID1) Part Number High Position */
#define DSU_PID1_PARTNBH_Msk (_U_(0xF) << DSU_PID1_PARTNBH_Pos) /**< (DSU_PID1) Part Number High Mask */
#define DSU_PID1_PARTNBH(value) (DSU_PID1_PARTNBH_Msk & ((value) << DSU_PID1_PARTNBH_Pos))
#define DSU_PID1_JEPIDCL_Pos 4 /**< (DSU_PID1) Low part of the JEP-106 Identity Code Position */
#define DSU_PID1_JEPIDCL_Msk (_U_(0xF) << DSU_PID1_JEPIDCL_Pos) /**< (DSU_PID1) Low part of the JEP-106 Identity Code Mask */
#define DSU_PID1_JEPIDCL(value) (DSU_PID1_JEPIDCL_Msk & ((value) << DSU_PID1_JEPIDCL_Pos))
#define DSU_PID1_MASK _U_(0xFF) /**< \deprecated (DSU_PID1) Register MASK (Use DSU_PID1_Msk instead) */
#define DSU_PID1_Msk _U_(0xFF) /**< (DSU_PID1) Register Mask */
/* -------- DSU_PID2 : (DSU Offset: 0x1fe8) (R/ 32) Peripheral Identification 2 -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t JEPIDCH:3; /**< bit: 0..2 JEP-106 Identity Code High */
uint32_t JEPU:1; /**< bit: 3 JEP-106 Identity Code is used */
uint32_t REVISION:4; /**< bit: 4..7 Revision Number */
uint32_t :24; /**< bit: 8..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} DSU_PID2_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define DSU_PID2_OFFSET (0x1FE8) /**< (DSU_PID2) Peripheral Identification 2 Offset */
#define DSU_PID2_RESETVALUE _U_(0x09) /**< (DSU_PID2) Peripheral Identification 2 Reset Value */
#define DSU_PID2_JEPIDCH_Pos 0 /**< (DSU_PID2) JEP-106 Identity Code High Position */
#define DSU_PID2_JEPIDCH_Msk (_U_(0x7) << DSU_PID2_JEPIDCH_Pos) /**< (DSU_PID2) JEP-106 Identity Code High Mask */
#define DSU_PID2_JEPIDCH(value) (DSU_PID2_JEPIDCH_Msk & ((value) << DSU_PID2_JEPIDCH_Pos))
#define DSU_PID2_JEPU_Pos 3 /**< (DSU_PID2) JEP-106 Identity Code is used Position */
#define DSU_PID2_JEPU_Msk (_U_(0x1) << DSU_PID2_JEPU_Pos) /**< (DSU_PID2) JEP-106 Identity Code is used Mask */
#define DSU_PID2_JEPU DSU_PID2_JEPU_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use DSU_PID2_JEPU_Msk instead */
#define DSU_PID2_REVISION_Pos 4 /**< (DSU_PID2) Revision Number Position */
#define DSU_PID2_REVISION_Msk (_U_(0xF) << DSU_PID2_REVISION_Pos) /**< (DSU_PID2) Revision Number Mask */
#define DSU_PID2_REVISION(value) (DSU_PID2_REVISION_Msk & ((value) << DSU_PID2_REVISION_Pos))
#define DSU_PID2_MASK _U_(0xFF) /**< \deprecated (DSU_PID2) Register MASK (Use DSU_PID2_Msk instead) */
#define DSU_PID2_Msk _U_(0xFF) /**< (DSU_PID2) Register Mask */
/* -------- DSU_PID3 : (DSU Offset: 0x1fec) (R/ 32) Peripheral Identification 3 -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t CUSMOD:4; /**< bit: 0..3 ARM CUSMOD */
uint32_t REVAND:4; /**< bit: 4..7 Revision Number */
uint32_t :24; /**< bit: 8..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} DSU_PID3_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define DSU_PID3_OFFSET (0x1FEC) /**< (DSU_PID3) Peripheral Identification 3 Offset */
#define DSU_PID3_RESETVALUE _U_(0x00) /**< (DSU_PID3) Peripheral Identification 3 Reset Value */
#define DSU_PID3_CUSMOD_Pos 0 /**< (DSU_PID3) ARM CUSMOD Position */
#define DSU_PID3_CUSMOD_Msk (_U_(0xF) << DSU_PID3_CUSMOD_Pos) /**< (DSU_PID3) ARM CUSMOD Mask */
#define DSU_PID3_CUSMOD(value) (DSU_PID3_CUSMOD_Msk & ((value) << DSU_PID3_CUSMOD_Pos))
#define DSU_PID3_REVAND_Pos 4 /**< (DSU_PID3) Revision Number Position */
#define DSU_PID3_REVAND_Msk (_U_(0xF) << DSU_PID3_REVAND_Pos) /**< (DSU_PID3) Revision Number Mask */
#define DSU_PID3_REVAND(value) (DSU_PID3_REVAND_Msk & ((value) << DSU_PID3_REVAND_Pos))
#define DSU_PID3_MASK _U_(0xFF) /**< \deprecated (DSU_PID3) Register MASK (Use DSU_PID3_Msk instead) */
#define DSU_PID3_Msk _U_(0xFF) /**< (DSU_PID3) Register Mask */
/* -------- DSU_CID0 : (DSU Offset: 0x1ff0) (R/ 32) Component Identification 0 -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t PREAMBLEB0:8; /**< bit: 0..7 Preamble Byte 0 */
uint32_t :24; /**< bit: 8..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} DSU_CID0_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define DSU_CID0_OFFSET (0x1FF0) /**< (DSU_CID0) Component Identification 0 Offset */
#define DSU_CID0_RESETVALUE _U_(0x0D) /**< (DSU_CID0) Component Identification 0 Reset Value */
#define DSU_CID0_PREAMBLEB0_Pos 0 /**< (DSU_CID0) Preamble Byte 0 Position */
#define DSU_CID0_PREAMBLEB0_Msk (_U_(0xFF) << DSU_CID0_PREAMBLEB0_Pos) /**< (DSU_CID0) Preamble Byte 0 Mask */
#define DSU_CID0_PREAMBLEB0(value) (DSU_CID0_PREAMBLEB0_Msk & ((value) << DSU_CID0_PREAMBLEB0_Pos))
#define DSU_CID0_MASK _U_(0xFF) /**< \deprecated (DSU_CID0) Register MASK (Use DSU_CID0_Msk instead) */
#define DSU_CID0_Msk _U_(0xFF) /**< (DSU_CID0) Register Mask */
/* -------- DSU_CID1 : (DSU Offset: 0x1ff4) (R/ 32) Component Identification 1 -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t PREAMBLE:4; /**< bit: 0..3 Preamble */
uint32_t CCLASS:4; /**< bit: 4..7 Component Class */
uint32_t :24; /**< bit: 8..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} DSU_CID1_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define DSU_CID1_OFFSET (0x1FF4) /**< (DSU_CID1) Component Identification 1 Offset */
#define DSU_CID1_RESETVALUE _U_(0x10) /**< (DSU_CID1) Component Identification 1 Reset Value */
#define DSU_CID1_PREAMBLE_Pos 0 /**< (DSU_CID1) Preamble Position */
#define DSU_CID1_PREAMBLE_Msk (_U_(0xF) << DSU_CID1_PREAMBLE_Pos) /**< (DSU_CID1) Preamble Mask */
#define DSU_CID1_PREAMBLE(value) (DSU_CID1_PREAMBLE_Msk & ((value) << DSU_CID1_PREAMBLE_Pos))
#define DSU_CID1_CCLASS_Pos 4 /**< (DSU_CID1) Component Class Position */
#define DSU_CID1_CCLASS_Msk (_U_(0xF) << DSU_CID1_CCLASS_Pos) /**< (DSU_CID1) Component Class Mask */
#define DSU_CID1_CCLASS(value) (DSU_CID1_CCLASS_Msk & ((value) << DSU_CID1_CCLASS_Pos))
#define DSU_CID1_MASK _U_(0xFF) /**< \deprecated (DSU_CID1) Register MASK (Use DSU_CID1_Msk instead) */
#define DSU_CID1_Msk _U_(0xFF) /**< (DSU_CID1) Register Mask */
/* -------- DSU_CID2 : (DSU Offset: 0x1ff8) (R/ 32) Component Identification 2 -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t PREAMBLEB2:8; /**< bit: 0..7 Preamble Byte 2 */
uint32_t :24; /**< bit: 8..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} DSU_CID2_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define DSU_CID2_OFFSET (0x1FF8) /**< (DSU_CID2) Component Identification 2 Offset */
#define DSU_CID2_RESETVALUE _U_(0x05) /**< (DSU_CID2) Component Identification 2 Reset Value */
#define DSU_CID2_PREAMBLEB2_Pos 0 /**< (DSU_CID2) Preamble Byte 2 Position */
#define DSU_CID2_PREAMBLEB2_Msk (_U_(0xFF) << DSU_CID2_PREAMBLEB2_Pos) /**< (DSU_CID2) Preamble Byte 2 Mask */
#define DSU_CID2_PREAMBLEB2(value) (DSU_CID2_PREAMBLEB2_Msk & ((value) << DSU_CID2_PREAMBLEB2_Pos))
#define DSU_CID2_MASK _U_(0xFF) /**< \deprecated (DSU_CID2) Register MASK (Use DSU_CID2_Msk instead) */
#define DSU_CID2_Msk _U_(0xFF) /**< (DSU_CID2) Register Mask */
/* -------- DSU_CID3 : (DSU Offset: 0x1ffc) (R/ 32) Component Identification 3 -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t PREAMBLEB3:8; /**< bit: 0..7 Preamble Byte 3 */
uint32_t :24; /**< bit: 8..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} DSU_CID3_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define DSU_CID3_OFFSET (0x1FFC) /**< (DSU_CID3) Component Identification 3 Offset */
#define DSU_CID3_RESETVALUE _U_(0xB1) /**< (DSU_CID3) Component Identification 3 Reset Value */
#define DSU_CID3_PREAMBLEB3_Pos 0 /**< (DSU_CID3) Preamble Byte 3 Position */
#define DSU_CID3_PREAMBLEB3_Msk (_U_(0xFF) << DSU_CID3_PREAMBLEB3_Pos) /**< (DSU_CID3) Preamble Byte 3 Mask */
#define DSU_CID3_PREAMBLEB3(value) (DSU_CID3_PREAMBLEB3_Msk & ((value) << DSU_CID3_PREAMBLEB3_Pos))
#define DSU_CID3_MASK _U_(0xFF) /**< \deprecated (DSU_CID3) Register MASK (Use DSU_CID3_Msk instead) */
#define DSU_CID3_Msk _U_(0xFF) /**< (DSU_CID3) Register Mask */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
/** \brief DSU hardware registers */
typedef struct { /* Device Service Unit */
__O DSU_CTRL_Type CTRL; /**< Offset: 0x00 ( /W 8) Control */
__IO DSU_STATUSA_Type STATUSA; /**< Offset: 0x01 (R/W 8) Status A */
__I DSU_STATUSB_Type STATUSB; /**< Offset: 0x02 (R/ 8) Status B */
__I DSU_STATUSC_Type STATUSC; /**< Offset: 0x03 (R/ 8) Status C */
__IO DSU_ADDR_Type ADDR; /**< Offset: 0x04 (R/W 32) Address */
__IO DSU_LENGTH_Type LENGTH; /**< Offset: 0x08 (R/W 32) Length */
__IO DSU_DATA_Type DATA; /**< Offset: 0x0C (R/W 32) Data */
__IO DSU_DCC_Type DCC[2]; /**< Offset: 0x10 (R/W 32) Debug Communication Channel n */
__I DSU_DID_Type DID; /**< Offset: 0x18 (R/ 32) Device Identification */
__IO DSU_CFG_Type CFG; /**< Offset: 0x1C (R/W 32) Configuration */
__IO DSU_BCC_Type BCC[2]; /**< Offset: 0x20 (R/W 32) Boot ROM Communication Channel n */
__I uint8_t Reserved1[200];
__IO DSU_DCFG_Type DCFG[2]; /**< Offset: 0xF0 (R/W 32) Device Configuration */
__I uint8_t Reserved2[3848];
__I DSU_ENTRY0_Type ENTRY0; /**< Offset: 0x1000 (R/ 32) CoreSight ROM Table Entry 0 */
__I DSU_ENTRY1_Type ENTRY1; /**< Offset: 0x1004 (R/ 32) CoreSight ROM Table Entry 1 */
__I DSU_END_Type END; /**< Offset: 0x1008 (R/ 32) CoreSight ROM Table End */
__I uint8_t Reserved3[4032];
__I DSU_MEMTYPE_Type MEMTYPE; /**< Offset: 0x1FCC (R/ 32) CoreSight ROM Table Memory Type */
__I DSU_PID4_Type PID4; /**< Offset: 0x1FD0 (R/ 32) Peripheral Identification 4 */
__I DSU_PID5_Type PID5; /**< Offset: 0x1FD4 (R/ 32) Peripheral Identification 5 */
__I DSU_PID6_Type PID6; /**< Offset: 0x1FD8 (R/ 32) Peripheral Identification 6 */
__I DSU_PID7_Type PID7; /**< Offset: 0x1FDC (R/ 32) Peripheral Identification 7 */
__I DSU_PID0_Type PID0; /**< Offset: 0x1FE0 (R/ 32) Peripheral Identification 0 */
__I DSU_PID1_Type PID1; /**< Offset: 0x1FE4 (R/ 32) Peripheral Identification 1 */
__I DSU_PID2_Type PID2; /**< Offset: 0x1FE8 (R/ 32) Peripheral Identification 2 */
__I DSU_PID3_Type PID3; /**< Offset: 0x1FEC (R/ 32) Peripheral Identification 3 */
__I DSU_CID0_Type CID0; /**< Offset: 0x1FF0 (R/ 32) Component Identification 0 */
__I DSU_CID1_Type CID1; /**< Offset: 0x1FF4 (R/ 32) Component Identification 1 */
__I DSU_CID2_Type CID2; /**< Offset: 0x1FF8 (R/ 32) Component Identification 2 */
__I DSU_CID3_Type CID3; /**< Offset: 0x1FFC (R/ 32) Component Identification 3 */
} Dsu;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/** @} end of Device Service Unit */
#endif /* _SAML10_DSU_COMPONENT_H_ */

View File

@ -0,0 +1,610 @@
/**
* \file
*
* \brief Component description for EIC
*
* Copyright (c) 2018 Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* 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
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
/* file generated from device description version 2018-08-31T13:51:50Z */
#ifndef _SAML10_EIC_COMPONENT_H_
#define _SAML10_EIC_COMPONENT_H_
#define _SAML10_EIC_COMPONENT_ /**< \deprecated Backward compatibility for ASF */
/** \addtogroup SAML_SAML10 External Interrupt Controller
* @{
*/
/* ========================================================================== */
/** SOFTWARE API DEFINITION FOR EIC */
/* ========================================================================== */
#define EIC_U2804 /**< (EIC) Module ID */
#define REV_EIC 0x100 /**< (EIC) Module revision */
/* -------- EIC_CTRLA : (EIC Offset: 0x00) (R/W 8) Control A -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t SWRST:1; /**< bit: 0 Software Reset */
uint8_t ENABLE:1; /**< bit: 1 Enable */
uint8_t :2; /**< bit: 2..3 Reserved */
uint8_t CKSEL:1; /**< bit: 4 Clock Selection */
uint8_t :3; /**< bit: 5..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} EIC_CTRLA_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define EIC_CTRLA_OFFSET (0x00) /**< (EIC_CTRLA) Control A Offset */
#define EIC_CTRLA_RESETVALUE _U_(0x00) /**< (EIC_CTRLA) Control A Reset Value */
#define EIC_CTRLA_SWRST_Pos 0 /**< (EIC_CTRLA) Software Reset Position */
#define EIC_CTRLA_SWRST_Msk (_U_(0x1) << EIC_CTRLA_SWRST_Pos) /**< (EIC_CTRLA) Software Reset Mask */
#define EIC_CTRLA_SWRST EIC_CTRLA_SWRST_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EIC_CTRLA_SWRST_Msk instead */
#define EIC_CTRLA_ENABLE_Pos 1 /**< (EIC_CTRLA) Enable Position */
#define EIC_CTRLA_ENABLE_Msk (_U_(0x1) << EIC_CTRLA_ENABLE_Pos) /**< (EIC_CTRLA) Enable Mask */
#define EIC_CTRLA_ENABLE EIC_CTRLA_ENABLE_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EIC_CTRLA_ENABLE_Msk instead */
#define EIC_CTRLA_CKSEL_Pos 4 /**< (EIC_CTRLA) Clock Selection Position */
#define EIC_CTRLA_CKSEL_Msk (_U_(0x1) << EIC_CTRLA_CKSEL_Pos) /**< (EIC_CTRLA) Clock Selection Mask */
#define EIC_CTRLA_CKSEL EIC_CTRLA_CKSEL_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EIC_CTRLA_CKSEL_Msk instead */
#define EIC_CTRLA_MASK _U_(0x13) /**< \deprecated (EIC_CTRLA) Register MASK (Use EIC_CTRLA_Msk instead) */
#define EIC_CTRLA_Msk _U_(0x13) /**< (EIC_CTRLA) Register Mask */
/* -------- EIC_NMICTRL : (EIC Offset: 0x01) (R/W 8) Non-Maskable Interrupt Control -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t NMISENSE:3; /**< bit: 0..2 Non-Maskable Interrupt Sense Configuration */
uint8_t NMIFILTEN:1; /**< bit: 3 Non-Maskable Interrupt Filter Enable */
uint8_t NMIASYNCH:1; /**< bit: 4 Asynchronous Edge Detection Mode */
uint8_t :3; /**< bit: 5..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} EIC_NMICTRL_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define EIC_NMICTRL_OFFSET (0x01) /**< (EIC_NMICTRL) Non-Maskable Interrupt Control Offset */
#define EIC_NMICTRL_RESETVALUE _U_(0x00) /**< (EIC_NMICTRL) Non-Maskable Interrupt Control Reset Value */
#define EIC_NMICTRL_NMISENSE_Pos 0 /**< (EIC_NMICTRL) Non-Maskable Interrupt Sense Configuration Position */
#define EIC_NMICTRL_NMISENSE_Msk (_U_(0x7) << EIC_NMICTRL_NMISENSE_Pos) /**< (EIC_NMICTRL) Non-Maskable Interrupt Sense Configuration Mask */
#define EIC_NMICTRL_NMISENSE(value) (EIC_NMICTRL_NMISENSE_Msk & ((value) << EIC_NMICTRL_NMISENSE_Pos))
#define EIC_NMICTRL_NMISENSE_NONE_Val _U_(0x0) /**< (EIC_NMICTRL) No detection */
#define EIC_NMICTRL_NMISENSE_RISE_Val _U_(0x1) /**< (EIC_NMICTRL) Rising-edge detection */
#define EIC_NMICTRL_NMISENSE_FALL_Val _U_(0x2) /**< (EIC_NMICTRL) Falling-edge detection */
#define EIC_NMICTRL_NMISENSE_BOTH_Val _U_(0x3) /**< (EIC_NMICTRL) Both-edges detection */
#define EIC_NMICTRL_NMISENSE_HIGH_Val _U_(0x4) /**< (EIC_NMICTRL) High-level detection */
#define EIC_NMICTRL_NMISENSE_LOW_Val _U_(0x5) /**< (EIC_NMICTRL) Low-level detection */
#define EIC_NMICTRL_NMISENSE_NONE (EIC_NMICTRL_NMISENSE_NONE_Val << EIC_NMICTRL_NMISENSE_Pos) /**< (EIC_NMICTRL) No detection Position */
#define EIC_NMICTRL_NMISENSE_RISE (EIC_NMICTRL_NMISENSE_RISE_Val << EIC_NMICTRL_NMISENSE_Pos) /**< (EIC_NMICTRL) Rising-edge detection Position */
#define EIC_NMICTRL_NMISENSE_FALL (EIC_NMICTRL_NMISENSE_FALL_Val << EIC_NMICTRL_NMISENSE_Pos) /**< (EIC_NMICTRL) Falling-edge detection Position */
#define EIC_NMICTRL_NMISENSE_BOTH (EIC_NMICTRL_NMISENSE_BOTH_Val << EIC_NMICTRL_NMISENSE_Pos) /**< (EIC_NMICTRL) Both-edges detection Position */
#define EIC_NMICTRL_NMISENSE_HIGH (EIC_NMICTRL_NMISENSE_HIGH_Val << EIC_NMICTRL_NMISENSE_Pos) /**< (EIC_NMICTRL) High-level detection Position */
#define EIC_NMICTRL_NMISENSE_LOW (EIC_NMICTRL_NMISENSE_LOW_Val << EIC_NMICTRL_NMISENSE_Pos) /**< (EIC_NMICTRL) Low-level detection Position */
#define EIC_NMICTRL_NMIFILTEN_Pos 3 /**< (EIC_NMICTRL) Non-Maskable Interrupt Filter Enable Position */
#define EIC_NMICTRL_NMIFILTEN_Msk (_U_(0x1) << EIC_NMICTRL_NMIFILTEN_Pos) /**< (EIC_NMICTRL) Non-Maskable Interrupt Filter Enable Mask */
#define EIC_NMICTRL_NMIFILTEN EIC_NMICTRL_NMIFILTEN_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EIC_NMICTRL_NMIFILTEN_Msk instead */
#define EIC_NMICTRL_NMIASYNCH_Pos 4 /**< (EIC_NMICTRL) Asynchronous Edge Detection Mode Position */
#define EIC_NMICTRL_NMIASYNCH_Msk (_U_(0x1) << EIC_NMICTRL_NMIASYNCH_Pos) /**< (EIC_NMICTRL) Asynchronous Edge Detection Mode Mask */
#define EIC_NMICTRL_NMIASYNCH EIC_NMICTRL_NMIASYNCH_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EIC_NMICTRL_NMIASYNCH_Msk instead */
#define EIC_NMICTRL_MASK _U_(0x1F) /**< \deprecated (EIC_NMICTRL) Register MASK (Use EIC_NMICTRL_Msk instead) */
#define EIC_NMICTRL_Msk _U_(0x1F) /**< (EIC_NMICTRL) Register Mask */
/* -------- EIC_NMIFLAG : (EIC Offset: 0x02) (R/W 16) Non-Maskable Interrupt Flag Status and Clear -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint16_t NMI:1; /**< bit: 0 Non-Maskable Interrupt */
uint16_t :15; /**< bit: 1..15 Reserved */
} bit; /**< Structure used for bit access */
uint16_t reg; /**< Type used for register access */
} EIC_NMIFLAG_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define EIC_NMIFLAG_OFFSET (0x02) /**< (EIC_NMIFLAG) Non-Maskable Interrupt Flag Status and Clear Offset */
#define EIC_NMIFLAG_RESETVALUE _U_(0x00) /**< (EIC_NMIFLAG) Non-Maskable Interrupt Flag Status and Clear Reset Value */
#define EIC_NMIFLAG_NMI_Pos 0 /**< (EIC_NMIFLAG) Non-Maskable Interrupt Position */
#define EIC_NMIFLAG_NMI_Msk (_U_(0x1) << EIC_NMIFLAG_NMI_Pos) /**< (EIC_NMIFLAG) Non-Maskable Interrupt Mask */
#define EIC_NMIFLAG_NMI EIC_NMIFLAG_NMI_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EIC_NMIFLAG_NMI_Msk instead */
#define EIC_NMIFLAG_MASK _U_(0x01) /**< \deprecated (EIC_NMIFLAG) Register MASK (Use EIC_NMIFLAG_Msk instead) */
#define EIC_NMIFLAG_Msk _U_(0x01) /**< (EIC_NMIFLAG) Register Mask */
/* -------- EIC_SYNCBUSY : (EIC Offset: 0x04) (R/ 32) Synchronization Busy -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t SWRST:1; /**< bit: 0 Software Reset Synchronization Busy Status */
uint32_t ENABLE:1; /**< bit: 1 Enable Synchronization Busy Status */
uint32_t :30; /**< bit: 2..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} EIC_SYNCBUSY_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define EIC_SYNCBUSY_OFFSET (0x04) /**< (EIC_SYNCBUSY) Synchronization Busy Offset */
#define EIC_SYNCBUSY_RESETVALUE _U_(0x00) /**< (EIC_SYNCBUSY) Synchronization Busy Reset Value */
#define EIC_SYNCBUSY_SWRST_Pos 0 /**< (EIC_SYNCBUSY) Software Reset Synchronization Busy Status Position */
#define EIC_SYNCBUSY_SWRST_Msk (_U_(0x1) << EIC_SYNCBUSY_SWRST_Pos) /**< (EIC_SYNCBUSY) Software Reset Synchronization Busy Status Mask */
#define EIC_SYNCBUSY_SWRST EIC_SYNCBUSY_SWRST_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EIC_SYNCBUSY_SWRST_Msk instead */
#define EIC_SYNCBUSY_ENABLE_Pos 1 /**< (EIC_SYNCBUSY) Enable Synchronization Busy Status Position */
#define EIC_SYNCBUSY_ENABLE_Msk (_U_(0x1) << EIC_SYNCBUSY_ENABLE_Pos) /**< (EIC_SYNCBUSY) Enable Synchronization Busy Status Mask */
#define EIC_SYNCBUSY_ENABLE EIC_SYNCBUSY_ENABLE_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EIC_SYNCBUSY_ENABLE_Msk instead */
#define EIC_SYNCBUSY_MASK _U_(0x03) /**< \deprecated (EIC_SYNCBUSY) Register MASK (Use EIC_SYNCBUSY_Msk instead) */
#define EIC_SYNCBUSY_Msk _U_(0x03) /**< (EIC_SYNCBUSY) Register Mask */
/* -------- EIC_EVCTRL : (EIC Offset: 0x08) (R/W 32) Event Control -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t EXTINTEO:8; /**< bit: 0..7 External Interrupt Event Output Enable */
uint32_t :24; /**< bit: 8..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} EIC_EVCTRL_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define EIC_EVCTRL_OFFSET (0x08) /**< (EIC_EVCTRL) Event Control Offset */
#define EIC_EVCTRL_RESETVALUE _U_(0x00) /**< (EIC_EVCTRL) Event Control Reset Value */
#define EIC_EVCTRL_EXTINTEO_Pos 0 /**< (EIC_EVCTRL) External Interrupt Event Output Enable Position */
#define EIC_EVCTRL_EXTINTEO_Msk (_U_(0xFF) << EIC_EVCTRL_EXTINTEO_Pos) /**< (EIC_EVCTRL) External Interrupt Event Output Enable Mask */
#define EIC_EVCTRL_EXTINTEO(value) (EIC_EVCTRL_EXTINTEO_Msk & ((value) << EIC_EVCTRL_EXTINTEO_Pos))
#define EIC_EVCTRL_MASK _U_(0xFF) /**< \deprecated (EIC_EVCTRL) Register MASK (Use EIC_EVCTRL_Msk instead) */
#define EIC_EVCTRL_Msk _U_(0xFF) /**< (EIC_EVCTRL) Register Mask */
/* -------- EIC_INTENCLR : (EIC Offset: 0x0c) (R/W 32) Interrupt Enable Clear -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t EXTINT:8; /**< bit: 0..7 External Interrupt Enable */
uint32_t :23; /**< bit: 8..30 Reserved */
uint32_t NSCHK:1; /**< bit: 31 Non-secure Check Interrupt Enable */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} EIC_INTENCLR_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define EIC_INTENCLR_OFFSET (0x0C) /**< (EIC_INTENCLR) Interrupt Enable Clear Offset */
#define EIC_INTENCLR_RESETVALUE _U_(0x00) /**< (EIC_INTENCLR) Interrupt Enable Clear Reset Value */
#define EIC_INTENCLR_EXTINT_Pos 0 /**< (EIC_INTENCLR) External Interrupt Enable Position */
#define EIC_INTENCLR_EXTINT_Msk (_U_(0xFF) << EIC_INTENCLR_EXTINT_Pos) /**< (EIC_INTENCLR) External Interrupt Enable Mask */
#define EIC_INTENCLR_EXTINT(value) (EIC_INTENCLR_EXTINT_Msk & ((value) << EIC_INTENCLR_EXTINT_Pos))
#define EIC_INTENCLR_NSCHK_Pos 31 /**< (EIC_INTENCLR) Non-secure Check Interrupt Enable Position */
#define EIC_INTENCLR_NSCHK_Msk (_U_(0x1) << EIC_INTENCLR_NSCHK_Pos) /**< (EIC_INTENCLR) Non-secure Check Interrupt Enable Mask */
#define EIC_INTENCLR_NSCHK EIC_INTENCLR_NSCHK_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EIC_INTENCLR_NSCHK_Msk instead */
#define EIC_INTENCLR_MASK _U_(0x800000FF) /**< \deprecated (EIC_INTENCLR) Register MASK (Use EIC_INTENCLR_Msk instead) */
#define EIC_INTENCLR_Msk _U_(0x800000FF) /**< (EIC_INTENCLR) Register Mask */
/* -------- EIC_INTENSET : (EIC Offset: 0x10) (R/W 32) Interrupt Enable Set -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t EXTINT:8; /**< bit: 0..7 External Interrupt Enable */
uint32_t :23; /**< bit: 8..30 Reserved */
uint32_t NSCHK:1; /**< bit: 31 Non-secure Check Interrupt Enable */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} EIC_INTENSET_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define EIC_INTENSET_OFFSET (0x10) /**< (EIC_INTENSET) Interrupt Enable Set Offset */
#define EIC_INTENSET_RESETVALUE _U_(0x00) /**< (EIC_INTENSET) Interrupt Enable Set Reset Value */
#define EIC_INTENSET_EXTINT_Pos 0 /**< (EIC_INTENSET) External Interrupt Enable Position */
#define EIC_INTENSET_EXTINT_Msk (_U_(0xFF) << EIC_INTENSET_EXTINT_Pos) /**< (EIC_INTENSET) External Interrupt Enable Mask */
#define EIC_INTENSET_EXTINT(value) (EIC_INTENSET_EXTINT_Msk & ((value) << EIC_INTENSET_EXTINT_Pos))
#define EIC_INTENSET_NSCHK_Pos 31 /**< (EIC_INTENSET) Non-secure Check Interrupt Enable Position */
#define EIC_INTENSET_NSCHK_Msk (_U_(0x1) << EIC_INTENSET_NSCHK_Pos) /**< (EIC_INTENSET) Non-secure Check Interrupt Enable Mask */
#define EIC_INTENSET_NSCHK EIC_INTENSET_NSCHK_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EIC_INTENSET_NSCHK_Msk instead */
#define EIC_INTENSET_MASK _U_(0x800000FF) /**< \deprecated (EIC_INTENSET) Register MASK (Use EIC_INTENSET_Msk instead) */
#define EIC_INTENSET_Msk _U_(0x800000FF) /**< (EIC_INTENSET) Register Mask */
/* -------- EIC_INTFLAG : (EIC Offset: 0x14) (R/W 32) Interrupt Flag Status and Clear -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union { // __I to avoid read-modify-write on write-to-clear register
struct {
__I uint32_t EXTINT:8; /**< bit: 0..7 External Interrupt */
__I uint32_t :23; /**< bit: 8..30 Reserved */
__I uint32_t NSCHK:1; /**< bit: 31 Non-secure Check Interrupt */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} EIC_INTFLAG_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define EIC_INTFLAG_OFFSET (0x14) /**< (EIC_INTFLAG) Interrupt Flag Status and Clear Offset */
#define EIC_INTFLAG_RESETVALUE _U_(0x00) /**< (EIC_INTFLAG) Interrupt Flag Status and Clear Reset Value */
#define EIC_INTFLAG_EXTINT_Pos 0 /**< (EIC_INTFLAG) External Interrupt Position */
#define EIC_INTFLAG_EXTINT_Msk (_U_(0xFF) << EIC_INTFLAG_EXTINT_Pos) /**< (EIC_INTFLAG) External Interrupt Mask */
#define EIC_INTFLAG_EXTINT(value) (EIC_INTFLAG_EXTINT_Msk & ((value) << EIC_INTFLAG_EXTINT_Pos))
#define EIC_INTFLAG_NSCHK_Pos 31 /**< (EIC_INTFLAG) Non-secure Check Interrupt Position */
#define EIC_INTFLAG_NSCHK_Msk (_U_(0x1) << EIC_INTFLAG_NSCHK_Pos) /**< (EIC_INTFLAG) Non-secure Check Interrupt Mask */
#define EIC_INTFLAG_NSCHK EIC_INTFLAG_NSCHK_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EIC_INTFLAG_NSCHK_Msk instead */
#define EIC_INTFLAG_MASK _U_(0x800000FF) /**< \deprecated (EIC_INTFLAG) Register MASK (Use EIC_INTFLAG_Msk instead) */
#define EIC_INTFLAG_Msk _U_(0x800000FF) /**< (EIC_INTFLAG) Register Mask */
/* -------- EIC_ASYNCH : (EIC Offset: 0x18) (R/W 32) External Interrupt Asynchronous Mode -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t ASYNCH:8; /**< bit: 0..7 Asynchronous Edge Detection Mode */
uint32_t :24; /**< bit: 8..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} EIC_ASYNCH_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define EIC_ASYNCH_OFFSET (0x18) /**< (EIC_ASYNCH) External Interrupt Asynchronous Mode Offset */
#define EIC_ASYNCH_RESETVALUE _U_(0x00) /**< (EIC_ASYNCH) External Interrupt Asynchronous Mode Reset Value */
#define EIC_ASYNCH_ASYNCH_Pos 0 /**< (EIC_ASYNCH) Asynchronous Edge Detection Mode Position */
#define EIC_ASYNCH_ASYNCH_Msk (_U_(0xFF) << EIC_ASYNCH_ASYNCH_Pos) /**< (EIC_ASYNCH) Asynchronous Edge Detection Mode Mask */
#define EIC_ASYNCH_ASYNCH(value) (EIC_ASYNCH_ASYNCH_Msk & ((value) << EIC_ASYNCH_ASYNCH_Pos))
#define EIC_ASYNCH_MASK _U_(0xFF) /**< \deprecated (EIC_ASYNCH) Register MASK (Use EIC_ASYNCH_Msk instead) */
#define EIC_ASYNCH_Msk _U_(0xFF) /**< (EIC_ASYNCH) Register Mask */
/* -------- EIC_CONFIG : (EIC Offset: 0x1c) (R/W 32) External Interrupt Sense Configuration -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t SENSE0:3; /**< bit: 0..2 Input Sense Configuration 0 */
uint32_t FILTEN0:1; /**< bit: 3 Filter Enable 0 */
uint32_t SENSE1:3; /**< bit: 4..6 Input Sense Configuration 1 */
uint32_t FILTEN1:1; /**< bit: 7 Filter Enable 1 */
uint32_t SENSE2:3; /**< bit: 8..10 Input Sense Configuration 2 */
uint32_t FILTEN2:1; /**< bit: 11 Filter Enable 2 */
uint32_t SENSE3:3; /**< bit: 12..14 Input Sense Configuration 3 */
uint32_t FILTEN3:1; /**< bit: 15 Filter Enable 3 */
uint32_t SENSE4:3; /**< bit: 16..18 Input Sense Configuration 4 */
uint32_t FILTEN4:1; /**< bit: 19 Filter Enable 4 */
uint32_t SENSE5:3; /**< bit: 20..22 Input Sense Configuration 5 */
uint32_t FILTEN5:1; /**< bit: 23 Filter Enable 5 */
uint32_t SENSE6:3; /**< bit: 24..26 Input Sense Configuration 6 */
uint32_t FILTEN6:1; /**< bit: 27 Filter Enable 6 */
uint32_t SENSE7:3; /**< bit: 28..30 Input Sense Configuration 7 */
uint32_t FILTEN7:1; /**< bit: 31 Filter Enable 7 */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} EIC_CONFIG_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define EIC_CONFIG_OFFSET (0x1C) /**< (EIC_CONFIG) External Interrupt Sense Configuration Offset */
#define EIC_CONFIG_RESETVALUE _U_(0x00) /**< (EIC_CONFIG) External Interrupt Sense Configuration Reset Value */
#define EIC_CONFIG_SENSE0_Pos 0 /**< (EIC_CONFIG) Input Sense Configuration 0 Position */
#define EIC_CONFIG_SENSE0_Msk (_U_(0x7) << EIC_CONFIG_SENSE0_Pos) /**< (EIC_CONFIG) Input Sense Configuration 0 Mask */
#define EIC_CONFIG_SENSE0(value) (EIC_CONFIG_SENSE0_Msk & ((value) << EIC_CONFIG_SENSE0_Pos))
#define EIC_CONFIG_SENSE0_NONE_Val _U_(0x0) /**< (EIC_CONFIG) No detection */
#define EIC_CONFIG_SENSE0_RISE_Val _U_(0x1) /**< (EIC_CONFIG) Rising edge detection */
#define EIC_CONFIG_SENSE0_FALL_Val _U_(0x2) /**< (EIC_CONFIG) Falling edge detection */
#define EIC_CONFIG_SENSE0_BOTH_Val _U_(0x3) /**< (EIC_CONFIG) Both edges detection */
#define EIC_CONFIG_SENSE0_HIGH_Val _U_(0x4) /**< (EIC_CONFIG) High level detection */
#define EIC_CONFIG_SENSE0_LOW_Val _U_(0x5) /**< (EIC_CONFIG) Low level detection */
#define EIC_CONFIG_SENSE0_NONE (EIC_CONFIG_SENSE0_NONE_Val << EIC_CONFIG_SENSE0_Pos) /**< (EIC_CONFIG) No detection Position */
#define EIC_CONFIG_SENSE0_RISE (EIC_CONFIG_SENSE0_RISE_Val << EIC_CONFIG_SENSE0_Pos) /**< (EIC_CONFIG) Rising edge detection Position */
#define EIC_CONFIG_SENSE0_FALL (EIC_CONFIG_SENSE0_FALL_Val << EIC_CONFIG_SENSE0_Pos) /**< (EIC_CONFIG) Falling edge detection Position */
#define EIC_CONFIG_SENSE0_BOTH (EIC_CONFIG_SENSE0_BOTH_Val << EIC_CONFIG_SENSE0_Pos) /**< (EIC_CONFIG) Both edges detection Position */
#define EIC_CONFIG_SENSE0_HIGH (EIC_CONFIG_SENSE0_HIGH_Val << EIC_CONFIG_SENSE0_Pos) /**< (EIC_CONFIG) High level detection Position */
#define EIC_CONFIG_SENSE0_LOW (EIC_CONFIG_SENSE0_LOW_Val << EIC_CONFIG_SENSE0_Pos) /**< (EIC_CONFIG) Low level detection Position */
#define EIC_CONFIG_FILTEN0_Pos 3 /**< (EIC_CONFIG) Filter Enable 0 Position */
#define EIC_CONFIG_FILTEN0_Msk (_U_(0x1) << EIC_CONFIG_FILTEN0_Pos) /**< (EIC_CONFIG) Filter Enable 0 Mask */
#define EIC_CONFIG_FILTEN0 EIC_CONFIG_FILTEN0_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EIC_CONFIG_FILTEN0_Msk instead */
#define EIC_CONFIG_SENSE1_Pos 4 /**< (EIC_CONFIG) Input Sense Configuration 1 Position */
#define EIC_CONFIG_SENSE1_Msk (_U_(0x7) << EIC_CONFIG_SENSE1_Pos) /**< (EIC_CONFIG) Input Sense Configuration 1 Mask */
#define EIC_CONFIG_SENSE1(value) (EIC_CONFIG_SENSE1_Msk & ((value) << EIC_CONFIG_SENSE1_Pos))
#define EIC_CONFIG_SENSE1_NONE_Val _U_(0x0) /**< (EIC_CONFIG) No detection */
#define EIC_CONFIG_SENSE1_RISE_Val _U_(0x1) /**< (EIC_CONFIG) Rising edge detection */
#define EIC_CONFIG_SENSE1_FALL_Val _U_(0x2) /**< (EIC_CONFIG) Falling edge detection */
#define EIC_CONFIG_SENSE1_BOTH_Val _U_(0x3) /**< (EIC_CONFIG) Both edges detection */
#define EIC_CONFIG_SENSE1_HIGH_Val _U_(0x4) /**< (EIC_CONFIG) High level detection */
#define EIC_CONFIG_SENSE1_LOW_Val _U_(0x5) /**< (EIC_CONFIG) Low level detection */
#define EIC_CONFIG_SENSE1_NONE (EIC_CONFIG_SENSE1_NONE_Val << EIC_CONFIG_SENSE1_Pos) /**< (EIC_CONFIG) No detection Position */
#define EIC_CONFIG_SENSE1_RISE (EIC_CONFIG_SENSE1_RISE_Val << EIC_CONFIG_SENSE1_Pos) /**< (EIC_CONFIG) Rising edge detection Position */
#define EIC_CONFIG_SENSE1_FALL (EIC_CONFIG_SENSE1_FALL_Val << EIC_CONFIG_SENSE1_Pos) /**< (EIC_CONFIG) Falling edge detection Position */
#define EIC_CONFIG_SENSE1_BOTH (EIC_CONFIG_SENSE1_BOTH_Val << EIC_CONFIG_SENSE1_Pos) /**< (EIC_CONFIG) Both edges detection Position */
#define EIC_CONFIG_SENSE1_HIGH (EIC_CONFIG_SENSE1_HIGH_Val << EIC_CONFIG_SENSE1_Pos) /**< (EIC_CONFIG) High level detection Position */
#define EIC_CONFIG_SENSE1_LOW (EIC_CONFIG_SENSE1_LOW_Val << EIC_CONFIG_SENSE1_Pos) /**< (EIC_CONFIG) Low level detection Position */
#define EIC_CONFIG_FILTEN1_Pos 7 /**< (EIC_CONFIG) Filter Enable 1 Position */
#define EIC_CONFIG_FILTEN1_Msk (_U_(0x1) << EIC_CONFIG_FILTEN1_Pos) /**< (EIC_CONFIG) Filter Enable 1 Mask */
#define EIC_CONFIG_FILTEN1 EIC_CONFIG_FILTEN1_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EIC_CONFIG_FILTEN1_Msk instead */
#define EIC_CONFIG_SENSE2_Pos 8 /**< (EIC_CONFIG) Input Sense Configuration 2 Position */
#define EIC_CONFIG_SENSE2_Msk (_U_(0x7) << EIC_CONFIG_SENSE2_Pos) /**< (EIC_CONFIG) Input Sense Configuration 2 Mask */
#define EIC_CONFIG_SENSE2(value) (EIC_CONFIG_SENSE2_Msk & ((value) << EIC_CONFIG_SENSE2_Pos))
#define EIC_CONFIG_SENSE2_NONE_Val _U_(0x0) /**< (EIC_CONFIG) No detection */
#define EIC_CONFIG_SENSE2_RISE_Val _U_(0x1) /**< (EIC_CONFIG) Rising edge detection */
#define EIC_CONFIG_SENSE2_FALL_Val _U_(0x2) /**< (EIC_CONFIG) Falling edge detection */
#define EIC_CONFIG_SENSE2_BOTH_Val _U_(0x3) /**< (EIC_CONFIG) Both edges detection */
#define EIC_CONFIG_SENSE2_HIGH_Val _U_(0x4) /**< (EIC_CONFIG) High level detection */
#define EIC_CONFIG_SENSE2_LOW_Val _U_(0x5) /**< (EIC_CONFIG) Low level detection */
#define EIC_CONFIG_SENSE2_NONE (EIC_CONFIG_SENSE2_NONE_Val << EIC_CONFIG_SENSE2_Pos) /**< (EIC_CONFIG) No detection Position */
#define EIC_CONFIG_SENSE2_RISE (EIC_CONFIG_SENSE2_RISE_Val << EIC_CONFIG_SENSE2_Pos) /**< (EIC_CONFIG) Rising edge detection Position */
#define EIC_CONFIG_SENSE2_FALL (EIC_CONFIG_SENSE2_FALL_Val << EIC_CONFIG_SENSE2_Pos) /**< (EIC_CONFIG) Falling edge detection Position */
#define EIC_CONFIG_SENSE2_BOTH (EIC_CONFIG_SENSE2_BOTH_Val << EIC_CONFIG_SENSE2_Pos) /**< (EIC_CONFIG) Both edges detection Position */
#define EIC_CONFIG_SENSE2_HIGH (EIC_CONFIG_SENSE2_HIGH_Val << EIC_CONFIG_SENSE2_Pos) /**< (EIC_CONFIG) High level detection Position */
#define EIC_CONFIG_SENSE2_LOW (EIC_CONFIG_SENSE2_LOW_Val << EIC_CONFIG_SENSE2_Pos) /**< (EIC_CONFIG) Low level detection Position */
#define EIC_CONFIG_FILTEN2_Pos 11 /**< (EIC_CONFIG) Filter Enable 2 Position */
#define EIC_CONFIG_FILTEN2_Msk (_U_(0x1) << EIC_CONFIG_FILTEN2_Pos) /**< (EIC_CONFIG) Filter Enable 2 Mask */
#define EIC_CONFIG_FILTEN2 EIC_CONFIG_FILTEN2_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EIC_CONFIG_FILTEN2_Msk instead */
#define EIC_CONFIG_SENSE3_Pos 12 /**< (EIC_CONFIG) Input Sense Configuration 3 Position */
#define EIC_CONFIG_SENSE3_Msk (_U_(0x7) << EIC_CONFIG_SENSE3_Pos) /**< (EIC_CONFIG) Input Sense Configuration 3 Mask */
#define EIC_CONFIG_SENSE3(value) (EIC_CONFIG_SENSE3_Msk & ((value) << EIC_CONFIG_SENSE3_Pos))
#define EIC_CONFIG_SENSE3_NONE_Val _U_(0x0) /**< (EIC_CONFIG) No detection */
#define EIC_CONFIG_SENSE3_RISE_Val _U_(0x1) /**< (EIC_CONFIG) Rising edge detection */
#define EIC_CONFIG_SENSE3_FALL_Val _U_(0x2) /**< (EIC_CONFIG) Falling edge detection */
#define EIC_CONFIG_SENSE3_BOTH_Val _U_(0x3) /**< (EIC_CONFIG) Both edges detection */
#define EIC_CONFIG_SENSE3_HIGH_Val _U_(0x4) /**< (EIC_CONFIG) High level detection */
#define EIC_CONFIG_SENSE3_LOW_Val _U_(0x5) /**< (EIC_CONFIG) Low level detection */
#define EIC_CONFIG_SENSE3_NONE (EIC_CONFIG_SENSE3_NONE_Val << EIC_CONFIG_SENSE3_Pos) /**< (EIC_CONFIG) No detection Position */
#define EIC_CONFIG_SENSE3_RISE (EIC_CONFIG_SENSE3_RISE_Val << EIC_CONFIG_SENSE3_Pos) /**< (EIC_CONFIG) Rising edge detection Position */
#define EIC_CONFIG_SENSE3_FALL (EIC_CONFIG_SENSE3_FALL_Val << EIC_CONFIG_SENSE3_Pos) /**< (EIC_CONFIG) Falling edge detection Position */
#define EIC_CONFIG_SENSE3_BOTH (EIC_CONFIG_SENSE3_BOTH_Val << EIC_CONFIG_SENSE3_Pos) /**< (EIC_CONFIG) Both edges detection Position */
#define EIC_CONFIG_SENSE3_HIGH (EIC_CONFIG_SENSE3_HIGH_Val << EIC_CONFIG_SENSE3_Pos) /**< (EIC_CONFIG) High level detection Position */
#define EIC_CONFIG_SENSE3_LOW (EIC_CONFIG_SENSE3_LOW_Val << EIC_CONFIG_SENSE3_Pos) /**< (EIC_CONFIG) Low level detection Position */
#define EIC_CONFIG_FILTEN3_Pos 15 /**< (EIC_CONFIG) Filter Enable 3 Position */
#define EIC_CONFIG_FILTEN3_Msk (_U_(0x1) << EIC_CONFIG_FILTEN3_Pos) /**< (EIC_CONFIG) Filter Enable 3 Mask */
#define EIC_CONFIG_FILTEN3 EIC_CONFIG_FILTEN3_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EIC_CONFIG_FILTEN3_Msk instead */
#define EIC_CONFIG_SENSE4_Pos 16 /**< (EIC_CONFIG) Input Sense Configuration 4 Position */
#define EIC_CONFIG_SENSE4_Msk (_U_(0x7) << EIC_CONFIG_SENSE4_Pos) /**< (EIC_CONFIG) Input Sense Configuration 4 Mask */
#define EIC_CONFIG_SENSE4(value) (EIC_CONFIG_SENSE4_Msk & ((value) << EIC_CONFIG_SENSE4_Pos))
#define EIC_CONFIG_SENSE4_NONE_Val _U_(0x0) /**< (EIC_CONFIG) No detection */
#define EIC_CONFIG_SENSE4_RISE_Val _U_(0x1) /**< (EIC_CONFIG) Rising edge detection */
#define EIC_CONFIG_SENSE4_FALL_Val _U_(0x2) /**< (EIC_CONFIG) Falling edge detection */
#define EIC_CONFIG_SENSE4_BOTH_Val _U_(0x3) /**< (EIC_CONFIG) Both edges detection */
#define EIC_CONFIG_SENSE4_HIGH_Val _U_(0x4) /**< (EIC_CONFIG) High level detection */
#define EIC_CONFIG_SENSE4_LOW_Val _U_(0x5) /**< (EIC_CONFIG) Low level detection */
#define EIC_CONFIG_SENSE4_NONE (EIC_CONFIG_SENSE4_NONE_Val << EIC_CONFIG_SENSE4_Pos) /**< (EIC_CONFIG) No detection Position */
#define EIC_CONFIG_SENSE4_RISE (EIC_CONFIG_SENSE4_RISE_Val << EIC_CONFIG_SENSE4_Pos) /**< (EIC_CONFIG) Rising edge detection Position */
#define EIC_CONFIG_SENSE4_FALL (EIC_CONFIG_SENSE4_FALL_Val << EIC_CONFIG_SENSE4_Pos) /**< (EIC_CONFIG) Falling edge detection Position */
#define EIC_CONFIG_SENSE4_BOTH (EIC_CONFIG_SENSE4_BOTH_Val << EIC_CONFIG_SENSE4_Pos) /**< (EIC_CONFIG) Both edges detection Position */
#define EIC_CONFIG_SENSE4_HIGH (EIC_CONFIG_SENSE4_HIGH_Val << EIC_CONFIG_SENSE4_Pos) /**< (EIC_CONFIG) High level detection Position */
#define EIC_CONFIG_SENSE4_LOW (EIC_CONFIG_SENSE4_LOW_Val << EIC_CONFIG_SENSE4_Pos) /**< (EIC_CONFIG) Low level detection Position */
#define EIC_CONFIG_FILTEN4_Pos 19 /**< (EIC_CONFIG) Filter Enable 4 Position */
#define EIC_CONFIG_FILTEN4_Msk (_U_(0x1) << EIC_CONFIG_FILTEN4_Pos) /**< (EIC_CONFIG) Filter Enable 4 Mask */
#define EIC_CONFIG_FILTEN4 EIC_CONFIG_FILTEN4_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EIC_CONFIG_FILTEN4_Msk instead */
#define EIC_CONFIG_SENSE5_Pos 20 /**< (EIC_CONFIG) Input Sense Configuration 5 Position */
#define EIC_CONFIG_SENSE5_Msk (_U_(0x7) << EIC_CONFIG_SENSE5_Pos) /**< (EIC_CONFIG) Input Sense Configuration 5 Mask */
#define EIC_CONFIG_SENSE5(value) (EIC_CONFIG_SENSE5_Msk & ((value) << EIC_CONFIG_SENSE5_Pos))
#define EIC_CONFIG_SENSE5_NONE_Val _U_(0x0) /**< (EIC_CONFIG) No detection */
#define EIC_CONFIG_SENSE5_RISE_Val _U_(0x1) /**< (EIC_CONFIG) Rising edge detection */
#define EIC_CONFIG_SENSE5_FALL_Val _U_(0x2) /**< (EIC_CONFIG) Falling edge detection */
#define EIC_CONFIG_SENSE5_BOTH_Val _U_(0x3) /**< (EIC_CONFIG) Both edges detection */
#define EIC_CONFIG_SENSE5_HIGH_Val _U_(0x4) /**< (EIC_CONFIG) High level detection */
#define EIC_CONFIG_SENSE5_LOW_Val _U_(0x5) /**< (EIC_CONFIG) Low level detection */
#define EIC_CONFIG_SENSE5_NONE (EIC_CONFIG_SENSE5_NONE_Val << EIC_CONFIG_SENSE5_Pos) /**< (EIC_CONFIG) No detection Position */
#define EIC_CONFIG_SENSE5_RISE (EIC_CONFIG_SENSE5_RISE_Val << EIC_CONFIG_SENSE5_Pos) /**< (EIC_CONFIG) Rising edge detection Position */
#define EIC_CONFIG_SENSE5_FALL (EIC_CONFIG_SENSE5_FALL_Val << EIC_CONFIG_SENSE5_Pos) /**< (EIC_CONFIG) Falling edge detection Position */
#define EIC_CONFIG_SENSE5_BOTH (EIC_CONFIG_SENSE5_BOTH_Val << EIC_CONFIG_SENSE5_Pos) /**< (EIC_CONFIG) Both edges detection Position */
#define EIC_CONFIG_SENSE5_HIGH (EIC_CONFIG_SENSE5_HIGH_Val << EIC_CONFIG_SENSE5_Pos) /**< (EIC_CONFIG) High level detection Position */
#define EIC_CONFIG_SENSE5_LOW (EIC_CONFIG_SENSE5_LOW_Val << EIC_CONFIG_SENSE5_Pos) /**< (EIC_CONFIG) Low level detection Position */
#define EIC_CONFIG_FILTEN5_Pos 23 /**< (EIC_CONFIG) Filter Enable 5 Position */
#define EIC_CONFIG_FILTEN5_Msk (_U_(0x1) << EIC_CONFIG_FILTEN5_Pos) /**< (EIC_CONFIG) Filter Enable 5 Mask */
#define EIC_CONFIG_FILTEN5 EIC_CONFIG_FILTEN5_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EIC_CONFIG_FILTEN5_Msk instead */
#define EIC_CONFIG_SENSE6_Pos 24 /**< (EIC_CONFIG) Input Sense Configuration 6 Position */
#define EIC_CONFIG_SENSE6_Msk (_U_(0x7) << EIC_CONFIG_SENSE6_Pos) /**< (EIC_CONFIG) Input Sense Configuration 6 Mask */
#define EIC_CONFIG_SENSE6(value) (EIC_CONFIG_SENSE6_Msk & ((value) << EIC_CONFIG_SENSE6_Pos))
#define EIC_CONFIG_SENSE6_NONE_Val _U_(0x0) /**< (EIC_CONFIG) No detection */
#define EIC_CONFIG_SENSE6_RISE_Val _U_(0x1) /**< (EIC_CONFIG) Rising edge detection */
#define EIC_CONFIG_SENSE6_FALL_Val _U_(0x2) /**< (EIC_CONFIG) Falling edge detection */
#define EIC_CONFIG_SENSE6_BOTH_Val _U_(0x3) /**< (EIC_CONFIG) Both edges detection */
#define EIC_CONFIG_SENSE6_HIGH_Val _U_(0x4) /**< (EIC_CONFIG) High level detection */
#define EIC_CONFIG_SENSE6_LOW_Val _U_(0x5) /**< (EIC_CONFIG) Low level detection */
#define EIC_CONFIG_SENSE6_NONE (EIC_CONFIG_SENSE6_NONE_Val << EIC_CONFIG_SENSE6_Pos) /**< (EIC_CONFIG) No detection Position */
#define EIC_CONFIG_SENSE6_RISE (EIC_CONFIG_SENSE6_RISE_Val << EIC_CONFIG_SENSE6_Pos) /**< (EIC_CONFIG) Rising edge detection Position */
#define EIC_CONFIG_SENSE6_FALL (EIC_CONFIG_SENSE6_FALL_Val << EIC_CONFIG_SENSE6_Pos) /**< (EIC_CONFIG) Falling edge detection Position */
#define EIC_CONFIG_SENSE6_BOTH (EIC_CONFIG_SENSE6_BOTH_Val << EIC_CONFIG_SENSE6_Pos) /**< (EIC_CONFIG) Both edges detection Position */
#define EIC_CONFIG_SENSE6_HIGH (EIC_CONFIG_SENSE6_HIGH_Val << EIC_CONFIG_SENSE6_Pos) /**< (EIC_CONFIG) High level detection Position */
#define EIC_CONFIG_SENSE6_LOW (EIC_CONFIG_SENSE6_LOW_Val << EIC_CONFIG_SENSE6_Pos) /**< (EIC_CONFIG) Low level detection Position */
#define EIC_CONFIG_FILTEN6_Pos 27 /**< (EIC_CONFIG) Filter Enable 6 Position */
#define EIC_CONFIG_FILTEN6_Msk (_U_(0x1) << EIC_CONFIG_FILTEN6_Pos) /**< (EIC_CONFIG) Filter Enable 6 Mask */
#define EIC_CONFIG_FILTEN6 EIC_CONFIG_FILTEN6_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EIC_CONFIG_FILTEN6_Msk instead */
#define EIC_CONFIG_SENSE7_Pos 28 /**< (EIC_CONFIG) Input Sense Configuration 7 Position */
#define EIC_CONFIG_SENSE7_Msk (_U_(0x7) << EIC_CONFIG_SENSE7_Pos) /**< (EIC_CONFIG) Input Sense Configuration 7 Mask */
#define EIC_CONFIG_SENSE7(value) (EIC_CONFIG_SENSE7_Msk & ((value) << EIC_CONFIG_SENSE7_Pos))
#define EIC_CONFIG_SENSE7_NONE_Val _U_(0x0) /**< (EIC_CONFIG) No detection */
#define EIC_CONFIG_SENSE7_RISE_Val _U_(0x1) /**< (EIC_CONFIG) Rising edge detection */
#define EIC_CONFIG_SENSE7_FALL_Val _U_(0x2) /**< (EIC_CONFIG) Falling edge detection */
#define EIC_CONFIG_SENSE7_BOTH_Val _U_(0x3) /**< (EIC_CONFIG) Both edges detection */
#define EIC_CONFIG_SENSE7_HIGH_Val _U_(0x4) /**< (EIC_CONFIG) High level detection */
#define EIC_CONFIG_SENSE7_LOW_Val _U_(0x5) /**< (EIC_CONFIG) Low level detection */
#define EIC_CONFIG_SENSE7_NONE (EIC_CONFIG_SENSE7_NONE_Val << EIC_CONFIG_SENSE7_Pos) /**< (EIC_CONFIG) No detection Position */
#define EIC_CONFIG_SENSE7_RISE (EIC_CONFIG_SENSE7_RISE_Val << EIC_CONFIG_SENSE7_Pos) /**< (EIC_CONFIG) Rising edge detection Position */
#define EIC_CONFIG_SENSE7_FALL (EIC_CONFIG_SENSE7_FALL_Val << EIC_CONFIG_SENSE7_Pos) /**< (EIC_CONFIG) Falling edge detection Position */
#define EIC_CONFIG_SENSE7_BOTH (EIC_CONFIG_SENSE7_BOTH_Val << EIC_CONFIG_SENSE7_Pos) /**< (EIC_CONFIG) Both edges detection Position */
#define EIC_CONFIG_SENSE7_HIGH (EIC_CONFIG_SENSE7_HIGH_Val << EIC_CONFIG_SENSE7_Pos) /**< (EIC_CONFIG) High level detection Position */
#define EIC_CONFIG_SENSE7_LOW (EIC_CONFIG_SENSE7_LOW_Val << EIC_CONFIG_SENSE7_Pos) /**< (EIC_CONFIG) Low level detection Position */
#define EIC_CONFIG_FILTEN7_Pos 31 /**< (EIC_CONFIG) Filter Enable 7 Position */
#define EIC_CONFIG_FILTEN7_Msk (_U_(0x1) << EIC_CONFIG_FILTEN7_Pos) /**< (EIC_CONFIG) Filter Enable 7 Mask */
#define EIC_CONFIG_FILTEN7 EIC_CONFIG_FILTEN7_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EIC_CONFIG_FILTEN7_Msk instead */
#define EIC_CONFIG_MASK _U_(0xFFFFFFFF) /**< \deprecated (EIC_CONFIG) Register MASK (Use EIC_CONFIG_Msk instead) */
#define EIC_CONFIG_Msk _U_(0xFFFFFFFF) /**< (EIC_CONFIG) Register Mask */
/* -------- EIC_DEBOUNCEN : (EIC Offset: 0x30) (R/W 32) Debouncer Enable -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t DEBOUNCEN:8; /**< bit: 0..7 Debouncer Enable */
uint32_t :24; /**< bit: 8..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} EIC_DEBOUNCEN_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define EIC_DEBOUNCEN_OFFSET (0x30) /**< (EIC_DEBOUNCEN) Debouncer Enable Offset */
#define EIC_DEBOUNCEN_RESETVALUE _U_(0x00) /**< (EIC_DEBOUNCEN) Debouncer Enable Reset Value */
#define EIC_DEBOUNCEN_DEBOUNCEN_Pos 0 /**< (EIC_DEBOUNCEN) Debouncer Enable Position */
#define EIC_DEBOUNCEN_DEBOUNCEN_Msk (_U_(0xFF) << EIC_DEBOUNCEN_DEBOUNCEN_Pos) /**< (EIC_DEBOUNCEN) Debouncer Enable Mask */
#define EIC_DEBOUNCEN_DEBOUNCEN(value) (EIC_DEBOUNCEN_DEBOUNCEN_Msk & ((value) << EIC_DEBOUNCEN_DEBOUNCEN_Pos))
#define EIC_DEBOUNCEN_MASK _U_(0xFF) /**< \deprecated (EIC_DEBOUNCEN) Register MASK (Use EIC_DEBOUNCEN_Msk instead) */
#define EIC_DEBOUNCEN_Msk _U_(0xFF) /**< (EIC_DEBOUNCEN) Register Mask */
/* -------- EIC_DPRESCALER : (EIC Offset: 0x34) (R/W 32) Debouncer Prescaler -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t PRESCALER0:3; /**< bit: 0..2 Debouncer Prescaler */
uint32_t STATES0:1; /**< bit: 3 Debouncer number of states */
uint32_t :12; /**< bit: 4..15 Reserved */
uint32_t TICKON:1; /**< bit: 16 Pin Sampler frequency selection */
uint32_t :15; /**< bit: 17..31 Reserved */
} bit; /**< Structure used for bit access */
struct {
uint32_t :3; /**< bit: 0..2 Reserved */
uint32_t STATES:1; /**< bit: 3 Debouncer number of states */
uint32_t :28; /**< bit: 4..31 Reserved */
} vec; /**< Structure used for vec access */
uint32_t reg; /**< Type used for register access */
} EIC_DPRESCALER_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define EIC_DPRESCALER_OFFSET (0x34) /**< (EIC_DPRESCALER) Debouncer Prescaler Offset */
#define EIC_DPRESCALER_RESETVALUE _U_(0x00) /**< (EIC_DPRESCALER) Debouncer Prescaler Reset Value */
#define EIC_DPRESCALER_PRESCALER0_Pos 0 /**< (EIC_DPRESCALER) Debouncer Prescaler Position */
#define EIC_DPRESCALER_PRESCALER0_Msk (_U_(0x7) << EIC_DPRESCALER_PRESCALER0_Pos) /**< (EIC_DPRESCALER) Debouncer Prescaler Mask */
#define EIC_DPRESCALER_PRESCALER0(value) (EIC_DPRESCALER_PRESCALER0_Msk & ((value) << EIC_DPRESCALER_PRESCALER0_Pos))
#define EIC_DPRESCALER_STATES0_Pos 3 /**< (EIC_DPRESCALER) Debouncer number of states Position */
#define EIC_DPRESCALER_STATES0_Msk (_U_(0x1) << EIC_DPRESCALER_STATES0_Pos) /**< (EIC_DPRESCALER) Debouncer number of states Mask */
#define EIC_DPRESCALER_STATES0 EIC_DPRESCALER_STATES0_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EIC_DPRESCALER_STATES0_Msk instead */
#define EIC_DPRESCALER_TICKON_Pos 16 /**< (EIC_DPRESCALER) Pin Sampler frequency selection Position */
#define EIC_DPRESCALER_TICKON_Msk (_U_(0x1) << EIC_DPRESCALER_TICKON_Pos) /**< (EIC_DPRESCALER) Pin Sampler frequency selection Mask */
#define EIC_DPRESCALER_TICKON EIC_DPRESCALER_TICKON_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EIC_DPRESCALER_TICKON_Msk instead */
#define EIC_DPRESCALER_MASK _U_(0x1000F) /**< \deprecated (EIC_DPRESCALER) Register MASK (Use EIC_DPRESCALER_Msk instead) */
#define EIC_DPRESCALER_Msk _U_(0x1000F) /**< (EIC_DPRESCALER) Register Mask */
#define EIC_DPRESCALER_STATES_Pos 3 /**< (EIC_DPRESCALER Position) Debouncer number of states */
#define EIC_DPRESCALER_STATES_Msk (_U_(0x1) << EIC_DPRESCALER_STATES_Pos) /**< (EIC_DPRESCALER Mask) STATES */
#define EIC_DPRESCALER_STATES(value) (EIC_DPRESCALER_STATES_Msk & ((value) << EIC_DPRESCALER_STATES_Pos))
/* -------- EIC_PINSTATE : (EIC Offset: 0x38) (R/ 32) Pin State -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t PINSTATE:8; /**< bit: 0..7 Pin State */
uint32_t :24; /**< bit: 8..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} EIC_PINSTATE_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define EIC_PINSTATE_OFFSET (0x38) /**< (EIC_PINSTATE) Pin State Offset */
#define EIC_PINSTATE_RESETVALUE _U_(0x00) /**< (EIC_PINSTATE) Pin State Reset Value */
#define EIC_PINSTATE_PINSTATE_Pos 0 /**< (EIC_PINSTATE) Pin State Position */
#define EIC_PINSTATE_PINSTATE_Msk (_U_(0xFF) << EIC_PINSTATE_PINSTATE_Pos) /**< (EIC_PINSTATE) Pin State Mask */
#define EIC_PINSTATE_PINSTATE(value) (EIC_PINSTATE_PINSTATE_Msk & ((value) << EIC_PINSTATE_PINSTATE_Pos))
#define EIC_PINSTATE_MASK _U_(0xFF) /**< \deprecated (EIC_PINSTATE) Register MASK (Use EIC_PINSTATE_Msk instead) */
#define EIC_PINSTATE_Msk _U_(0xFF) /**< (EIC_PINSTATE) Register Mask */
/* -------- EIC_NSCHK : (EIC Offset: 0x3c) (R/W 32) Non-secure Interrupt Check Enable -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t EXTINT:8; /**< bit: 0..7 External Interrupt Nonsecure Check Enable */
uint32_t :23; /**< bit: 8..30 Reserved */
uint32_t NMI:1; /**< bit: 31 Non-Maskable External Interrupt Nonsecure Check Enable */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} EIC_NSCHK_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define EIC_NSCHK_OFFSET (0x3C) /**< (EIC_NSCHK) Non-secure Interrupt Check Enable Offset */
#define EIC_NSCHK_RESETVALUE _U_(0x00) /**< (EIC_NSCHK) Non-secure Interrupt Check Enable Reset Value */
#define EIC_NSCHK_EXTINT_Pos 0 /**< (EIC_NSCHK) External Interrupt Nonsecure Check Enable Position */
#define EIC_NSCHK_EXTINT_Msk (_U_(0xFF) << EIC_NSCHK_EXTINT_Pos) /**< (EIC_NSCHK) External Interrupt Nonsecure Check Enable Mask */
#define EIC_NSCHK_EXTINT(value) (EIC_NSCHK_EXTINT_Msk & ((value) << EIC_NSCHK_EXTINT_Pos))
#define EIC_NSCHK_NMI_Pos 31 /**< (EIC_NSCHK) Non-Maskable External Interrupt Nonsecure Check Enable Position */
#define EIC_NSCHK_NMI_Msk (_U_(0x1) << EIC_NSCHK_NMI_Pos) /**< (EIC_NSCHK) Non-Maskable External Interrupt Nonsecure Check Enable Mask */
#define EIC_NSCHK_NMI EIC_NSCHK_NMI_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EIC_NSCHK_NMI_Msk instead */
#define EIC_NSCHK_MASK _U_(0x800000FF) /**< \deprecated (EIC_NSCHK) Register MASK (Use EIC_NSCHK_Msk instead) */
#define EIC_NSCHK_Msk _U_(0x800000FF) /**< (EIC_NSCHK) Register Mask */
/* -------- EIC_NONSEC : (EIC Offset: 0x40) (R/W 32) Non-secure Interrupt -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t EXTINT:8; /**< bit: 0..7 External Interrupt Nonsecure Enable */
uint32_t :23; /**< bit: 8..30 Reserved */
uint32_t NMI:1; /**< bit: 31 Non-Maskable Interrupt Nonsecure Enable */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} EIC_NONSEC_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define EIC_NONSEC_OFFSET (0x40) /**< (EIC_NONSEC) Non-secure Interrupt Offset */
#define EIC_NONSEC_RESETVALUE _U_(0x00) /**< (EIC_NONSEC) Non-secure Interrupt Reset Value */
#define EIC_NONSEC_EXTINT_Pos 0 /**< (EIC_NONSEC) External Interrupt Nonsecure Enable Position */
#define EIC_NONSEC_EXTINT_Msk (_U_(0xFF) << EIC_NONSEC_EXTINT_Pos) /**< (EIC_NONSEC) External Interrupt Nonsecure Enable Mask */
#define EIC_NONSEC_EXTINT(value) (EIC_NONSEC_EXTINT_Msk & ((value) << EIC_NONSEC_EXTINT_Pos))
#define EIC_NONSEC_NMI_Pos 31 /**< (EIC_NONSEC) Non-Maskable Interrupt Nonsecure Enable Position */
#define EIC_NONSEC_NMI_Msk (_U_(0x1) << EIC_NONSEC_NMI_Pos) /**< (EIC_NONSEC) Non-Maskable Interrupt Nonsecure Enable Mask */
#define EIC_NONSEC_NMI EIC_NONSEC_NMI_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EIC_NONSEC_NMI_Msk instead */
#define EIC_NONSEC_MASK _U_(0x800000FF) /**< \deprecated (EIC_NONSEC) Register MASK (Use EIC_NONSEC_Msk instead) */
#define EIC_NONSEC_Msk _U_(0x800000FF) /**< (EIC_NONSEC) Register Mask */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
/** \brief EIC hardware registers */
typedef struct { /* External Interrupt Controller */
__IO EIC_CTRLA_Type CTRLA; /**< Offset: 0x00 (R/W 8) Control A */
__IO EIC_NMICTRL_Type NMICTRL; /**< Offset: 0x01 (R/W 8) Non-Maskable Interrupt Control */
__IO EIC_NMIFLAG_Type NMIFLAG; /**< Offset: 0x02 (R/W 16) Non-Maskable Interrupt Flag Status and Clear */
__I EIC_SYNCBUSY_Type SYNCBUSY; /**< Offset: 0x04 (R/ 32) Synchronization Busy */
__IO EIC_EVCTRL_Type EVCTRL; /**< Offset: 0x08 (R/W 32) Event Control */
__IO EIC_INTENCLR_Type INTENCLR; /**< Offset: 0x0C (R/W 32) Interrupt Enable Clear */
__IO EIC_INTENSET_Type INTENSET; /**< Offset: 0x10 (R/W 32) Interrupt Enable Set */
__IO EIC_INTFLAG_Type INTFLAG; /**< Offset: 0x14 (R/W 32) Interrupt Flag Status and Clear */
__IO EIC_ASYNCH_Type ASYNCH; /**< Offset: 0x18 (R/W 32) External Interrupt Asynchronous Mode */
__IO EIC_CONFIG_Type CONFIG[1]; /**< Offset: 0x1C (R/W 32) External Interrupt Sense Configuration */
__I uint8_t Reserved1[16];
__IO EIC_DEBOUNCEN_Type DEBOUNCEN; /**< Offset: 0x30 (R/W 32) Debouncer Enable */
__IO EIC_DPRESCALER_Type DPRESCALER; /**< Offset: 0x34 (R/W 32) Debouncer Prescaler */
__I EIC_PINSTATE_Type PINSTATE; /**< Offset: 0x38 (R/ 32) Pin State */
__IO EIC_NSCHK_Type NSCHK; /**< Offset: 0x3C (R/W 32) Non-secure Interrupt Check Enable */
__IO EIC_NONSEC_Type NONSEC; /**< Offset: 0x40 (R/W 32) Non-secure Interrupt */
} Eic;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/** @} end of External Interrupt Controller */
#endif /* _SAML10_EIC_COMPONENT_H_ */

View File

@ -0,0 +1,927 @@
/**
* \file
*
* \brief Component description for EVSYS
*
* Copyright (c) 2018 Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* 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
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
/* file generated from device description version 2018-08-31T13:51:50Z */
#ifndef _SAML10_EVSYS_COMPONENT_H_
#define _SAML10_EVSYS_COMPONENT_H_
#define _SAML10_EVSYS_COMPONENT_ /**< \deprecated Backward compatibility for ASF */
/** \addtogroup SAML_SAML10 Event System Interface
* @{
*/
/* ========================================================================== */
/** SOFTWARE API DEFINITION FOR EVSYS */
/* ========================================================================== */
#define EVSYS_U2504 /**< (EVSYS) Module ID */
#define REV_EVSYS 0x200 /**< (EVSYS) Module revision */
/* -------- EVSYS_CHANNEL : (EVSYS Offset: 0x00) (R/W 32) Channel n Control -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t EVGEN:6; /**< bit: 0..5 Event Generator Selection */
uint32_t :2; /**< bit: 6..7 Reserved */
uint32_t PATH:2; /**< bit: 8..9 Path Selection */
uint32_t EDGSEL:2; /**< bit: 10..11 Edge Detection Selection */
uint32_t :2; /**< bit: 12..13 Reserved */
uint32_t RUNSTDBY:1; /**< bit: 14 Run in standby */
uint32_t ONDEMAND:1; /**< bit: 15 Generic Clock On Demand */
uint32_t :16; /**< bit: 16..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} EVSYS_CHANNEL_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define EVSYS_CHANNEL_OFFSET (0x00) /**< (EVSYS_CHANNEL) Channel n Control Offset */
#define EVSYS_CHANNEL_RESETVALUE _U_(0x8000) /**< (EVSYS_CHANNEL) Channel n Control Reset Value */
#define EVSYS_CHANNEL_EVGEN_Pos 0 /**< (EVSYS_CHANNEL) Event Generator Selection Position */
#define EVSYS_CHANNEL_EVGEN_Msk (_U_(0x3F) << EVSYS_CHANNEL_EVGEN_Pos) /**< (EVSYS_CHANNEL) Event Generator Selection Mask */
#define EVSYS_CHANNEL_EVGEN(value) (EVSYS_CHANNEL_EVGEN_Msk & ((value) << EVSYS_CHANNEL_EVGEN_Pos))
#define EVSYS_CHANNEL_PATH_Pos 8 /**< (EVSYS_CHANNEL) Path Selection Position */
#define EVSYS_CHANNEL_PATH_Msk (_U_(0x3) << EVSYS_CHANNEL_PATH_Pos) /**< (EVSYS_CHANNEL) Path Selection Mask */
#define EVSYS_CHANNEL_PATH(value) (EVSYS_CHANNEL_PATH_Msk & ((value) << EVSYS_CHANNEL_PATH_Pos))
#define EVSYS_CHANNEL_PATH_SYNCHRONOUS_Val _U_(0x0) /**< (EVSYS_CHANNEL) Synchronous path */
#define EVSYS_CHANNEL_PATH_RESYNCHRONIZED_Val _U_(0x1) /**< (EVSYS_CHANNEL) Resynchronized path */
#define EVSYS_CHANNEL_PATH_ASYNCHRONOUS_Val _U_(0x2) /**< (EVSYS_CHANNEL) Asynchronous path */
#define EVSYS_CHANNEL_PATH_SYNCHRONOUS (EVSYS_CHANNEL_PATH_SYNCHRONOUS_Val << EVSYS_CHANNEL_PATH_Pos) /**< (EVSYS_CHANNEL) Synchronous path Position */
#define EVSYS_CHANNEL_PATH_RESYNCHRONIZED (EVSYS_CHANNEL_PATH_RESYNCHRONIZED_Val << EVSYS_CHANNEL_PATH_Pos) /**< (EVSYS_CHANNEL) Resynchronized path Position */
#define EVSYS_CHANNEL_PATH_ASYNCHRONOUS (EVSYS_CHANNEL_PATH_ASYNCHRONOUS_Val << EVSYS_CHANNEL_PATH_Pos) /**< (EVSYS_CHANNEL) Asynchronous path Position */
#define EVSYS_CHANNEL_EDGSEL_Pos 10 /**< (EVSYS_CHANNEL) Edge Detection Selection Position */
#define EVSYS_CHANNEL_EDGSEL_Msk (_U_(0x3) << EVSYS_CHANNEL_EDGSEL_Pos) /**< (EVSYS_CHANNEL) Edge Detection Selection Mask */
#define EVSYS_CHANNEL_EDGSEL(value) (EVSYS_CHANNEL_EDGSEL_Msk & ((value) << EVSYS_CHANNEL_EDGSEL_Pos))
#define EVSYS_CHANNEL_EDGSEL_NO_EVT_OUTPUT_Val _U_(0x0) /**< (EVSYS_CHANNEL) No event output when using the resynchronized or synchronous path */
#define EVSYS_CHANNEL_EDGSEL_RISING_EDGE_Val _U_(0x1) /**< (EVSYS_CHANNEL) Event detection only on the rising edge of the signal from the event generator when using the resynchronized or synchronous path */
#define EVSYS_CHANNEL_EDGSEL_FALLING_EDGE_Val _U_(0x2) /**< (EVSYS_CHANNEL) Event detection only on the falling edge of the signal from the event generator when using the resynchronized or synchronous path */
#define EVSYS_CHANNEL_EDGSEL_BOTH_EDGES_Val _U_(0x3) /**< (EVSYS_CHANNEL) Event detection on rising and falling edges of the signal from the event generator when using the resynchronized or synchronous path */
#define EVSYS_CHANNEL_EDGSEL_NO_EVT_OUTPUT (EVSYS_CHANNEL_EDGSEL_NO_EVT_OUTPUT_Val << EVSYS_CHANNEL_EDGSEL_Pos) /**< (EVSYS_CHANNEL) No event output when using the resynchronized or synchronous path Position */
#define EVSYS_CHANNEL_EDGSEL_RISING_EDGE (EVSYS_CHANNEL_EDGSEL_RISING_EDGE_Val << EVSYS_CHANNEL_EDGSEL_Pos) /**< (EVSYS_CHANNEL) Event detection only on the rising edge of the signal from the event generator when using the resynchronized or synchronous path Position */
#define EVSYS_CHANNEL_EDGSEL_FALLING_EDGE (EVSYS_CHANNEL_EDGSEL_FALLING_EDGE_Val << EVSYS_CHANNEL_EDGSEL_Pos) /**< (EVSYS_CHANNEL) Event detection only on the falling edge of the signal from the event generator when using the resynchronized or synchronous path Position */
#define EVSYS_CHANNEL_EDGSEL_BOTH_EDGES (EVSYS_CHANNEL_EDGSEL_BOTH_EDGES_Val << EVSYS_CHANNEL_EDGSEL_Pos) /**< (EVSYS_CHANNEL) Event detection on rising and falling edges of the signal from the event generator when using the resynchronized or synchronous path Position */
#define EVSYS_CHANNEL_RUNSTDBY_Pos 14 /**< (EVSYS_CHANNEL) Run in standby Position */
#define EVSYS_CHANNEL_RUNSTDBY_Msk (_U_(0x1) << EVSYS_CHANNEL_RUNSTDBY_Pos) /**< (EVSYS_CHANNEL) Run in standby Mask */
#define EVSYS_CHANNEL_RUNSTDBY EVSYS_CHANNEL_RUNSTDBY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_CHANNEL_RUNSTDBY_Msk instead */
#define EVSYS_CHANNEL_ONDEMAND_Pos 15 /**< (EVSYS_CHANNEL) Generic Clock On Demand Position */
#define EVSYS_CHANNEL_ONDEMAND_Msk (_U_(0x1) << EVSYS_CHANNEL_ONDEMAND_Pos) /**< (EVSYS_CHANNEL) Generic Clock On Demand Mask */
#define EVSYS_CHANNEL_ONDEMAND EVSYS_CHANNEL_ONDEMAND_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_CHANNEL_ONDEMAND_Msk instead */
#define EVSYS_CHANNEL_MASK _U_(0xCF3F) /**< \deprecated (EVSYS_CHANNEL) Register MASK (Use EVSYS_CHANNEL_Msk instead) */
#define EVSYS_CHANNEL_Msk _U_(0xCF3F) /**< (EVSYS_CHANNEL) Register Mask */
/* -------- EVSYS_CHINTENCLR : (EVSYS Offset: 0x04) (R/W 8) Channel n Interrupt Enable Clear -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t OVR:1; /**< bit: 0 Channel Overrun Interrupt Disable */
uint8_t EVD:1; /**< bit: 1 Channel Event Detected Interrupt Disable */
uint8_t :6; /**< bit: 2..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} EVSYS_CHINTENCLR_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define EVSYS_CHINTENCLR_OFFSET (0x04) /**< (EVSYS_CHINTENCLR) Channel n Interrupt Enable Clear Offset */
#define EVSYS_CHINTENCLR_RESETVALUE _U_(0x00) /**< (EVSYS_CHINTENCLR) Channel n Interrupt Enable Clear Reset Value */
#define EVSYS_CHINTENCLR_OVR_Pos 0 /**< (EVSYS_CHINTENCLR) Channel Overrun Interrupt Disable Position */
#define EVSYS_CHINTENCLR_OVR_Msk (_U_(0x1) << EVSYS_CHINTENCLR_OVR_Pos) /**< (EVSYS_CHINTENCLR) Channel Overrun Interrupt Disable Mask */
#define EVSYS_CHINTENCLR_OVR EVSYS_CHINTENCLR_OVR_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_CHINTENCLR_OVR_Msk instead */
#define EVSYS_CHINTENCLR_EVD_Pos 1 /**< (EVSYS_CHINTENCLR) Channel Event Detected Interrupt Disable Position */
#define EVSYS_CHINTENCLR_EVD_Msk (_U_(0x1) << EVSYS_CHINTENCLR_EVD_Pos) /**< (EVSYS_CHINTENCLR) Channel Event Detected Interrupt Disable Mask */
#define EVSYS_CHINTENCLR_EVD EVSYS_CHINTENCLR_EVD_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_CHINTENCLR_EVD_Msk instead */
#define EVSYS_CHINTENCLR_MASK _U_(0x03) /**< \deprecated (EVSYS_CHINTENCLR) Register MASK (Use EVSYS_CHINTENCLR_Msk instead) */
#define EVSYS_CHINTENCLR_Msk _U_(0x03) /**< (EVSYS_CHINTENCLR) Register Mask */
/* -------- EVSYS_CHINTENSET : (EVSYS Offset: 0x05) (R/W 8) Channel n Interrupt Enable Set -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t OVR:1; /**< bit: 0 Channel Overrun Interrupt Enable */
uint8_t EVD:1; /**< bit: 1 Channel Event Detected Interrupt Enable */
uint8_t :6; /**< bit: 2..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} EVSYS_CHINTENSET_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define EVSYS_CHINTENSET_OFFSET (0x05) /**< (EVSYS_CHINTENSET) Channel n Interrupt Enable Set Offset */
#define EVSYS_CHINTENSET_RESETVALUE _U_(0x00) /**< (EVSYS_CHINTENSET) Channel n Interrupt Enable Set Reset Value */
#define EVSYS_CHINTENSET_OVR_Pos 0 /**< (EVSYS_CHINTENSET) Channel Overrun Interrupt Enable Position */
#define EVSYS_CHINTENSET_OVR_Msk (_U_(0x1) << EVSYS_CHINTENSET_OVR_Pos) /**< (EVSYS_CHINTENSET) Channel Overrun Interrupt Enable Mask */
#define EVSYS_CHINTENSET_OVR EVSYS_CHINTENSET_OVR_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_CHINTENSET_OVR_Msk instead */
#define EVSYS_CHINTENSET_EVD_Pos 1 /**< (EVSYS_CHINTENSET) Channel Event Detected Interrupt Enable Position */
#define EVSYS_CHINTENSET_EVD_Msk (_U_(0x1) << EVSYS_CHINTENSET_EVD_Pos) /**< (EVSYS_CHINTENSET) Channel Event Detected Interrupt Enable Mask */
#define EVSYS_CHINTENSET_EVD EVSYS_CHINTENSET_EVD_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_CHINTENSET_EVD_Msk instead */
#define EVSYS_CHINTENSET_MASK _U_(0x03) /**< \deprecated (EVSYS_CHINTENSET) Register MASK (Use EVSYS_CHINTENSET_Msk instead) */
#define EVSYS_CHINTENSET_Msk _U_(0x03) /**< (EVSYS_CHINTENSET) Register Mask */
/* -------- EVSYS_CHINTFLAG : (EVSYS Offset: 0x06) (R/W 8) Channel n Interrupt Flag Status and Clear -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union { // __I to avoid read-modify-write on write-to-clear register
struct {
__I uint8_t OVR:1; /**< bit: 0 Channel Overrun */
__I uint8_t EVD:1; /**< bit: 1 Channel Event Detected */
__I uint8_t :6; /**< bit: 2..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} EVSYS_CHINTFLAG_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define EVSYS_CHINTFLAG_OFFSET (0x06) /**< (EVSYS_CHINTFLAG) Channel n Interrupt Flag Status and Clear Offset */
#define EVSYS_CHINTFLAG_RESETVALUE _U_(0x00) /**< (EVSYS_CHINTFLAG) Channel n Interrupt Flag Status and Clear Reset Value */
#define EVSYS_CHINTFLAG_OVR_Pos 0 /**< (EVSYS_CHINTFLAG) Channel Overrun Position */
#define EVSYS_CHINTFLAG_OVR_Msk (_U_(0x1) << EVSYS_CHINTFLAG_OVR_Pos) /**< (EVSYS_CHINTFLAG) Channel Overrun Mask */
#define EVSYS_CHINTFLAG_OVR EVSYS_CHINTFLAG_OVR_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_CHINTFLAG_OVR_Msk instead */
#define EVSYS_CHINTFLAG_EVD_Pos 1 /**< (EVSYS_CHINTFLAG) Channel Event Detected Position */
#define EVSYS_CHINTFLAG_EVD_Msk (_U_(0x1) << EVSYS_CHINTFLAG_EVD_Pos) /**< (EVSYS_CHINTFLAG) Channel Event Detected Mask */
#define EVSYS_CHINTFLAG_EVD EVSYS_CHINTFLAG_EVD_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_CHINTFLAG_EVD_Msk instead */
#define EVSYS_CHINTFLAG_MASK _U_(0x03) /**< \deprecated (EVSYS_CHINTFLAG) Register MASK (Use EVSYS_CHINTFLAG_Msk instead) */
#define EVSYS_CHINTFLAG_Msk _U_(0x03) /**< (EVSYS_CHINTFLAG) Register Mask */
/* -------- EVSYS_CHSTATUS : (EVSYS Offset: 0x07) (R/ 8) Channel n Status -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t RDYUSR:1; /**< bit: 0 Ready User */
uint8_t BUSYCH:1; /**< bit: 1 Busy Channel */
uint8_t :6; /**< bit: 2..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} EVSYS_CHSTATUS_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define EVSYS_CHSTATUS_OFFSET (0x07) /**< (EVSYS_CHSTATUS) Channel n Status Offset */
#define EVSYS_CHSTATUS_RESETVALUE _U_(0x01) /**< (EVSYS_CHSTATUS) Channel n Status Reset Value */
#define EVSYS_CHSTATUS_RDYUSR_Pos 0 /**< (EVSYS_CHSTATUS) Ready User Position */
#define EVSYS_CHSTATUS_RDYUSR_Msk (_U_(0x1) << EVSYS_CHSTATUS_RDYUSR_Pos) /**< (EVSYS_CHSTATUS) Ready User Mask */
#define EVSYS_CHSTATUS_RDYUSR EVSYS_CHSTATUS_RDYUSR_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_CHSTATUS_RDYUSR_Msk instead */
#define EVSYS_CHSTATUS_BUSYCH_Pos 1 /**< (EVSYS_CHSTATUS) Busy Channel Position */
#define EVSYS_CHSTATUS_BUSYCH_Msk (_U_(0x1) << EVSYS_CHSTATUS_BUSYCH_Pos) /**< (EVSYS_CHSTATUS) Busy Channel Mask */
#define EVSYS_CHSTATUS_BUSYCH EVSYS_CHSTATUS_BUSYCH_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_CHSTATUS_BUSYCH_Msk instead */
#define EVSYS_CHSTATUS_MASK _U_(0x03) /**< \deprecated (EVSYS_CHSTATUS) Register MASK (Use EVSYS_CHSTATUS_Msk instead) */
#define EVSYS_CHSTATUS_Msk _U_(0x03) /**< (EVSYS_CHSTATUS) Register Mask */
/* -------- EVSYS_CTRLA : (EVSYS Offset: 0x00) (/W 8) Control -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t SWRST:1; /**< bit: 0 Software Reset */
uint8_t :7; /**< bit: 1..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} EVSYS_CTRLA_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define EVSYS_CTRLA_OFFSET (0x00) /**< (EVSYS_CTRLA) Control Offset */
#define EVSYS_CTRLA_RESETVALUE _U_(0x00) /**< (EVSYS_CTRLA) Control Reset Value */
#define EVSYS_CTRLA_SWRST_Pos 0 /**< (EVSYS_CTRLA) Software Reset Position */
#define EVSYS_CTRLA_SWRST_Msk (_U_(0x1) << EVSYS_CTRLA_SWRST_Pos) /**< (EVSYS_CTRLA) Software Reset Mask */
#define EVSYS_CTRLA_SWRST EVSYS_CTRLA_SWRST_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_CTRLA_SWRST_Msk instead */
#define EVSYS_CTRLA_MASK _U_(0x01) /**< \deprecated (EVSYS_CTRLA) Register MASK (Use EVSYS_CTRLA_Msk instead) */
#define EVSYS_CTRLA_Msk _U_(0x01) /**< (EVSYS_CTRLA) Register Mask */
/* -------- EVSYS_SWEVT : (EVSYS Offset: 0x04) (/W 32) Software Event -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t CHANNEL0:1; /**< bit: 0 Channel 0 Software Selection */
uint32_t CHANNEL1:1; /**< bit: 1 Channel 1 Software Selection */
uint32_t CHANNEL2:1; /**< bit: 2 Channel 2 Software Selection */
uint32_t CHANNEL3:1; /**< bit: 3 Channel 3 Software Selection */
uint32_t CHANNEL4:1; /**< bit: 4 Channel 4 Software Selection */
uint32_t CHANNEL5:1; /**< bit: 5 Channel 5 Software Selection */
uint32_t CHANNEL6:1; /**< bit: 6 Channel 6 Software Selection */
uint32_t CHANNEL7:1; /**< bit: 7 Channel 7 Software Selection */
uint32_t :24; /**< bit: 8..31 Reserved */
} bit; /**< Structure used for bit access */
struct {
uint32_t CHANNEL:8; /**< bit: 0..7 Channel 7 Software Selection */
uint32_t :24; /**< bit: 8..31 Reserved */
} vec; /**< Structure used for vec access */
uint32_t reg; /**< Type used for register access */
} EVSYS_SWEVT_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define EVSYS_SWEVT_OFFSET (0x04) /**< (EVSYS_SWEVT) Software Event Offset */
#define EVSYS_SWEVT_RESETVALUE _U_(0x00) /**< (EVSYS_SWEVT) Software Event Reset Value */
#define EVSYS_SWEVT_CHANNEL0_Pos 0 /**< (EVSYS_SWEVT) Channel 0 Software Selection Position */
#define EVSYS_SWEVT_CHANNEL0_Msk (_U_(0x1) << EVSYS_SWEVT_CHANNEL0_Pos) /**< (EVSYS_SWEVT) Channel 0 Software Selection Mask */
#define EVSYS_SWEVT_CHANNEL0 EVSYS_SWEVT_CHANNEL0_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_SWEVT_CHANNEL0_Msk instead */
#define EVSYS_SWEVT_CHANNEL1_Pos 1 /**< (EVSYS_SWEVT) Channel 1 Software Selection Position */
#define EVSYS_SWEVT_CHANNEL1_Msk (_U_(0x1) << EVSYS_SWEVT_CHANNEL1_Pos) /**< (EVSYS_SWEVT) Channel 1 Software Selection Mask */
#define EVSYS_SWEVT_CHANNEL1 EVSYS_SWEVT_CHANNEL1_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_SWEVT_CHANNEL1_Msk instead */
#define EVSYS_SWEVT_CHANNEL2_Pos 2 /**< (EVSYS_SWEVT) Channel 2 Software Selection Position */
#define EVSYS_SWEVT_CHANNEL2_Msk (_U_(0x1) << EVSYS_SWEVT_CHANNEL2_Pos) /**< (EVSYS_SWEVT) Channel 2 Software Selection Mask */
#define EVSYS_SWEVT_CHANNEL2 EVSYS_SWEVT_CHANNEL2_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_SWEVT_CHANNEL2_Msk instead */
#define EVSYS_SWEVT_CHANNEL3_Pos 3 /**< (EVSYS_SWEVT) Channel 3 Software Selection Position */
#define EVSYS_SWEVT_CHANNEL3_Msk (_U_(0x1) << EVSYS_SWEVT_CHANNEL3_Pos) /**< (EVSYS_SWEVT) Channel 3 Software Selection Mask */
#define EVSYS_SWEVT_CHANNEL3 EVSYS_SWEVT_CHANNEL3_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_SWEVT_CHANNEL3_Msk instead */
#define EVSYS_SWEVT_CHANNEL4_Pos 4 /**< (EVSYS_SWEVT) Channel 4 Software Selection Position */
#define EVSYS_SWEVT_CHANNEL4_Msk (_U_(0x1) << EVSYS_SWEVT_CHANNEL4_Pos) /**< (EVSYS_SWEVT) Channel 4 Software Selection Mask */
#define EVSYS_SWEVT_CHANNEL4 EVSYS_SWEVT_CHANNEL4_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_SWEVT_CHANNEL4_Msk instead */
#define EVSYS_SWEVT_CHANNEL5_Pos 5 /**< (EVSYS_SWEVT) Channel 5 Software Selection Position */
#define EVSYS_SWEVT_CHANNEL5_Msk (_U_(0x1) << EVSYS_SWEVT_CHANNEL5_Pos) /**< (EVSYS_SWEVT) Channel 5 Software Selection Mask */
#define EVSYS_SWEVT_CHANNEL5 EVSYS_SWEVT_CHANNEL5_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_SWEVT_CHANNEL5_Msk instead */
#define EVSYS_SWEVT_CHANNEL6_Pos 6 /**< (EVSYS_SWEVT) Channel 6 Software Selection Position */
#define EVSYS_SWEVT_CHANNEL6_Msk (_U_(0x1) << EVSYS_SWEVT_CHANNEL6_Pos) /**< (EVSYS_SWEVT) Channel 6 Software Selection Mask */
#define EVSYS_SWEVT_CHANNEL6 EVSYS_SWEVT_CHANNEL6_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_SWEVT_CHANNEL6_Msk instead */
#define EVSYS_SWEVT_CHANNEL7_Pos 7 /**< (EVSYS_SWEVT) Channel 7 Software Selection Position */
#define EVSYS_SWEVT_CHANNEL7_Msk (_U_(0x1) << EVSYS_SWEVT_CHANNEL7_Pos) /**< (EVSYS_SWEVT) Channel 7 Software Selection Mask */
#define EVSYS_SWEVT_CHANNEL7 EVSYS_SWEVT_CHANNEL7_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_SWEVT_CHANNEL7_Msk instead */
#define EVSYS_SWEVT_MASK _U_(0xFF) /**< \deprecated (EVSYS_SWEVT) Register MASK (Use EVSYS_SWEVT_Msk instead) */
#define EVSYS_SWEVT_Msk _U_(0xFF) /**< (EVSYS_SWEVT) Register Mask */
#define EVSYS_SWEVT_CHANNEL_Pos 0 /**< (EVSYS_SWEVT Position) Channel 7 Software Selection */
#define EVSYS_SWEVT_CHANNEL_Msk (_U_(0xFF) << EVSYS_SWEVT_CHANNEL_Pos) /**< (EVSYS_SWEVT Mask) CHANNEL */
#define EVSYS_SWEVT_CHANNEL(value) (EVSYS_SWEVT_CHANNEL_Msk & ((value) << EVSYS_SWEVT_CHANNEL_Pos))
/* -------- EVSYS_PRICTRL : (EVSYS Offset: 0x08) (R/W 8) Priority Control -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t PRI:2; /**< bit: 0..1 Channel Priority Number */
uint8_t :5; /**< bit: 2..6 Reserved */
uint8_t RREN:1; /**< bit: 7 Round-Robin Scheduling Enable */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} EVSYS_PRICTRL_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define EVSYS_PRICTRL_OFFSET (0x08) /**< (EVSYS_PRICTRL) Priority Control Offset */
#define EVSYS_PRICTRL_RESETVALUE _U_(0x00) /**< (EVSYS_PRICTRL) Priority Control Reset Value */
#define EVSYS_PRICTRL_PRI_Pos 0 /**< (EVSYS_PRICTRL) Channel Priority Number Position */
#define EVSYS_PRICTRL_PRI_Msk (_U_(0x3) << EVSYS_PRICTRL_PRI_Pos) /**< (EVSYS_PRICTRL) Channel Priority Number Mask */
#define EVSYS_PRICTRL_PRI(value) (EVSYS_PRICTRL_PRI_Msk & ((value) << EVSYS_PRICTRL_PRI_Pos))
#define EVSYS_PRICTRL_RREN_Pos 7 /**< (EVSYS_PRICTRL) Round-Robin Scheduling Enable Position */
#define EVSYS_PRICTRL_RREN_Msk (_U_(0x1) << EVSYS_PRICTRL_RREN_Pos) /**< (EVSYS_PRICTRL) Round-Robin Scheduling Enable Mask */
#define EVSYS_PRICTRL_RREN EVSYS_PRICTRL_RREN_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_PRICTRL_RREN_Msk instead */
#define EVSYS_PRICTRL_MASK _U_(0x83) /**< \deprecated (EVSYS_PRICTRL) Register MASK (Use EVSYS_PRICTRL_Msk instead) */
#define EVSYS_PRICTRL_Msk _U_(0x83) /**< (EVSYS_PRICTRL) Register Mask */
/* -------- EVSYS_INTPEND : (EVSYS Offset: 0x10) (R/W 16) Channel Pending Interrupt -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint16_t ID:2; /**< bit: 0..1 Channel ID */
uint16_t :6; /**< bit: 2..7 Reserved */
uint16_t OVR:1; /**< bit: 8 Channel Overrun */
uint16_t EVD:1; /**< bit: 9 Channel Event Detected */
uint16_t :4; /**< bit: 10..13 Reserved */
uint16_t READY:1; /**< bit: 14 Ready */
uint16_t BUSY:1; /**< bit: 15 Busy */
} bit; /**< Structure used for bit access */
uint16_t reg; /**< Type used for register access */
} EVSYS_INTPEND_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define EVSYS_INTPEND_OFFSET (0x10) /**< (EVSYS_INTPEND) Channel Pending Interrupt Offset */
#define EVSYS_INTPEND_RESETVALUE _U_(0x4000) /**< (EVSYS_INTPEND) Channel Pending Interrupt Reset Value */
#define EVSYS_INTPEND_ID_Pos 0 /**< (EVSYS_INTPEND) Channel ID Position */
#define EVSYS_INTPEND_ID_Msk (_U_(0x3) << EVSYS_INTPEND_ID_Pos) /**< (EVSYS_INTPEND) Channel ID Mask */
#define EVSYS_INTPEND_ID(value) (EVSYS_INTPEND_ID_Msk & ((value) << EVSYS_INTPEND_ID_Pos))
#define EVSYS_INTPEND_OVR_Pos 8 /**< (EVSYS_INTPEND) Channel Overrun Position */
#define EVSYS_INTPEND_OVR_Msk (_U_(0x1) << EVSYS_INTPEND_OVR_Pos) /**< (EVSYS_INTPEND) Channel Overrun Mask */
#define EVSYS_INTPEND_OVR EVSYS_INTPEND_OVR_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_INTPEND_OVR_Msk instead */
#define EVSYS_INTPEND_EVD_Pos 9 /**< (EVSYS_INTPEND) Channel Event Detected Position */
#define EVSYS_INTPEND_EVD_Msk (_U_(0x1) << EVSYS_INTPEND_EVD_Pos) /**< (EVSYS_INTPEND) Channel Event Detected Mask */
#define EVSYS_INTPEND_EVD EVSYS_INTPEND_EVD_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_INTPEND_EVD_Msk instead */
#define EVSYS_INTPEND_READY_Pos 14 /**< (EVSYS_INTPEND) Ready Position */
#define EVSYS_INTPEND_READY_Msk (_U_(0x1) << EVSYS_INTPEND_READY_Pos) /**< (EVSYS_INTPEND) Ready Mask */
#define EVSYS_INTPEND_READY EVSYS_INTPEND_READY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_INTPEND_READY_Msk instead */
#define EVSYS_INTPEND_BUSY_Pos 15 /**< (EVSYS_INTPEND) Busy Position */
#define EVSYS_INTPEND_BUSY_Msk (_U_(0x1) << EVSYS_INTPEND_BUSY_Pos) /**< (EVSYS_INTPEND) Busy Mask */
#define EVSYS_INTPEND_BUSY EVSYS_INTPEND_BUSY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_INTPEND_BUSY_Msk instead */
#define EVSYS_INTPEND_MASK _U_(0xC303) /**< \deprecated (EVSYS_INTPEND) Register MASK (Use EVSYS_INTPEND_Msk instead) */
#define EVSYS_INTPEND_Msk _U_(0xC303) /**< (EVSYS_INTPEND) Register Mask */
/* -------- EVSYS_INTSTATUS : (EVSYS Offset: 0x14) (R/ 32) Interrupt Status -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t CHINT0:1; /**< bit: 0 Channel 0 Pending Interrupt */
uint32_t CHINT1:1; /**< bit: 1 Channel 1 Pending Interrupt */
uint32_t CHINT2:1; /**< bit: 2 Channel 2 Pending Interrupt */
uint32_t CHINT3:1; /**< bit: 3 Channel 3 Pending Interrupt */
uint32_t :28; /**< bit: 4..31 Reserved */
} bit; /**< Structure used for bit access */
struct {
uint32_t CHINT:4; /**< bit: 0..3 Channel 3 Pending Interrupt */
uint32_t :28; /**< bit: 4..31 Reserved */
} vec; /**< Structure used for vec access */
uint32_t reg; /**< Type used for register access */
} EVSYS_INTSTATUS_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define EVSYS_INTSTATUS_OFFSET (0x14) /**< (EVSYS_INTSTATUS) Interrupt Status Offset */
#define EVSYS_INTSTATUS_RESETVALUE _U_(0x00) /**< (EVSYS_INTSTATUS) Interrupt Status Reset Value */
#define EVSYS_INTSTATUS_CHINT0_Pos 0 /**< (EVSYS_INTSTATUS) Channel 0 Pending Interrupt Position */
#define EVSYS_INTSTATUS_CHINT0_Msk (_U_(0x1) << EVSYS_INTSTATUS_CHINT0_Pos) /**< (EVSYS_INTSTATUS) Channel 0 Pending Interrupt Mask */
#define EVSYS_INTSTATUS_CHINT0 EVSYS_INTSTATUS_CHINT0_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_INTSTATUS_CHINT0_Msk instead */
#define EVSYS_INTSTATUS_CHINT1_Pos 1 /**< (EVSYS_INTSTATUS) Channel 1 Pending Interrupt Position */
#define EVSYS_INTSTATUS_CHINT1_Msk (_U_(0x1) << EVSYS_INTSTATUS_CHINT1_Pos) /**< (EVSYS_INTSTATUS) Channel 1 Pending Interrupt Mask */
#define EVSYS_INTSTATUS_CHINT1 EVSYS_INTSTATUS_CHINT1_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_INTSTATUS_CHINT1_Msk instead */
#define EVSYS_INTSTATUS_CHINT2_Pos 2 /**< (EVSYS_INTSTATUS) Channel 2 Pending Interrupt Position */
#define EVSYS_INTSTATUS_CHINT2_Msk (_U_(0x1) << EVSYS_INTSTATUS_CHINT2_Pos) /**< (EVSYS_INTSTATUS) Channel 2 Pending Interrupt Mask */
#define EVSYS_INTSTATUS_CHINT2 EVSYS_INTSTATUS_CHINT2_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_INTSTATUS_CHINT2_Msk instead */
#define EVSYS_INTSTATUS_CHINT3_Pos 3 /**< (EVSYS_INTSTATUS) Channel 3 Pending Interrupt Position */
#define EVSYS_INTSTATUS_CHINT3_Msk (_U_(0x1) << EVSYS_INTSTATUS_CHINT3_Pos) /**< (EVSYS_INTSTATUS) Channel 3 Pending Interrupt Mask */
#define EVSYS_INTSTATUS_CHINT3 EVSYS_INTSTATUS_CHINT3_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_INTSTATUS_CHINT3_Msk instead */
#define EVSYS_INTSTATUS_MASK _U_(0x0F) /**< \deprecated (EVSYS_INTSTATUS) Register MASK (Use EVSYS_INTSTATUS_Msk instead) */
#define EVSYS_INTSTATUS_Msk _U_(0x0F) /**< (EVSYS_INTSTATUS) Register Mask */
#define EVSYS_INTSTATUS_CHINT_Pos 0 /**< (EVSYS_INTSTATUS Position) Channel 3 Pending Interrupt */
#define EVSYS_INTSTATUS_CHINT_Msk (_U_(0xF) << EVSYS_INTSTATUS_CHINT_Pos) /**< (EVSYS_INTSTATUS Mask) CHINT */
#define EVSYS_INTSTATUS_CHINT(value) (EVSYS_INTSTATUS_CHINT_Msk & ((value) << EVSYS_INTSTATUS_CHINT_Pos))
/* -------- EVSYS_BUSYCH : (EVSYS Offset: 0x18) (R/ 32) Busy Channels -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t BUSYCH0:1; /**< bit: 0 Busy Channel 0 */
uint32_t BUSYCH1:1; /**< bit: 1 Busy Channel 1 */
uint32_t BUSYCH2:1; /**< bit: 2 Busy Channel 2 */
uint32_t BUSYCH3:1; /**< bit: 3 Busy Channel 3 */
uint32_t :28; /**< bit: 4..31 Reserved */
} bit; /**< Structure used for bit access */
struct {
uint32_t BUSYCH:4; /**< bit: 0..3 Busy Channel 3 */
uint32_t :28; /**< bit: 4..31 Reserved */
} vec; /**< Structure used for vec access */
uint32_t reg; /**< Type used for register access */
} EVSYS_BUSYCH_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define EVSYS_BUSYCH_OFFSET (0x18) /**< (EVSYS_BUSYCH) Busy Channels Offset */
#define EVSYS_BUSYCH_RESETVALUE _U_(0x00) /**< (EVSYS_BUSYCH) Busy Channels Reset Value */
#define EVSYS_BUSYCH_BUSYCH0_Pos 0 /**< (EVSYS_BUSYCH) Busy Channel 0 Position */
#define EVSYS_BUSYCH_BUSYCH0_Msk (_U_(0x1) << EVSYS_BUSYCH_BUSYCH0_Pos) /**< (EVSYS_BUSYCH) Busy Channel 0 Mask */
#define EVSYS_BUSYCH_BUSYCH0 EVSYS_BUSYCH_BUSYCH0_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_BUSYCH_BUSYCH0_Msk instead */
#define EVSYS_BUSYCH_BUSYCH1_Pos 1 /**< (EVSYS_BUSYCH) Busy Channel 1 Position */
#define EVSYS_BUSYCH_BUSYCH1_Msk (_U_(0x1) << EVSYS_BUSYCH_BUSYCH1_Pos) /**< (EVSYS_BUSYCH) Busy Channel 1 Mask */
#define EVSYS_BUSYCH_BUSYCH1 EVSYS_BUSYCH_BUSYCH1_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_BUSYCH_BUSYCH1_Msk instead */
#define EVSYS_BUSYCH_BUSYCH2_Pos 2 /**< (EVSYS_BUSYCH) Busy Channel 2 Position */
#define EVSYS_BUSYCH_BUSYCH2_Msk (_U_(0x1) << EVSYS_BUSYCH_BUSYCH2_Pos) /**< (EVSYS_BUSYCH) Busy Channel 2 Mask */
#define EVSYS_BUSYCH_BUSYCH2 EVSYS_BUSYCH_BUSYCH2_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_BUSYCH_BUSYCH2_Msk instead */
#define EVSYS_BUSYCH_BUSYCH3_Pos 3 /**< (EVSYS_BUSYCH) Busy Channel 3 Position */
#define EVSYS_BUSYCH_BUSYCH3_Msk (_U_(0x1) << EVSYS_BUSYCH_BUSYCH3_Pos) /**< (EVSYS_BUSYCH) Busy Channel 3 Mask */
#define EVSYS_BUSYCH_BUSYCH3 EVSYS_BUSYCH_BUSYCH3_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_BUSYCH_BUSYCH3_Msk instead */
#define EVSYS_BUSYCH_MASK _U_(0x0F) /**< \deprecated (EVSYS_BUSYCH) Register MASK (Use EVSYS_BUSYCH_Msk instead) */
#define EVSYS_BUSYCH_Msk _U_(0x0F) /**< (EVSYS_BUSYCH) Register Mask */
#define EVSYS_BUSYCH_BUSYCH_Pos 0 /**< (EVSYS_BUSYCH Position) Busy Channel 3 */
#define EVSYS_BUSYCH_BUSYCH_Msk (_U_(0xF) << EVSYS_BUSYCH_BUSYCH_Pos) /**< (EVSYS_BUSYCH Mask) BUSYCH */
#define EVSYS_BUSYCH_BUSYCH(value) (EVSYS_BUSYCH_BUSYCH_Msk & ((value) << EVSYS_BUSYCH_BUSYCH_Pos))
/* -------- EVSYS_READYUSR : (EVSYS Offset: 0x1c) (R/ 32) Ready Users -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t READYUSR0:1; /**< bit: 0 Ready User for Channel 0 */
uint32_t READYUSR1:1; /**< bit: 1 Ready User for Channel 1 */
uint32_t READYUSR2:1; /**< bit: 2 Ready User for Channel 2 */
uint32_t READYUSR3:1; /**< bit: 3 Ready User for Channel 3 */
uint32_t :28; /**< bit: 4..31 Reserved */
} bit; /**< Structure used for bit access */
struct {
uint32_t READYUSR:4; /**< bit: 0..3 Ready User for Channel 3 */
uint32_t :28; /**< bit: 4..31 Reserved */
} vec; /**< Structure used for vec access */
uint32_t reg; /**< Type used for register access */
} EVSYS_READYUSR_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define EVSYS_READYUSR_OFFSET (0x1C) /**< (EVSYS_READYUSR) Ready Users Offset */
#define EVSYS_READYUSR_RESETVALUE _U_(0xFFFFFFFF) /**< (EVSYS_READYUSR) Ready Users Reset Value */
#define EVSYS_READYUSR_READYUSR0_Pos 0 /**< (EVSYS_READYUSR) Ready User for Channel 0 Position */
#define EVSYS_READYUSR_READYUSR0_Msk (_U_(0x1) << EVSYS_READYUSR_READYUSR0_Pos) /**< (EVSYS_READYUSR) Ready User for Channel 0 Mask */
#define EVSYS_READYUSR_READYUSR0 EVSYS_READYUSR_READYUSR0_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_READYUSR_READYUSR0_Msk instead */
#define EVSYS_READYUSR_READYUSR1_Pos 1 /**< (EVSYS_READYUSR) Ready User for Channel 1 Position */
#define EVSYS_READYUSR_READYUSR1_Msk (_U_(0x1) << EVSYS_READYUSR_READYUSR1_Pos) /**< (EVSYS_READYUSR) Ready User for Channel 1 Mask */
#define EVSYS_READYUSR_READYUSR1 EVSYS_READYUSR_READYUSR1_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_READYUSR_READYUSR1_Msk instead */
#define EVSYS_READYUSR_READYUSR2_Pos 2 /**< (EVSYS_READYUSR) Ready User for Channel 2 Position */
#define EVSYS_READYUSR_READYUSR2_Msk (_U_(0x1) << EVSYS_READYUSR_READYUSR2_Pos) /**< (EVSYS_READYUSR) Ready User for Channel 2 Mask */
#define EVSYS_READYUSR_READYUSR2 EVSYS_READYUSR_READYUSR2_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_READYUSR_READYUSR2_Msk instead */
#define EVSYS_READYUSR_READYUSR3_Pos 3 /**< (EVSYS_READYUSR) Ready User for Channel 3 Position */
#define EVSYS_READYUSR_READYUSR3_Msk (_U_(0x1) << EVSYS_READYUSR_READYUSR3_Pos) /**< (EVSYS_READYUSR) Ready User for Channel 3 Mask */
#define EVSYS_READYUSR_READYUSR3 EVSYS_READYUSR_READYUSR3_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_READYUSR_READYUSR3_Msk instead */
#define EVSYS_READYUSR_MASK _U_(0x0F) /**< \deprecated (EVSYS_READYUSR) Register MASK (Use EVSYS_READYUSR_Msk instead) */
#define EVSYS_READYUSR_Msk _U_(0x0F) /**< (EVSYS_READYUSR) Register Mask */
#define EVSYS_READYUSR_READYUSR_Pos 0 /**< (EVSYS_READYUSR Position) Ready User for Channel 3 */
#define EVSYS_READYUSR_READYUSR_Msk (_U_(0xF) << EVSYS_READYUSR_READYUSR_Pos) /**< (EVSYS_READYUSR Mask) READYUSR */
#define EVSYS_READYUSR_READYUSR(value) (EVSYS_READYUSR_READYUSR_Msk & ((value) << EVSYS_READYUSR_READYUSR_Pos))
/* -------- EVSYS_USER : (EVSYS Offset: 0x120) (R/W 8) User Multiplexer n -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t CHANNEL:4; /**< bit: 0..3 Channel Event Selection */
uint8_t :4; /**< bit: 4..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} EVSYS_USER_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define EVSYS_USER_OFFSET (0x120) /**< (EVSYS_USER) User Multiplexer n Offset */
#define EVSYS_USER_RESETVALUE _U_(0x00) /**< (EVSYS_USER) User Multiplexer n Reset Value */
#define EVSYS_USER_CHANNEL_Pos 0 /**< (EVSYS_USER) Channel Event Selection Position */
#define EVSYS_USER_CHANNEL_Msk (_U_(0xF) << EVSYS_USER_CHANNEL_Pos) /**< (EVSYS_USER) Channel Event Selection Mask */
#define EVSYS_USER_CHANNEL(value) (EVSYS_USER_CHANNEL_Msk & ((value) << EVSYS_USER_CHANNEL_Pos))
#define EVSYS_USER_MASK _U_(0x0F) /**< \deprecated (EVSYS_USER) Register MASK (Use EVSYS_USER_Msk instead) */
#define EVSYS_USER_Msk _U_(0x0F) /**< (EVSYS_USER) Register Mask */
/* -------- EVSYS_INTENCLR : (EVSYS Offset: 0x1d4) (R/W 8) Interrupt Enable Clear -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t NSCHK:1; /**< bit: 0 Non-Secure Check Interrupt Enable */
uint8_t :7; /**< bit: 1..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} EVSYS_INTENCLR_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define EVSYS_INTENCLR_OFFSET (0x1D4) /**< (EVSYS_INTENCLR) Interrupt Enable Clear Offset */
#define EVSYS_INTENCLR_RESETVALUE _U_(0x00) /**< (EVSYS_INTENCLR) Interrupt Enable Clear Reset Value */
#define EVSYS_INTENCLR_NSCHK_Pos 0 /**< (EVSYS_INTENCLR) Non-Secure Check Interrupt Enable Position */
#define EVSYS_INTENCLR_NSCHK_Msk (_U_(0x1) << EVSYS_INTENCLR_NSCHK_Pos) /**< (EVSYS_INTENCLR) Non-Secure Check Interrupt Enable Mask */
#define EVSYS_INTENCLR_NSCHK EVSYS_INTENCLR_NSCHK_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_INTENCLR_NSCHK_Msk instead */
#define EVSYS_INTENCLR_MASK _U_(0x01) /**< \deprecated (EVSYS_INTENCLR) Register MASK (Use EVSYS_INTENCLR_Msk instead) */
#define EVSYS_INTENCLR_Msk _U_(0x01) /**< (EVSYS_INTENCLR) Register Mask */
/* -------- EVSYS_INTENSET : (EVSYS Offset: 0x1d5) (R/W 8) Interrupt Enable Set -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t NSCHK:1; /**< bit: 0 Non-Secure Check Interrupt Enable */
uint8_t :7; /**< bit: 1..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} EVSYS_INTENSET_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define EVSYS_INTENSET_OFFSET (0x1D5) /**< (EVSYS_INTENSET) Interrupt Enable Set Offset */
#define EVSYS_INTENSET_RESETVALUE _U_(0x00) /**< (EVSYS_INTENSET) Interrupt Enable Set Reset Value */
#define EVSYS_INTENSET_NSCHK_Pos 0 /**< (EVSYS_INTENSET) Non-Secure Check Interrupt Enable Position */
#define EVSYS_INTENSET_NSCHK_Msk (_U_(0x1) << EVSYS_INTENSET_NSCHK_Pos) /**< (EVSYS_INTENSET) Non-Secure Check Interrupt Enable Mask */
#define EVSYS_INTENSET_NSCHK EVSYS_INTENSET_NSCHK_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_INTENSET_NSCHK_Msk instead */
#define EVSYS_INTENSET_MASK _U_(0x01) /**< \deprecated (EVSYS_INTENSET) Register MASK (Use EVSYS_INTENSET_Msk instead) */
#define EVSYS_INTENSET_Msk _U_(0x01) /**< (EVSYS_INTENSET) Register Mask */
/* -------- EVSYS_INTFLAG : (EVSYS Offset: 0x1d6) (R/W 8) Interrupt Flag Status and Clear -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union { // __I to avoid read-modify-write on write-to-clear register
struct {
__I uint8_t NSCHK:1; /**< bit: 0 Non-Secure Check */
__I uint8_t :7; /**< bit: 1..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} EVSYS_INTFLAG_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define EVSYS_INTFLAG_OFFSET (0x1D6) /**< (EVSYS_INTFLAG) Interrupt Flag Status and Clear Offset */
#define EVSYS_INTFLAG_RESETVALUE _U_(0x00) /**< (EVSYS_INTFLAG) Interrupt Flag Status and Clear Reset Value */
#define EVSYS_INTFLAG_NSCHK_Pos 0 /**< (EVSYS_INTFLAG) Non-Secure Check Position */
#define EVSYS_INTFLAG_NSCHK_Msk (_U_(0x1) << EVSYS_INTFLAG_NSCHK_Pos) /**< (EVSYS_INTFLAG) Non-Secure Check Mask */
#define EVSYS_INTFLAG_NSCHK EVSYS_INTFLAG_NSCHK_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_INTFLAG_NSCHK_Msk instead */
#define EVSYS_INTFLAG_MASK _U_(0x01) /**< \deprecated (EVSYS_INTFLAG) Register MASK (Use EVSYS_INTFLAG_Msk instead) */
#define EVSYS_INTFLAG_Msk _U_(0x01) /**< (EVSYS_INTFLAG) Register Mask */
/* -------- EVSYS_NONSECCHAN : (EVSYS Offset: 0x1d8) (R/W 32) Channels Security Attribution -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t CHANNEL0:1; /**< bit: 0 Non-Secure for Channel 0 */
uint32_t CHANNEL1:1; /**< bit: 1 Non-Secure for Channel 1 */
uint32_t CHANNEL2:1; /**< bit: 2 Non-Secure for Channel 2 */
uint32_t CHANNEL3:1; /**< bit: 3 Non-Secure for Channel 3 */
uint32_t CHANNEL4:1; /**< bit: 4 Non-Secure for Channel 4 */
uint32_t CHANNEL5:1; /**< bit: 5 Non-Secure for Channel 5 */
uint32_t CHANNEL6:1; /**< bit: 6 Non-Secure for Channel 6 */
uint32_t CHANNEL7:1; /**< bit: 7 Non-Secure for Channel 7 */
uint32_t :24; /**< bit: 8..31 Reserved */
} bit; /**< Structure used for bit access */
struct {
uint32_t CHANNEL:8; /**< bit: 0..7 Non-Secure for Channel 7 */
uint32_t :24; /**< bit: 8..31 Reserved */
} vec; /**< Structure used for vec access */
uint32_t reg; /**< Type used for register access */
} EVSYS_NONSECCHAN_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define EVSYS_NONSECCHAN_OFFSET (0x1D8) /**< (EVSYS_NONSECCHAN) Channels Security Attribution Offset */
#define EVSYS_NONSECCHAN_RESETVALUE _U_(0x00) /**< (EVSYS_NONSECCHAN) Channels Security Attribution Reset Value */
#define EVSYS_NONSECCHAN_CHANNEL0_Pos 0 /**< (EVSYS_NONSECCHAN) Non-Secure for Channel 0 Position */
#define EVSYS_NONSECCHAN_CHANNEL0_Msk (_U_(0x1) << EVSYS_NONSECCHAN_CHANNEL0_Pos) /**< (EVSYS_NONSECCHAN) Non-Secure for Channel 0 Mask */
#define EVSYS_NONSECCHAN_CHANNEL0 EVSYS_NONSECCHAN_CHANNEL0_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_NONSECCHAN_CHANNEL0_Msk instead */
#define EVSYS_NONSECCHAN_CHANNEL1_Pos 1 /**< (EVSYS_NONSECCHAN) Non-Secure for Channel 1 Position */
#define EVSYS_NONSECCHAN_CHANNEL1_Msk (_U_(0x1) << EVSYS_NONSECCHAN_CHANNEL1_Pos) /**< (EVSYS_NONSECCHAN) Non-Secure for Channel 1 Mask */
#define EVSYS_NONSECCHAN_CHANNEL1 EVSYS_NONSECCHAN_CHANNEL1_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_NONSECCHAN_CHANNEL1_Msk instead */
#define EVSYS_NONSECCHAN_CHANNEL2_Pos 2 /**< (EVSYS_NONSECCHAN) Non-Secure for Channel 2 Position */
#define EVSYS_NONSECCHAN_CHANNEL2_Msk (_U_(0x1) << EVSYS_NONSECCHAN_CHANNEL2_Pos) /**< (EVSYS_NONSECCHAN) Non-Secure for Channel 2 Mask */
#define EVSYS_NONSECCHAN_CHANNEL2 EVSYS_NONSECCHAN_CHANNEL2_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_NONSECCHAN_CHANNEL2_Msk instead */
#define EVSYS_NONSECCHAN_CHANNEL3_Pos 3 /**< (EVSYS_NONSECCHAN) Non-Secure for Channel 3 Position */
#define EVSYS_NONSECCHAN_CHANNEL3_Msk (_U_(0x1) << EVSYS_NONSECCHAN_CHANNEL3_Pos) /**< (EVSYS_NONSECCHAN) Non-Secure for Channel 3 Mask */
#define EVSYS_NONSECCHAN_CHANNEL3 EVSYS_NONSECCHAN_CHANNEL3_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_NONSECCHAN_CHANNEL3_Msk instead */
#define EVSYS_NONSECCHAN_CHANNEL4_Pos 4 /**< (EVSYS_NONSECCHAN) Non-Secure for Channel 4 Position */
#define EVSYS_NONSECCHAN_CHANNEL4_Msk (_U_(0x1) << EVSYS_NONSECCHAN_CHANNEL4_Pos) /**< (EVSYS_NONSECCHAN) Non-Secure for Channel 4 Mask */
#define EVSYS_NONSECCHAN_CHANNEL4 EVSYS_NONSECCHAN_CHANNEL4_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_NONSECCHAN_CHANNEL4_Msk instead */
#define EVSYS_NONSECCHAN_CHANNEL5_Pos 5 /**< (EVSYS_NONSECCHAN) Non-Secure for Channel 5 Position */
#define EVSYS_NONSECCHAN_CHANNEL5_Msk (_U_(0x1) << EVSYS_NONSECCHAN_CHANNEL5_Pos) /**< (EVSYS_NONSECCHAN) Non-Secure for Channel 5 Mask */
#define EVSYS_NONSECCHAN_CHANNEL5 EVSYS_NONSECCHAN_CHANNEL5_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_NONSECCHAN_CHANNEL5_Msk instead */
#define EVSYS_NONSECCHAN_CHANNEL6_Pos 6 /**< (EVSYS_NONSECCHAN) Non-Secure for Channel 6 Position */
#define EVSYS_NONSECCHAN_CHANNEL6_Msk (_U_(0x1) << EVSYS_NONSECCHAN_CHANNEL6_Pos) /**< (EVSYS_NONSECCHAN) Non-Secure for Channel 6 Mask */
#define EVSYS_NONSECCHAN_CHANNEL6 EVSYS_NONSECCHAN_CHANNEL6_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_NONSECCHAN_CHANNEL6_Msk instead */
#define EVSYS_NONSECCHAN_CHANNEL7_Pos 7 /**< (EVSYS_NONSECCHAN) Non-Secure for Channel 7 Position */
#define EVSYS_NONSECCHAN_CHANNEL7_Msk (_U_(0x1) << EVSYS_NONSECCHAN_CHANNEL7_Pos) /**< (EVSYS_NONSECCHAN) Non-Secure for Channel 7 Mask */
#define EVSYS_NONSECCHAN_CHANNEL7 EVSYS_NONSECCHAN_CHANNEL7_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_NONSECCHAN_CHANNEL7_Msk instead */
#define EVSYS_NONSECCHAN_MASK _U_(0xFF) /**< \deprecated (EVSYS_NONSECCHAN) Register MASK (Use EVSYS_NONSECCHAN_Msk instead) */
#define EVSYS_NONSECCHAN_Msk _U_(0xFF) /**< (EVSYS_NONSECCHAN) Register Mask */
#define EVSYS_NONSECCHAN_CHANNEL_Pos 0 /**< (EVSYS_NONSECCHAN Position) Non-Secure for Channel 7 */
#define EVSYS_NONSECCHAN_CHANNEL_Msk (_U_(0xFF) << EVSYS_NONSECCHAN_CHANNEL_Pos) /**< (EVSYS_NONSECCHAN Mask) CHANNEL */
#define EVSYS_NONSECCHAN_CHANNEL(value) (EVSYS_NONSECCHAN_CHANNEL_Msk & ((value) << EVSYS_NONSECCHAN_CHANNEL_Pos))
/* -------- EVSYS_NSCHKCHAN : (EVSYS Offset: 0x1dc) (R/W 32) Non-Secure Channels Check -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t CHANNEL0:1; /**< bit: 0 Channel 0 to be checked as non-secured */
uint32_t CHANNEL1:1; /**< bit: 1 Channel 1 to be checked as non-secured */
uint32_t CHANNEL2:1; /**< bit: 2 Channel 2 to be checked as non-secured */
uint32_t CHANNEL3:1; /**< bit: 3 Channel 3 to be checked as non-secured */
uint32_t CHANNEL4:1; /**< bit: 4 Channel 4 to be checked as non-secured */
uint32_t CHANNEL5:1; /**< bit: 5 Channel 5 to be checked as non-secured */
uint32_t CHANNEL6:1; /**< bit: 6 Channel 6 to be checked as non-secured */
uint32_t CHANNEL7:1; /**< bit: 7 Channel 7 to be checked as non-secured */
uint32_t :24; /**< bit: 8..31 Reserved */
} bit; /**< Structure used for bit access */
struct {
uint32_t CHANNEL:8; /**< bit: 0..7 Channel 7 to be checked as non-secured */
uint32_t :24; /**< bit: 8..31 Reserved */
} vec; /**< Structure used for vec access */
uint32_t reg; /**< Type used for register access */
} EVSYS_NSCHKCHAN_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define EVSYS_NSCHKCHAN_OFFSET (0x1DC) /**< (EVSYS_NSCHKCHAN) Non-Secure Channels Check Offset */
#define EVSYS_NSCHKCHAN_RESETVALUE _U_(0x00) /**< (EVSYS_NSCHKCHAN) Non-Secure Channels Check Reset Value */
#define EVSYS_NSCHKCHAN_CHANNEL0_Pos 0 /**< (EVSYS_NSCHKCHAN) Channel 0 to be checked as non-secured Position */
#define EVSYS_NSCHKCHAN_CHANNEL0_Msk (_U_(0x1) << EVSYS_NSCHKCHAN_CHANNEL0_Pos) /**< (EVSYS_NSCHKCHAN) Channel 0 to be checked as non-secured Mask */
#define EVSYS_NSCHKCHAN_CHANNEL0 EVSYS_NSCHKCHAN_CHANNEL0_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_NSCHKCHAN_CHANNEL0_Msk instead */
#define EVSYS_NSCHKCHAN_CHANNEL1_Pos 1 /**< (EVSYS_NSCHKCHAN) Channel 1 to be checked as non-secured Position */
#define EVSYS_NSCHKCHAN_CHANNEL1_Msk (_U_(0x1) << EVSYS_NSCHKCHAN_CHANNEL1_Pos) /**< (EVSYS_NSCHKCHAN) Channel 1 to be checked as non-secured Mask */
#define EVSYS_NSCHKCHAN_CHANNEL1 EVSYS_NSCHKCHAN_CHANNEL1_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_NSCHKCHAN_CHANNEL1_Msk instead */
#define EVSYS_NSCHKCHAN_CHANNEL2_Pos 2 /**< (EVSYS_NSCHKCHAN) Channel 2 to be checked as non-secured Position */
#define EVSYS_NSCHKCHAN_CHANNEL2_Msk (_U_(0x1) << EVSYS_NSCHKCHAN_CHANNEL2_Pos) /**< (EVSYS_NSCHKCHAN) Channel 2 to be checked as non-secured Mask */
#define EVSYS_NSCHKCHAN_CHANNEL2 EVSYS_NSCHKCHAN_CHANNEL2_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_NSCHKCHAN_CHANNEL2_Msk instead */
#define EVSYS_NSCHKCHAN_CHANNEL3_Pos 3 /**< (EVSYS_NSCHKCHAN) Channel 3 to be checked as non-secured Position */
#define EVSYS_NSCHKCHAN_CHANNEL3_Msk (_U_(0x1) << EVSYS_NSCHKCHAN_CHANNEL3_Pos) /**< (EVSYS_NSCHKCHAN) Channel 3 to be checked as non-secured Mask */
#define EVSYS_NSCHKCHAN_CHANNEL3 EVSYS_NSCHKCHAN_CHANNEL3_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_NSCHKCHAN_CHANNEL3_Msk instead */
#define EVSYS_NSCHKCHAN_CHANNEL4_Pos 4 /**< (EVSYS_NSCHKCHAN) Channel 4 to be checked as non-secured Position */
#define EVSYS_NSCHKCHAN_CHANNEL4_Msk (_U_(0x1) << EVSYS_NSCHKCHAN_CHANNEL4_Pos) /**< (EVSYS_NSCHKCHAN) Channel 4 to be checked as non-secured Mask */
#define EVSYS_NSCHKCHAN_CHANNEL4 EVSYS_NSCHKCHAN_CHANNEL4_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_NSCHKCHAN_CHANNEL4_Msk instead */
#define EVSYS_NSCHKCHAN_CHANNEL5_Pos 5 /**< (EVSYS_NSCHKCHAN) Channel 5 to be checked as non-secured Position */
#define EVSYS_NSCHKCHAN_CHANNEL5_Msk (_U_(0x1) << EVSYS_NSCHKCHAN_CHANNEL5_Pos) /**< (EVSYS_NSCHKCHAN) Channel 5 to be checked as non-secured Mask */
#define EVSYS_NSCHKCHAN_CHANNEL5 EVSYS_NSCHKCHAN_CHANNEL5_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_NSCHKCHAN_CHANNEL5_Msk instead */
#define EVSYS_NSCHKCHAN_CHANNEL6_Pos 6 /**< (EVSYS_NSCHKCHAN) Channel 6 to be checked as non-secured Position */
#define EVSYS_NSCHKCHAN_CHANNEL6_Msk (_U_(0x1) << EVSYS_NSCHKCHAN_CHANNEL6_Pos) /**< (EVSYS_NSCHKCHAN) Channel 6 to be checked as non-secured Mask */
#define EVSYS_NSCHKCHAN_CHANNEL6 EVSYS_NSCHKCHAN_CHANNEL6_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_NSCHKCHAN_CHANNEL6_Msk instead */
#define EVSYS_NSCHKCHAN_CHANNEL7_Pos 7 /**< (EVSYS_NSCHKCHAN) Channel 7 to be checked as non-secured Position */
#define EVSYS_NSCHKCHAN_CHANNEL7_Msk (_U_(0x1) << EVSYS_NSCHKCHAN_CHANNEL7_Pos) /**< (EVSYS_NSCHKCHAN) Channel 7 to be checked as non-secured Mask */
#define EVSYS_NSCHKCHAN_CHANNEL7 EVSYS_NSCHKCHAN_CHANNEL7_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_NSCHKCHAN_CHANNEL7_Msk instead */
#define EVSYS_NSCHKCHAN_MASK _U_(0xFF) /**< \deprecated (EVSYS_NSCHKCHAN) Register MASK (Use EVSYS_NSCHKCHAN_Msk instead) */
#define EVSYS_NSCHKCHAN_Msk _U_(0xFF) /**< (EVSYS_NSCHKCHAN) Register Mask */
#define EVSYS_NSCHKCHAN_CHANNEL_Pos 0 /**< (EVSYS_NSCHKCHAN Position) Channel 7 to be checked as non-secured */
#define EVSYS_NSCHKCHAN_CHANNEL_Msk (_U_(0xFF) << EVSYS_NSCHKCHAN_CHANNEL_Pos) /**< (EVSYS_NSCHKCHAN Mask) CHANNEL */
#define EVSYS_NSCHKCHAN_CHANNEL(value) (EVSYS_NSCHKCHAN_CHANNEL_Msk & ((value) << EVSYS_NSCHKCHAN_CHANNEL_Pos))
/* -------- EVSYS_NONSECUSER : (EVSYS Offset: 0x1e0) (R/W 32) Users Security Attribution -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t USER0:1; /**< bit: 0 Non-Secure for User 0 */
uint32_t USER1:1; /**< bit: 1 Non-Secure for User 1 */
uint32_t USER2:1; /**< bit: 2 Non-Secure for User 2 */
uint32_t USER3:1; /**< bit: 3 Non-Secure for User 3 */
uint32_t USER4:1; /**< bit: 4 Non-Secure for User 4 */
uint32_t USER5:1; /**< bit: 5 Non-Secure for User 5 */
uint32_t USER6:1; /**< bit: 6 Non-Secure for User 6 */
uint32_t USER7:1; /**< bit: 7 Non-Secure for User 7 */
uint32_t USER8:1; /**< bit: 8 Non-Secure for User 8 */
uint32_t USER9:1; /**< bit: 9 Non-Secure for User 9 */
uint32_t USER10:1; /**< bit: 10 Non-Secure for User 10 */
uint32_t USER11:1; /**< bit: 11 Non-Secure for User 11 */
uint32_t USER12:1; /**< bit: 12 Non-Secure for User 12 */
uint32_t USER13:1; /**< bit: 13 Non-Secure for User 13 */
uint32_t USER14:1; /**< bit: 14 Non-Secure for User 14 */
uint32_t USER15:1; /**< bit: 15 Non-Secure for User 15 */
uint32_t USER16:1; /**< bit: 16 Non-Secure for User 16 */
uint32_t USER17:1; /**< bit: 17 Non-Secure for User 17 */
uint32_t USER18:1; /**< bit: 18 Non-Secure for User 18 */
uint32_t USER19:1; /**< bit: 19 Non-Secure for User 19 */
uint32_t USER20:1; /**< bit: 20 Non-Secure for User 20 */
uint32_t USER21:1; /**< bit: 21 Non-Secure for User 21 */
uint32_t USER22:1; /**< bit: 22 Non-Secure for User 22 */
uint32_t :9; /**< bit: 23..31 Reserved */
} bit; /**< Structure used for bit access */
struct {
uint32_t USER:23; /**< bit: 0..22 Non-Secure for User 22 */
uint32_t :9; /**< bit: 23..31 Reserved */
} vec; /**< Structure used for vec access */
uint32_t reg; /**< Type used for register access */
} EVSYS_NONSECUSER_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define EVSYS_NONSECUSER_OFFSET (0x1E0) /**< (EVSYS_NONSECUSER) Users Security Attribution Offset */
#define EVSYS_NONSECUSER_RESETVALUE _U_(0x00) /**< (EVSYS_NONSECUSER) Users Security Attribution Reset Value */
#define EVSYS_NONSECUSER_USER0_Pos 0 /**< (EVSYS_NONSECUSER) Non-Secure for User 0 Position */
#define EVSYS_NONSECUSER_USER0_Msk (_U_(0x1) << EVSYS_NONSECUSER_USER0_Pos) /**< (EVSYS_NONSECUSER) Non-Secure for User 0 Mask */
#define EVSYS_NONSECUSER_USER0 EVSYS_NONSECUSER_USER0_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_NONSECUSER_USER0_Msk instead */
#define EVSYS_NONSECUSER_USER1_Pos 1 /**< (EVSYS_NONSECUSER) Non-Secure for User 1 Position */
#define EVSYS_NONSECUSER_USER1_Msk (_U_(0x1) << EVSYS_NONSECUSER_USER1_Pos) /**< (EVSYS_NONSECUSER) Non-Secure for User 1 Mask */
#define EVSYS_NONSECUSER_USER1 EVSYS_NONSECUSER_USER1_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_NONSECUSER_USER1_Msk instead */
#define EVSYS_NONSECUSER_USER2_Pos 2 /**< (EVSYS_NONSECUSER) Non-Secure for User 2 Position */
#define EVSYS_NONSECUSER_USER2_Msk (_U_(0x1) << EVSYS_NONSECUSER_USER2_Pos) /**< (EVSYS_NONSECUSER) Non-Secure for User 2 Mask */
#define EVSYS_NONSECUSER_USER2 EVSYS_NONSECUSER_USER2_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_NONSECUSER_USER2_Msk instead */
#define EVSYS_NONSECUSER_USER3_Pos 3 /**< (EVSYS_NONSECUSER) Non-Secure for User 3 Position */
#define EVSYS_NONSECUSER_USER3_Msk (_U_(0x1) << EVSYS_NONSECUSER_USER3_Pos) /**< (EVSYS_NONSECUSER) Non-Secure for User 3 Mask */
#define EVSYS_NONSECUSER_USER3 EVSYS_NONSECUSER_USER3_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_NONSECUSER_USER3_Msk instead */
#define EVSYS_NONSECUSER_USER4_Pos 4 /**< (EVSYS_NONSECUSER) Non-Secure for User 4 Position */
#define EVSYS_NONSECUSER_USER4_Msk (_U_(0x1) << EVSYS_NONSECUSER_USER4_Pos) /**< (EVSYS_NONSECUSER) Non-Secure for User 4 Mask */
#define EVSYS_NONSECUSER_USER4 EVSYS_NONSECUSER_USER4_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_NONSECUSER_USER4_Msk instead */
#define EVSYS_NONSECUSER_USER5_Pos 5 /**< (EVSYS_NONSECUSER) Non-Secure for User 5 Position */
#define EVSYS_NONSECUSER_USER5_Msk (_U_(0x1) << EVSYS_NONSECUSER_USER5_Pos) /**< (EVSYS_NONSECUSER) Non-Secure for User 5 Mask */
#define EVSYS_NONSECUSER_USER5 EVSYS_NONSECUSER_USER5_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_NONSECUSER_USER5_Msk instead */
#define EVSYS_NONSECUSER_USER6_Pos 6 /**< (EVSYS_NONSECUSER) Non-Secure for User 6 Position */
#define EVSYS_NONSECUSER_USER6_Msk (_U_(0x1) << EVSYS_NONSECUSER_USER6_Pos) /**< (EVSYS_NONSECUSER) Non-Secure for User 6 Mask */
#define EVSYS_NONSECUSER_USER6 EVSYS_NONSECUSER_USER6_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_NONSECUSER_USER6_Msk instead */
#define EVSYS_NONSECUSER_USER7_Pos 7 /**< (EVSYS_NONSECUSER) Non-Secure for User 7 Position */
#define EVSYS_NONSECUSER_USER7_Msk (_U_(0x1) << EVSYS_NONSECUSER_USER7_Pos) /**< (EVSYS_NONSECUSER) Non-Secure for User 7 Mask */
#define EVSYS_NONSECUSER_USER7 EVSYS_NONSECUSER_USER7_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_NONSECUSER_USER7_Msk instead */
#define EVSYS_NONSECUSER_USER8_Pos 8 /**< (EVSYS_NONSECUSER) Non-Secure for User 8 Position */
#define EVSYS_NONSECUSER_USER8_Msk (_U_(0x1) << EVSYS_NONSECUSER_USER8_Pos) /**< (EVSYS_NONSECUSER) Non-Secure for User 8 Mask */
#define EVSYS_NONSECUSER_USER8 EVSYS_NONSECUSER_USER8_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_NONSECUSER_USER8_Msk instead */
#define EVSYS_NONSECUSER_USER9_Pos 9 /**< (EVSYS_NONSECUSER) Non-Secure for User 9 Position */
#define EVSYS_NONSECUSER_USER9_Msk (_U_(0x1) << EVSYS_NONSECUSER_USER9_Pos) /**< (EVSYS_NONSECUSER) Non-Secure for User 9 Mask */
#define EVSYS_NONSECUSER_USER9 EVSYS_NONSECUSER_USER9_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_NONSECUSER_USER9_Msk instead */
#define EVSYS_NONSECUSER_USER10_Pos 10 /**< (EVSYS_NONSECUSER) Non-Secure for User 10 Position */
#define EVSYS_NONSECUSER_USER10_Msk (_U_(0x1) << EVSYS_NONSECUSER_USER10_Pos) /**< (EVSYS_NONSECUSER) Non-Secure for User 10 Mask */
#define EVSYS_NONSECUSER_USER10 EVSYS_NONSECUSER_USER10_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_NONSECUSER_USER10_Msk instead */
#define EVSYS_NONSECUSER_USER11_Pos 11 /**< (EVSYS_NONSECUSER) Non-Secure for User 11 Position */
#define EVSYS_NONSECUSER_USER11_Msk (_U_(0x1) << EVSYS_NONSECUSER_USER11_Pos) /**< (EVSYS_NONSECUSER) Non-Secure for User 11 Mask */
#define EVSYS_NONSECUSER_USER11 EVSYS_NONSECUSER_USER11_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_NONSECUSER_USER11_Msk instead */
#define EVSYS_NONSECUSER_USER12_Pos 12 /**< (EVSYS_NONSECUSER) Non-Secure for User 12 Position */
#define EVSYS_NONSECUSER_USER12_Msk (_U_(0x1) << EVSYS_NONSECUSER_USER12_Pos) /**< (EVSYS_NONSECUSER) Non-Secure for User 12 Mask */
#define EVSYS_NONSECUSER_USER12 EVSYS_NONSECUSER_USER12_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_NONSECUSER_USER12_Msk instead */
#define EVSYS_NONSECUSER_USER13_Pos 13 /**< (EVSYS_NONSECUSER) Non-Secure for User 13 Position */
#define EVSYS_NONSECUSER_USER13_Msk (_U_(0x1) << EVSYS_NONSECUSER_USER13_Pos) /**< (EVSYS_NONSECUSER) Non-Secure for User 13 Mask */
#define EVSYS_NONSECUSER_USER13 EVSYS_NONSECUSER_USER13_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_NONSECUSER_USER13_Msk instead */
#define EVSYS_NONSECUSER_USER14_Pos 14 /**< (EVSYS_NONSECUSER) Non-Secure for User 14 Position */
#define EVSYS_NONSECUSER_USER14_Msk (_U_(0x1) << EVSYS_NONSECUSER_USER14_Pos) /**< (EVSYS_NONSECUSER) Non-Secure for User 14 Mask */
#define EVSYS_NONSECUSER_USER14 EVSYS_NONSECUSER_USER14_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_NONSECUSER_USER14_Msk instead */
#define EVSYS_NONSECUSER_USER15_Pos 15 /**< (EVSYS_NONSECUSER) Non-Secure for User 15 Position */
#define EVSYS_NONSECUSER_USER15_Msk (_U_(0x1) << EVSYS_NONSECUSER_USER15_Pos) /**< (EVSYS_NONSECUSER) Non-Secure for User 15 Mask */
#define EVSYS_NONSECUSER_USER15 EVSYS_NONSECUSER_USER15_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_NONSECUSER_USER15_Msk instead */
#define EVSYS_NONSECUSER_USER16_Pos 16 /**< (EVSYS_NONSECUSER) Non-Secure for User 16 Position */
#define EVSYS_NONSECUSER_USER16_Msk (_U_(0x1) << EVSYS_NONSECUSER_USER16_Pos) /**< (EVSYS_NONSECUSER) Non-Secure for User 16 Mask */
#define EVSYS_NONSECUSER_USER16 EVSYS_NONSECUSER_USER16_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_NONSECUSER_USER16_Msk instead */
#define EVSYS_NONSECUSER_USER17_Pos 17 /**< (EVSYS_NONSECUSER) Non-Secure for User 17 Position */
#define EVSYS_NONSECUSER_USER17_Msk (_U_(0x1) << EVSYS_NONSECUSER_USER17_Pos) /**< (EVSYS_NONSECUSER) Non-Secure for User 17 Mask */
#define EVSYS_NONSECUSER_USER17 EVSYS_NONSECUSER_USER17_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_NONSECUSER_USER17_Msk instead */
#define EVSYS_NONSECUSER_USER18_Pos 18 /**< (EVSYS_NONSECUSER) Non-Secure for User 18 Position */
#define EVSYS_NONSECUSER_USER18_Msk (_U_(0x1) << EVSYS_NONSECUSER_USER18_Pos) /**< (EVSYS_NONSECUSER) Non-Secure for User 18 Mask */
#define EVSYS_NONSECUSER_USER18 EVSYS_NONSECUSER_USER18_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_NONSECUSER_USER18_Msk instead */
#define EVSYS_NONSECUSER_USER19_Pos 19 /**< (EVSYS_NONSECUSER) Non-Secure for User 19 Position */
#define EVSYS_NONSECUSER_USER19_Msk (_U_(0x1) << EVSYS_NONSECUSER_USER19_Pos) /**< (EVSYS_NONSECUSER) Non-Secure for User 19 Mask */
#define EVSYS_NONSECUSER_USER19 EVSYS_NONSECUSER_USER19_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_NONSECUSER_USER19_Msk instead */
#define EVSYS_NONSECUSER_USER20_Pos 20 /**< (EVSYS_NONSECUSER) Non-Secure for User 20 Position */
#define EVSYS_NONSECUSER_USER20_Msk (_U_(0x1) << EVSYS_NONSECUSER_USER20_Pos) /**< (EVSYS_NONSECUSER) Non-Secure for User 20 Mask */
#define EVSYS_NONSECUSER_USER20 EVSYS_NONSECUSER_USER20_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_NONSECUSER_USER20_Msk instead */
#define EVSYS_NONSECUSER_USER21_Pos 21 /**< (EVSYS_NONSECUSER) Non-Secure for User 21 Position */
#define EVSYS_NONSECUSER_USER21_Msk (_U_(0x1) << EVSYS_NONSECUSER_USER21_Pos) /**< (EVSYS_NONSECUSER) Non-Secure for User 21 Mask */
#define EVSYS_NONSECUSER_USER21 EVSYS_NONSECUSER_USER21_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_NONSECUSER_USER21_Msk instead */
#define EVSYS_NONSECUSER_USER22_Pos 22 /**< (EVSYS_NONSECUSER) Non-Secure for User 22 Position */
#define EVSYS_NONSECUSER_USER22_Msk (_U_(0x1) << EVSYS_NONSECUSER_USER22_Pos) /**< (EVSYS_NONSECUSER) Non-Secure for User 22 Mask */
#define EVSYS_NONSECUSER_USER22 EVSYS_NONSECUSER_USER22_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_NONSECUSER_USER22_Msk instead */
#define EVSYS_NONSECUSER_MASK _U_(0x7FFFFF) /**< \deprecated (EVSYS_NONSECUSER) Register MASK (Use EVSYS_NONSECUSER_Msk instead) */
#define EVSYS_NONSECUSER_Msk _U_(0x7FFFFF) /**< (EVSYS_NONSECUSER) Register Mask */
#define EVSYS_NONSECUSER_USER_Pos 0 /**< (EVSYS_NONSECUSER Position) Non-Secure for User 22 */
#define EVSYS_NONSECUSER_USER_Msk (_U_(0x7FFFFF) << EVSYS_NONSECUSER_USER_Pos) /**< (EVSYS_NONSECUSER Mask) USER */
#define EVSYS_NONSECUSER_USER(value) (EVSYS_NONSECUSER_USER_Msk & ((value) << EVSYS_NONSECUSER_USER_Pos))
/* -------- EVSYS_NSCHKUSER : (EVSYS Offset: 0x1f0) (R/W 32) Non-Secure Users Check -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t USER0:1; /**< bit: 0 User 0 to be checked as non-secured */
uint32_t USER1:1; /**< bit: 1 User 1 to be checked as non-secured */
uint32_t USER2:1; /**< bit: 2 User 2 to be checked as non-secured */
uint32_t USER3:1; /**< bit: 3 User 3 to be checked as non-secured */
uint32_t USER4:1; /**< bit: 4 User 4 to be checked as non-secured */
uint32_t USER5:1; /**< bit: 5 User 5 to be checked as non-secured */
uint32_t USER6:1; /**< bit: 6 User 6 to be checked as non-secured */
uint32_t USER7:1; /**< bit: 7 User 7 to be checked as non-secured */
uint32_t USER8:1; /**< bit: 8 User 8 to be checked as non-secured */
uint32_t USER9:1; /**< bit: 9 User 9 to be checked as non-secured */
uint32_t USER10:1; /**< bit: 10 User 10 to be checked as non-secured */
uint32_t USER11:1; /**< bit: 11 User 11 to be checked as non-secured */
uint32_t USER12:1; /**< bit: 12 User 12 to be checked as non-secured */
uint32_t USER13:1; /**< bit: 13 User 13 to be checked as non-secured */
uint32_t USER14:1; /**< bit: 14 User 14 to be checked as non-secured */
uint32_t USER15:1; /**< bit: 15 User 15 to be checked as non-secured */
uint32_t USER16:1; /**< bit: 16 User 16 to be checked as non-secured */
uint32_t USER17:1; /**< bit: 17 User 17 to be checked as non-secured */
uint32_t USER18:1; /**< bit: 18 User 18 to be checked as non-secured */
uint32_t USER19:1; /**< bit: 19 User 19 to be checked as non-secured */
uint32_t USER20:1; /**< bit: 20 User 20 to be checked as non-secured */
uint32_t USER21:1; /**< bit: 21 User 21 to be checked as non-secured */
uint32_t USER22:1; /**< bit: 22 User 22 to be checked as non-secured */
uint32_t :9; /**< bit: 23..31 Reserved */
} bit; /**< Structure used for bit access */
struct {
uint32_t USER:23; /**< bit: 0..22 User 22 to be checked as non-secured */
uint32_t :9; /**< bit: 23..31 Reserved */
} vec; /**< Structure used for vec access */
uint32_t reg; /**< Type used for register access */
} EVSYS_NSCHKUSER_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define EVSYS_NSCHKUSER_OFFSET (0x1F0) /**< (EVSYS_NSCHKUSER) Non-Secure Users Check Offset */
#define EVSYS_NSCHKUSER_RESETVALUE _U_(0x00) /**< (EVSYS_NSCHKUSER) Non-Secure Users Check Reset Value */
#define EVSYS_NSCHKUSER_USER0_Pos 0 /**< (EVSYS_NSCHKUSER) User 0 to be checked as non-secured Position */
#define EVSYS_NSCHKUSER_USER0_Msk (_U_(0x1) << EVSYS_NSCHKUSER_USER0_Pos) /**< (EVSYS_NSCHKUSER) User 0 to be checked as non-secured Mask */
#define EVSYS_NSCHKUSER_USER0 EVSYS_NSCHKUSER_USER0_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_NSCHKUSER_USER0_Msk instead */
#define EVSYS_NSCHKUSER_USER1_Pos 1 /**< (EVSYS_NSCHKUSER) User 1 to be checked as non-secured Position */
#define EVSYS_NSCHKUSER_USER1_Msk (_U_(0x1) << EVSYS_NSCHKUSER_USER1_Pos) /**< (EVSYS_NSCHKUSER) User 1 to be checked as non-secured Mask */
#define EVSYS_NSCHKUSER_USER1 EVSYS_NSCHKUSER_USER1_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_NSCHKUSER_USER1_Msk instead */
#define EVSYS_NSCHKUSER_USER2_Pos 2 /**< (EVSYS_NSCHKUSER) User 2 to be checked as non-secured Position */
#define EVSYS_NSCHKUSER_USER2_Msk (_U_(0x1) << EVSYS_NSCHKUSER_USER2_Pos) /**< (EVSYS_NSCHKUSER) User 2 to be checked as non-secured Mask */
#define EVSYS_NSCHKUSER_USER2 EVSYS_NSCHKUSER_USER2_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_NSCHKUSER_USER2_Msk instead */
#define EVSYS_NSCHKUSER_USER3_Pos 3 /**< (EVSYS_NSCHKUSER) User 3 to be checked as non-secured Position */
#define EVSYS_NSCHKUSER_USER3_Msk (_U_(0x1) << EVSYS_NSCHKUSER_USER3_Pos) /**< (EVSYS_NSCHKUSER) User 3 to be checked as non-secured Mask */
#define EVSYS_NSCHKUSER_USER3 EVSYS_NSCHKUSER_USER3_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_NSCHKUSER_USER3_Msk instead */
#define EVSYS_NSCHKUSER_USER4_Pos 4 /**< (EVSYS_NSCHKUSER) User 4 to be checked as non-secured Position */
#define EVSYS_NSCHKUSER_USER4_Msk (_U_(0x1) << EVSYS_NSCHKUSER_USER4_Pos) /**< (EVSYS_NSCHKUSER) User 4 to be checked as non-secured Mask */
#define EVSYS_NSCHKUSER_USER4 EVSYS_NSCHKUSER_USER4_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_NSCHKUSER_USER4_Msk instead */
#define EVSYS_NSCHKUSER_USER5_Pos 5 /**< (EVSYS_NSCHKUSER) User 5 to be checked as non-secured Position */
#define EVSYS_NSCHKUSER_USER5_Msk (_U_(0x1) << EVSYS_NSCHKUSER_USER5_Pos) /**< (EVSYS_NSCHKUSER) User 5 to be checked as non-secured Mask */
#define EVSYS_NSCHKUSER_USER5 EVSYS_NSCHKUSER_USER5_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_NSCHKUSER_USER5_Msk instead */
#define EVSYS_NSCHKUSER_USER6_Pos 6 /**< (EVSYS_NSCHKUSER) User 6 to be checked as non-secured Position */
#define EVSYS_NSCHKUSER_USER6_Msk (_U_(0x1) << EVSYS_NSCHKUSER_USER6_Pos) /**< (EVSYS_NSCHKUSER) User 6 to be checked as non-secured Mask */
#define EVSYS_NSCHKUSER_USER6 EVSYS_NSCHKUSER_USER6_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_NSCHKUSER_USER6_Msk instead */
#define EVSYS_NSCHKUSER_USER7_Pos 7 /**< (EVSYS_NSCHKUSER) User 7 to be checked as non-secured Position */
#define EVSYS_NSCHKUSER_USER7_Msk (_U_(0x1) << EVSYS_NSCHKUSER_USER7_Pos) /**< (EVSYS_NSCHKUSER) User 7 to be checked as non-secured Mask */
#define EVSYS_NSCHKUSER_USER7 EVSYS_NSCHKUSER_USER7_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_NSCHKUSER_USER7_Msk instead */
#define EVSYS_NSCHKUSER_USER8_Pos 8 /**< (EVSYS_NSCHKUSER) User 8 to be checked as non-secured Position */
#define EVSYS_NSCHKUSER_USER8_Msk (_U_(0x1) << EVSYS_NSCHKUSER_USER8_Pos) /**< (EVSYS_NSCHKUSER) User 8 to be checked as non-secured Mask */
#define EVSYS_NSCHKUSER_USER8 EVSYS_NSCHKUSER_USER8_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_NSCHKUSER_USER8_Msk instead */
#define EVSYS_NSCHKUSER_USER9_Pos 9 /**< (EVSYS_NSCHKUSER) User 9 to be checked as non-secured Position */
#define EVSYS_NSCHKUSER_USER9_Msk (_U_(0x1) << EVSYS_NSCHKUSER_USER9_Pos) /**< (EVSYS_NSCHKUSER) User 9 to be checked as non-secured Mask */
#define EVSYS_NSCHKUSER_USER9 EVSYS_NSCHKUSER_USER9_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_NSCHKUSER_USER9_Msk instead */
#define EVSYS_NSCHKUSER_USER10_Pos 10 /**< (EVSYS_NSCHKUSER) User 10 to be checked as non-secured Position */
#define EVSYS_NSCHKUSER_USER10_Msk (_U_(0x1) << EVSYS_NSCHKUSER_USER10_Pos) /**< (EVSYS_NSCHKUSER) User 10 to be checked as non-secured Mask */
#define EVSYS_NSCHKUSER_USER10 EVSYS_NSCHKUSER_USER10_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_NSCHKUSER_USER10_Msk instead */
#define EVSYS_NSCHKUSER_USER11_Pos 11 /**< (EVSYS_NSCHKUSER) User 11 to be checked as non-secured Position */
#define EVSYS_NSCHKUSER_USER11_Msk (_U_(0x1) << EVSYS_NSCHKUSER_USER11_Pos) /**< (EVSYS_NSCHKUSER) User 11 to be checked as non-secured Mask */
#define EVSYS_NSCHKUSER_USER11 EVSYS_NSCHKUSER_USER11_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_NSCHKUSER_USER11_Msk instead */
#define EVSYS_NSCHKUSER_USER12_Pos 12 /**< (EVSYS_NSCHKUSER) User 12 to be checked as non-secured Position */
#define EVSYS_NSCHKUSER_USER12_Msk (_U_(0x1) << EVSYS_NSCHKUSER_USER12_Pos) /**< (EVSYS_NSCHKUSER) User 12 to be checked as non-secured Mask */
#define EVSYS_NSCHKUSER_USER12 EVSYS_NSCHKUSER_USER12_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_NSCHKUSER_USER12_Msk instead */
#define EVSYS_NSCHKUSER_USER13_Pos 13 /**< (EVSYS_NSCHKUSER) User 13 to be checked as non-secured Position */
#define EVSYS_NSCHKUSER_USER13_Msk (_U_(0x1) << EVSYS_NSCHKUSER_USER13_Pos) /**< (EVSYS_NSCHKUSER) User 13 to be checked as non-secured Mask */
#define EVSYS_NSCHKUSER_USER13 EVSYS_NSCHKUSER_USER13_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_NSCHKUSER_USER13_Msk instead */
#define EVSYS_NSCHKUSER_USER14_Pos 14 /**< (EVSYS_NSCHKUSER) User 14 to be checked as non-secured Position */
#define EVSYS_NSCHKUSER_USER14_Msk (_U_(0x1) << EVSYS_NSCHKUSER_USER14_Pos) /**< (EVSYS_NSCHKUSER) User 14 to be checked as non-secured Mask */
#define EVSYS_NSCHKUSER_USER14 EVSYS_NSCHKUSER_USER14_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_NSCHKUSER_USER14_Msk instead */
#define EVSYS_NSCHKUSER_USER15_Pos 15 /**< (EVSYS_NSCHKUSER) User 15 to be checked as non-secured Position */
#define EVSYS_NSCHKUSER_USER15_Msk (_U_(0x1) << EVSYS_NSCHKUSER_USER15_Pos) /**< (EVSYS_NSCHKUSER) User 15 to be checked as non-secured Mask */
#define EVSYS_NSCHKUSER_USER15 EVSYS_NSCHKUSER_USER15_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_NSCHKUSER_USER15_Msk instead */
#define EVSYS_NSCHKUSER_USER16_Pos 16 /**< (EVSYS_NSCHKUSER) User 16 to be checked as non-secured Position */
#define EVSYS_NSCHKUSER_USER16_Msk (_U_(0x1) << EVSYS_NSCHKUSER_USER16_Pos) /**< (EVSYS_NSCHKUSER) User 16 to be checked as non-secured Mask */
#define EVSYS_NSCHKUSER_USER16 EVSYS_NSCHKUSER_USER16_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_NSCHKUSER_USER16_Msk instead */
#define EVSYS_NSCHKUSER_USER17_Pos 17 /**< (EVSYS_NSCHKUSER) User 17 to be checked as non-secured Position */
#define EVSYS_NSCHKUSER_USER17_Msk (_U_(0x1) << EVSYS_NSCHKUSER_USER17_Pos) /**< (EVSYS_NSCHKUSER) User 17 to be checked as non-secured Mask */
#define EVSYS_NSCHKUSER_USER17 EVSYS_NSCHKUSER_USER17_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_NSCHKUSER_USER17_Msk instead */
#define EVSYS_NSCHKUSER_USER18_Pos 18 /**< (EVSYS_NSCHKUSER) User 18 to be checked as non-secured Position */
#define EVSYS_NSCHKUSER_USER18_Msk (_U_(0x1) << EVSYS_NSCHKUSER_USER18_Pos) /**< (EVSYS_NSCHKUSER) User 18 to be checked as non-secured Mask */
#define EVSYS_NSCHKUSER_USER18 EVSYS_NSCHKUSER_USER18_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_NSCHKUSER_USER18_Msk instead */
#define EVSYS_NSCHKUSER_USER19_Pos 19 /**< (EVSYS_NSCHKUSER) User 19 to be checked as non-secured Position */
#define EVSYS_NSCHKUSER_USER19_Msk (_U_(0x1) << EVSYS_NSCHKUSER_USER19_Pos) /**< (EVSYS_NSCHKUSER) User 19 to be checked as non-secured Mask */
#define EVSYS_NSCHKUSER_USER19 EVSYS_NSCHKUSER_USER19_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_NSCHKUSER_USER19_Msk instead */
#define EVSYS_NSCHKUSER_USER20_Pos 20 /**< (EVSYS_NSCHKUSER) User 20 to be checked as non-secured Position */
#define EVSYS_NSCHKUSER_USER20_Msk (_U_(0x1) << EVSYS_NSCHKUSER_USER20_Pos) /**< (EVSYS_NSCHKUSER) User 20 to be checked as non-secured Mask */
#define EVSYS_NSCHKUSER_USER20 EVSYS_NSCHKUSER_USER20_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_NSCHKUSER_USER20_Msk instead */
#define EVSYS_NSCHKUSER_USER21_Pos 21 /**< (EVSYS_NSCHKUSER) User 21 to be checked as non-secured Position */
#define EVSYS_NSCHKUSER_USER21_Msk (_U_(0x1) << EVSYS_NSCHKUSER_USER21_Pos) /**< (EVSYS_NSCHKUSER) User 21 to be checked as non-secured Mask */
#define EVSYS_NSCHKUSER_USER21 EVSYS_NSCHKUSER_USER21_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_NSCHKUSER_USER21_Msk instead */
#define EVSYS_NSCHKUSER_USER22_Pos 22 /**< (EVSYS_NSCHKUSER) User 22 to be checked as non-secured Position */
#define EVSYS_NSCHKUSER_USER22_Msk (_U_(0x1) << EVSYS_NSCHKUSER_USER22_Pos) /**< (EVSYS_NSCHKUSER) User 22 to be checked as non-secured Mask */
#define EVSYS_NSCHKUSER_USER22 EVSYS_NSCHKUSER_USER22_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use EVSYS_NSCHKUSER_USER22_Msk instead */
#define EVSYS_NSCHKUSER_MASK _U_(0x7FFFFF) /**< \deprecated (EVSYS_NSCHKUSER) Register MASK (Use EVSYS_NSCHKUSER_Msk instead) */
#define EVSYS_NSCHKUSER_Msk _U_(0x7FFFFF) /**< (EVSYS_NSCHKUSER) Register Mask */
#define EVSYS_NSCHKUSER_USER_Pos 0 /**< (EVSYS_NSCHKUSER Position) User 22 to be checked as non-secured */
#define EVSYS_NSCHKUSER_USER_Msk (_U_(0x7FFFFF) << EVSYS_NSCHKUSER_USER_Pos) /**< (EVSYS_NSCHKUSER Mask) USER */
#define EVSYS_NSCHKUSER_USER(value) (EVSYS_NSCHKUSER_USER_Msk & ((value) << EVSYS_NSCHKUSER_USER_Pos))
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
/** \brief CHANNEL hardware registers */
typedef struct {
__IO EVSYS_CHANNEL_Type CHANNEL; /**< Offset: 0x00 (R/W 32) Channel n Control */
__IO EVSYS_CHINTENCLR_Type CHINTENCLR; /**< Offset: 0x04 (R/W 8) Channel n Interrupt Enable Clear */
__IO EVSYS_CHINTENSET_Type CHINTENSET; /**< Offset: 0x05 (R/W 8) Channel n Interrupt Enable Set */
__IO EVSYS_CHINTFLAG_Type CHINTFLAG; /**< Offset: 0x06 (R/W 8) Channel n Interrupt Flag Status and Clear */
__I EVSYS_CHSTATUS_Type CHSTATUS; /**< Offset: 0x07 (R/ 8) Channel n Status */
} EvsysChannel;
/** \brief EVSYS hardware registers */
typedef struct { /* Event System Interface */
__O EVSYS_CTRLA_Type CTRLA; /**< Offset: 0x00 ( /W 8) Control */
__I uint8_t Reserved1[3];
__O EVSYS_SWEVT_Type SWEVT; /**< Offset: 0x04 ( /W 32) Software Event */
__IO EVSYS_PRICTRL_Type PRICTRL; /**< Offset: 0x08 (R/W 8) Priority Control */
__I uint8_t Reserved2[7];
__IO EVSYS_INTPEND_Type INTPEND; /**< Offset: 0x10 (R/W 16) Channel Pending Interrupt */
__I uint8_t Reserved3[2];
__I EVSYS_INTSTATUS_Type INTSTATUS; /**< Offset: 0x14 (R/ 32) Interrupt Status */
__I EVSYS_BUSYCH_Type BUSYCH; /**< Offset: 0x18 (R/ 32) Busy Channels */
__I EVSYS_READYUSR_Type READYUSR; /**< Offset: 0x1C (R/ 32) Ready Users */
EvsysChannel Channel[8]; /**< Offset: 0x20 */
__I uint8_t Reserved4[192];
__IO EVSYS_USER_Type USER[23]; /**< Offset: 0x120 (R/W 8) User Multiplexer n */
__I uint8_t Reserved5[157];
__IO EVSYS_INTENCLR_Type INTENCLR; /**< Offset: 0x1D4 (R/W 8) Interrupt Enable Clear */
__IO EVSYS_INTENSET_Type INTENSET; /**< Offset: 0x1D5 (R/W 8) Interrupt Enable Set */
__IO EVSYS_INTFLAG_Type INTFLAG; /**< Offset: 0x1D6 (R/W 8) Interrupt Flag Status and Clear */
__I uint8_t Reserved6[1];
__IO EVSYS_NONSECCHAN_Type NONSECCHAN; /**< Offset: 0x1D8 (R/W 32) Channels Security Attribution */
__IO EVSYS_NSCHKCHAN_Type NSCHKCHAN; /**< Offset: 0x1DC (R/W 32) Non-Secure Channels Check */
__IO EVSYS_NONSECUSER_Type NONSECUSER[1]; /**< Offset: 0x1E0 (R/W 32) Users Security Attribution */
__I uint8_t Reserved7[12];
__IO EVSYS_NSCHKUSER_Type NSCHKUSER[1]; /**< Offset: 0x1F0 (R/W 32) Non-Secure Users Check */
} Evsys;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/** @} end of Event System Interface */
#endif /* _SAML10_EVSYS_COMPONENT_H_ */

View File

@ -0,0 +1,269 @@
/**
* \file
*
* \brief Component description for FREQM
*
* Copyright (c) 2018 Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* 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
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
/* file generated from device description version 2018-08-31T13:51:50Z */
#ifndef _SAML10_FREQM_COMPONENT_H_
#define _SAML10_FREQM_COMPONENT_H_
#define _SAML10_FREQM_COMPONENT_ /**< \deprecated Backward compatibility for ASF */
/** \addtogroup SAML_SAML10 Frequency Meter
* @{
*/
/* ========================================================================== */
/** SOFTWARE API DEFINITION FOR FREQM */
/* ========================================================================== */
#define FREQM_U2257 /**< (FREQM) Module ID */
#define REV_FREQM 0x210 /**< (FREQM) Module revision */
/* -------- FREQM_CTRLA : (FREQM Offset: 0x00) (R/W 8) Control A Register -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t SWRST:1; /**< bit: 0 Software Reset */
uint8_t ENABLE:1; /**< bit: 1 Enable */
uint8_t :6; /**< bit: 2..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} FREQM_CTRLA_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define FREQM_CTRLA_OFFSET (0x00) /**< (FREQM_CTRLA) Control A Register Offset */
#define FREQM_CTRLA_RESETVALUE _U_(0x00) /**< (FREQM_CTRLA) Control A Register Reset Value */
#define FREQM_CTRLA_SWRST_Pos 0 /**< (FREQM_CTRLA) Software Reset Position */
#define FREQM_CTRLA_SWRST_Msk (_U_(0x1) << FREQM_CTRLA_SWRST_Pos) /**< (FREQM_CTRLA) Software Reset Mask */
#define FREQM_CTRLA_SWRST FREQM_CTRLA_SWRST_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use FREQM_CTRLA_SWRST_Msk instead */
#define FREQM_CTRLA_ENABLE_Pos 1 /**< (FREQM_CTRLA) Enable Position */
#define FREQM_CTRLA_ENABLE_Msk (_U_(0x1) << FREQM_CTRLA_ENABLE_Pos) /**< (FREQM_CTRLA) Enable Mask */
#define FREQM_CTRLA_ENABLE FREQM_CTRLA_ENABLE_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use FREQM_CTRLA_ENABLE_Msk instead */
#define FREQM_CTRLA_MASK _U_(0x03) /**< \deprecated (FREQM_CTRLA) Register MASK (Use FREQM_CTRLA_Msk instead) */
#define FREQM_CTRLA_Msk _U_(0x03) /**< (FREQM_CTRLA) Register Mask */
/* -------- FREQM_CTRLB : (FREQM Offset: 0x01) (/W 8) Control B Register -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t START:1; /**< bit: 0 Start Measurement */
uint8_t :7; /**< bit: 1..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} FREQM_CTRLB_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define FREQM_CTRLB_OFFSET (0x01) /**< (FREQM_CTRLB) Control B Register Offset */
#define FREQM_CTRLB_RESETVALUE _U_(0x00) /**< (FREQM_CTRLB) Control B Register Reset Value */
#define FREQM_CTRLB_START_Pos 0 /**< (FREQM_CTRLB) Start Measurement Position */
#define FREQM_CTRLB_START_Msk (_U_(0x1) << FREQM_CTRLB_START_Pos) /**< (FREQM_CTRLB) Start Measurement Mask */
#define FREQM_CTRLB_START FREQM_CTRLB_START_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use FREQM_CTRLB_START_Msk instead */
#define FREQM_CTRLB_MASK _U_(0x01) /**< \deprecated (FREQM_CTRLB) Register MASK (Use FREQM_CTRLB_Msk instead) */
#define FREQM_CTRLB_Msk _U_(0x01) /**< (FREQM_CTRLB) Register Mask */
/* -------- FREQM_CFGA : (FREQM Offset: 0x02) (R/W 16) Config A register -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint16_t REFNUM:8; /**< bit: 0..7 Number of Reference Clock Cycles */
uint16_t :7; /**< bit: 8..14 Reserved */
uint16_t DIVREF:1; /**< bit: 15 Divide Reference Clock */
} bit; /**< Structure used for bit access */
uint16_t reg; /**< Type used for register access */
} FREQM_CFGA_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define FREQM_CFGA_OFFSET (0x02) /**< (FREQM_CFGA) Config A register Offset */
#define FREQM_CFGA_RESETVALUE _U_(0x00) /**< (FREQM_CFGA) Config A register Reset Value */
#define FREQM_CFGA_REFNUM_Pos 0 /**< (FREQM_CFGA) Number of Reference Clock Cycles Position */
#define FREQM_CFGA_REFNUM_Msk (_U_(0xFF) << FREQM_CFGA_REFNUM_Pos) /**< (FREQM_CFGA) Number of Reference Clock Cycles Mask */
#define FREQM_CFGA_REFNUM(value) (FREQM_CFGA_REFNUM_Msk & ((value) << FREQM_CFGA_REFNUM_Pos))
#define FREQM_CFGA_DIVREF_Pos 15 /**< (FREQM_CFGA) Divide Reference Clock Position */
#define FREQM_CFGA_DIVREF_Msk (_U_(0x1) << FREQM_CFGA_DIVREF_Pos) /**< (FREQM_CFGA) Divide Reference Clock Mask */
#define FREQM_CFGA_DIVREF FREQM_CFGA_DIVREF_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use FREQM_CFGA_DIVREF_Msk instead */
#define FREQM_CFGA_MASK _U_(0x80FF) /**< \deprecated (FREQM_CFGA) Register MASK (Use FREQM_CFGA_Msk instead) */
#define FREQM_CFGA_Msk _U_(0x80FF) /**< (FREQM_CFGA) Register Mask */
/* -------- FREQM_INTENCLR : (FREQM Offset: 0x08) (R/W 8) Interrupt Enable Clear Register -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t DONE:1; /**< bit: 0 Measurement Done Interrupt Enable */
uint8_t :7; /**< bit: 1..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} FREQM_INTENCLR_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define FREQM_INTENCLR_OFFSET (0x08) /**< (FREQM_INTENCLR) Interrupt Enable Clear Register Offset */
#define FREQM_INTENCLR_RESETVALUE _U_(0x00) /**< (FREQM_INTENCLR) Interrupt Enable Clear Register Reset Value */
#define FREQM_INTENCLR_DONE_Pos 0 /**< (FREQM_INTENCLR) Measurement Done Interrupt Enable Position */
#define FREQM_INTENCLR_DONE_Msk (_U_(0x1) << FREQM_INTENCLR_DONE_Pos) /**< (FREQM_INTENCLR) Measurement Done Interrupt Enable Mask */
#define FREQM_INTENCLR_DONE FREQM_INTENCLR_DONE_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use FREQM_INTENCLR_DONE_Msk instead */
#define FREQM_INTENCLR_MASK _U_(0x01) /**< \deprecated (FREQM_INTENCLR) Register MASK (Use FREQM_INTENCLR_Msk instead) */
#define FREQM_INTENCLR_Msk _U_(0x01) /**< (FREQM_INTENCLR) Register Mask */
/* -------- FREQM_INTENSET : (FREQM Offset: 0x09) (R/W 8) Interrupt Enable Set Register -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t DONE:1; /**< bit: 0 Measurement Done Interrupt Enable */
uint8_t :7; /**< bit: 1..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} FREQM_INTENSET_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define FREQM_INTENSET_OFFSET (0x09) /**< (FREQM_INTENSET) Interrupt Enable Set Register Offset */
#define FREQM_INTENSET_RESETVALUE _U_(0x00) /**< (FREQM_INTENSET) Interrupt Enable Set Register Reset Value */
#define FREQM_INTENSET_DONE_Pos 0 /**< (FREQM_INTENSET) Measurement Done Interrupt Enable Position */
#define FREQM_INTENSET_DONE_Msk (_U_(0x1) << FREQM_INTENSET_DONE_Pos) /**< (FREQM_INTENSET) Measurement Done Interrupt Enable Mask */
#define FREQM_INTENSET_DONE FREQM_INTENSET_DONE_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use FREQM_INTENSET_DONE_Msk instead */
#define FREQM_INTENSET_MASK _U_(0x01) /**< \deprecated (FREQM_INTENSET) Register MASK (Use FREQM_INTENSET_Msk instead) */
#define FREQM_INTENSET_Msk _U_(0x01) /**< (FREQM_INTENSET) Register Mask */
/* -------- FREQM_INTFLAG : (FREQM Offset: 0x0a) (R/W 8) Interrupt Flag Register -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union { // __I to avoid read-modify-write on write-to-clear register
struct {
__I uint8_t DONE:1; /**< bit: 0 Measurement Done */
__I uint8_t :7; /**< bit: 1..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} FREQM_INTFLAG_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define FREQM_INTFLAG_OFFSET (0x0A) /**< (FREQM_INTFLAG) Interrupt Flag Register Offset */
#define FREQM_INTFLAG_RESETVALUE _U_(0x00) /**< (FREQM_INTFLAG) Interrupt Flag Register Reset Value */
#define FREQM_INTFLAG_DONE_Pos 0 /**< (FREQM_INTFLAG) Measurement Done Position */
#define FREQM_INTFLAG_DONE_Msk (_U_(0x1) << FREQM_INTFLAG_DONE_Pos) /**< (FREQM_INTFLAG) Measurement Done Mask */
#define FREQM_INTFLAG_DONE FREQM_INTFLAG_DONE_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use FREQM_INTFLAG_DONE_Msk instead */
#define FREQM_INTFLAG_MASK _U_(0x01) /**< \deprecated (FREQM_INTFLAG) Register MASK (Use FREQM_INTFLAG_Msk instead) */
#define FREQM_INTFLAG_Msk _U_(0x01) /**< (FREQM_INTFLAG) Register Mask */
/* -------- FREQM_STATUS : (FREQM Offset: 0x0b) (R/W 8) Status Register -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t BUSY:1; /**< bit: 0 FREQM Status */
uint8_t OVF:1; /**< bit: 1 Sticky Count Value Overflow */
uint8_t :6; /**< bit: 2..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} FREQM_STATUS_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define FREQM_STATUS_OFFSET (0x0B) /**< (FREQM_STATUS) Status Register Offset */
#define FREQM_STATUS_RESETVALUE _U_(0x00) /**< (FREQM_STATUS) Status Register Reset Value */
#define FREQM_STATUS_BUSY_Pos 0 /**< (FREQM_STATUS) FREQM Status Position */
#define FREQM_STATUS_BUSY_Msk (_U_(0x1) << FREQM_STATUS_BUSY_Pos) /**< (FREQM_STATUS) FREQM Status Mask */
#define FREQM_STATUS_BUSY FREQM_STATUS_BUSY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use FREQM_STATUS_BUSY_Msk instead */
#define FREQM_STATUS_OVF_Pos 1 /**< (FREQM_STATUS) Sticky Count Value Overflow Position */
#define FREQM_STATUS_OVF_Msk (_U_(0x1) << FREQM_STATUS_OVF_Pos) /**< (FREQM_STATUS) Sticky Count Value Overflow Mask */
#define FREQM_STATUS_OVF FREQM_STATUS_OVF_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use FREQM_STATUS_OVF_Msk instead */
#define FREQM_STATUS_MASK _U_(0x03) /**< \deprecated (FREQM_STATUS) Register MASK (Use FREQM_STATUS_Msk instead) */
#define FREQM_STATUS_Msk _U_(0x03) /**< (FREQM_STATUS) Register Mask */
/* -------- FREQM_SYNCBUSY : (FREQM Offset: 0x0c) (R/ 32) Synchronization Busy Register -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t SWRST:1; /**< bit: 0 Software Reset */
uint32_t ENABLE:1; /**< bit: 1 Enable */
uint32_t :30; /**< bit: 2..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} FREQM_SYNCBUSY_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define FREQM_SYNCBUSY_OFFSET (0x0C) /**< (FREQM_SYNCBUSY) Synchronization Busy Register Offset */
#define FREQM_SYNCBUSY_RESETVALUE _U_(0x00) /**< (FREQM_SYNCBUSY) Synchronization Busy Register Reset Value */
#define FREQM_SYNCBUSY_SWRST_Pos 0 /**< (FREQM_SYNCBUSY) Software Reset Position */
#define FREQM_SYNCBUSY_SWRST_Msk (_U_(0x1) << FREQM_SYNCBUSY_SWRST_Pos) /**< (FREQM_SYNCBUSY) Software Reset Mask */
#define FREQM_SYNCBUSY_SWRST FREQM_SYNCBUSY_SWRST_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use FREQM_SYNCBUSY_SWRST_Msk instead */
#define FREQM_SYNCBUSY_ENABLE_Pos 1 /**< (FREQM_SYNCBUSY) Enable Position */
#define FREQM_SYNCBUSY_ENABLE_Msk (_U_(0x1) << FREQM_SYNCBUSY_ENABLE_Pos) /**< (FREQM_SYNCBUSY) Enable Mask */
#define FREQM_SYNCBUSY_ENABLE FREQM_SYNCBUSY_ENABLE_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use FREQM_SYNCBUSY_ENABLE_Msk instead */
#define FREQM_SYNCBUSY_MASK _U_(0x03) /**< \deprecated (FREQM_SYNCBUSY) Register MASK (Use FREQM_SYNCBUSY_Msk instead) */
#define FREQM_SYNCBUSY_Msk _U_(0x03) /**< (FREQM_SYNCBUSY) Register Mask */
/* -------- FREQM_VALUE : (FREQM Offset: 0x10) (R/ 32) Count Value Register -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t VALUE:24; /**< bit: 0..23 Measurement Value */
uint32_t :8; /**< bit: 24..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} FREQM_VALUE_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define FREQM_VALUE_OFFSET (0x10) /**< (FREQM_VALUE) Count Value Register Offset */
#define FREQM_VALUE_RESETVALUE _U_(0x00) /**< (FREQM_VALUE) Count Value Register Reset Value */
#define FREQM_VALUE_VALUE_Pos 0 /**< (FREQM_VALUE) Measurement Value Position */
#define FREQM_VALUE_VALUE_Msk (_U_(0xFFFFFF) << FREQM_VALUE_VALUE_Pos) /**< (FREQM_VALUE) Measurement Value Mask */
#define FREQM_VALUE_VALUE(value) (FREQM_VALUE_VALUE_Msk & ((value) << FREQM_VALUE_VALUE_Pos))
#define FREQM_VALUE_MASK _U_(0xFFFFFF) /**< \deprecated (FREQM_VALUE) Register MASK (Use FREQM_VALUE_Msk instead) */
#define FREQM_VALUE_Msk _U_(0xFFFFFF) /**< (FREQM_VALUE) Register Mask */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
/** \brief FREQM hardware registers */
typedef struct { /* Frequency Meter */
__IO FREQM_CTRLA_Type CTRLA; /**< Offset: 0x00 (R/W 8) Control A Register */
__O FREQM_CTRLB_Type CTRLB; /**< Offset: 0x01 ( /W 8) Control B Register */
__IO FREQM_CFGA_Type CFGA; /**< Offset: 0x02 (R/W 16) Config A register */
__I uint8_t Reserved1[4];
__IO FREQM_INTENCLR_Type INTENCLR; /**< Offset: 0x08 (R/W 8) Interrupt Enable Clear Register */
__IO FREQM_INTENSET_Type INTENSET; /**< Offset: 0x09 (R/W 8) Interrupt Enable Set Register */
__IO FREQM_INTFLAG_Type INTFLAG; /**< Offset: 0x0A (R/W 8) Interrupt Flag Register */
__IO FREQM_STATUS_Type STATUS; /**< Offset: 0x0B (R/W 8) Status Register */
__I FREQM_SYNCBUSY_Type SYNCBUSY; /**< Offset: 0x0C (R/ 32) Synchronization Busy Register */
__I FREQM_VALUE_Type VALUE; /**< Offset: 0x10 (R/ 32) Count Value Register */
} Freqm;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/** @} end of Frequency Meter */
#endif /* _SAML10_FREQM_COMPONENT_H_ */

View File

@ -0,0 +1,238 @@
/**
* \file
*
* \brief Component description for GCLK
*
* Copyright (c) 2018 Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* 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
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
/* file generated from device description version 2018-08-31T13:51:50Z */
#ifndef _SAML10_GCLK_COMPONENT_H_
#define _SAML10_GCLK_COMPONENT_H_
#define _SAML10_GCLK_COMPONENT_ /**< \deprecated Backward compatibility for ASF */
/** \addtogroup SAML_SAML10 Generic Clock Generator
* @{
*/
/* ========================================================================== */
/** SOFTWARE API DEFINITION FOR GCLK */
/* ========================================================================== */
#define GCLK_U2122 /**< (GCLK) Module ID */
#define REV_GCLK 0x112 /**< (GCLK) Module revision */
/* -------- GCLK_CTRLA : (GCLK Offset: 0x00) (R/W 8) Control -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t SWRST:1; /**< bit: 0 Software Reset */
uint8_t :7; /**< bit: 1..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} GCLK_CTRLA_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define GCLK_CTRLA_OFFSET (0x00) /**< (GCLK_CTRLA) Control Offset */
#define GCLK_CTRLA_RESETVALUE _U_(0x00) /**< (GCLK_CTRLA) Control Reset Value */
#define GCLK_CTRLA_SWRST_Pos 0 /**< (GCLK_CTRLA) Software Reset Position */
#define GCLK_CTRLA_SWRST_Msk (_U_(0x1) << GCLK_CTRLA_SWRST_Pos) /**< (GCLK_CTRLA) Software Reset Mask */
#define GCLK_CTRLA_SWRST GCLK_CTRLA_SWRST_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use GCLK_CTRLA_SWRST_Msk instead */
#define GCLK_CTRLA_MASK _U_(0x01) /**< \deprecated (GCLK_CTRLA) Register MASK (Use GCLK_CTRLA_Msk instead) */
#define GCLK_CTRLA_Msk _U_(0x01) /**< (GCLK_CTRLA) Register Mask */
/* -------- GCLK_SYNCBUSY : (GCLK Offset: 0x04) (R/ 32) Synchronization Busy -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t SWRST:1; /**< bit: 0 Software Reset Synchroniation Busy bit */
uint32_t :1; /**< bit: 1 Reserved */
uint32_t GENCTRL0:1; /**< bit: 2 Generic Clock Generator Control 0 Synchronization Busy bit */
uint32_t GENCTRL1:1; /**< bit: 3 Generic Clock Generator Control 1 Synchronization Busy bit */
uint32_t GENCTRL2:1; /**< bit: 4 Generic Clock Generator Control 2 Synchronization Busy bit */
uint32_t GENCTRL3:1; /**< bit: 5 Generic Clock Generator Control 3 Synchronization Busy bit */
uint32_t GENCTRL4:1; /**< bit: 6 Generic Clock Generator Control 4 Synchronization Busy bit */
uint32_t :25; /**< bit: 7..31 Reserved */
} bit; /**< Structure used for bit access */
struct {
uint32_t :2; /**< bit: 0..1 Reserved */
uint32_t GENCTRL:5; /**< bit: 2..6 Generic Clock Generator Control 4 Synchronization Busy bit */
uint32_t :25; /**< bit: 7..31 Reserved */
} vec; /**< Structure used for vec access */
uint32_t reg; /**< Type used for register access */
} GCLK_SYNCBUSY_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define GCLK_SYNCBUSY_OFFSET (0x04) /**< (GCLK_SYNCBUSY) Synchronization Busy Offset */
#define GCLK_SYNCBUSY_RESETVALUE _U_(0x00) /**< (GCLK_SYNCBUSY) Synchronization Busy Reset Value */
#define GCLK_SYNCBUSY_SWRST_Pos 0 /**< (GCLK_SYNCBUSY) Software Reset Synchroniation Busy bit Position */
#define GCLK_SYNCBUSY_SWRST_Msk (_U_(0x1) << GCLK_SYNCBUSY_SWRST_Pos) /**< (GCLK_SYNCBUSY) Software Reset Synchroniation Busy bit Mask */
#define GCLK_SYNCBUSY_SWRST GCLK_SYNCBUSY_SWRST_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use GCLK_SYNCBUSY_SWRST_Msk instead */
#define GCLK_SYNCBUSY_GENCTRL0_Pos 2 /**< (GCLK_SYNCBUSY) Generic Clock Generator Control 0 Synchronization Busy bit Position */
#define GCLK_SYNCBUSY_GENCTRL0_Msk (_U_(0x1) << GCLK_SYNCBUSY_GENCTRL0_Pos) /**< (GCLK_SYNCBUSY) Generic Clock Generator Control 0 Synchronization Busy bit Mask */
#define GCLK_SYNCBUSY_GENCTRL0 GCLK_SYNCBUSY_GENCTRL0_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use GCLK_SYNCBUSY_GENCTRL0_Msk instead */
#define GCLK_SYNCBUSY_GENCTRL1_Pos 3 /**< (GCLK_SYNCBUSY) Generic Clock Generator Control 1 Synchronization Busy bit Position */
#define GCLK_SYNCBUSY_GENCTRL1_Msk (_U_(0x1) << GCLK_SYNCBUSY_GENCTRL1_Pos) /**< (GCLK_SYNCBUSY) Generic Clock Generator Control 1 Synchronization Busy bit Mask */
#define GCLK_SYNCBUSY_GENCTRL1 GCLK_SYNCBUSY_GENCTRL1_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use GCLK_SYNCBUSY_GENCTRL1_Msk instead */
#define GCLK_SYNCBUSY_GENCTRL2_Pos 4 /**< (GCLK_SYNCBUSY) Generic Clock Generator Control 2 Synchronization Busy bit Position */
#define GCLK_SYNCBUSY_GENCTRL2_Msk (_U_(0x1) << GCLK_SYNCBUSY_GENCTRL2_Pos) /**< (GCLK_SYNCBUSY) Generic Clock Generator Control 2 Synchronization Busy bit Mask */
#define GCLK_SYNCBUSY_GENCTRL2 GCLK_SYNCBUSY_GENCTRL2_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use GCLK_SYNCBUSY_GENCTRL2_Msk instead */
#define GCLK_SYNCBUSY_GENCTRL3_Pos 5 /**< (GCLK_SYNCBUSY) Generic Clock Generator Control 3 Synchronization Busy bit Position */
#define GCLK_SYNCBUSY_GENCTRL3_Msk (_U_(0x1) << GCLK_SYNCBUSY_GENCTRL3_Pos) /**< (GCLK_SYNCBUSY) Generic Clock Generator Control 3 Synchronization Busy bit Mask */
#define GCLK_SYNCBUSY_GENCTRL3 GCLK_SYNCBUSY_GENCTRL3_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use GCLK_SYNCBUSY_GENCTRL3_Msk instead */
#define GCLK_SYNCBUSY_GENCTRL4_Pos 6 /**< (GCLK_SYNCBUSY) Generic Clock Generator Control 4 Synchronization Busy bit Position */
#define GCLK_SYNCBUSY_GENCTRL4_Msk (_U_(0x1) << GCLK_SYNCBUSY_GENCTRL4_Pos) /**< (GCLK_SYNCBUSY) Generic Clock Generator Control 4 Synchronization Busy bit Mask */
#define GCLK_SYNCBUSY_GENCTRL4 GCLK_SYNCBUSY_GENCTRL4_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use GCLK_SYNCBUSY_GENCTRL4_Msk instead */
#define GCLK_SYNCBUSY_MASK _U_(0x7D) /**< \deprecated (GCLK_SYNCBUSY) Register MASK (Use GCLK_SYNCBUSY_Msk instead) */
#define GCLK_SYNCBUSY_Msk _U_(0x7D) /**< (GCLK_SYNCBUSY) Register Mask */
#define GCLK_SYNCBUSY_GENCTRL_Pos 2 /**< (GCLK_SYNCBUSY Position) Generic Clock Generator Control 4 Synchronization Busy bit */
#define GCLK_SYNCBUSY_GENCTRL_Msk (_U_(0x1F) << GCLK_SYNCBUSY_GENCTRL_Pos) /**< (GCLK_SYNCBUSY Mask) GENCTRL */
#define GCLK_SYNCBUSY_GENCTRL(value) (GCLK_SYNCBUSY_GENCTRL_Msk & ((value) << GCLK_SYNCBUSY_GENCTRL_Pos))
/* -------- GCLK_GENCTRL : (GCLK Offset: 0x20) (R/W 32) Generic Clock Generator Control -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t SRC:3; /**< bit: 0..2 Source Select */
uint32_t :5; /**< bit: 3..7 Reserved */
uint32_t GENEN:1; /**< bit: 8 Generic Clock Generator Enable */
uint32_t IDC:1; /**< bit: 9 Improve Duty Cycle */
uint32_t OOV:1; /**< bit: 10 Output Off Value */
uint32_t OE:1; /**< bit: 11 Output Enable */
uint32_t DIVSEL:1; /**< bit: 12 Divide Selection */
uint32_t RUNSTDBY:1; /**< bit: 13 Run in Standby */
uint32_t :2; /**< bit: 14..15 Reserved */
uint32_t DIV:16; /**< bit: 16..31 Division Factor */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} GCLK_GENCTRL_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define GCLK_GENCTRL_OFFSET (0x20) /**< (GCLK_GENCTRL) Generic Clock Generator Control Offset */
#define GCLK_GENCTRL_RESETVALUE _U_(0x00) /**< (GCLK_GENCTRL) Generic Clock Generator Control Reset Value */
#define GCLK_GENCTRL_SRC_Pos 0 /**< (GCLK_GENCTRL) Source Select Position */
#define GCLK_GENCTRL_SRC_Msk (_U_(0x7) << GCLK_GENCTRL_SRC_Pos) /**< (GCLK_GENCTRL) Source Select Mask */
#define GCLK_GENCTRL_SRC(value) (GCLK_GENCTRL_SRC_Msk & ((value) << GCLK_GENCTRL_SRC_Pos))
#define GCLK_GENCTRL_SRC_XOSC_Val _U_(0x0) /**< (GCLK_GENCTRL) XOSC oscillator output */
#define GCLK_GENCTRL_SRC_GCLKIN_Val _U_(0x1) /**< (GCLK_GENCTRL) Generator input pad */
#define GCLK_GENCTRL_SRC_GCLKGEN1_Val _U_(0x2) /**< (GCLK_GENCTRL) Generic clock generator 1 output */
#define GCLK_GENCTRL_SRC_OSCULP32K_Val _U_(0x3) /**< (GCLK_GENCTRL) OSCULP32K oscillator output */
#define GCLK_GENCTRL_SRC_XOSC32K_Val _U_(0x4) /**< (GCLK_GENCTRL) XOSC32K oscillator output */
#define GCLK_GENCTRL_SRC_OSC16M_Val _U_(0x5) /**< (GCLK_GENCTRL) OSC16M oscillator output */
#define GCLK_GENCTRL_SRC_DFLLULP_Val _U_(0x6) /**< (GCLK_GENCTRL) DFLLULP output */
#define GCLK_GENCTRL_SRC_FDPLL96M_Val _U_(0x7) /**< (GCLK_GENCTRL) FDPLL output */
#define GCLK_GENCTRL_SRC_XOSC (GCLK_GENCTRL_SRC_XOSC_Val << GCLK_GENCTRL_SRC_Pos) /**< (GCLK_GENCTRL) XOSC oscillator output Position */
#define GCLK_GENCTRL_SRC_GCLKIN (GCLK_GENCTRL_SRC_GCLKIN_Val << GCLK_GENCTRL_SRC_Pos) /**< (GCLK_GENCTRL) Generator input pad Position */
#define GCLK_GENCTRL_SRC_GCLKGEN1 (GCLK_GENCTRL_SRC_GCLKGEN1_Val << GCLK_GENCTRL_SRC_Pos) /**< (GCLK_GENCTRL) Generic clock generator 1 output Position */
#define GCLK_GENCTRL_SRC_OSCULP32K (GCLK_GENCTRL_SRC_OSCULP32K_Val << GCLK_GENCTRL_SRC_Pos) /**< (GCLK_GENCTRL) OSCULP32K oscillator output Position */
#define GCLK_GENCTRL_SRC_XOSC32K (GCLK_GENCTRL_SRC_XOSC32K_Val << GCLK_GENCTRL_SRC_Pos) /**< (GCLK_GENCTRL) XOSC32K oscillator output Position */
#define GCLK_GENCTRL_SRC_OSC16M (GCLK_GENCTRL_SRC_OSC16M_Val << GCLK_GENCTRL_SRC_Pos) /**< (GCLK_GENCTRL) OSC16M oscillator output Position */
#define GCLK_GENCTRL_SRC_DFLLULP (GCLK_GENCTRL_SRC_DFLLULP_Val << GCLK_GENCTRL_SRC_Pos) /**< (GCLK_GENCTRL) DFLLULP output Position */
#define GCLK_GENCTRL_SRC_FDPLL96M (GCLK_GENCTRL_SRC_FDPLL96M_Val << GCLK_GENCTRL_SRC_Pos) /**< (GCLK_GENCTRL) FDPLL output Position */
#define GCLK_GENCTRL_GENEN_Pos 8 /**< (GCLK_GENCTRL) Generic Clock Generator Enable Position */
#define GCLK_GENCTRL_GENEN_Msk (_U_(0x1) << GCLK_GENCTRL_GENEN_Pos) /**< (GCLK_GENCTRL) Generic Clock Generator Enable Mask */
#define GCLK_GENCTRL_GENEN GCLK_GENCTRL_GENEN_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use GCLK_GENCTRL_GENEN_Msk instead */
#define GCLK_GENCTRL_IDC_Pos 9 /**< (GCLK_GENCTRL) Improve Duty Cycle Position */
#define GCLK_GENCTRL_IDC_Msk (_U_(0x1) << GCLK_GENCTRL_IDC_Pos) /**< (GCLK_GENCTRL) Improve Duty Cycle Mask */
#define GCLK_GENCTRL_IDC GCLK_GENCTRL_IDC_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use GCLK_GENCTRL_IDC_Msk instead */
#define GCLK_GENCTRL_OOV_Pos 10 /**< (GCLK_GENCTRL) Output Off Value Position */
#define GCLK_GENCTRL_OOV_Msk (_U_(0x1) << GCLK_GENCTRL_OOV_Pos) /**< (GCLK_GENCTRL) Output Off Value Mask */
#define GCLK_GENCTRL_OOV GCLK_GENCTRL_OOV_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use GCLK_GENCTRL_OOV_Msk instead */
#define GCLK_GENCTRL_OE_Pos 11 /**< (GCLK_GENCTRL) Output Enable Position */
#define GCLK_GENCTRL_OE_Msk (_U_(0x1) << GCLK_GENCTRL_OE_Pos) /**< (GCLK_GENCTRL) Output Enable Mask */
#define GCLK_GENCTRL_OE GCLK_GENCTRL_OE_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use GCLK_GENCTRL_OE_Msk instead */
#define GCLK_GENCTRL_DIVSEL_Pos 12 /**< (GCLK_GENCTRL) Divide Selection Position */
#define GCLK_GENCTRL_DIVSEL_Msk (_U_(0x1) << GCLK_GENCTRL_DIVSEL_Pos) /**< (GCLK_GENCTRL) Divide Selection Mask */
#define GCLK_GENCTRL_DIVSEL GCLK_GENCTRL_DIVSEL_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use GCLK_GENCTRL_DIVSEL_Msk instead */
#define GCLK_GENCTRL_RUNSTDBY_Pos 13 /**< (GCLK_GENCTRL) Run in Standby Position */
#define GCLK_GENCTRL_RUNSTDBY_Msk (_U_(0x1) << GCLK_GENCTRL_RUNSTDBY_Pos) /**< (GCLK_GENCTRL) Run in Standby Mask */
#define GCLK_GENCTRL_RUNSTDBY GCLK_GENCTRL_RUNSTDBY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use GCLK_GENCTRL_RUNSTDBY_Msk instead */
#define GCLK_GENCTRL_DIV_Pos 16 /**< (GCLK_GENCTRL) Division Factor Position */
#define GCLK_GENCTRL_DIV_Msk (_U_(0xFFFF) << GCLK_GENCTRL_DIV_Pos) /**< (GCLK_GENCTRL) Division Factor Mask */
#define GCLK_GENCTRL_DIV(value) (GCLK_GENCTRL_DIV_Msk & ((value) << GCLK_GENCTRL_DIV_Pos))
#define GCLK_GENCTRL_MASK _U_(0xFFFF3F07) /**< \deprecated (GCLK_GENCTRL) Register MASK (Use GCLK_GENCTRL_Msk instead) */
#define GCLK_GENCTRL_Msk _U_(0xFFFF3F07) /**< (GCLK_GENCTRL) Register Mask */
/* -------- GCLK_PCHCTRL : (GCLK Offset: 0x80) (R/W 32) Peripheral Clock Control -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t GEN:3; /**< bit: 0..2 Generic Clock Generator */
uint32_t :3; /**< bit: 3..5 Reserved */
uint32_t CHEN:1; /**< bit: 6 Channel Enable */
uint32_t WRTLOCK:1; /**< bit: 7 Write Lock */
uint32_t :24; /**< bit: 8..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} GCLK_PCHCTRL_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define GCLK_PCHCTRL_OFFSET (0x80) /**< (GCLK_PCHCTRL) Peripheral Clock Control Offset */
#define GCLK_PCHCTRL_RESETVALUE _U_(0x00) /**< (GCLK_PCHCTRL) Peripheral Clock Control Reset Value */
#define GCLK_PCHCTRL_GEN_Pos 0 /**< (GCLK_PCHCTRL) Generic Clock Generator Position */
#define GCLK_PCHCTRL_GEN_Msk (_U_(0x7) << GCLK_PCHCTRL_GEN_Pos) /**< (GCLK_PCHCTRL) Generic Clock Generator Mask */
#define GCLK_PCHCTRL_GEN(value) (GCLK_PCHCTRL_GEN_Msk & ((value) << GCLK_PCHCTRL_GEN_Pos))
#define GCLK_PCHCTRL_GEN_GCLK0_Val _U_(0x0) /**< (GCLK_PCHCTRL) Generic clock generator 0 */
#define GCLK_PCHCTRL_GEN_GCLK1_Val _U_(0x1) /**< (GCLK_PCHCTRL) Generic clock generator 1 */
#define GCLK_PCHCTRL_GEN_GCLK2_Val _U_(0x2) /**< (GCLK_PCHCTRL) Generic clock generator 2 */
#define GCLK_PCHCTRL_GEN_GCLK3_Val _U_(0x3) /**< (GCLK_PCHCTRL) Generic clock generator 3 */
#define GCLK_PCHCTRL_GEN_GCLK4_Val _U_(0x4) /**< (GCLK_PCHCTRL) Generic clock generator 4 */
#define GCLK_PCHCTRL_GEN_GCLK0 (GCLK_PCHCTRL_GEN_GCLK0_Val << GCLK_PCHCTRL_GEN_Pos) /**< (GCLK_PCHCTRL) Generic clock generator 0 Position */
#define GCLK_PCHCTRL_GEN_GCLK1 (GCLK_PCHCTRL_GEN_GCLK1_Val << GCLK_PCHCTRL_GEN_Pos) /**< (GCLK_PCHCTRL) Generic clock generator 1 Position */
#define GCLK_PCHCTRL_GEN_GCLK2 (GCLK_PCHCTRL_GEN_GCLK2_Val << GCLK_PCHCTRL_GEN_Pos) /**< (GCLK_PCHCTRL) Generic clock generator 2 Position */
#define GCLK_PCHCTRL_GEN_GCLK3 (GCLK_PCHCTRL_GEN_GCLK3_Val << GCLK_PCHCTRL_GEN_Pos) /**< (GCLK_PCHCTRL) Generic clock generator 3 Position */
#define GCLK_PCHCTRL_GEN_GCLK4 (GCLK_PCHCTRL_GEN_GCLK4_Val << GCLK_PCHCTRL_GEN_Pos) /**< (GCLK_PCHCTRL) Generic clock generator 4 Position */
#define GCLK_PCHCTRL_CHEN_Pos 6 /**< (GCLK_PCHCTRL) Channel Enable Position */
#define GCLK_PCHCTRL_CHEN_Msk (_U_(0x1) << GCLK_PCHCTRL_CHEN_Pos) /**< (GCLK_PCHCTRL) Channel Enable Mask */
#define GCLK_PCHCTRL_CHEN GCLK_PCHCTRL_CHEN_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use GCLK_PCHCTRL_CHEN_Msk instead */
#define GCLK_PCHCTRL_WRTLOCK_Pos 7 /**< (GCLK_PCHCTRL) Write Lock Position */
#define GCLK_PCHCTRL_WRTLOCK_Msk (_U_(0x1) << GCLK_PCHCTRL_WRTLOCK_Pos) /**< (GCLK_PCHCTRL) Write Lock Mask */
#define GCLK_PCHCTRL_WRTLOCK GCLK_PCHCTRL_WRTLOCK_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use GCLK_PCHCTRL_WRTLOCK_Msk instead */
#define GCLK_PCHCTRL_MASK _U_(0xC7) /**< \deprecated (GCLK_PCHCTRL) Register MASK (Use GCLK_PCHCTRL_Msk instead) */
#define GCLK_PCHCTRL_Msk _U_(0xC7) /**< (GCLK_PCHCTRL) Register Mask */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
/** \brief GCLK hardware registers */
typedef struct { /* Generic Clock Generator */
__IO GCLK_CTRLA_Type CTRLA; /**< Offset: 0x00 (R/W 8) Control */
__I uint8_t Reserved1[3];
__I GCLK_SYNCBUSY_Type SYNCBUSY; /**< Offset: 0x04 (R/ 32) Synchronization Busy */
__I uint8_t Reserved2[24];
__IO GCLK_GENCTRL_Type GENCTRL[5]; /**< Offset: 0x20 (R/W 32) Generic Clock Generator Control */
__I uint8_t Reserved3[76];
__IO GCLK_PCHCTRL_Type PCHCTRL[21]; /**< Offset: 0x80 (R/W 32) Peripheral Clock Control */
} Gclk;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/** @} end of Generic Clock Generator */
#endif /* _SAML10_GCLK_COMPONENT_H_ */

View File

@ -0,0 +1,53 @@
/**
* \file
*
* \brief Component description for IDAU
*
* Copyright (c) 2018 Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* 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
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
/* file generated from device description version 2018-08-31T13:51:50Z */
#ifndef _SAML10_IDAU_COMPONENT_H_
#define _SAML10_IDAU_COMPONENT_H_
#define _SAML10_IDAU_COMPONENT_ /**< \deprecated Backward compatibility for ASF */
/** \addtogroup SAML_SAML10 Implementation Defined Attribution Unit
* @{
*/
/* ========================================================================== */
/** SOFTWARE API DEFINITION FOR IDAU */
/* ========================================================================== */
#define IDAU_U2803 /**< (IDAU) Module ID */
#define REV_IDAU 0x100 /**< (IDAU) Module revision */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
/** \brief No hardware registers defined for IDAU */
typedef void Idau;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/** @} end of Implementation Defined Attribution Unit */
#endif /* _SAML10_IDAU_COMPONENT_H_ */

View File

@ -0,0 +1,416 @@
/**
* \file
*
* \brief Component description for MCLK
*
* Copyright (c) 2018 Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* 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
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
/* file generated from device description version 2018-08-31T13:51:50Z */
#ifndef _SAML10_MCLK_COMPONENT_H_
#define _SAML10_MCLK_COMPONENT_H_
#define _SAML10_MCLK_COMPONENT_ /**< \deprecated Backward compatibility for ASF */
/** \addtogroup SAML_SAML10 Main Clock
* @{
*/
/* ========================================================================== */
/** SOFTWARE API DEFINITION FOR MCLK */
/* ========================================================================== */
#define MCLK_U2234 /**< (MCLK) Module ID */
#define REV_MCLK 0x300 /**< (MCLK) Module revision */
/* -------- MCLK_CTRLA : (MCLK Offset: 0x00) (R/W 8) Control -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t :2; /**< bit: 0..1 Reserved */
uint8_t CKSEL:1; /**< bit: 2 Clock Select */
uint8_t :5; /**< bit: 3..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} MCLK_CTRLA_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define MCLK_CTRLA_OFFSET (0x00) /**< (MCLK_CTRLA) Control Offset */
#define MCLK_CTRLA_RESETVALUE _U_(0x00) /**< (MCLK_CTRLA) Control Reset Value */
#define MCLK_CTRLA_CKSEL_Pos 2 /**< (MCLK_CTRLA) Clock Select Position */
#define MCLK_CTRLA_CKSEL_Msk (_U_(0x1) << MCLK_CTRLA_CKSEL_Pos) /**< (MCLK_CTRLA) Clock Select Mask */
#define MCLK_CTRLA_CKSEL MCLK_CTRLA_CKSEL_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use MCLK_CTRLA_CKSEL_Msk instead */
#define MCLK_CTRLA_MASK _U_(0x04) /**< \deprecated (MCLK_CTRLA) Register MASK (Use MCLK_CTRLA_Msk instead) */
#define MCLK_CTRLA_Msk _U_(0x04) /**< (MCLK_CTRLA) Register Mask */
/* -------- MCLK_INTENCLR : (MCLK Offset: 0x01) (R/W 8) Interrupt Enable Clear -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t CKRDY:1; /**< bit: 0 Clock Ready Interrupt Enable */
uint8_t :7; /**< bit: 1..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} MCLK_INTENCLR_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define MCLK_INTENCLR_OFFSET (0x01) /**< (MCLK_INTENCLR) Interrupt Enable Clear Offset */
#define MCLK_INTENCLR_RESETVALUE _U_(0x00) /**< (MCLK_INTENCLR) Interrupt Enable Clear Reset Value */
#define MCLK_INTENCLR_CKRDY_Pos 0 /**< (MCLK_INTENCLR) Clock Ready Interrupt Enable Position */
#define MCLK_INTENCLR_CKRDY_Msk (_U_(0x1) << MCLK_INTENCLR_CKRDY_Pos) /**< (MCLK_INTENCLR) Clock Ready Interrupt Enable Mask */
#define MCLK_INTENCLR_CKRDY MCLK_INTENCLR_CKRDY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use MCLK_INTENCLR_CKRDY_Msk instead */
#define MCLK_INTENCLR_MASK _U_(0x01) /**< \deprecated (MCLK_INTENCLR) Register MASK (Use MCLK_INTENCLR_Msk instead) */
#define MCLK_INTENCLR_Msk _U_(0x01) /**< (MCLK_INTENCLR) Register Mask */
/* -------- MCLK_INTENSET : (MCLK Offset: 0x02) (R/W 8) Interrupt Enable Set -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t CKRDY:1; /**< bit: 0 Clock Ready Interrupt Enable */
uint8_t :7; /**< bit: 1..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} MCLK_INTENSET_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define MCLK_INTENSET_OFFSET (0x02) /**< (MCLK_INTENSET) Interrupt Enable Set Offset */
#define MCLK_INTENSET_RESETVALUE _U_(0x00) /**< (MCLK_INTENSET) Interrupt Enable Set Reset Value */
#define MCLK_INTENSET_CKRDY_Pos 0 /**< (MCLK_INTENSET) Clock Ready Interrupt Enable Position */
#define MCLK_INTENSET_CKRDY_Msk (_U_(0x1) << MCLK_INTENSET_CKRDY_Pos) /**< (MCLK_INTENSET) Clock Ready Interrupt Enable Mask */
#define MCLK_INTENSET_CKRDY MCLK_INTENSET_CKRDY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use MCLK_INTENSET_CKRDY_Msk instead */
#define MCLK_INTENSET_MASK _U_(0x01) /**< \deprecated (MCLK_INTENSET) Register MASK (Use MCLK_INTENSET_Msk instead) */
#define MCLK_INTENSET_Msk _U_(0x01) /**< (MCLK_INTENSET) Register Mask */
/* -------- MCLK_INTFLAG : (MCLK Offset: 0x03) (R/W 8) Interrupt Flag Status and Clear -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union { // __I to avoid read-modify-write on write-to-clear register
struct {
__I uint8_t CKRDY:1; /**< bit: 0 Clock Ready */
__I uint8_t :7; /**< bit: 1..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} MCLK_INTFLAG_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define MCLK_INTFLAG_OFFSET (0x03) /**< (MCLK_INTFLAG) Interrupt Flag Status and Clear Offset */
#define MCLK_INTFLAG_RESETVALUE _U_(0x01) /**< (MCLK_INTFLAG) Interrupt Flag Status and Clear Reset Value */
#define MCLK_INTFLAG_CKRDY_Pos 0 /**< (MCLK_INTFLAG) Clock Ready Position */
#define MCLK_INTFLAG_CKRDY_Msk (_U_(0x1) << MCLK_INTFLAG_CKRDY_Pos) /**< (MCLK_INTFLAG) Clock Ready Mask */
#define MCLK_INTFLAG_CKRDY MCLK_INTFLAG_CKRDY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use MCLK_INTFLAG_CKRDY_Msk instead */
#define MCLK_INTFLAG_MASK _U_(0x01) /**< \deprecated (MCLK_INTFLAG) Register MASK (Use MCLK_INTFLAG_Msk instead) */
#define MCLK_INTFLAG_Msk _U_(0x01) /**< (MCLK_INTFLAG) Register Mask */
/* -------- MCLK_CPUDIV : (MCLK Offset: 0x04) (R/W 8) CPU Clock Division -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t CPUDIV:8; /**< bit: 0..7 CPU Clock Division Factor */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} MCLK_CPUDIV_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define MCLK_CPUDIV_OFFSET (0x04) /**< (MCLK_CPUDIV) CPU Clock Division Offset */
#define MCLK_CPUDIV_RESETVALUE _U_(0x01) /**< (MCLK_CPUDIV) CPU Clock Division Reset Value */
#define MCLK_CPUDIV_CPUDIV_Pos 0 /**< (MCLK_CPUDIV) CPU Clock Division Factor Position */
#define MCLK_CPUDIV_CPUDIV_Msk (_U_(0xFF) << MCLK_CPUDIV_CPUDIV_Pos) /**< (MCLK_CPUDIV) CPU Clock Division Factor Mask */
#define MCLK_CPUDIV_CPUDIV(value) (MCLK_CPUDIV_CPUDIV_Msk & ((value) << MCLK_CPUDIV_CPUDIV_Pos))
#define MCLK_CPUDIV_CPUDIV_DIV1_Val _U_(0x1) /**< (MCLK_CPUDIV) Divide by 1 */
#define MCLK_CPUDIV_CPUDIV_DIV2_Val _U_(0x2) /**< (MCLK_CPUDIV) Divide by 2 */
#define MCLK_CPUDIV_CPUDIV_DIV4_Val _U_(0x4) /**< (MCLK_CPUDIV) Divide by 4 */
#define MCLK_CPUDIV_CPUDIV_DIV8_Val _U_(0x8) /**< (MCLK_CPUDIV) Divide by 8 */
#define MCLK_CPUDIV_CPUDIV_DIV16_Val _U_(0x10) /**< (MCLK_CPUDIV) Divide by 16 */
#define MCLK_CPUDIV_CPUDIV_DIV32_Val _U_(0x20) /**< (MCLK_CPUDIV) Divide by 32 */
#define MCLK_CPUDIV_CPUDIV_DIV64_Val _U_(0x40) /**< (MCLK_CPUDIV) Divide by 64 */
#define MCLK_CPUDIV_CPUDIV_DIV128_Val _U_(0x80) /**< (MCLK_CPUDIV) Divide by 128 */
#define MCLK_CPUDIV_CPUDIV_DIV1 (MCLK_CPUDIV_CPUDIV_DIV1_Val << MCLK_CPUDIV_CPUDIV_Pos) /**< (MCLK_CPUDIV) Divide by 1 Position */
#define MCLK_CPUDIV_CPUDIV_DIV2 (MCLK_CPUDIV_CPUDIV_DIV2_Val << MCLK_CPUDIV_CPUDIV_Pos) /**< (MCLK_CPUDIV) Divide by 2 Position */
#define MCLK_CPUDIV_CPUDIV_DIV4 (MCLK_CPUDIV_CPUDIV_DIV4_Val << MCLK_CPUDIV_CPUDIV_Pos) /**< (MCLK_CPUDIV) Divide by 4 Position */
#define MCLK_CPUDIV_CPUDIV_DIV8 (MCLK_CPUDIV_CPUDIV_DIV8_Val << MCLK_CPUDIV_CPUDIV_Pos) /**< (MCLK_CPUDIV) Divide by 8 Position */
#define MCLK_CPUDIV_CPUDIV_DIV16 (MCLK_CPUDIV_CPUDIV_DIV16_Val << MCLK_CPUDIV_CPUDIV_Pos) /**< (MCLK_CPUDIV) Divide by 16 Position */
#define MCLK_CPUDIV_CPUDIV_DIV32 (MCLK_CPUDIV_CPUDIV_DIV32_Val << MCLK_CPUDIV_CPUDIV_Pos) /**< (MCLK_CPUDIV) Divide by 32 Position */
#define MCLK_CPUDIV_CPUDIV_DIV64 (MCLK_CPUDIV_CPUDIV_DIV64_Val << MCLK_CPUDIV_CPUDIV_Pos) /**< (MCLK_CPUDIV) Divide by 64 Position */
#define MCLK_CPUDIV_CPUDIV_DIV128 (MCLK_CPUDIV_CPUDIV_DIV128_Val << MCLK_CPUDIV_CPUDIV_Pos) /**< (MCLK_CPUDIV) Divide by 128 Position */
#define MCLK_CPUDIV_MASK _U_(0xFF) /**< \deprecated (MCLK_CPUDIV) Register MASK (Use MCLK_CPUDIV_Msk instead) */
#define MCLK_CPUDIV_Msk _U_(0xFF) /**< (MCLK_CPUDIV) Register Mask */
/* -------- MCLK_AHBMASK : (MCLK Offset: 0x10) (R/W 32) AHB Mask -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t HPB0_:1; /**< bit: 0 HPB0 AHB Clock Mask */
uint32_t HPB1_:1; /**< bit: 1 HPB1 AHB Clock Mask */
uint32_t HPB2_:1; /**< bit: 2 HPB2 AHB Clock Mask */
uint32_t DMAC_:1; /**< bit: 3 DMAC AHB Clock Mask */
uint32_t DSU_:1; /**< bit: 4 DSU AHB Clock Mask */
uint32_t :1; /**< bit: 5 Reserved */
uint32_t PAC_:1; /**< bit: 6 PAC AHB Clock Mask */
uint32_t NVMCTRL_:1; /**< bit: 7 NVMCTRL AHB Clock Mask */
uint32_t :4; /**< bit: 8..11 Reserved */
uint32_t TRAM_:1; /**< bit: 12 TRAM AHB Clock Mask */
uint32_t :19; /**< bit: 13..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} MCLK_AHBMASK_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define MCLK_AHBMASK_OFFSET (0x10) /**< (MCLK_AHBMASK) AHB Mask Offset */
#define MCLK_AHBMASK_RESETVALUE _U_(0x1FFF) /**< (MCLK_AHBMASK) AHB Mask Reset Value */
#define MCLK_AHBMASK_HPB0_Pos 0 /**< (MCLK_AHBMASK) HPB0 AHB Clock Mask Position */
#define MCLK_AHBMASK_HPB0_Msk (_U_(0x1) << MCLK_AHBMASK_HPB0_Pos) /**< (MCLK_AHBMASK) HPB0 AHB Clock Mask Mask */
#define MCLK_AHBMASK_HPB0 MCLK_AHBMASK_HPB0_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use MCLK_AHBMASK_HPB0_Msk instead */
#define MCLK_AHBMASK_HPB1_Pos 1 /**< (MCLK_AHBMASK) HPB1 AHB Clock Mask Position */
#define MCLK_AHBMASK_HPB1_Msk (_U_(0x1) << MCLK_AHBMASK_HPB1_Pos) /**< (MCLK_AHBMASK) HPB1 AHB Clock Mask Mask */
#define MCLK_AHBMASK_HPB1 MCLK_AHBMASK_HPB1_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use MCLK_AHBMASK_HPB1_Msk instead */
#define MCLK_AHBMASK_HPB2_Pos 2 /**< (MCLK_AHBMASK) HPB2 AHB Clock Mask Position */
#define MCLK_AHBMASK_HPB2_Msk (_U_(0x1) << MCLK_AHBMASK_HPB2_Pos) /**< (MCLK_AHBMASK) HPB2 AHB Clock Mask Mask */
#define MCLK_AHBMASK_HPB2 MCLK_AHBMASK_HPB2_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use MCLK_AHBMASK_HPB2_Msk instead */
#define MCLK_AHBMASK_DMAC_Pos 3 /**< (MCLK_AHBMASK) DMAC AHB Clock Mask Position */
#define MCLK_AHBMASK_DMAC_Msk (_U_(0x1) << MCLK_AHBMASK_DMAC_Pos) /**< (MCLK_AHBMASK) DMAC AHB Clock Mask Mask */
#define MCLK_AHBMASK_DMAC MCLK_AHBMASK_DMAC_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use MCLK_AHBMASK_DMAC_Msk instead */
#define MCLK_AHBMASK_DSU_Pos 4 /**< (MCLK_AHBMASK) DSU AHB Clock Mask Position */
#define MCLK_AHBMASK_DSU_Msk (_U_(0x1) << MCLK_AHBMASK_DSU_Pos) /**< (MCLK_AHBMASK) DSU AHB Clock Mask Mask */
#define MCLK_AHBMASK_DSU MCLK_AHBMASK_DSU_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use MCLK_AHBMASK_DSU_Msk instead */
#define MCLK_AHBMASK_PAC_Pos 6 /**< (MCLK_AHBMASK) PAC AHB Clock Mask Position */
#define MCLK_AHBMASK_PAC_Msk (_U_(0x1) << MCLK_AHBMASK_PAC_Pos) /**< (MCLK_AHBMASK) PAC AHB Clock Mask Mask */
#define MCLK_AHBMASK_PAC MCLK_AHBMASK_PAC_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use MCLK_AHBMASK_PAC_Msk instead */
#define MCLK_AHBMASK_NVMCTRL_Pos 7 /**< (MCLK_AHBMASK) NVMCTRL AHB Clock Mask Position */
#define MCLK_AHBMASK_NVMCTRL_Msk (_U_(0x1) << MCLK_AHBMASK_NVMCTRL_Pos) /**< (MCLK_AHBMASK) NVMCTRL AHB Clock Mask Mask */
#define MCLK_AHBMASK_NVMCTRL MCLK_AHBMASK_NVMCTRL_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use MCLK_AHBMASK_NVMCTRL_Msk instead */
#define MCLK_AHBMASK_TRAM_Pos 12 /**< (MCLK_AHBMASK) TRAM AHB Clock Mask Position */
#define MCLK_AHBMASK_TRAM_Msk (_U_(0x1) << MCLK_AHBMASK_TRAM_Pos) /**< (MCLK_AHBMASK) TRAM AHB Clock Mask Mask */
#define MCLK_AHBMASK_TRAM MCLK_AHBMASK_TRAM_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use MCLK_AHBMASK_TRAM_Msk instead */
#define MCLK_AHBMASK_MASK _U_(0x10DF) /**< \deprecated (MCLK_AHBMASK) Register MASK (Use MCLK_AHBMASK_Msk instead) */
#define MCLK_AHBMASK_Msk _U_(0x10DF) /**< (MCLK_AHBMASK) Register Mask */
#define MCLK_AHBMASK_HPB_Pos 0 /**< (MCLK_AHBMASK Position) HPBx AHB Clock Mask */
#define MCLK_AHBMASK_HPB_Msk (_U_(0x7) << MCLK_AHBMASK_HPB_Pos) /**< (MCLK_AHBMASK Mask) HPB */
#define MCLK_AHBMASK_HPB(value) (MCLK_AHBMASK_HPB_Msk & ((value) << MCLK_AHBMASK_HPB_Pos))
/* -------- MCLK_APBAMASK : (MCLK Offset: 0x14) (R/W 32) APBA Mask -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t PAC_:1; /**< bit: 0 PAC APB Clock Enable */
uint32_t PM_:1; /**< bit: 1 PM APB Clock Enable */
uint32_t MCLK_:1; /**< bit: 2 MCLK APB Clock Enable */
uint32_t RSTC_:1; /**< bit: 3 RSTC APB Clock Enable */
uint32_t OSCCTRL_:1; /**< bit: 4 OSCCTRL APB Clock Enable */
uint32_t OSC32KCTRL_:1; /**< bit: 5 OSC32KCTRL APB Clock Enable */
uint32_t SUPC_:1; /**< bit: 6 SUPC APB Clock Enable */
uint32_t GCLK_:1; /**< bit: 7 GCLK APB Clock Enable */
uint32_t WDT_:1; /**< bit: 8 WDT APB Clock Enable */
uint32_t RTC_:1; /**< bit: 9 RTC APB Clock Enable */
uint32_t EIC_:1; /**< bit: 10 EIC APB Clock Enable */
uint32_t FREQM_:1; /**< bit: 11 FREQM APB Clock Enable */
uint32_t PORT_:1; /**< bit: 12 PORT APB Clock Enable */
uint32_t AC_:1; /**< bit: 13 AC APB Clock Enable */
uint32_t :18; /**< bit: 14..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} MCLK_APBAMASK_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define MCLK_APBAMASK_OFFSET (0x14) /**< (MCLK_APBAMASK) APBA Mask Offset */
#define MCLK_APBAMASK_RESETVALUE _U_(0x7FFF) /**< (MCLK_APBAMASK) APBA Mask Reset Value */
#define MCLK_APBAMASK_PAC_Pos 0 /**< (MCLK_APBAMASK) PAC APB Clock Enable Position */
#define MCLK_APBAMASK_PAC_Msk (_U_(0x1) << MCLK_APBAMASK_PAC_Pos) /**< (MCLK_APBAMASK) PAC APB Clock Enable Mask */
#define MCLK_APBAMASK_PAC MCLK_APBAMASK_PAC_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use MCLK_APBAMASK_PAC_Msk instead */
#define MCLK_APBAMASK_PM_Pos 1 /**< (MCLK_APBAMASK) PM APB Clock Enable Position */
#define MCLK_APBAMASK_PM_Msk (_U_(0x1) << MCLK_APBAMASK_PM_Pos) /**< (MCLK_APBAMASK) PM APB Clock Enable Mask */
#define MCLK_APBAMASK_PM MCLK_APBAMASK_PM_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use MCLK_APBAMASK_PM_Msk instead */
#define MCLK_APBAMASK_MCLK_Pos 2 /**< (MCLK_APBAMASK) MCLK APB Clock Enable Position */
#define MCLK_APBAMASK_MCLK_Msk (_U_(0x1) << MCLK_APBAMASK_MCLK_Pos) /**< (MCLK_APBAMASK) MCLK APB Clock Enable Mask */
#define MCLK_APBAMASK_MCLK MCLK_APBAMASK_MCLK_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use MCLK_APBAMASK_MCLK_Msk instead */
#define MCLK_APBAMASK_RSTC_Pos 3 /**< (MCLK_APBAMASK) RSTC APB Clock Enable Position */
#define MCLK_APBAMASK_RSTC_Msk (_U_(0x1) << MCLK_APBAMASK_RSTC_Pos) /**< (MCLK_APBAMASK) RSTC APB Clock Enable Mask */
#define MCLK_APBAMASK_RSTC MCLK_APBAMASK_RSTC_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use MCLK_APBAMASK_RSTC_Msk instead */
#define MCLK_APBAMASK_OSCCTRL_Pos 4 /**< (MCLK_APBAMASK) OSCCTRL APB Clock Enable Position */
#define MCLK_APBAMASK_OSCCTRL_Msk (_U_(0x1) << MCLK_APBAMASK_OSCCTRL_Pos) /**< (MCLK_APBAMASK) OSCCTRL APB Clock Enable Mask */
#define MCLK_APBAMASK_OSCCTRL MCLK_APBAMASK_OSCCTRL_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use MCLK_APBAMASK_OSCCTRL_Msk instead */
#define MCLK_APBAMASK_OSC32KCTRL_Pos 5 /**< (MCLK_APBAMASK) OSC32KCTRL APB Clock Enable Position */
#define MCLK_APBAMASK_OSC32KCTRL_Msk (_U_(0x1) << MCLK_APBAMASK_OSC32KCTRL_Pos) /**< (MCLK_APBAMASK) OSC32KCTRL APB Clock Enable Mask */
#define MCLK_APBAMASK_OSC32KCTRL MCLK_APBAMASK_OSC32KCTRL_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use MCLK_APBAMASK_OSC32KCTRL_Msk instead */
#define MCLK_APBAMASK_SUPC_Pos 6 /**< (MCLK_APBAMASK) SUPC APB Clock Enable Position */
#define MCLK_APBAMASK_SUPC_Msk (_U_(0x1) << MCLK_APBAMASK_SUPC_Pos) /**< (MCLK_APBAMASK) SUPC APB Clock Enable Mask */
#define MCLK_APBAMASK_SUPC MCLK_APBAMASK_SUPC_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use MCLK_APBAMASK_SUPC_Msk instead */
#define MCLK_APBAMASK_GCLK_Pos 7 /**< (MCLK_APBAMASK) GCLK APB Clock Enable Position */
#define MCLK_APBAMASK_GCLK_Msk (_U_(0x1) << MCLK_APBAMASK_GCLK_Pos) /**< (MCLK_APBAMASK) GCLK APB Clock Enable Mask */
#define MCLK_APBAMASK_GCLK MCLK_APBAMASK_GCLK_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use MCLK_APBAMASK_GCLK_Msk instead */
#define MCLK_APBAMASK_WDT_Pos 8 /**< (MCLK_APBAMASK) WDT APB Clock Enable Position */
#define MCLK_APBAMASK_WDT_Msk (_U_(0x1) << MCLK_APBAMASK_WDT_Pos) /**< (MCLK_APBAMASK) WDT APB Clock Enable Mask */
#define MCLK_APBAMASK_WDT MCLK_APBAMASK_WDT_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use MCLK_APBAMASK_WDT_Msk instead */
#define MCLK_APBAMASK_RTC_Pos 9 /**< (MCLK_APBAMASK) RTC APB Clock Enable Position */
#define MCLK_APBAMASK_RTC_Msk (_U_(0x1) << MCLK_APBAMASK_RTC_Pos) /**< (MCLK_APBAMASK) RTC APB Clock Enable Mask */
#define MCLK_APBAMASK_RTC MCLK_APBAMASK_RTC_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use MCLK_APBAMASK_RTC_Msk instead */
#define MCLK_APBAMASK_EIC_Pos 10 /**< (MCLK_APBAMASK) EIC APB Clock Enable Position */
#define MCLK_APBAMASK_EIC_Msk (_U_(0x1) << MCLK_APBAMASK_EIC_Pos) /**< (MCLK_APBAMASK) EIC APB Clock Enable Mask */
#define MCLK_APBAMASK_EIC MCLK_APBAMASK_EIC_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use MCLK_APBAMASK_EIC_Msk instead */
#define MCLK_APBAMASK_FREQM_Pos 11 /**< (MCLK_APBAMASK) FREQM APB Clock Enable Position */
#define MCLK_APBAMASK_FREQM_Msk (_U_(0x1) << MCLK_APBAMASK_FREQM_Pos) /**< (MCLK_APBAMASK) FREQM APB Clock Enable Mask */
#define MCLK_APBAMASK_FREQM MCLK_APBAMASK_FREQM_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use MCLK_APBAMASK_FREQM_Msk instead */
#define MCLK_APBAMASK_PORT_Pos 12 /**< (MCLK_APBAMASK) PORT APB Clock Enable Position */
#define MCLK_APBAMASK_PORT_Msk (_U_(0x1) << MCLK_APBAMASK_PORT_Pos) /**< (MCLK_APBAMASK) PORT APB Clock Enable Mask */
#define MCLK_APBAMASK_PORT MCLK_APBAMASK_PORT_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use MCLK_APBAMASK_PORT_Msk instead */
#define MCLK_APBAMASK_AC_Pos 13 /**< (MCLK_APBAMASK) AC APB Clock Enable Position */
#define MCLK_APBAMASK_AC_Msk (_U_(0x1) << MCLK_APBAMASK_AC_Pos) /**< (MCLK_APBAMASK) AC APB Clock Enable Mask */
#define MCLK_APBAMASK_AC MCLK_APBAMASK_AC_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use MCLK_APBAMASK_AC_Msk instead */
#define MCLK_APBAMASK_MASK _U_(0x3FFF) /**< \deprecated (MCLK_APBAMASK) Register MASK (Use MCLK_APBAMASK_Msk instead) */
#define MCLK_APBAMASK_Msk _U_(0x3FFF) /**< (MCLK_APBAMASK) Register Mask */
/* -------- MCLK_APBBMASK : (MCLK Offset: 0x18) (R/W 32) APBB Mask -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t IDAU_:1; /**< bit: 0 IDAU APB Clock Enable */
uint32_t DSU_:1; /**< bit: 1 DSU APB Clock Enable */
uint32_t NVMCTRL_:1; /**< bit: 2 NVMCTRL APB Clock Enable */
uint32_t :29; /**< bit: 3..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} MCLK_APBBMASK_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define MCLK_APBBMASK_OFFSET (0x18) /**< (MCLK_APBBMASK) APBB Mask Offset */
#define MCLK_APBBMASK_RESETVALUE _U_(0x17) /**< (MCLK_APBBMASK) APBB Mask Reset Value */
#define MCLK_APBBMASK_IDAU_Pos 0 /**< (MCLK_APBBMASK) IDAU APB Clock Enable Position */
#define MCLK_APBBMASK_IDAU_Msk (_U_(0x1) << MCLK_APBBMASK_IDAU_Pos) /**< (MCLK_APBBMASK) IDAU APB Clock Enable Mask */
#define MCLK_APBBMASK_IDAU MCLK_APBBMASK_IDAU_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use MCLK_APBBMASK_IDAU_Msk instead */
#define MCLK_APBBMASK_DSU_Pos 1 /**< (MCLK_APBBMASK) DSU APB Clock Enable Position */
#define MCLK_APBBMASK_DSU_Msk (_U_(0x1) << MCLK_APBBMASK_DSU_Pos) /**< (MCLK_APBBMASK) DSU APB Clock Enable Mask */
#define MCLK_APBBMASK_DSU MCLK_APBBMASK_DSU_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use MCLK_APBBMASK_DSU_Msk instead */
#define MCLK_APBBMASK_NVMCTRL_Pos 2 /**< (MCLK_APBBMASK) NVMCTRL APB Clock Enable Position */
#define MCLK_APBBMASK_NVMCTRL_Msk (_U_(0x1) << MCLK_APBBMASK_NVMCTRL_Pos) /**< (MCLK_APBBMASK) NVMCTRL APB Clock Enable Mask */
#define MCLK_APBBMASK_NVMCTRL MCLK_APBBMASK_NVMCTRL_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use MCLK_APBBMASK_NVMCTRL_Msk instead */
#define MCLK_APBBMASK_MASK _U_(0x07) /**< \deprecated (MCLK_APBBMASK) Register MASK (Use MCLK_APBBMASK_Msk instead) */
#define MCLK_APBBMASK_Msk _U_(0x07) /**< (MCLK_APBBMASK) Register Mask */
/* -------- MCLK_APBCMASK : (MCLK Offset: 0x1c) (R/W 32) APBC Mask -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t EVSYS_:1; /**< bit: 0 EVSYS APB Clock Enable */
uint32_t SERCOM0_:1; /**< bit: 1 SERCOM0 APB Clock Enable */
uint32_t SERCOM1_:1; /**< bit: 2 SERCOM1 APB Clock Enable */
uint32_t SERCOM2_:1; /**< bit: 3 SERCOM2 APB Clock Enable */
uint32_t TC0_:1; /**< bit: 4 TC0 APB Clock Enable */
uint32_t TC1_:1; /**< bit: 5 TC1 APB Clock Enable */
uint32_t TC2_:1; /**< bit: 6 TC2 APB Clock Enable */
uint32_t ADC_:1; /**< bit: 7 ADC APB Clock Enable */
uint32_t DAC_:1; /**< bit: 8 DAC APB Clock Enable */
uint32_t PTC_:1; /**< bit: 9 PTC APB Clock Enable */
uint32_t TRNG_:1; /**< bit: 10 TRNG APB Clock Enable */
uint32_t CCL_:1; /**< bit: 11 CCL APB Clock Enable */
uint32_t OPAMP_:1; /**< bit: 12 OPAMP APB Clock Enable */
uint32_t :19; /**< bit: 13..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} MCLK_APBCMASK_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define MCLK_APBCMASK_OFFSET (0x1C) /**< (MCLK_APBCMASK) APBC Mask Offset */
#define MCLK_APBCMASK_RESETVALUE _U_(0x1FFF) /**< (MCLK_APBCMASK) APBC Mask Reset Value */
#define MCLK_APBCMASK_EVSYS_Pos 0 /**< (MCLK_APBCMASK) EVSYS APB Clock Enable Position */
#define MCLK_APBCMASK_EVSYS_Msk (_U_(0x1) << MCLK_APBCMASK_EVSYS_Pos) /**< (MCLK_APBCMASK) EVSYS APB Clock Enable Mask */
#define MCLK_APBCMASK_EVSYS MCLK_APBCMASK_EVSYS_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use MCLK_APBCMASK_EVSYS_Msk instead */
#define MCLK_APBCMASK_SERCOM0_Pos 1 /**< (MCLK_APBCMASK) SERCOM0 APB Clock Enable Position */
#define MCLK_APBCMASK_SERCOM0_Msk (_U_(0x1) << MCLK_APBCMASK_SERCOM0_Pos) /**< (MCLK_APBCMASK) SERCOM0 APB Clock Enable Mask */
#define MCLK_APBCMASK_SERCOM0 MCLK_APBCMASK_SERCOM0_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use MCLK_APBCMASK_SERCOM0_Msk instead */
#define MCLK_APBCMASK_SERCOM1_Pos 2 /**< (MCLK_APBCMASK) SERCOM1 APB Clock Enable Position */
#define MCLK_APBCMASK_SERCOM1_Msk (_U_(0x1) << MCLK_APBCMASK_SERCOM1_Pos) /**< (MCLK_APBCMASK) SERCOM1 APB Clock Enable Mask */
#define MCLK_APBCMASK_SERCOM1 MCLK_APBCMASK_SERCOM1_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use MCLK_APBCMASK_SERCOM1_Msk instead */
#define MCLK_APBCMASK_SERCOM2_Pos 3 /**< (MCLK_APBCMASK) SERCOM2 APB Clock Enable Position */
#define MCLK_APBCMASK_SERCOM2_Msk (_U_(0x1) << MCLK_APBCMASK_SERCOM2_Pos) /**< (MCLK_APBCMASK) SERCOM2 APB Clock Enable Mask */
#define MCLK_APBCMASK_SERCOM2 MCLK_APBCMASK_SERCOM2_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use MCLK_APBCMASK_SERCOM2_Msk instead */
#define MCLK_APBCMASK_TC0_Pos 4 /**< (MCLK_APBCMASK) TC0 APB Clock Enable Position */
#define MCLK_APBCMASK_TC0_Msk (_U_(0x1) << MCLK_APBCMASK_TC0_Pos) /**< (MCLK_APBCMASK) TC0 APB Clock Enable Mask */
#define MCLK_APBCMASK_TC0 MCLK_APBCMASK_TC0_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use MCLK_APBCMASK_TC0_Msk instead */
#define MCLK_APBCMASK_TC1_Pos 5 /**< (MCLK_APBCMASK) TC1 APB Clock Enable Position */
#define MCLK_APBCMASK_TC1_Msk (_U_(0x1) << MCLK_APBCMASK_TC1_Pos) /**< (MCLK_APBCMASK) TC1 APB Clock Enable Mask */
#define MCLK_APBCMASK_TC1 MCLK_APBCMASK_TC1_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use MCLK_APBCMASK_TC1_Msk instead */
#define MCLK_APBCMASK_TC2_Pos 6 /**< (MCLK_APBCMASK) TC2 APB Clock Enable Position */
#define MCLK_APBCMASK_TC2_Msk (_U_(0x1) << MCLK_APBCMASK_TC2_Pos) /**< (MCLK_APBCMASK) TC2 APB Clock Enable Mask */
#define MCLK_APBCMASK_TC2 MCLK_APBCMASK_TC2_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use MCLK_APBCMASK_TC2_Msk instead */
#define MCLK_APBCMASK_ADC_Pos 7 /**< (MCLK_APBCMASK) ADC APB Clock Enable Position */
#define MCLK_APBCMASK_ADC_Msk (_U_(0x1) << MCLK_APBCMASK_ADC_Pos) /**< (MCLK_APBCMASK) ADC APB Clock Enable Mask */
#define MCLK_APBCMASK_ADC MCLK_APBCMASK_ADC_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use MCLK_APBCMASK_ADC_Msk instead */
#define MCLK_APBCMASK_DAC_Pos 8 /**< (MCLK_APBCMASK) DAC APB Clock Enable Position */
#define MCLK_APBCMASK_DAC_Msk (_U_(0x1) << MCLK_APBCMASK_DAC_Pos) /**< (MCLK_APBCMASK) DAC APB Clock Enable Mask */
#define MCLK_APBCMASK_DAC MCLK_APBCMASK_DAC_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use MCLK_APBCMASK_DAC_Msk instead */
#define MCLK_APBCMASK_PTC_Pos 9 /**< (MCLK_APBCMASK) PTC APB Clock Enable Position */
#define MCLK_APBCMASK_PTC_Msk (_U_(0x1) << MCLK_APBCMASK_PTC_Pos) /**< (MCLK_APBCMASK) PTC APB Clock Enable Mask */
#define MCLK_APBCMASK_PTC MCLK_APBCMASK_PTC_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use MCLK_APBCMASK_PTC_Msk instead */
#define MCLK_APBCMASK_TRNG_Pos 10 /**< (MCLK_APBCMASK) TRNG APB Clock Enable Position */
#define MCLK_APBCMASK_TRNG_Msk (_U_(0x1) << MCLK_APBCMASK_TRNG_Pos) /**< (MCLK_APBCMASK) TRNG APB Clock Enable Mask */
#define MCLK_APBCMASK_TRNG MCLK_APBCMASK_TRNG_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use MCLK_APBCMASK_TRNG_Msk instead */
#define MCLK_APBCMASK_CCL_Pos 11 /**< (MCLK_APBCMASK) CCL APB Clock Enable Position */
#define MCLK_APBCMASK_CCL_Msk (_U_(0x1) << MCLK_APBCMASK_CCL_Pos) /**< (MCLK_APBCMASK) CCL APB Clock Enable Mask */
#define MCLK_APBCMASK_CCL MCLK_APBCMASK_CCL_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use MCLK_APBCMASK_CCL_Msk instead */
#define MCLK_APBCMASK_OPAMP_Pos 12 /**< (MCLK_APBCMASK) OPAMP APB Clock Enable Position */
#define MCLK_APBCMASK_OPAMP_Msk (_U_(0x1) << MCLK_APBCMASK_OPAMP_Pos) /**< (MCLK_APBCMASK) OPAMP APB Clock Enable Mask */
#define MCLK_APBCMASK_OPAMP MCLK_APBCMASK_OPAMP_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use MCLK_APBCMASK_OPAMP_Msk instead */
#define MCLK_APBCMASK_MASK _U_(0x1FFF) /**< \deprecated (MCLK_APBCMASK) Register MASK (Use MCLK_APBCMASK_Msk instead) */
#define MCLK_APBCMASK_Msk _U_(0x1FFF) /**< (MCLK_APBCMASK) Register Mask */
#define MCLK_APBCMASK_SERCOM_Pos 1 /**< (MCLK_APBCMASK Position) SERCOMx APB Clock Enable */
#define MCLK_APBCMASK_SERCOM_Msk (_U_(0x7) << MCLK_APBCMASK_SERCOM_Pos) /**< (MCLK_APBCMASK Mask) SERCOM */
#define MCLK_APBCMASK_SERCOM(value) (MCLK_APBCMASK_SERCOM_Msk & ((value) << MCLK_APBCMASK_SERCOM_Pos))
#define MCLK_APBCMASK_TC_Pos 4 /**< (MCLK_APBCMASK Position) TCx APB Clock Enable */
#define MCLK_APBCMASK_TC_Msk (_U_(0x7) << MCLK_APBCMASK_TC_Pos) /**< (MCLK_APBCMASK Mask) TC */
#define MCLK_APBCMASK_TC(value) (MCLK_APBCMASK_TC_Msk & ((value) << MCLK_APBCMASK_TC_Pos))
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
/** \brief MCLK hardware registers */
typedef struct { /* Main Clock */
__IO MCLK_CTRLA_Type CTRLA; /**< Offset: 0x00 (R/W 8) Control */
__IO MCLK_INTENCLR_Type INTENCLR; /**< Offset: 0x01 (R/W 8) Interrupt Enable Clear */
__IO MCLK_INTENSET_Type INTENSET; /**< Offset: 0x02 (R/W 8) Interrupt Enable Set */
__IO MCLK_INTFLAG_Type INTFLAG; /**< Offset: 0x03 (R/W 8) Interrupt Flag Status and Clear */
__IO MCLK_CPUDIV_Type CPUDIV; /**< Offset: 0x04 (R/W 8) CPU Clock Division */
__I uint8_t Reserved1[11];
__IO MCLK_AHBMASK_Type AHBMASK; /**< Offset: 0x10 (R/W 32) AHB Mask */
__IO MCLK_APBAMASK_Type APBAMASK; /**< Offset: 0x14 (R/W 32) APBA Mask */
__IO MCLK_APBBMASK_Type APBBMASK; /**< Offset: 0x18 (R/W 32) APBB Mask */
__IO MCLK_APBCMASK_Type APBCMASK; /**< Offset: 0x1C (R/W 32) APBC Mask */
} Mclk;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/** @} end of Main Clock */
#endif /* _SAML10_MCLK_COMPONENT_H_ */

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,227 @@
/**
* \file
*
* \brief Component description for OPAMP
*
* Copyright (c) 2018 Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* 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
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
/* file generated from device description version 2018-08-31T13:51:50Z */
#ifndef _SAML10_OPAMP_COMPONENT_H_
#define _SAML10_OPAMP_COMPONENT_H_
#define _SAML10_OPAMP_COMPONENT_ /**< \deprecated Backward compatibility for ASF */
/** \addtogroup SAML_SAML10 Operational Amplifier
* @{
*/
/* ========================================================================== */
/** SOFTWARE API DEFINITION FOR OPAMP */
/* ========================================================================== */
#define OPAMP_U2237 /**< (OPAMP) Module ID */
#define REV_OPAMP 0x200 /**< (OPAMP) Module revision */
/* -------- OPAMP_CTRLA : (OPAMP Offset: 0x00) (R/W 8) Control A -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t SWRST:1; /**< bit: 0 Software Reset */
uint8_t ENABLE:1; /**< bit: 1 Enable */
uint8_t :5; /**< bit: 2..6 Reserved */
uint8_t LPMUX:1; /**< bit: 7 Low-Power Mux */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} OPAMP_CTRLA_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define OPAMP_CTRLA_OFFSET (0x00) /**< (OPAMP_CTRLA) Control A Offset */
#define OPAMP_CTRLA_RESETVALUE _U_(0x00) /**< (OPAMP_CTRLA) Control A Reset Value */
#define OPAMP_CTRLA_SWRST_Pos 0 /**< (OPAMP_CTRLA) Software Reset Position */
#define OPAMP_CTRLA_SWRST_Msk (_U_(0x1) << OPAMP_CTRLA_SWRST_Pos) /**< (OPAMP_CTRLA) Software Reset Mask */
#define OPAMP_CTRLA_SWRST OPAMP_CTRLA_SWRST_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OPAMP_CTRLA_SWRST_Msk instead */
#define OPAMP_CTRLA_ENABLE_Pos 1 /**< (OPAMP_CTRLA) Enable Position */
#define OPAMP_CTRLA_ENABLE_Msk (_U_(0x1) << OPAMP_CTRLA_ENABLE_Pos) /**< (OPAMP_CTRLA) Enable Mask */
#define OPAMP_CTRLA_ENABLE OPAMP_CTRLA_ENABLE_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OPAMP_CTRLA_ENABLE_Msk instead */
#define OPAMP_CTRLA_LPMUX_Pos 7 /**< (OPAMP_CTRLA) Low-Power Mux Position */
#define OPAMP_CTRLA_LPMUX_Msk (_U_(0x1) << OPAMP_CTRLA_LPMUX_Pos) /**< (OPAMP_CTRLA) Low-Power Mux Mask */
#define OPAMP_CTRLA_LPMUX OPAMP_CTRLA_LPMUX_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OPAMP_CTRLA_LPMUX_Msk instead */
#define OPAMP_CTRLA_MASK _U_(0x83) /**< \deprecated (OPAMP_CTRLA) Register MASK (Use OPAMP_CTRLA_Msk instead) */
#define OPAMP_CTRLA_Msk _U_(0x83) /**< (OPAMP_CTRLA) Register Mask */
/* -------- OPAMP_STATUS : (OPAMP Offset: 0x02) (R/ 8) Status -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t READY0:1; /**< bit: 0 OPAMP 0 Ready */
uint8_t READY1:1; /**< bit: 1 OPAMP 1 Ready */
uint8_t READY2:1; /**< bit: 2 OPAMP 2 Ready */
uint8_t :5; /**< bit: 3..7 Reserved */
} bit; /**< Structure used for bit access */
struct {
uint8_t READY:3; /**< bit: 0..2 OPAMP 2 Ready */
uint8_t :5; /**< bit: 3..7 Reserved */
} vec; /**< Structure used for vec access */
uint8_t reg; /**< Type used for register access */
} OPAMP_STATUS_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define OPAMP_STATUS_OFFSET (0x02) /**< (OPAMP_STATUS) Status Offset */
#define OPAMP_STATUS_RESETVALUE _U_(0x00) /**< (OPAMP_STATUS) Status Reset Value */
#define OPAMP_STATUS_READY0_Pos 0 /**< (OPAMP_STATUS) OPAMP 0 Ready Position */
#define OPAMP_STATUS_READY0_Msk (_U_(0x1) << OPAMP_STATUS_READY0_Pos) /**< (OPAMP_STATUS) OPAMP 0 Ready Mask */
#define OPAMP_STATUS_READY0 OPAMP_STATUS_READY0_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OPAMP_STATUS_READY0_Msk instead */
#define OPAMP_STATUS_READY1_Pos 1 /**< (OPAMP_STATUS) OPAMP 1 Ready Position */
#define OPAMP_STATUS_READY1_Msk (_U_(0x1) << OPAMP_STATUS_READY1_Pos) /**< (OPAMP_STATUS) OPAMP 1 Ready Mask */
#define OPAMP_STATUS_READY1 OPAMP_STATUS_READY1_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OPAMP_STATUS_READY1_Msk instead */
#define OPAMP_STATUS_READY2_Pos 2 /**< (OPAMP_STATUS) OPAMP 2 Ready Position */
#define OPAMP_STATUS_READY2_Msk (_U_(0x1) << OPAMP_STATUS_READY2_Pos) /**< (OPAMP_STATUS) OPAMP 2 Ready Mask */
#define OPAMP_STATUS_READY2 OPAMP_STATUS_READY2_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OPAMP_STATUS_READY2_Msk instead */
#define OPAMP_STATUS_MASK _U_(0x07) /**< \deprecated (OPAMP_STATUS) Register MASK (Use OPAMP_STATUS_Msk instead) */
#define OPAMP_STATUS_Msk _U_(0x07) /**< (OPAMP_STATUS) Register Mask */
#define OPAMP_STATUS_READY_Pos 0 /**< (OPAMP_STATUS Position) OPAMP 2 Ready */
#define OPAMP_STATUS_READY_Msk (_U_(0x7) << OPAMP_STATUS_READY_Pos) /**< (OPAMP_STATUS Mask) READY */
#define OPAMP_STATUS_READY(value) (OPAMP_STATUS_READY_Msk & ((value) << OPAMP_STATUS_READY_Pos))
/* -------- OPAMP_OPAMPCTRL : (OPAMP Offset: 0x04) (R/W 32) OPAMP n Control -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t :1; /**< bit: 0 Reserved */
uint32_t ENABLE:1; /**< bit: 1 Operational Amplifier Enable */
uint32_t ANAOUT:1; /**< bit: 2 Analog Output */
uint32_t BIAS:2; /**< bit: 3..4 Bias Selection */
uint32_t RES2VCC:1; /**< bit: 5 Resistor ladder To VCC */
uint32_t RUNSTDBY:1; /**< bit: 6 Run in Standby */
uint32_t ONDEMAND:1; /**< bit: 7 On Demand Control */
uint32_t RES2OUT:1; /**< bit: 8 Resistor ladder To Output */
uint32_t RES1EN:1; /**< bit: 9 Resistor 1 Enable */
uint32_t RES1MUX:3; /**< bit: 10..12 Resistor 1 Mux */
uint32_t POTMUX:3; /**< bit: 13..15 Potentiometer Selection */
uint32_t MUXPOS:4; /**< bit: 16..19 Positive Input Mux Selection */
uint32_t MUXNEG:4; /**< bit: 20..23 Negative Input Mux Selection */
uint32_t :8; /**< bit: 24..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} OPAMP_OPAMPCTRL_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define OPAMP_OPAMPCTRL_OFFSET (0x04) /**< (OPAMP_OPAMPCTRL) OPAMP n Control Offset */
#define OPAMP_OPAMPCTRL_RESETVALUE _U_(0x00) /**< (OPAMP_OPAMPCTRL) OPAMP n Control Reset Value */
#define OPAMP_OPAMPCTRL_ENABLE_Pos 1 /**< (OPAMP_OPAMPCTRL) Operational Amplifier Enable Position */
#define OPAMP_OPAMPCTRL_ENABLE_Msk (_U_(0x1) << OPAMP_OPAMPCTRL_ENABLE_Pos) /**< (OPAMP_OPAMPCTRL) Operational Amplifier Enable Mask */
#define OPAMP_OPAMPCTRL_ENABLE OPAMP_OPAMPCTRL_ENABLE_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OPAMP_OPAMPCTRL_ENABLE_Msk instead */
#define OPAMP_OPAMPCTRL_ANAOUT_Pos 2 /**< (OPAMP_OPAMPCTRL) Analog Output Position */
#define OPAMP_OPAMPCTRL_ANAOUT_Msk (_U_(0x1) << OPAMP_OPAMPCTRL_ANAOUT_Pos) /**< (OPAMP_OPAMPCTRL) Analog Output Mask */
#define OPAMP_OPAMPCTRL_ANAOUT OPAMP_OPAMPCTRL_ANAOUT_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OPAMP_OPAMPCTRL_ANAOUT_Msk instead */
#define OPAMP_OPAMPCTRL_BIAS_Pos 3 /**< (OPAMP_OPAMPCTRL) Bias Selection Position */
#define OPAMP_OPAMPCTRL_BIAS_Msk (_U_(0x3) << OPAMP_OPAMPCTRL_BIAS_Pos) /**< (OPAMP_OPAMPCTRL) Bias Selection Mask */
#define OPAMP_OPAMPCTRL_BIAS(value) (OPAMP_OPAMPCTRL_BIAS_Msk & ((value) << OPAMP_OPAMPCTRL_BIAS_Pos))
#define OPAMP_OPAMPCTRL_RES2VCC_Pos 5 /**< (OPAMP_OPAMPCTRL) Resistor ladder To VCC Position */
#define OPAMP_OPAMPCTRL_RES2VCC_Msk (_U_(0x1) << OPAMP_OPAMPCTRL_RES2VCC_Pos) /**< (OPAMP_OPAMPCTRL) Resistor ladder To VCC Mask */
#define OPAMP_OPAMPCTRL_RES2VCC OPAMP_OPAMPCTRL_RES2VCC_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OPAMP_OPAMPCTRL_RES2VCC_Msk instead */
#define OPAMP_OPAMPCTRL_RUNSTDBY_Pos 6 /**< (OPAMP_OPAMPCTRL) Run in Standby Position */
#define OPAMP_OPAMPCTRL_RUNSTDBY_Msk (_U_(0x1) << OPAMP_OPAMPCTRL_RUNSTDBY_Pos) /**< (OPAMP_OPAMPCTRL) Run in Standby Mask */
#define OPAMP_OPAMPCTRL_RUNSTDBY OPAMP_OPAMPCTRL_RUNSTDBY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OPAMP_OPAMPCTRL_RUNSTDBY_Msk instead */
#define OPAMP_OPAMPCTRL_ONDEMAND_Pos 7 /**< (OPAMP_OPAMPCTRL) On Demand Control Position */
#define OPAMP_OPAMPCTRL_ONDEMAND_Msk (_U_(0x1) << OPAMP_OPAMPCTRL_ONDEMAND_Pos) /**< (OPAMP_OPAMPCTRL) On Demand Control Mask */
#define OPAMP_OPAMPCTRL_ONDEMAND OPAMP_OPAMPCTRL_ONDEMAND_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OPAMP_OPAMPCTRL_ONDEMAND_Msk instead */
#define OPAMP_OPAMPCTRL_RES2OUT_Pos 8 /**< (OPAMP_OPAMPCTRL) Resistor ladder To Output Position */
#define OPAMP_OPAMPCTRL_RES2OUT_Msk (_U_(0x1) << OPAMP_OPAMPCTRL_RES2OUT_Pos) /**< (OPAMP_OPAMPCTRL) Resistor ladder To Output Mask */
#define OPAMP_OPAMPCTRL_RES2OUT OPAMP_OPAMPCTRL_RES2OUT_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OPAMP_OPAMPCTRL_RES2OUT_Msk instead */
#define OPAMP_OPAMPCTRL_RES1EN_Pos 9 /**< (OPAMP_OPAMPCTRL) Resistor 1 Enable Position */
#define OPAMP_OPAMPCTRL_RES1EN_Msk (_U_(0x1) << OPAMP_OPAMPCTRL_RES1EN_Pos) /**< (OPAMP_OPAMPCTRL) Resistor 1 Enable Mask */
#define OPAMP_OPAMPCTRL_RES1EN OPAMP_OPAMPCTRL_RES1EN_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OPAMP_OPAMPCTRL_RES1EN_Msk instead */
#define OPAMP_OPAMPCTRL_RES1MUX_Pos 10 /**< (OPAMP_OPAMPCTRL) Resistor 1 Mux Position */
#define OPAMP_OPAMPCTRL_RES1MUX_Msk (_U_(0x7) << OPAMP_OPAMPCTRL_RES1MUX_Pos) /**< (OPAMP_OPAMPCTRL) Resistor 1 Mux Mask */
#define OPAMP_OPAMPCTRL_RES1MUX(value) (OPAMP_OPAMPCTRL_RES1MUX_Msk & ((value) << OPAMP_OPAMPCTRL_RES1MUX_Pos))
#define OPAMP_OPAMPCTRL_POTMUX_Pos 13 /**< (OPAMP_OPAMPCTRL) Potentiometer Selection Position */
#define OPAMP_OPAMPCTRL_POTMUX_Msk (_U_(0x7) << OPAMP_OPAMPCTRL_POTMUX_Pos) /**< (OPAMP_OPAMPCTRL) Potentiometer Selection Mask */
#define OPAMP_OPAMPCTRL_POTMUX(value) (OPAMP_OPAMPCTRL_POTMUX_Msk & ((value) << OPAMP_OPAMPCTRL_POTMUX_Pos))
#define OPAMP_OPAMPCTRL_MUXPOS_Pos 16 /**< (OPAMP_OPAMPCTRL) Positive Input Mux Selection Position */
#define OPAMP_OPAMPCTRL_MUXPOS_Msk (_U_(0xF) << OPAMP_OPAMPCTRL_MUXPOS_Pos) /**< (OPAMP_OPAMPCTRL) Positive Input Mux Selection Mask */
#define OPAMP_OPAMPCTRL_MUXPOS(value) (OPAMP_OPAMPCTRL_MUXPOS_Msk & ((value) << OPAMP_OPAMPCTRL_MUXPOS_Pos))
#define OPAMP_OPAMPCTRL_MUXNEG_Pos 20 /**< (OPAMP_OPAMPCTRL) Negative Input Mux Selection Position */
#define OPAMP_OPAMPCTRL_MUXNEG_Msk (_U_(0xF) << OPAMP_OPAMPCTRL_MUXNEG_Pos) /**< (OPAMP_OPAMPCTRL) Negative Input Mux Selection Mask */
#define OPAMP_OPAMPCTRL_MUXNEG(value) (OPAMP_OPAMPCTRL_MUXNEG_Msk & ((value) << OPAMP_OPAMPCTRL_MUXNEG_Pos))
#define OPAMP_OPAMPCTRL_MASK _U_(0xFFFFFE) /**< \deprecated (OPAMP_OPAMPCTRL) Register MASK (Use OPAMP_OPAMPCTRL_Msk instead) */
#define OPAMP_OPAMPCTRL_Msk _U_(0xFFFFFE) /**< (OPAMP_OPAMPCTRL) Register Mask */
/* -------- OPAMP_RESCTRL : (OPAMP Offset: 0x10) (R/W 8) Resister Control -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t RES2OUT:1; /**< bit: 0 Resistor ladder To Output */
uint8_t RES1EN:1; /**< bit: 1 Resistor 1 Enable */
uint8_t RES1MUX:1; /**< bit: 2 Resistor 1 Mux */
uint8_t POTMUX:3; /**< bit: 3..5 Potentiometer Selection */
uint8_t REFBUFLEVEL:2; /**< bit: 6..7 Reference output voltage level select */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} OPAMP_RESCTRL_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define OPAMP_RESCTRL_OFFSET (0x10) /**< (OPAMP_RESCTRL) Resister Control Offset */
#define OPAMP_RESCTRL_RESETVALUE _U_(0x00) /**< (OPAMP_RESCTRL) Resister Control Reset Value */
#define OPAMP_RESCTRL_RES2OUT_Pos 0 /**< (OPAMP_RESCTRL) Resistor ladder To Output Position */
#define OPAMP_RESCTRL_RES2OUT_Msk (_U_(0x1) << OPAMP_RESCTRL_RES2OUT_Pos) /**< (OPAMP_RESCTRL) Resistor ladder To Output Mask */
#define OPAMP_RESCTRL_RES2OUT OPAMP_RESCTRL_RES2OUT_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OPAMP_RESCTRL_RES2OUT_Msk instead */
#define OPAMP_RESCTRL_RES1EN_Pos 1 /**< (OPAMP_RESCTRL) Resistor 1 Enable Position */
#define OPAMP_RESCTRL_RES1EN_Msk (_U_(0x1) << OPAMP_RESCTRL_RES1EN_Pos) /**< (OPAMP_RESCTRL) Resistor 1 Enable Mask */
#define OPAMP_RESCTRL_RES1EN OPAMP_RESCTRL_RES1EN_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OPAMP_RESCTRL_RES1EN_Msk instead */
#define OPAMP_RESCTRL_RES1MUX_Pos 2 /**< (OPAMP_RESCTRL) Resistor 1 Mux Position */
#define OPAMP_RESCTRL_RES1MUX_Msk (_U_(0x1) << OPAMP_RESCTRL_RES1MUX_Pos) /**< (OPAMP_RESCTRL) Resistor 1 Mux Mask */
#define OPAMP_RESCTRL_RES1MUX OPAMP_RESCTRL_RES1MUX_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OPAMP_RESCTRL_RES1MUX_Msk instead */
#define OPAMP_RESCTRL_POTMUX_Pos 3 /**< (OPAMP_RESCTRL) Potentiometer Selection Position */
#define OPAMP_RESCTRL_POTMUX_Msk (_U_(0x7) << OPAMP_RESCTRL_POTMUX_Pos) /**< (OPAMP_RESCTRL) Potentiometer Selection Mask */
#define OPAMP_RESCTRL_POTMUX(value) (OPAMP_RESCTRL_POTMUX_Msk & ((value) << OPAMP_RESCTRL_POTMUX_Pos))
#define OPAMP_RESCTRL_REFBUFLEVEL_Pos 6 /**< (OPAMP_RESCTRL) Reference output voltage level select Position */
#define OPAMP_RESCTRL_REFBUFLEVEL_Msk (_U_(0x3) << OPAMP_RESCTRL_REFBUFLEVEL_Pos) /**< (OPAMP_RESCTRL) Reference output voltage level select Mask */
#define OPAMP_RESCTRL_REFBUFLEVEL(value) (OPAMP_RESCTRL_REFBUFLEVEL_Msk & ((value) << OPAMP_RESCTRL_REFBUFLEVEL_Pos))
#define OPAMP_RESCTRL_MASK _U_(0xFF) /**< \deprecated (OPAMP_RESCTRL) Register MASK (Use OPAMP_RESCTRL_Msk instead) */
#define OPAMP_RESCTRL_Msk _U_(0xFF) /**< (OPAMP_RESCTRL) Register Mask */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
/** \brief OPAMP hardware registers */
typedef struct { /* Operational Amplifier */
__IO OPAMP_CTRLA_Type CTRLA; /**< Offset: 0x00 (R/W 8) Control A */
__I uint8_t Reserved1[1];
__I OPAMP_STATUS_Type STATUS; /**< Offset: 0x02 (R/ 8) Status */
__I uint8_t Reserved2[1];
__IO OPAMP_OPAMPCTRL_Type OPAMPCTRL[3]; /**< Offset: 0x04 (R/W 32) OPAMP n Control */
__IO OPAMP_RESCTRL_Type RESCTRL; /**< Offset: 0x10 (R/W 8) Resister Control */
} Opamp;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/** @} end of Operational Amplifier */
#endif /* _SAML10_OPAMP_COMPONENT_H_ */

View File

@ -0,0 +1,344 @@
/**
* \file
*
* \brief Component description for OSC32KCTRL
*
* Copyright (c) 2018 Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* 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
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
/* file generated from device description version 2018-08-31T13:51:50Z */
#ifndef _SAML10_OSC32KCTRL_COMPONENT_H_
#define _SAML10_OSC32KCTRL_COMPONENT_H_
#define _SAML10_OSC32KCTRL_COMPONENT_ /**< \deprecated Backward compatibility for ASF */
/** \addtogroup SAML_SAML10 32k Oscillators Control
* @{
*/
/* ========================================================================== */
/** SOFTWARE API DEFINITION FOR OSC32KCTRL */
/* ========================================================================== */
#define OSC32KCTRL_U2246 /**< (OSC32KCTRL) Module ID */
#define REV_OSC32KCTRL 0x400 /**< (OSC32KCTRL) Module revision */
/* -------- OSC32KCTRL_INTENCLR : (OSC32KCTRL Offset: 0x00) (R/W 32) Interrupt Enable Clear -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t XOSC32KRDY:1; /**< bit: 0 XOSC32K Ready Interrupt Enable */
uint32_t :1; /**< bit: 1 Reserved */
uint32_t CLKFAIL:1; /**< bit: 2 XOSC32K Clock Failure Detector Interrupt Enable */
uint32_t :29; /**< bit: 3..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} OSC32KCTRL_INTENCLR_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define OSC32KCTRL_INTENCLR_OFFSET (0x00) /**< (OSC32KCTRL_INTENCLR) Interrupt Enable Clear Offset */
#define OSC32KCTRL_INTENCLR_RESETVALUE _U_(0x00) /**< (OSC32KCTRL_INTENCLR) Interrupt Enable Clear Reset Value */
#define OSC32KCTRL_INTENCLR_XOSC32KRDY_Pos 0 /**< (OSC32KCTRL_INTENCLR) XOSC32K Ready Interrupt Enable Position */
#define OSC32KCTRL_INTENCLR_XOSC32KRDY_Msk (_U_(0x1) << OSC32KCTRL_INTENCLR_XOSC32KRDY_Pos) /**< (OSC32KCTRL_INTENCLR) XOSC32K Ready Interrupt Enable Mask */
#define OSC32KCTRL_INTENCLR_XOSC32KRDY OSC32KCTRL_INTENCLR_XOSC32KRDY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSC32KCTRL_INTENCLR_XOSC32KRDY_Msk instead */
#define OSC32KCTRL_INTENCLR_CLKFAIL_Pos 2 /**< (OSC32KCTRL_INTENCLR) XOSC32K Clock Failure Detector Interrupt Enable Position */
#define OSC32KCTRL_INTENCLR_CLKFAIL_Msk (_U_(0x1) << OSC32KCTRL_INTENCLR_CLKFAIL_Pos) /**< (OSC32KCTRL_INTENCLR) XOSC32K Clock Failure Detector Interrupt Enable Mask */
#define OSC32KCTRL_INTENCLR_CLKFAIL OSC32KCTRL_INTENCLR_CLKFAIL_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSC32KCTRL_INTENCLR_CLKFAIL_Msk instead */
#define OSC32KCTRL_INTENCLR_MASK _U_(0x05) /**< \deprecated (OSC32KCTRL_INTENCLR) Register MASK (Use OSC32KCTRL_INTENCLR_Msk instead) */
#define OSC32KCTRL_INTENCLR_Msk _U_(0x05) /**< (OSC32KCTRL_INTENCLR) Register Mask */
/* -------- OSC32KCTRL_INTENSET : (OSC32KCTRL Offset: 0x04) (R/W 32) Interrupt Enable Set -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t XOSC32KRDY:1; /**< bit: 0 XOSC32K Ready Interrupt Enable */
uint32_t :1; /**< bit: 1 Reserved */
uint32_t CLKFAIL:1; /**< bit: 2 XOSC32K Clock Failure Detector Interrupt Enable */
uint32_t :29; /**< bit: 3..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} OSC32KCTRL_INTENSET_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define OSC32KCTRL_INTENSET_OFFSET (0x04) /**< (OSC32KCTRL_INTENSET) Interrupt Enable Set Offset */
#define OSC32KCTRL_INTENSET_RESETVALUE _U_(0x00) /**< (OSC32KCTRL_INTENSET) Interrupt Enable Set Reset Value */
#define OSC32KCTRL_INTENSET_XOSC32KRDY_Pos 0 /**< (OSC32KCTRL_INTENSET) XOSC32K Ready Interrupt Enable Position */
#define OSC32KCTRL_INTENSET_XOSC32KRDY_Msk (_U_(0x1) << OSC32KCTRL_INTENSET_XOSC32KRDY_Pos) /**< (OSC32KCTRL_INTENSET) XOSC32K Ready Interrupt Enable Mask */
#define OSC32KCTRL_INTENSET_XOSC32KRDY OSC32KCTRL_INTENSET_XOSC32KRDY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSC32KCTRL_INTENSET_XOSC32KRDY_Msk instead */
#define OSC32KCTRL_INTENSET_CLKFAIL_Pos 2 /**< (OSC32KCTRL_INTENSET) XOSC32K Clock Failure Detector Interrupt Enable Position */
#define OSC32KCTRL_INTENSET_CLKFAIL_Msk (_U_(0x1) << OSC32KCTRL_INTENSET_CLKFAIL_Pos) /**< (OSC32KCTRL_INTENSET) XOSC32K Clock Failure Detector Interrupt Enable Mask */
#define OSC32KCTRL_INTENSET_CLKFAIL OSC32KCTRL_INTENSET_CLKFAIL_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSC32KCTRL_INTENSET_CLKFAIL_Msk instead */
#define OSC32KCTRL_INTENSET_MASK _U_(0x05) /**< \deprecated (OSC32KCTRL_INTENSET) Register MASK (Use OSC32KCTRL_INTENSET_Msk instead) */
#define OSC32KCTRL_INTENSET_Msk _U_(0x05) /**< (OSC32KCTRL_INTENSET) Register Mask */
/* -------- OSC32KCTRL_INTFLAG : (OSC32KCTRL Offset: 0x08) (R/W 32) Interrupt Flag Status and Clear -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union { // __I to avoid read-modify-write on write-to-clear register
struct {
__I uint32_t XOSC32KRDY:1; /**< bit: 0 XOSC32K Ready */
__I uint32_t :1; /**< bit: 1 Reserved */
__I uint32_t CLKFAIL:1; /**< bit: 2 XOSC32K Clock Failure Detector */
__I uint32_t :29; /**< bit: 3..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} OSC32KCTRL_INTFLAG_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define OSC32KCTRL_INTFLAG_OFFSET (0x08) /**< (OSC32KCTRL_INTFLAG) Interrupt Flag Status and Clear Offset */
#define OSC32KCTRL_INTFLAG_RESETVALUE _U_(0x00) /**< (OSC32KCTRL_INTFLAG) Interrupt Flag Status and Clear Reset Value */
#define OSC32KCTRL_INTFLAG_XOSC32KRDY_Pos 0 /**< (OSC32KCTRL_INTFLAG) XOSC32K Ready Position */
#define OSC32KCTRL_INTFLAG_XOSC32KRDY_Msk (_U_(0x1) << OSC32KCTRL_INTFLAG_XOSC32KRDY_Pos) /**< (OSC32KCTRL_INTFLAG) XOSC32K Ready Mask */
#define OSC32KCTRL_INTFLAG_XOSC32KRDY OSC32KCTRL_INTFLAG_XOSC32KRDY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSC32KCTRL_INTFLAG_XOSC32KRDY_Msk instead */
#define OSC32KCTRL_INTFLAG_CLKFAIL_Pos 2 /**< (OSC32KCTRL_INTFLAG) XOSC32K Clock Failure Detector Position */
#define OSC32KCTRL_INTFLAG_CLKFAIL_Msk (_U_(0x1) << OSC32KCTRL_INTFLAG_CLKFAIL_Pos) /**< (OSC32KCTRL_INTFLAG) XOSC32K Clock Failure Detector Mask */
#define OSC32KCTRL_INTFLAG_CLKFAIL OSC32KCTRL_INTFLAG_CLKFAIL_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSC32KCTRL_INTFLAG_CLKFAIL_Msk instead */
#define OSC32KCTRL_INTFLAG_MASK _U_(0x05) /**< \deprecated (OSC32KCTRL_INTFLAG) Register MASK (Use OSC32KCTRL_INTFLAG_Msk instead) */
#define OSC32KCTRL_INTFLAG_Msk _U_(0x05) /**< (OSC32KCTRL_INTFLAG) Register Mask */
/* -------- OSC32KCTRL_STATUS : (OSC32KCTRL Offset: 0x0c) (R/ 32) Power and Clocks Status -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t XOSC32KRDY:1; /**< bit: 0 XOSC32K Ready */
uint32_t :1; /**< bit: 1 Reserved */
uint32_t CLKFAIL:1; /**< bit: 2 XOSC32K Clock Failure Detector */
uint32_t CLKSW:1; /**< bit: 3 XOSC32K Clock switch */
uint32_t ULP32KSW:1; /**< bit: 4 OSCULP32K Clock Switch */
uint32_t :27; /**< bit: 5..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} OSC32KCTRL_STATUS_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define OSC32KCTRL_STATUS_OFFSET (0x0C) /**< (OSC32KCTRL_STATUS) Power and Clocks Status Offset */
#define OSC32KCTRL_STATUS_RESETVALUE _U_(0x00) /**< (OSC32KCTRL_STATUS) Power and Clocks Status Reset Value */
#define OSC32KCTRL_STATUS_XOSC32KRDY_Pos 0 /**< (OSC32KCTRL_STATUS) XOSC32K Ready Position */
#define OSC32KCTRL_STATUS_XOSC32KRDY_Msk (_U_(0x1) << OSC32KCTRL_STATUS_XOSC32KRDY_Pos) /**< (OSC32KCTRL_STATUS) XOSC32K Ready Mask */
#define OSC32KCTRL_STATUS_XOSC32KRDY OSC32KCTRL_STATUS_XOSC32KRDY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSC32KCTRL_STATUS_XOSC32KRDY_Msk instead */
#define OSC32KCTRL_STATUS_CLKFAIL_Pos 2 /**< (OSC32KCTRL_STATUS) XOSC32K Clock Failure Detector Position */
#define OSC32KCTRL_STATUS_CLKFAIL_Msk (_U_(0x1) << OSC32KCTRL_STATUS_CLKFAIL_Pos) /**< (OSC32KCTRL_STATUS) XOSC32K Clock Failure Detector Mask */
#define OSC32KCTRL_STATUS_CLKFAIL OSC32KCTRL_STATUS_CLKFAIL_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSC32KCTRL_STATUS_CLKFAIL_Msk instead */
#define OSC32KCTRL_STATUS_CLKSW_Pos 3 /**< (OSC32KCTRL_STATUS) XOSC32K Clock switch Position */
#define OSC32KCTRL_STATUS_CLKSW_Msk (_U_(0x1) << OSC32KCTRL_STATUS_CLKSW_Pos) /**< (OSC32KCTRL_STATUS) XOSC32K Clock switch Mask */
#define OSC32KCTRL_STATUS_CLKSW OSC32KCTRL_STATUS_CLKSW_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSC32KCTRL_STATUS_CLKSW_Msk instead */
#define OSC32KCTRL_STATUS_ULP32KSW_Pos 4 /**< (OSC32KCTRL_STATUS) OSCULP32K Clock Switch Position */
#define OSC32KCTRL_STATUS_ULP32KSW_Msk (_U_(0x1) << OSC32KCTRL_STATUS_ULP32KSW_Pos) /**< (OSC32KCTRL_STATUS) OSCULP32K Clock Switch Mask */
#define OSC32KCTRL_STATUS_ULP32KSW OSC32KCTRL_STATUS_ULP32KSW_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSC32KCTRL_STATUS_ULP32KSW_Msk instead */
#define OSC32KCTRL_STATUS_MASK _U_(0x1D) /**< \deprecated (OSC32KCTRL_STATUS) Register MASK (Use OSC32KCTRL_STATUS_Msk instead) */
#define OSC32KCTRL_STATUS_Msk _U_(0x1D) /**< (OSC32KCTRL_STATUS) Register Mask */
/* -------- OSC32KCTRL_RTCCTRL : (OSC32KCTRL Offset: 0x10) (R/W 8) RTC Clock Selection -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t RTCSEL:3; /**< bit: 0..2 RTC Clock Selection */
uint8_t :5; /**< bit: 3..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} OSC32KCTRL_RTCCTRL_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define OSC32KCTRL_RTCCTRL_OFFSET (0x10) /**< (OSC32KCTRL_RTCCTRL) RTC Clock Selection Offset */
#define OSC32KCTRL_RTCCTRL_RESETVALUE _U_(0x00) /**< (OSC32KCTRL_RTCCTRL) RTC Clock Selection Reset Value */
#define OSC32KCTRL_RTCCTRL_RTCSEL_Pos 0 /**< (OSC32KCTRL_RTCCTRL) RTC Clock Selection Position */
#define OSC32KCTRL_RTCCTRL_RTCSEL_Msk (_U_(0x7) << OSC32KCTRL_RTCCTRL_RTCSEL_Pos) /**< (OSC32KCTRL_RTCCTRL) RTC Clock Selection Mask */
#define OSC32KCTRL_RTCCTRL_RTCSEL(value) (OSC32KCTRL_RTCCTRL_RTCSEL_Msk & ((value) << OSC32KCTRL_RTCCTRL_RTCSEL_Pos))
#define OSC32KCTRL_RTCCTRL_RTCSEL_ULP1K_Val _U_(0x0) /**< (OSC32KCTRL_RTCCTRL) 1.024kHz from 32kHz internal ULP oscillator */
#define OSC32KCTRL_RTCCTRL_RTCSEL_ULP32K_Val _U_(0x1) /**< (OSC32KCTRL_RTCCTRL) 32.768kHz from 32kHz internal ULP oscillator */
#define OSC32KCTRL_RTCCTRL_RTCSEL_OSC1K_Val _U_(0x2) /**< (OSC32KCTRL_RTCCTRL) 1.024kHz from 32.768kHz internal oscillator */
#define OSC32KCTRL_RTCCTRL_RTCSEL_OSC32K_Val _U_(0x3) /**< (OSC32KCTRL_RTCCTRL) 32.768kHz from 32.768kHz internal oscillator */
#define OSC32KCTRL_RTCCTRL_RTCSEL_XOSC1K_Val _U_(0x4) /**< (OSC32KCTRL_RTCCTRL) 1.024kHz from 32.768kHz internal oscillator */
#define OSC32KCTRL_RTCCTRL_RTCSEL_XOSC32K_Val _U_(0x5) /**< (OSC32KCTRL_RTCCTRL) 32.768kHz from 32.768kHz external crystal oscillator */
#define OSC32KCTRL_RTCCTRL_RTCSEL_ULP1K (OSC32KCTRL_RTCCTRL_RTCSEL_ULP1K_Val << OSC32KCTRL_RTCCTRL_RTCSEL_Pos) /**< (OSC32KCTRL_RTCCTRL) 1.024kHz from 32kHz internal ULP oscillator Position */
#define OSC32KCTRL_RTCCTRL_RTCSEL_ULP32K (OSC32KCTRL_RTCCTRL_RTCSEL_ULP32K_Val << OSC32KCTRL_RTCCTRL_RTCSEL_Pos) /**< (OSC32KCTRL_RTCCTRL) 32.768kHz from 32kHz internal ULP oscillator Position */
#define OSC32KCTRL_RTCCTRL_RTCSEL_OSC1K (OSC32KCTRL_RTCCTRL_RTCSEL_OSC1K_Val << OSC32KCTRL_RTCCTRL_RTCSEL_Pos) /**< (OSC32KCTRL_RTCCTRL) 1.024kHz from 32.768kHz internal oscillator Position */
#define OSC32KCTRL_RTCCTRL_RTCSEL_OSC32K (OSC32KCTRL_RTCCTRL_RTCSEL_OSC32K_Val << OSC32KCTRL_RTCCTRL_RTCSEL_Pos) /**< (OSC32KCTRL_RTCCTRL) 32.768kHz from 32.768kHz internal oscillator Position */
#define OSC32KCTRL_RTCCTRL_RTCSEL_XOSC1K (OSC32KCTRL_RTCCTRL_RTCSEL_XOSC1K_Val << OSC32KCTRL_RTCCTRL_RTCSEL_Pos) /**< (OSC32KCTRL_RTCCTRL) 1.024kHz from 32.768kHz internal oscillator Position */
#define OSC32KCTRL_RTCCTRL_RTCSEL_XOSC32K (OSC32KCTRL_RTCCTRL_RTCSEL_XOSC32K_Val << OSC32KCTRL_RTCCTRL_RTCSEL_Pos) /**< (OSC32KCTRL_RTCCTRL) 32.768kHz from 32.768kHz external crystal oscillator Position */
#define OSC32KCTRL_RTCCTRL_MASK _U_(0x07) /**< \deprecated (OSC32KCTRL_RTCCTRL) Register MASK (Use OSC32KCTRL_RTCCTRL_Msk instead) */
#define OSC32KCTRL_RTCCTRL_Msk _U_(0x07) /**< (OSC32KCTRL_RTCCTRL) Register Mask */
/* -------- OSC32KCTRL_XOSC32K : (OSC32KCTRL Offset: 0x14) (R/W 16) 32kHz External Crystal Oscillator (XOSC32K) Control -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint16_t :1; /**< bit: 0 Reserved */
uint16_t ENABLE:1; /**< bit: 1 Oscillator Enable */
uint16_t XTALEN:1; /**< bit: 2 Crystal Oscillator Enable */
uint16_t EN32K:1; /**< bit: 3 32kHz Output Enable */
uint16_t EN1K:1; /**< bit: 4 1kHz Output Enable */
uint16_t :1; /**< bit: 5 Reserved */
uint16_t RUNSTDBY:1; /**< bit: 6 Run in Standby */
uint16_t ONDEMAND:1; /**< bit: 7 On Demand Control */
uint16_t STARTUP:3; /**< bit: 8..10 Oscillator Start-Up Time */
uint16_t :1; /**< bit: 11 Reserved */
uint16_t WRTLOCK:1; /**< bit: 12 Write Lock */
uint16_t :3; /**< bit: 13..15 Reserved */
} bit; /**< Structure used for bit access */
uint16_t reg; /**< Type used for register access */
} OSC32KCTRL_XOSC32K_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define OSC32KCTRL_XOSC32K_OFFSET (0x14) /**< (OSC32KCTRL_XOSC32K) 32kHz External Crystal Oscillator (XOSC32K) Control Offset */
#define OSC32KCTRL_XOSC32K_RESETVALUE _U_(0x80) /**< (OSC32KCTRL_XOSC32K) 32kHz External Crystal Oscillator (XOSC32K) Control Reset Value */
#define OSC32KCTRL_XOSC32K_ENABLE_Pos 1 /**< (OSC32KCTRL_XOSC32K) Oscillator Enable Position */
#define OSC32KCTRL_XOSC32K_ENABLE_Msk (_U_(0x1) << OSC32KCTRL_XOSC32K_ENABLE_Pos) /**< (OSC32KCTRL_XOSC32K) Oscillator Enable Mask */
#define OSC32KCTRL_XOSC32K_ENABLE OSC32KCTRL_XOSC32K_ENABLE_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSC32KCTRL_XOSC32K_ENABLE_Msk instead */
#define OSC32KCTRL_XOSC32K_XTALEN_Pos 2 /**< (OSC32KCTRL_XOSC32K) Crystal Oscillator Enable Position */
#define OSC32KCTRL_XOSC32K_XTALEN_Msk (_U_(0x1) << OSC32KCTRL_XOSC32K_XTALEN_Pos) /**< (OSC32KCTRL_XOSC32K) Crystal Oscillator Enable Mask */
#define OSC32KCTRL_XOSC32K_XTALEN OSC32KCTRL_XOSC32K_XTALEN_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSC32KCTRL_XOSC32K_XTALEN_Msk instead */
#define OSC32KCTRL_XOSC32K_EN32K_Pos 3 /**< (OSC32KCTRL_XOSC32K) 32kHz Output Enable Position */
#define OSC32KCTRL_XOSC32K_EN32K_Msk (_U_(0x1) << OSC32KCTRL_XOSC32K_EN32K_Pos) /**< (OSC32KCTRL_XOSC32K) 32kHz Output Enable Mask */
#define OSC32KCTRL_XOSC32K_EN32K OSC32KCTRL_XOSC32K_EN32K_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSC32KCTRL_XOSC32K_EN32K_Msk instead */
#define OSC32KCTRL_XOSC32K_EN1K_Pos 4 /**< (OSC32KCTRL_XOSC32K) 1kHz Output Enable Position */
#define OSC32KCTRL_XOSC32K_EN1K_Msk (_U_(0x1) << OSC32KCTRL_XOSC32K_EN1K_Pos) /**< (OSC32KCTRL_XOSC32K) 1kHz Output Enable Mask */
#define OSC32KCTRL_XOSC32K_EN1K OSC32KCTRL_XOSC32K_EN1K_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSC32KCTRL_XOSC32K_EN1K_Msk instead */
#define OSC32KCTRL_XOSC32K_RUNSTDBY_Pos 6 /**< (OSC32KCTRL_XOSC32K) Run in Standby Position */
#define OSC32KCTRL_XOSC32K_RUNSTDBY_Msk (_U_(0x1) << OSC32KCTRL_XOSC32K_RUNSTDBY_Pos) /**< (OSC32KCTRL_XOSC32K) Run in Standby Mask */
#define OSC32KCTRL_XOSC32K_RUNSTDBY OSC32KCTRL_XOSC32K_RUNSTDBY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSC32KCTRL_XOSC32K_RUNSTDBY_Msk instead */
#define OSC32KCTRL_XOSC32K_ONDEMAND_Pos 7 /**< (OSC32KCTRL_XOSC32K) On Demand Control Position */
#define OSC32KCTRL_XOSC32K_ONDEMAND_Msk (_U_(0x1) << OSC32KCTRL_XOSC32K_ONDEMAND_Pos) /**< (OSC32KCTRL_XOSC32K) On Demand Control Mask */
#define OSC32KCTRL_XOSC32K_ONDEMAND OSC32KCTRL_XOSC32K_ONDEMAND_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSC32KCTRL_XOSC32K_ONDEMAND_Msk instead */
#define OSC32KCTRL_XOSC32K_STARTUP_Pos 8 /**< (OSC32KCTRL_XOSC32K) Oscillator Start-Up Time Position */
#define OSC32KCTRL_XOSC32K_STARTUP_Msk (_U_(0x7) << OSC32KCTRL_XOSC32K_STARTUP_Pos) /**< (OSC32KCTRL_XOSC32K) Oscillator Start-Up Time Mask */
#define OSC32KCTRL_XOSC32K_STARTUP(value) (OSC32KCTRL_XOSC32K_STARTUP_Msk & ((value) << OSC32KCTRL_XOSC32K_STARTUP_Pos))
#define OSC32KCTRL_XOSC32K_WRTLOCK_Pos 12 /**< (OSC32KCTRL_XOSC32K) Write Lock Position */
#define OSC32KCTRL_XOSC32K_WRTLOCK_Msk (_U_(0x1) << OSC32KCTRL_XOSC32K_WRTLOCK_Pos) /**< (OSC32KCTRL_XOSC32K) Write Lock Mask */
#define OSC32KCTRL_XOSC32K_WRTLOCK OSC32KCTRL_XOSC32K_WRTLOCK_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSC32KCTRL_XOSC32K_WRTLOCK_Msk instead */
#define OSC32KCTRL_XOSC32K_MASK _U_(0x17DE) /**< \deprecated (OSC32KCTRL_XOSC32K) Register MASK (Use OSC32KCTRL_XOSC32K_Msk instead) */
#define OSC32KCTRL_XOSC32K_Msk _U_(0x17DE) /**< (OSC32KCTRL_XOSC32K) Register Mask */
/* -------- OSC32KCTRL_CFDCTRL : (OSC32KCTRL Offset: 0x16) (R/W 8) Clock Failure Detector Control -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t CFDEN:1; /**< bit: 0 Clock Failure Detector Enable */
uint8_t SWBACK:1; /**< bit: 1 Clock Switch Back */
uint8_t CFDPRESC:1; /**< bit: 2 Clock Failure Detector Prescaler */
uint8_t :5; /**< bit: 3..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} OSC32KCTRL_CFDCTRL_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define OSC32KCTRL_CFDCTRL_OFFSET (0x16) /**< (OSC32KCTRL_CFDCTRL) Clock Failure Detector Control Offset */
#define OSC32KCTRL_CFDCTRL_RESETVALUE _U_(0x00) /**< (OSC32KCTRL_CFDCTRL) Clock Failure Detector Control Reset Value */
#define OSC32KCTRL_CFDCTRL_CFDEN_Pos 0 /**< (OSC32KCTRL_CFDCTRL) Clock Failure Detector Enable Position */
#define OSC32KCTRL_CFDCTRL_CFDEN_Msk (_U_(0x1) << OSC32KCTRL_CFDCTRL_CFDEN_Pos) /**< (OSC32KCTRL_CFDCTRL) Clock Failure Detector Enable Mask */
#define OSC32KCTRL_CFDCTRL_CFDEN OSC32KCTRL_CFDCTRL_CFDEN_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSC32KCTRL_CFDCTRL_CFDEN_Msk instead */
#define OSC32KCTRL_CFDCTRL_SWBACK_Pos 1 /**< (OSC32KCTRL_CFDCTRL) Clock Switch Back Position */
#define OSC32KCTRL_CFDCTRL_SWBACK_Msk (_U_(0x1) << OSC32KCTRL_CFDCTRL_SWBACK_Pos) /**< (OSC32KCTRL_CFDCTRL) Clock Switch Back Mask */
#define OSC32KCTRL_CFDCTRL_SWBACK OSC32KCTRL_CFDCTRL_SWBACK_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSC32KCTRL_CFDCTRL_SWBACK_Msk instead */
#define OSC32KCTRL_CFDCTRL_CFDPRESC_Pos 2 /**< (OSC32KCTRL_CFDCTRL) Clock Failure Detector Prescaler Position */
#define OSC32KCTRL_CFDCTRL_CFDPRESC_Msk (_U_(0x1) << OSC32KCTRL_CFDCTRL_CFDPRESC_Pos) /**< (OSC32KCTRL_CFDCTRL) Clock Failure Detector Prescaler Mask */
#define OSC32KCTRL_CFDCTRL_CFDPRESC OSC32KCTRL_CFDCTRL_CFDPRESC_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSC32KCTRL_CFDCTRL_CFDPRESC_Msk instead */
#define OSC32KCTRL_CFDCTRL_MASK _U_(0x07) /**< \deprecated (OSC32KCTRL_CFDCTRL) Register MASK (Use OSC32KCTRL_CFDCTRL_Msk instead) */
#define OSC32KCTRL_CFDCTRL_Msk _U_(0x07) /**< (OSC32KCTRL_CFDCTRL) Register Mask */
/* -------- OSC32KCTRL_EVCTRL : (OSC32KCTRL Offset: 0x17) (R/W 8) Event Control -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t CFDEO:1; /**< bit: 0 Clock Failure Detector Event Output Enable */
uint8_t :7; /**< bit: 1..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} OSC32KCTRL_EVCTRL_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define OSC32KCTRL_EVCTRL_OFFSET (0x17) /**< (OSC32KCTRL_EVCTRL) Event Control Offset */
#define OSC32KCTRL_EVCTRL_RESETVALUE _U_(0x00) /**< (OSC32KCTRL_EVCTRL) Event Control Reset Value */
#define OSC32KCTRL_EVCTRL_CFDEO_Pos 0 /**< (OSC32KCTRL_EVCTRL) Clock Failure Detector Event Output Enable Position */
#define OSC32KCTRL_EVCTRL_CFDEO_Msk (_U_(0x1) << OSC32KCTRL_EVCTRL_CFDEO_Pos) /**< (OSC32KCTRL_EVCTRL) Clock Failure Detector Event Output Enable Mask */
#define OSC32KCTRL_EVCTRL_CFDEO OSC32KCTRL_EVCTRL_CFDEO_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSC32KCTRL_EVCTRL_CFDEO_Msk instead */
#define OSC32KCTRL_EVCTRL_MASK _U_(0x01) /**< \deprecated (OSC32KCTRL_EVCTRL) Register MASK (Use OSC32KCTRL_EVCTRL_Msk instead) */
#define OSC32KCTRL_EVCTRL_Msk _U_(0x01) /**< (OSC32KCTRL_EVCTRL) Register Mask */
/* -------- OSC32KCTRL_OSCULP32K : (OSC32KCTRL Offset: 0x1c) (R/W 32) 32kHz Ultra Low Power Internal Oscillator (OSCULP32K) Control -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t :5; /**< bit: 0..4 Reserved */
uint32_t ULP32KSW:1; /**< bit: 5 OSCULP32K Clock Switch Enable */
uint32_t :2; /**< bit: 6..7 Reserved */
uint32_t CALIB:5; /**< bit: 8..12 Oscillator Calibration */
uint32_t :2; /**< bit: 13..14 Reserved */
uint32_t WRTLOCK:1; /**< bit: 15 Write Lock */
uint32_t :16; /**< bit: 16..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} OSC32KCTRL_OSCULP32K_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define OSC32KCTRL_OSCULP32K_OFFSET (0x1C) /**< (OSC32KCTRL_OSCULP32K) 32kHz Ultra Low Power Internal Oscillator (OSCULP32K) Control Offset */
#define OSC32KCTRL_OSCULP32K_RESETVALUE _U_(0x00) /**< (OSC32KCTRL_OSCULP32K) 32kHz Ultra Low Power Internal Oscillator (OSCULP32K) Control Reset Value */
#define OSC32KCTRL_OSCULP32K_ULP32KSW_Pos 5 /**< (OSC32KCTRL_OSCULP32K) OSCULP32K Clock Switch Enable Position */
#define OSC32KCTRL_OSCULP32K_ULP32KSW_Msk (_U_(0x1) << OSC32KCTRL_OSCULP32K_ULP32KSW_Pos) /**< (OSC32KCTRL_OSCULP32K) OSCULP32K Clock Switch Enable Mask */
#define OSC32KCTRL_OSCULP32K_ULP32KSW OSC32KCTRL_OSCULP32K_ULP32KSW_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSC32KCTRL_OSCULP32K_ULP32KSW_Msk instead */
#define OSC32KCTRL_OSCULP32K_CALIB_Pos 8 /**< (OSC32KCTRL_OSCULP32K) Oscillator Calibration Position */
#define OSC32KCTRL_OSCULP32K_CALIB_Msk (_U_(0x1F) << OSC32KCTRL_OSCULP32K_CALIB_Pos) /**< (OSC32KCTRL_OSCULP32K) Oscillator Calibration Mask */
#define OSC32KCTRL_OSCULP32K_CALIB(value) (OSC32KCTRL_OSCULP32K_CALIB_Msk & ((value) << OSC32KCTRL_OSCULP32K_CALIB_Pos))
#define OSC32KCTRL_OSCULP32K_WRTLOCK_Pos 15 /**< (OSC32KCTRL_OSCULP32K) Write Lock Position */
#define OSC32KCTRL_OSCULP32K_WRTLOCK_Msk (_U_(0x1) << OSC32KCTRL_OSCULP32K_WRTLOCK_Pos) /**< (OSC32KCTRL_OSCULP32K) Write Lock Mask */
#define OSC32KCTRL_OSCULP32K_WRTLOCK OSC32KCTRL_OSCULP32K_WRTLOCK_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSC32KCTRL_OSCULP32K_WRTLOCK_Msk instead */
#define OSC32KCTRL_OSCULP32K_MASK _U_(0x9F20) /**< \deprecated (OSC32KCTRL_OSCULP32K) Register MASK (Use OSC32KCTRL_OSCULP32K_Msk instead) */
#define OSC32KCTRL_OSCULP32K_Msk _U_(0x9F20) /**< (OSC32KCTRL_OSCULP32K) Register Mask */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
/** \brief OSC32KCTRL hardware registers */
typedef struct { /* 32k Oscillators Control */
__IO OSC32KCTRL_INTENCLR_Type INTENCLR; /**< Offset: 0x00 (R/W 32) Interrupt Enable Clear */
__IO OSC32KCTRL_INTENSET_Type INTENSET; /**< Offset: 0x04 (R/W 32) Interrupt Enable Set */
__IO OSC32KCTRL_INTFLAG_Type INTFLAG; /**< Offset: 0x08 (R/W 32) Interrupt Flag Status and Clear */
__I OSC32KCTRL_STATUS_Type STATUS; /**< Offset: 0x0C (R/ 32) Power and Clocks Status */
__IO OSC32KCTRL_RTCCTRL_Type RTCCTRL; /**< Offset: 0x10 (R/W 8) RTC Clock Selection */
__I uint8_t Reserved1[3];
__IO OSC32KCTRL_XOSC32K_Type XOSC32K; /**< Offset: 0x14 (R/W 16) 32kHz External Crystal Oscillator (XOSC32K) Control */
__IO OSC32KCTRL_CFDCTRL_Type CFDCTRL; /**< Offset: 0x16 (R/W 8) Clock Failure Detector Control */
__IO OSC32KCTRL_EVCTRL_Type EVCTRL; /**< Offset: 0x17 (R/W 8) Event Control */
__I uint8_t Reserved2[4];
__IO OSC32KCTRL_OSCULP32K_Type OSCULP32K; /**< Offset: 0x1C (R/W 32) 32kHz Ultra Low Power Internal Oscillator (OSCULP32K) Control */
} Osc32kctrl;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/** @} end of 32k Oscillators Control */
#endif /* _SAML10_OSC32KCTRL_COMPONENT_H_ */

View File

@ -0,0 +1,878 @@
/**
* \file
*
* \brief Component description for OSCCTRL
*
* Copyright (c) 2018 Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* 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
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
/* file generated from device description version 2018-08-31T13:51:50Z */
#ifndef _SAML10_OSCCTRL_COMPONENT_H_
#define _SAML10_OSCCTRL_COMPONENT_H_
#define _SAML10_OSCCTRL_COMPONENT_ /**< \deprecated Backward compatibility for ASF */
/** \addtogroup SAML_SAML10 Oscillators Control
* @{
*/
/* ========================================================================== */
/** SOFTWARE API DEFINITION FOR OSCCTRL */
/* ========================================================================== */
#define OSCCTRL_U2119 /**< (OSCCTRL) Module ID */
#define REV_OSCCTRL 0x400 /**< (OSCCTRL) Module revision */
/* -------- OSCCTRL_EVCTRL : (OSCCTRL Offset: 0x00) (R/W 8) Event Control -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t CFDEO:1; /**< bit: 0 Clock Failure Detector Event Output Enable */
uint8_t TUNEEI:1; /**< bit: 1 Tune Event Input Enable */
uint8_t TUNEINV:1; /**< bit: 2 Tune Event Input Invert */
uint8_t :5; /**< bit: 3..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} OSCCTRL_EVCTRL_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define OSCCTRL_EVCTRL_OFFSET (0x00) /**< (OSCCTRL_EVCTRL) Event Control Offset */
#define OSCCTRL_EVCTRL_RESETVALUE _U_(0x00) /**< (OSCCTRL_EVCTRL) Event Control Reset Value */
#define OSCCTRL_EVCTRL_CFDEO_Pos 0 /**< (OSCCTRL_EVCTRL) Clock Failure Detector Event Output Enable Position */
#define OSCCTRL_EVCTRL_CFDEO_Msk (_U_(0x1) << OSCCTRL_EVCTRL_CFDEO_Pos) /**< (OSCCTRL_EVCTRL) Clock Failure Detector Event Output Enable Mask */
#define OSCCTRL_EVCTRL_CFDEO OSCCTRL_EVCTRL_CFDEO_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_EVCTRL_CFDEO_Msk instead */
#define OSCCTRL_EVCTRL_TUNEEI_Pos 1 /**< (OSCCTRL_EVCTRL) Tune Event Input Enable Position */
#define OSCCTRL_EVCTRL_TUNEEI_Msk (_U_(0x1) << OSCCTRL_EVCTRL_TUNEEI_Pos) /**< (OSCCTRL_EVCTRL) Tune Event Input Enable Mask */
#define OSCCTRL_EVCTRL_TUNEEI OSCCTRL_EVCTRL_TUNEEI_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_EVCTRL_TUNEEI_Msk instead */
#define OSCCTRL_EVCTRL_TUNEINV_Pos 2 /**< (OSCCTRL_EVCTRL) Tune Event Input Invert Position */
#define OSCCTRL_EVCTRL_TUNEINV_Msk (_U_(0x1) << OSCCTRL_EVCTRL_TUNEINV_Pos) /**< (OSCCTRL_EVCTRL) Tune Event Input Invert Mask */
#define OSCCTRL_EVCTRL_TUNEINV OSCCTRL_EVCTRL_TUNEINV_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_EVCTRL_TUNEINV_Msk instead */
#define OSCCTRL_EVCTRL_MASK _U_(0x07) /**< \deprecated (OSCCTRL_EVCTRL) Register MASK (Use OSCCTRL_EVCTRL_Msk instead) */
#define OSCCTRL_EVCTRL_Msk _U_(0x07) /**< (OSCCTRL_EVCTRL) Register Mask */
/* -------- OSCCTRL_INTENCLR : (OSCCTRL Offset: 0x04) (R/W 32) Interrupt Enable Clear -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t XOSCRDY:1; /**< bit: 0 XOSC Ready Interrupt Enable */
uint32_t XOSCFAIL:1; /**< bit: 1 XOSC Clock Failure Detector Interrupt Enable */
uint32_t :2; /**< bit: 2..3 Reserved */
uint32_t OSC16MRDY:1; /**< bit: 4 OSC16M Ready Interrupt Enable */
uint32_t :3; /**< bit: 5..7 Reserved */
uint32_t DFLLULPRDY:1; /**< bit: 8 DFLLULP Ready interrupt Enable */
uint32_t DFLLULPLOCK:1; /**< bit: 9 DFLLULP Lock Interrupt Enable */
uint32_t DFLLULPNOLOCK:1; /**< bit: 10 DFLLULP No Lock Interrupt Enable */
uint32_t :5; /**< bit: 11..15 Reserved */
uint32_t DPLLLCKR:1; /**< bit: 16 DPLL Lock Rise Interrupt Enable */
uint32_t DPLLLCKF:1; /**< bit: 17 DPLL Lock Fall Interrupt Enable */
uint32_t DPLLLTO:1; /**< bit: 18 DPLL Lock Timeout Interrupt Enable */
uint32_t DPLLLDRTO:1; /**< bit: 19 DPLL Loop Divider Ratio Update Complete Interrupt Enable */
uint32_t :12; /**< bit: 20..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} OSCCTRL_INTENCLR_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define OSCCTRL_INTENCLR_OFFSET (0x04) /**< (OSCCTRL_INTENCLR) Interrupt Enable Clear Offset */
#define OSCCTRL_INTENCLR_RESETVALUE _U_(0x00) /**< (OSCCTRL_INTENCLR) Interrupt Enable Clear Reset Value */
#define OSCCTRL_INTENCLR_XOSCRDY_Pos 0 /**< (OSCCTRL_INTENCLR) XOSC Ready Interrupt Enable Position */
#define OSCCTRL_INTENCLR_XOSCRDY_Msk (_U_(0x1) << OSCCTRL_INTENCLR_XOSCRDY_Pos) /**< (OSCCTRL_INTENCLR) XOSC Ready Interrupt Enable Mask */
#define OSCCTRL_INTENCLR_XOSCRDY OSCCTRL_INTENCLR_XOSCRDY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_INTENCLR_XOSCRDY_Msk instead */
#define OSCCTRL_INTENCLR_XOSCFAIL_Pos 1 /**< (OSCCTRL_INTENCLR) XOSC Clock Failure Detector Interrupt Enable Position */
#define OSCCTRL_INTENCLR_XOSCFAIL_Msk (_U_(0x1) << OSCCTRL_INTENCLR_XOSCFAIL_Pos) /**< (OSCCTRL_INTENCLR) XOSC Clock Failure Detector Interrupt Enable Mask */
#define OSCCTRL_INTENCLR_XOSCFAIL OSCCTRL_INTENCLR_XOSCFAIL_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_INTENCLR_XOSCFAIL_Msk instead */
#define OSCCTRL_INTENCLR_OSC16MRDY_Pos 4 /**< (OSCCTRL_INTENCLR) OSC16M Ready Interrupt Enable Position */
#define OSCCTRL_INTENCLR_OSC16MRDY_Msk (_U_(0x1) << OSCCTRL_INTENCLR_OSC16MRDY_Pos) /**< (OSCCTRL_INTENCLR) OSC16M Ready Interrupt Enable Mask */
#define OSCCTRL_INTENCLR_OSC16MRDY OSCCTRL_INTENCLR_OSC16MRDY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_INTENCLR_OSC16MRDY_Msk instead */
#define OSCCTRL_INTENCLR_DFLLULPRDY_Pos 8 /**< (OSCCTRL_INTENCLR) DFLLULP Ready interrupt Enable Position */
#define OSCCTRL_INTENCLR_DFLLULPRDY_Msk (_U_(0x1) << OSCCTRL_INTENCLR_DFLLULPRDY_Pos) /**< (OSCCTRL_INTENCLR) DFLLULP Ready interrupt Enable Mask */
#define OSCCTRL_INTENCLR_DFLLULPRDY OSCCTRL_INTENCLR_DFLLULPRDY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_INTENCLR_DFLLULPRDY_Msk instead */
#define OSCCTRL_INTENCLR_DFLLULPLOCK_Pos 9 /**< (OSCCTRL_INTENCLR) DFLLULP Lock Interrupt Enable Position */
#define OSCCTRL_INTENCLR_DFLLULPLOCK_Msk (_U_(0x1) << OSCCTRL_INTENCLR_DFLLULPLOCK_Pos) /**< (OSCCTRL_INTENCLR) DFLLULP Lock Interrupt Enable Mask */
#define OSCCTRL_INTENCLR_DFLLULPLOCK OSCCTRL_INTENCLR_DFLLULPLOCK_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_INTENCLR_DFLLULPLOCK_Msk instead */
#define OSCCTRL_INTENCLR_DFLLULPNOLOCK_Pos 10 /**< (OSCCTRL_INTENCLR) DFLLULP No Lock Interrupt Enable Position */
#define OSCCTRL_INTENCLR_DFLLULPNOLOCK_Msk (_U_(0x1) << OSCCTRL_INTENCLR_DFLLULPNOLOCK_Pos) /**< (OSCCTRL_INTENCLR) DFLLULP No Lock Interrupt Enable Mask */
#define OSCCTRL_INTENCLR_DFLLULPNOLOCK OSCCTRL_INTENCLR_DFLLULPNOLOCK_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_INTENCLR_DFLLULPNOLOCK_Msk instead */
#define OSCCTRL_INTENCLR_DPLLLCKR_Pos 16 /**< (OSCCTRL_INTENCLR) DPLL Lock Rise Interrupt Enable Position */
#define OSCCTRL_INTENCLR_DPLLLCKR_Msk (_U_(0x1) << OSCCTRL_INTENCLR_DPLLLCKR_Pos) /**< (OSCCTRL_INTENCLR) DPLL Lock Rise Interrupt Enable Mask */
#define OSCCTRL_INTENCLR_DPLLLCKR OSCCTRL_INTENCLR_DPLLLCKR_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_INTENCLR_DPLLLCKR_Msk instead */
#define OSCCTRL_INTENCLR_DPLLLCKF_Pos 17 /**< (OSCCTRL_INTENCLR) DPLL Lock Fall Interrupt Enable Position */
#define OSCCTRL_INTENCLR_DPLLLCKF_Msk (_U_(0x1) << OSCCTRL_INTENCLR_DPLLLCKF_Pos) /**< (OSCCTRL_INTENCLR) DPLL Lock Fall Interrupt Enable Mask */
#define OSCCTRL_INTENCLR_DPLLLCKF OSCCTRL_INTENCLR_DPLLLCKF_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_INTENCLR_DPLLLCKF_Msk instead */
#define OSCCTRL_INTENCLR_DPLLLTO_Pos 18 /**< (OSCCTRL_INTENCLR) DPLL Lock Timeout Interrupt Enable Position */
#define OSCCTRL_INTENCLR_DPLLLTO_Msk (_U_(0x1) << OSCCTRL_INTENCLR_DPLLLTO_Pos) /**< (OSCCTRL_INTENCLR) DPLL Lock Timeout Interrupt Enable Mask */
#define OSCCTRL_INTENCLR_DPLLLTO OSCCTRL_INTENCLR_DPLLLTO_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_INTENCLR_DPLLLTO_Msk instead */
#define OSCCTRL_INTENCLR_DPLLLDRTO_Pos 19 /**< (OSCCTRL_INTENCLR) DPLL Loop Divider Ratio Update Complete Interrupt Enable Position */
#define OSCCTRL_INTENCLR_DPLLLDRTO_Msk (_U_(0x1) << OSCCTRL_INTENCLR_DPLLLDRTO_Pos) /**< (OSCCTRL_INTENCLR) DPLL Loop Divider Ratio Update Complete Interrupt Enable Mask */
#define OSCCTRL_INTENCLR_DPLLLDRTO OSCCTRL_INTENCLR_DPLLLDRTO_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_INTENCLR_DPLLLDRTO_Msk instead */
#define OSCCTRL_INTENCLR_MASK _U_(0xF0713) /**< \deprecated (OSCCTRL_INTENCLR) Register MASK (Use OSCCTRL_INTENCLR_Msk instead) */
#define OSCCTRL_INTENCLR_Msk _U_(0xF0713) /**< (OSCCTRL_INTENCLR) Register Mask */
/* -------- OSCCTRL_INTENSET : (OSCCTRL Offset: 0x08) (R/W 32) Interrupt Enable Set -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t XOSCRDY:1; /**< bit: 0 XOSC Ready Interrupt Enable */
uint32_t XOSCFAIL:1; /**< bit: 1 XOSC Clock Failure Detector Interrupt Enable */
uint32_t :2; /**< bit: 2..3 Reserved */
uint32_t OSC16MRDY:1; /**< bit: 4 OSC16M Ready Interrupt Enable */
uint32_t :3; /**< bit: 5..7 Reserved */
uint32_t DFLLULPRDY:1; /**< bit: 8 DFLLULP Ready interrupt Enable */
uint32_t DFLLULPLOCK:1; /**< bit: 9 DFLLULP Lock Interrupt Enable */
uint32_t DFLLULPNOLOCK:1; /**< bit: 10 DFLLULP No Lock Interrupt Enable */
uint32_t :5; /**< bit: 11..15 Reserved */
uint32_t DPLLLCKR:1; /**< bit: 16 DPLL Lock Rise Interrupt Enable */
uint32_t DPLLLCKF:1; /**< bit: 17 DPLL Lock Fall Interrupt Enable */
uint32_t DPLLLTO:1; /**< bit: 18 DPLL Lock Timeout Interrupt Enable */
uint32_t DPLLLDRTO:1; /**< bit: 19 DPLL Loop Divider Ratio Update Complete Interrupt Enable */
uint32_t :12; /**< bit: 20..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} OSCCTRL_INTENSET_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define OSCCTRL_INTENSET_OFFSET (0x08) /**< (OSCCTRL_INTENSET) Interrupt Enable Set Offset */
#define OSCCTRL_INTENSET_RESETVALUE _U_(0x00) /**< (OSCCTRL_INTENSET) Interrupt Enable Set Reset Value */
#define OSCCTRL_INTENSET_XOSCRDY_Pos 0 /**< (OSCCTRL_INTENSET) XOSC Ready Interrupt Enable Position */
#define OSCCTRL_INTENSET_XOSCRDY_Msk (_U_(0x1) << OSCCTRL_INTENSET_XOSCRDY_Pos) /**< (OSCCTRL_INTENSET) XOSC Ready Interrupt Enable Mask */
#define OSCCTRL_INTENSET_XOSCRDY OSCCTRL_INTENSET_XOSCRDY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_INTENSET_XOSCRDY_Msk instead */
#define OSCCTRL_INTENSET_XOSCFAIL_Pos 1 /**< (OSCCTRL_INTENSET) XOSC Clock Failure Detector Interrupt Enable Position */
#define OSCCTRL_INTENSET_XOSCFAIL_Msk (_U_(0x1) << OSCCTRL_INTENSET_XOSCFAIL_Pos) /**< (OSCCTRL_INTENSET) XOSC Clock Failure Detector Interrupt Enable Mask */
#define OSCCTRL_INTENSET_XOSCFAIL OSCCTRL_INTENSET_XOSCFAIL_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_INTENSET_XOSCFAIL_Msk instead */
#define OSCCTRL_INTENSET_OSC16MRDY_Pos 4 /**< (OSCCTRL_INTENSET) OSC16M Ready Interrupt Enable Position */
#define OSCCTRL_INTENSET_OSC16MRDY_Msk (_U_(0x1) << OSCCTRL_INTENSET_OSC16MRDY_Pos) /**< (OSCCTRL_INTENSET) OSC16M Ready Interrupt Enable Mask */
#define OSCCTRL_INTENSET_OSC16MRDY OSCCTRL_INTENSET_OSC16MRDY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_INTENSET_OSC16MRDY_Msk instead */
#define OSCCTRL_INTENSET_DFLLULPRDY_Pos 8 /**< (OSCCTRL_INTENSET) DFLLULP Ready interrupt Enable Position */
#define OSCCTRL_INTENSET_DFLLULPRDY_Msk (_U_(0x1) << OSCCTRL_INTENSET_DFLLULPRDY_Pos) /**< (OSCCTRL_INTENSET) DFLLULP Ready interrupt Enable Mask */
#define OSCCTRL_INTENSET_DFLLULPRDY OSCCTRL_INTENSET_DFLLULPRDY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_INTENSET_DFLLULPRDY_Msk instead */
#define OSCCTRL_INTENSET_DFLLULPLOCK_Pos 9 /**< (OSCCTRL_INTENSET) DFLLULP Lock Interrupt Enable Position */
#define OSCCTRL_INTENSET_DFLLULPLOCK_Msk (_U_(0x1) << OSCCTRL_INTENSET_DFLLULPLOCK_Pos) /**< (OSCCTRL_INTENSET) DFLLULP Lock Interrupt Enable Mask */
#define OSCCTRL_INTENSET_DFLLULPLOCK OSCCTRL_INTENSET_DFLLULPLOCK_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_INTENSET_DFLLULPLOCK_Msk instead */
#define OSCCTRL_INTENSET_DFLLULPNOLOCK_Pos 10 /**< (OSCCTRL_INTENSET) DFLLULP No Lock Interrupt Enable Position */
#define OSCCTRL_INTENSET_DFLLULPNOLOCK_Msk (_U_(0x1) << OSCCTRL_INTENSET_DFLLULPNOLOCK_Pos) /**< (OSCCTRL_INTENSET) DFLLULP No Lock Interrupt Enable Mask */
#define OSCCTRL_INTENSET_DFLLULPNOLOCK OSCCTRL_INTENSET_DFLLULPNOLOCK_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_INTENSET_DFLLULPNOLOCK_Msk instead */
#define OSCCTRL_INTENSET_DPLLLCKR_Pos 16 /**< (OSCCTRL_INTENSET) DPLL Lock Rise Interrupt Enable Position */
#define OSCCTRL_INTENSET_DPLLLCKR_Msk (_U_(0x1) << OSCCTRL_INTENSET_DPLLLCKR_Pos) /**< (OSCCTRL_INTENSET) DPLL Lock Rise Interrupt Enable Mask */
#define OSCCTRL_INTENSET_DPLLLCKR OSCCTRL_INTENSET_DPLLLCKR_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_INTENSET_DPLLLCKR_Msk instead */
#define OSCCTRL_INTENSET_DPLLLCKF_Pos 17 /**< (OSCCTRL_INTENSET) DPLL Lock Fall Interrupt Enable Position */
#define OSCCTRL_INTENSET_DPLLLCKF_Msk (_U_(0x1) << OSCCTRL_INTENSET_DPLLLCKF_Pos) /**< (OSCCTRL_INTENSET) DPLL Lock Fall Interrupt Enable Mask */
#define OSCCTRL_INTENSET_DPLLLCKF OSCCTRL_INTENSET_DPLLLCKF_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_INTENSET_DPLLLCKF_Msk instead */
#define OSCCTRL_INTENSET_DPLLLTO_Pos 18 /**< (OSCCTRL_INTENSET) DPLL Lock Timeout Interrupt Enable Position */
#define OSCCTRL_INTENSET_DPLLLTO_Msk (_U_(0x1) << OSCCTRL_INTENSET_DPLLLTO_Pos) /**< (OSCCTRL_INTENSET) DPLL Lock Timeout Interrupt Enable Mask */
#define OSCCTRL_INTENSET_DPLLLTO OSCCTRL_INTENSET_DPLLLTO_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_INTENSET_DPLLLTO_Msk instead */
#define OSCCTRL_INTENSET_DPLLLDRTO_Pos 19 /**< (OSCCTRL_INTENSET) DPLL Loop Divider Ratio Update Complete Interrupt Enable Position */
#define OSCCTRL_INTENSET_DPLLLDRTO_Msk (_U_(0x1) << OSCCTRL_INTENSET_DPLLLDRTO_Pos) /**< (OSCCTRL_INTENSET) DPLL Loop Divider Ratio Update Complete Interrupt Enable Mask */
#define OSCCTRL_INTENSET_DPLLLDRTO OSCCTRL_INTENSET_DPLLLDRTO_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_INTENSET_DPLLLDRTO_Msk instead */
#define OSCCTRL_INTENSET_MASK _U_(0xF0713) /**< \deprecated (OSCCTRL_INTENSET) Register MASK (Use OSCCTRL_INTENSET_Msk instead) */
#define OSCCTRL_INTENSET_Msk _U_(0xF0713) /**< (OSCCTRL_INTENSET) Register Mask */
/* -------- OSCCTRL_INTFLAG : (OSCCTRL Offset: 0x0c) (R/W 32) Interrupt Flag Status and Clear -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union { // __I to avoid read-modify-write on write-to-clear register
struct {
__I uint32_t XOSCRDY:1; /**< bit: 0 XOSC Ready */
__I uint32_t XOSCFAIL:1; /**< bit: 1 XOSC Clock Failure Detector */
__I uint32_t :2; /**< bit: 2..3 Reserved */
__I uint32_t OSC16MRDY:1; /**< bit: 4 OSC16M Ready */
__I uint32_t :3; /**< bit: 5..7 Reserved */
__I uint32_t DFLLULPRDY:1; /**< bit: 8 DFLLULP Ready */
__I uint32_t DFLLULPLOCK:1; /**< bit: 9 DFLLULP Lock */
__I uint32_t DFLLULPNOLOCK:1; /**< bit: 10 DFLLULP No Lock */
__I uint32_t :5; /**< bit: 11..15 Reserved */
__I uint32_t DPLLLCKR:1; /**< bit: 16 DPLL Lock Rise */
__I uint32_t DPLLLCKF:1; /**< bit: 17 DPLL Lock Fall */
__I uint32_t DPLLLTO:1; /**< bit: 18 DPLL Lock Timeout */
__I uint32_t DPLLLDRTO:1; /**< bit: 19 DPLL Loop Divider Ratio Update Complete */
__I uint32_t :12; /**< bit: 20..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} OSCCTRL_INTFLAG_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define OSCCTRL_INTFLAG_OFFSET (0x0C) /**< (OSCCTRL_INTFLAG) Interrupt Flag Status and Clear Offset */
#define OSCCTRL_INTFLAG_RESETVALUE _U_(0x00) /**< (OSCCTRL_INTFLAG) Interrupt Flag Status and Clear Reset Value */
#define OSCCTRL_INTFLAG_XOSCRDY_Pos 0 /**< (OSCCTRL_INTFLAG) XOSC Ready Position */
#define OSCCTRL_INTFLAG_XOSCRDY_Msk (_U_(0x1) << OSCCTRL_INTFLAG_XOSCRDY_Pos) /**< (OSCCTRL_INTFLAG) XOSC Ready Mask */
#define OSCCTRL_INTFLAG_XOSCRDY OSCCTRL_INTFLAG_XOSCRDY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_INTFLAG_XOSCRDY_Msk instead */
#define OSCCTRL_INTFLAG_XOSCFAIL_Pos 1 /**< (OSCCTRL_INTFLAG) XOSC Clock Failure Detector Position */
#define OSCCTRL_INTFLAG_XOSCFAIL_Msk (_U_(0x1) << OSCCTRL_INTFLAG_XOSCFAIL_Pos) /**< (OSCCTRL_INTFLAG) XOSC Clock Failure Detector Mask */
#define OSCCTRL_INTFLAG_XOSCFAIL OSCCTRL_INTFLAG_XOSCFAIL_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_INTFLAG_XOSCFAIL_Msk instead */
#define OSCCTRL_INTFLAG_OSC16MRDY_Pos 4 /**< (OSCCTRL_INTFLAG) OSC16M Ready Position */
#define OSCCTRL_INTFLAG_OSC16MRDY_Msk (_U_(0x1) << OSCCTRL_INTFLAG_OSC16MRDY_Pos) /**< (OSCCTRL_INTFLAG) OSC16M Ready Mask */
#define OSCCTRL_INTFLAG_OSC16MRDY OSCCTRL_INTFLAG_OSC16MRDY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_INTFLAG_OSC16MRDY_Msk instead */
#define OSCCTRL_INTFLAG_DFLLULPRDY_Pos 8 /**< (OSCCTRL_INTFLAG) DFLLULP Ready Position */
#define OSCCTRL_INTFLAG_DFLLULPRDY_Msk (_U_(0x1) << OSCCTRL_INTFLAG_DFLLULPRDY_Pos) /**< (OSCCTRL_INTFLAG) DFLLULP Ready Mask */
#define OSCCTRL_INTFLAG_DFLLULPRDY OSCCTRL_INTFLAG_DFLLULPRDY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_INTFLAG_DFLLULPRDY_Msk instead */
#define OSCCTRL_INTFLAG_DFLLULPLOCK_Pos 9 /**< (OSCCTRL_INTFLAG) DFLLULP Lock Position */
#define OSCCTRL_INTFLAG_DFLLULPLOCK_Msk (_U_(0x1) << OSCCTRL_INTFLAG_DFLLULPLOCK_Pos) /**< (OSCCTRL_INTFLAG) DFLLULP Lock Mask */
#define OSCCTRL_INTFLAG_DFLLULPLOCK OSCCTRL_INTFLAG_DFLLULPLOCK_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_INTFLAG_DFLLULPLOCK_Msk instead */
#define OSCCTRL_INTFLAG_DFLLULPNOLOCK_Pos 10 /**< (OSCCTRL_INTFLAG) DFLLULP No Lock Position */
#define OSCCTRL_INTFLAG_DFLLULPNOLOCK_Msk (_U_(0x1) << OSCCTRL_INTFLAG_DFLLULPNOLOCK_Pos) /**< (OSCCTRL_INTFLAG) DFLLULP No Lock Mask */
#define OSCCTRL_INTFLAG_DFLLULPNOLOCK OSCCTRL_INTFLAG_DFLLULPNOLOCK_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_INTFLAG_DFLLULPNOLOCK_Msk instead */
#define OSCCTRL_INTFLAG_DPLLLCKR_Pos 16 /**< (OSCCTRL_INTFLAG) DPLL Lock Rise Position */
#define OSCCTRL_INTFLAG_DPLLLCKR_Msk (_U_(0x1) << OSCCTRL_INTFLAG_DPLLLCKR_Pos) /**< (OSCCTRL_INTFLAG) DPLL Lock Rise Mask */
#define OSCCTRL_INTFLAG_DPLLLCKR OSCCTRL_INTFLAG_DPLLLCKR_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_INTFLAG_DPLLLCKR_Msk instead */
#define OSCCTRL_INTFLAG_DPLLLCKF_Pos 17 /**< (OSCCTRL_INTFLAG) DPLL Lock Fall Position */
#define OSCCTRL_INTFLAG_DPLLLCKF_Msk (_U_(0x1) << OSCCTRL_INTFLAG_DPLLLCKF_Pos) /**< (OSCCTRL_INTFLAG) DPLL Lock Fall Mask */
#define OSCCTRL_INTFLAG_DPLLLCKF OSCCTRL_INTFLAG_DPLLLCKF_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_INTFLAG_DPLLLCKF_Msk instead */
#define OSCCTRL_INTFLAG_DPLLLTO_Pos 18 /**< (OSCCTRL_INTFLAG) DPLL Lock Timeout Position */
#define OSCCTRL_INTFLAG_DPLLLTO_Msk (_U_(0x1) << OSCCTRL_INTFLAG_DPLLLTO_Pos) /**< (OSCCTRL_INTFLAG) DPLL Lock Timeout Mask */
#define OSCCTRL_INTFLAG_DPLLLTO OSCCTRL_INTFLAG_DPLLLTO_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_INTFLAG_DPLLLTO_Msk instead */
#define OSCCTRL_INTFLAG_DPLLLDRTO_Pos 19 /**< (OSCCTRL_INTFLAG) DPLL Loop Divider Ratio Update Complete Position */
#define OSCCTRL_INTFLAG_DPLLLDRTO_Msk (_U_(0x1) << OSCCTRL_INTFLAG_DPLLLDRTO_Pos) /**< (OSCCTRL_INTFLAG) DPLL Loop Divider Ratio Update Complete Mask */
#define OSCCTRL_INTFLAG_DPLLLDRTO OSCCTRL_INTFLAG_DPLLLDRTO_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_INTFLAG_DPLLLDRTO_Msk instead */
#define OSCCTRL_INTFLAG_MASK _U_(0xF0713) /**< \deprecated (OSCCTRL_INTFLAG) Register MASK (Use OSCCTRL_INTFLAG_Msk instead) */
#define OSCCTRL_INTFLAG_Msk _U_(0xF0713) /**< (OSCCTRL_INTFLAG) Register Mask */
/* -------- OSCCTRL_STATUS : (OSCCTRL Offset: 0x10) (R/ 32) Status -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t XOSCRDY:1; /**< bit: 0 XOSC Ready */
uint32_t XOSCFAIL:1; /**< bit: 1 XOSC Clock Failure Detector */
uint32_t XOSCCKSW:1; /**< bit: 2 XOSC Clock Switch */
uint32_t :1; /**< bit: 3 Reserved */
uint32_t OSC16MRDY:1; /**< bit: 4 OSC16M Ready */
uint32_t :3; /**< bit: 5..7 Reserved */
uint32_t DFLLULPRDY:1; /**< bit: 8 DFLLULP Ready */
uint32_t DFLLULPLOCK:1; /**< bit: 9 DFLLULP Lock */
uint32_t DFLLULPNOLOCK:1; /**< bit: 10 DFLLULP No Lock */
uint32_t :5; /**< bit: 11..15 Reserved */
uint32_t DPLLLCKR:1; /**< bit: 16 DPLL Lock Rise */
uint32_t DPLLLCKF:1; /**< bit: 17 DPLL Lock Fall */
uint32_t DPLLTO:1; /**< bit: 18 DPLL Lock Timeout */
uint32_t DPLLLDRTO:1; /**< bit: 19 DPLL Loop Divider Ratio Update Complete */
uint32_t :12; /**< bit: 20..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} OSCCTRL_STATUS_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define OSCCTRL_STATUS_OFFSET (0x10) /**< (OSCCTRL_STATUS) Status Offset */
#define OSCCTRL_STATUS_RESETVALUE _U_(0x00) /**< (OSCCTRL_STATUS) Status Reset Value */
#define OSCCTRL_STATUS_XOSCRDY_Pos 0 /**< (OSCCTRL_STATUS) XOSC Ready Position */
#define OSCCTRL_STATUS_XOSCRDY_Msk (_U_(0x1) << OSCCTRL_STATUS_XOSCRDY_Pos) /**< (OSCCTRL_STATUS) XOSC Ready Mask */
#define OSCCTRL_STATUS_XOSCRDY OSCCTRL_STATUS_XOSCRDY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_STATUS_XOSCRDY_Msk instead */
#define OSCCTRL_STATUS_XOSCFAIL_Pos 1 /**< (OSCCTRL_STATUS) XOSC Clock Failure Detector Position */
#define OSCCTRL_STATUS_XOSCFAIL_Msk (_U_(0x1) << OSCCTRL_STATUS_XOSCFAIL_Pos) /**< (OSCCTRL_STATUS) XOSC Clock Failure Detector Mask */
#define OSCCTRL_STATUS_XOSCFAIL OSCCTRL_STATUS_XOSCFAIL_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_STATUS_XOSCFAIL_Msk instead */
#define OSCCTRL_STATUS_XOSCCKSW_Pos 2 /**< (OSCCTRL_STATUS) XOSC Clock Switch Position */
#define OSCCTRL_STATUS_XOSCCKSW_Msk (_U_(0x1) << OSCCTRL_STATUS_XOSCCKSW_Pos) /**< (OSCCTRL_STATUS) XOSC Clock Switch Mask */
#define OSCCTRL_STATUS_XOSCCKSW OSCCTRL_STATUS_XOSCCKSW_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_STATUS_XOSCCKSW_Msk instead */
#define OSCCTRL_STATUS_OSC16MRDY_Pos 4 /**< (OSCCTRL_STATUS) OSC16M Ready Position */
#define OSCCTRL_STATUS_OSC16MRDY_Msk (_U_(0x1) << OSCCTRL_STATUS_OSC16MRDY_Pos) /**< (OSCCTRL_STATUS) OSC16M Ready Mask */
#define OSCCTRL_STATUS_OSC16MRDY OSCCTRL_STATUS_OSC16MRDY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_STATUS_OSC16MRDY_Msk instead */
#define OSCCTRL_STATUS_DFLLULPRDY_Pos 8 /**< (OSCCTRL_STATUS) DFLLULP Ready Position */
#define OSCCTRL_STATUS_DFLLULPRDY_Msk (_U_(0x1) << OSCCTRL_STATUS_DFLLULPRDY_Pos) /**< (OSCCTRL_STATUS) DFLLULP Ready Mask */
#define OSCCTRL_STATUS_DFLLULPRDY OSCCTRL_STATUS_DFLLULPRDY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_STATUS_DFLLULPRDY_Msk instead */
#define OSCCTRL_STATUS_DFLLULPLOCK_Pos 9 /**< (OSCCTRL_STATUS) DFLLULP Lock Position */
#define OSCCTRL_STATUS_DFLLULPLOCK_Msk (_U_(0x1) << OSCCTRL_STATUS_DFLLULPLOCK_Pos) /**< (OSCCTRL_STATUS) DFLLULP Lock Mask */
#define OSCCTRL_STATUS_DFLLULPLOCK OSCCTRL_STATUS_DFLLULPLOCK_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_STATUS_DFLLULPLOCK_Msk instead */
#define OSCCTRL_STATUS_DFLLULPNOLOCK_Pos 10 /**< (OSCCTRL_STATUS) DFLLULP No Lock Position */
#define OSCCTRL_STATUS_DFLLULPNOLOCK_Msk (_U_(0x1) << OSCCTRL_STATUS_DFLLULPNOLOCK_Pos) /**< (OSCCTRL_STATUS) DFLLULP No Lock Mask */
#define OSCCTRL_STATUS_DFLLULPNOLOCK OSCCTRL_STATUS_DFLLULPNOLOCK_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_STATUS_DFLLULPNOLOCK_Msk instead */
#define OSCCTRL_STATUS_DPLLLCKR_Pos 16 /**< (OSCCTRL_STATUS) DPLL Lock Rise Position */
#define OSCCTRL_STATUS_DPLLLCKR_Msk (_U_(0x1) << OSCCTRL_STATUS_DPLLLCKR_Pos) /**< (OSCCTRL_STATUS) DPLL Lock Rise Mask */
#define OSCCTRL_STATUS_DPLLLCKR OSCCTRL_STATUS_DPLLLCKR_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_STATUS_DPLLLCKR_Msk instead */
#define OSCCTRL_STATUS_DPLLLCKF_Pos 17 /**< (OSCCTRL_STATUS) DPLL Lock Fall Position */
#define OSCCTRL_STATUS_DPLLLCKF_Msk (_U_(0x1) << OSCCTRL_STATUS_DPLLLCKF_Pos) /**< (OSCCTRL_STATUS) DPLL Lock Fall Mask */
#define OSCCTRL_STATUS_DPLLLCKF OSCCTRL_STATUS_DPLLLCKF_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_STATUS_DPLLLCKF_Msk instead */
#define OSCCTRL_STATUS_DPLLTO_Pos 18 /**< (OSCCTRL_STATUS) DPLL Lock Timeout Position */
#define OSCCTRL_STATUS_DPLLTO_Msk (_U_(0x1) << OSCCTRL_STATUS_DPLLTO_Pos) /**< (OSCCTRL_STATUS) DPLL Lock Timeout Mask */
#define OSCCTRL_STATUS_DPLLTO OSCCTRL_STATUS_DPLLTO_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_STATUS_DPLLTO_Msk instead */
#define OSCCTRL_STATUS_DPLLLDRTO_Pos 19 /**< (OSCCTRL_STATUS) DPLL Loop Divider Ratio Update Complete Position */
#define OSCCTRL_STATUS_DPLLLDRTO_Msk (_U_(0x1) << OSCCTRL_STATUS_DPLLLDRTO_Pos) /**< (OSCCTRL_STATUS) DPLL Loop Divider Ratio Update Complete Mask */
#define OSCCTRL_STATUS_DPLLLDRTO OSCCTRL_STATUS_DPLLLDRTO_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_STATUS_DPLLLDRTO_Msk instead */
#define OSCCTRL_STATUS_MASK _U_(0xF0717) /**< \deprecated (OSCCTRL_STATUS) Register MASK (Use OSCCTRL_STATUS_Msk instead) */
#define OSCCTRL_STATUS_Msk _U_(0xF0717) /**< (OSCCTRL_STATUS) Register Mask */
/* -------- OSCCTRL_XOSCCTRL : (OSCCTRL Offset: 0x14) (R/W 16) External Multipurpose Crystal Oscillator (XOSC) Control -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint16_t :1; /**< bit: 0 Reserved */
uint16_t ENABLE:1; /**< bit: 1 Oscillator Enable */
uint16_t XTALEN:1; /**< bit: 2 Crystal Oscillator Enable */
uint16_t CFDEN:1; /**< bit: 3 Clock Failure Detector Enable */
uint16_t SWBEN:1; /**< bit: 4 Xosc Clock Switch Enable */
uint16_t :1; /**< bit: 5 Reserved */
uint16_t RUNSTDBY:1; /**< bit: 6 Run in Standby */
uint16_t ONDEMAND:1; /**< bit: 7 On Demand Control */
uint16_t GAIN:3; /**< bit: 8..10 Oscillator Gain */
uint16_t AMPGC:1; /**< bit: 11 Automatic Amplitude Gain Control */
uint16_t STARTUP:4; /**< bit: 12..15 Start-Up Time */
} bit; /**< Structure used for bit access */
uint16_t reg; /**< Type used for register access */
} OSCCTRL_XOSCCTRL_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define OSCCTRL_XOSCCTRL_OFFSET (0x14) /**< (OSCCTRL_XOSCCTRL) External Multipurpose Crystal Oscillator (XOSC) Control Offset */
#define OSCCTRL_XOSCCTRL_RESETVALUE _U_(0x80) /**< (OSCCTRL_XOSCCTRL) External Multipurpose Crystal Oscillator (XOSC) Control Reset Value */
#define OSCCTRL_XOSCCTRL_ENABLE_Pos 1 /**< (OSCCTRL_XOSCCTRL) Oscillator Enable Position */
#define OSCCTRL_XOSCCTRL_ENABLE_Msk (_U_(0x1) << OSCCTRL_XOSCCTRL_ENABLE_Pos) /**< (OSCCTRL_XOSCCTRL) Oscillator Enable Mask */
#define OSCCTRL_XOSCCTRL_ENABLE OSCCTRL_XOSCCTRL_ENABLE_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_XOSCCTRL_ENABLE_Msk instead */
#define OSCCTRL_XOSCCTRL_XTALEN_Pos 2 /**< (OSCCTRL_XOSCCTRL) Crystal Oscillator Enable Position */
#define OSCCTRL_XOSCCTRL_XTALEN_Msk (_U_(0x1) << OSCCTRL_XOSCCTRL_XTALEN_Pos) /**< (OSCCTRL_XOSCCTRL) Crystal Oscillator Enable Mask */
#define OSCCTRL_XOSCCTRL_XTALEN OSCCTRL_XOSCCTRL_XTALEN_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_XOSCCTRL_XTALEN_Msk instead */
#define OSCCTRL_XOSCCTRL_CFDEN_Pos 3 /**< (OSCCTRL_XOSCCTRL) Clock Failure Detector Enable Position */
#define OSCCTRL_XOSCCTRL_CFDEN_Msk (_U_(0x1) << OSCCTRL_XOSCCTRL_CFDEN_Pos) /**< (OSCCTRL_XOSCCTRL) Clock Failure Detector Enable Mask */
#define OSCCTRL_XOSCCTRL_CFDEN OSCCTRL_XOSCCTRL_CFDEN_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_XOSCCTRL_CFDEN_Msk instead */
#define OSCCTRL_XOSCCTRL_SWBEN_Pos 4 /**< (OSCCTRL_XOSCCTRL) Xosc Clock Switch Enable Position */
#define OSCCTRL_XOSCCTRL_SWBEN_Msk (_U_(0x1) << OSCCTRL_XOSCCTRL_SWBEN_Pos) /**< (OSCCTRL_XOSCCTRL) Xosc Clock Switch Enable Mask */
#define OSCCTRL_XOSCCTRL_SWBEN OSCCTRL_XOSCCTRL_SWBEN_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_XOSCCTRL_SWBEN_Msk instead */
#define OSCCTRL_XOSCCTRL_RUNSTDBY_Pos 6 /**< (OSCCTRL_XOSCCTRL) Run in Standby Position */
#define OSCCTRL_XOSCCTRL_RUNSTDBY_Msk (_U_(0x1) << OSCCTRL_XOSCCTRL_RUNSTDBY_Pos) /**< (OSCCTRL_XOSCCTRL) Run in Standby Mask */
#define OSCCTRL_XOSCCTRL_RUNSTDBY OSCCTRL_XOSCCTRL_RUNSTDBY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_XOSCCTRL_RUNSTDBY_Msk instead */
#define OSCCTRL_XOSCCTRL_ONDEMAND_Pos 7 /**< (OSCCTRL_XOSCCTRL) On Demand Control Position */
#define OSCCTRL_XOSCCTRL_ONDEMAND_Msk (_U_(0x1) << OSCCTRL_XOSCCTRL_ONDEMAND_Pos) /**< (OSCCTRL_XOSCCTRL) On Demand Control Mask */
#define OSCCTRL_XOSCCTRL_ONDEMAND OSCCTRL_XOSCCTRL_ONDEMAND_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_XOSCCTRL_ONDEMAND_Msk instead */
#define OSCCTRL_XOSCCTRL_GAIN_Pos 8 /**< (OSCCTRL_XOSCCTRL) Oscillator Gain Position */
#define OSCCTRL_XOSCCTRL_GAIN_Msk (_U_(0x7) << OSCCTRL_XOSCCTRL_GAIN_Pos) /**< (OSCCTRL_XOSCCTRL) Oscillator Gain Mask */
#define OSCCTRL_XOSCCTRL_GAIN(value) (OSCCTRL_XOSCCTRL_GAIN_Msk & ((value) << OSCCTRL_XOSCCTRL_GAIN_Pos))
#define OSCCTRL_XOSCCTRL_AMPGC_Pos 11 /**< (OSCCTRL_XOSCCTRL) Automatic Amplitude Gain Control Position */
#define OSCCTRL_XOSCCTRL_AMPGC_Msk (_U_(0x1) << OSCCTRL_XOSCCTRL_AMPGC_Pos) /**< (OSCCTRL_XOSCCTRL) Automatic Amplitude Gain Control Mask */
#define OSCCTRL_XOSCCTRL_AMPGC OSCCTRL_XOSCCTRL_AMPGC_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_XOSCCTRL_AMPGC_Msk instead */
#define OSCCTRL_XOSCCTRL_STARTUP_Pos 12 /**< (OSCCTRL_XOSCCTRL) Start-Up Time Position */
#define OSCCTRL_XOSCCTRL_STARTUP_Msk (_U_(0xF) << OSCCTRL_XOSCCTRL_STARTUP_Pos) /**< (OSCCTRL_XOSCCTRL) Start-Up Time Mask */
#define OSCCTRL_XOSCCTRL_STARTUP(value) (OSCCTRL_XOSCCTRL_STARTUP_Msk & ((value) << OSCCTRL_XOSCCTRL_STARTUP_Pos))
#define OSCCTRL_XOSCCTRL_MASK _U_(0xFFDE) /**< \deprecated (OSCCTRL_XOSCCTRL) Register MASK (Use OSCCTRL_XOSCCTRL_Msk instead) */
#define OSCCTRL_XOSCCTRL_Msk _U_(0xFFDE) /**< (OSCCTRL_XOSCCTRL) Register Mask */
/* -------- OSCCTRL_CFDPRESC : (OSCCTRL Offset: 0x16) (R/W 8) Clock Failure Detector Prescaler -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t CFDPRESC:3; /**< bit: 0..2 Clock Failure Detector Prescaler */
uint8_t :5; /**< bit: 3..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} OSCCTRL_CFDPRESC_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define OSCCTRL_CFDPRESC_OFFSET (0x16) /**< (OSCCTRL_CFDPRESC) Clock Failure Detector Prescaler Offset */
#define OSCCTRL_CFDPRESC_RESETVALUE _U_(0x00) /**< (OSCCTRL_CFDPRESC) Clock Failure Detector Prescaler Reset Value */
#define OSCCTRL_CFDPRESC_CFDPRESC_Pos 0 /**< (OSCCTRL_CFDPRESC) Clock Failure Detector Prescaler Position */
#define OSCCTRL_CFDPRESC_CFDPRESC_Msk (_U_(0x7) << OSCCTRL_CFDPRESC_CFDPRESC_Pos) /**< (OSCCTRL_CFDPRESC) Clock Failure Detector Prescaler Mask */
#define OSCCTRL_CFDPRESC_CFDPRESC(value) (OSCCTRL_CFDPRESC_CFDPRESC_Msk & ((value) << OSCCTRL_CFDPRESC_CFDPRESC_Pos))
#define OSCCTRL_CFDPRESC_MASK _U_(0x07) /**< \deprecated (OSCCTRL_CFDPRESC) Register MASK (Use OSCCTRL_CFDPRESC_Msk instead) */
#define OSCCTRL_CFDPRESC_Msk _U_(0x07) /**< (OSCCTRL_CFDPRESC) Register Mask */
/* -------- OSCCTRL_OSC16MCTRL : (OSCCTRL Offset: 0x18) (R/W 8) 16MHz Internal Oscillator (OSC16M) Control -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t :1; /**< bit: 0 Reserved */
uint8_t ENABLE:1; /**< bit: 1 Oscillator Enable */
uint8_t FSEL:2; /**< bit: 2..3 Oscillator Frequency Selection */
uint8_t :2; /**< bit: 4..5 Reserved */
uint8_t RUNSTDBY:1; /**< bit: 6 Run in Standby */
uint8_t ONDEMAND:1; /**< bit: 7 On Demand Control */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} OSCCTRL_OSC16MCTRL_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define OSCCTRL_OSC16MCTRL_OFFSET (0x18) /**< (OSCCTRL_OSC16MCTRL) 16MHz Internal Oscillator (OSC16M) Control Offset */
#define OSCCTRL_OSC16MCTRL_RESETVALUE _U_(0x82) /**< (OSCCTRL_OSC16MCTRL) 16MHz Internal Oscillator (OSC16M) Control Reset Value */
#define OSCCTRL_OSC16MCTRL_ENABLE_Pos 1 /**< (OSCCTRL_OSC16MCTRL) Oscillator Enable Position */
#define OSCCTRL_OSC16MCTRL_ENABLE_Msk (_U_(0x1) << OSCCTRL_OSC16MCTRL_ENABLE_Pos) /**< (OSCCTRL_OSC16MCTRL) Oscillator Enable Mask */
#define OSCCTRL_OSC16MCTRL_ENABLE OSCCTRL_OSC16MCTRL_ENABLE_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_OSC16MCTRL_ENABLE_Msk instead */
#define OSCCTRL_OSC16MCTRL_FSEL_Pos 2 /**< (OSCCTRL_OSC16MCTRL) Oscillator Frequency Selection Position */
#define OSCCTRL_OSC16MCTRL_FSEL_Msk (_U_(0x3) << OSCCTRL_OSC16MCTRL_FSEL_Pos) /**< (OSCCTRL_OSC16MCTRL) Oscillator Frequency Selection Mask */
#define OSCCTRL_OSC16MCTRL_FSEL(value) (OSCCTRL_OSC16MCTRL_FSEL_Msk & ((value) << OSCCTRL_OSC16MCTRL_FSEL_Pos))
#define OSCCTRL_OSC16MCTRL_FSEL_4_Val _U_(0x0) /**< (OSCCTRL_OSC16MCTRL) 4MHz */
#define OSCCTRL_OSC16MCTRL_FSEL_8_Val _U_(0x1) /**< (OSCCTRL_OSC16MCTRL) 8MHz */
#define OSCCTRL_OSC16MCTRL_FSEL_12_Val _U_(0x2) /**< (OSCCTRL_OSC16MCTRL) 12MHz */
#define OSCCTRL_OSC16MCTRL_FSEL_16_Val _U_(0x3) /**< (OSCCTRL_OSC16MCTRL) 16MHz */
#define OSCCTRL_OSC16MCTRL_FSEL_4 (OSCCTRL_OSC16MCTRL_FSEL_4_Val << OSCCTRL_OSC16MCTRL_FSEL_Pos) /**< (OSCCTRL_OSC16MCTRL) 4MHz Position */
#define OSCCTRL_OSC16MCTRL_FSEL_8 (OSCCTRL_OSC16MCTRL_FSEL_8_Val << OSCCTRL_OSC16MCTRL_FSEL_Pos) /**< (OSCCTRL_OSC16MCTRL) 8MHz Position */
#define OSCCTRL_OSC16MCTRL_FSEL_12 (OSCCTRL_OSC16MCTRL_FSEL_12_Val << OSCCTRL_OSC16MCTRL_FSEL_Pos) /**< (OSCCTRL_OSC16MCTRL) 12MHz Position */
#define OSCCTRL_OSC16MCTRL_FSEL_16 (OSCCTRL_OSC16MCTRL_FSEL_16_Val << OSCCTRL_OSC16MCTRL_FSEL_Pos) /**< (OSCCTRL_OSC16MCTRL) 16MHz Position */
#define OSCCTRL_OSC16MCTRL_RUNSTDBY_Pos 6 /**< (OSCCTRL_OSC16MCTRL) Run in Standby Position */
#define OSCCTRL_OSC16MCTRL_RUNSTDBY_Msk (_U_(0x1) << OSCCTRL_OSC16MCTRL_RUNSTDBY_Pos) /**< (OSCCTRL_OSC16MCTRL) Run in Standby Mask */
#define OSCCTRL_OSC16MCTRL_RUNSTDBY OSCCTRL_OSC16MCTRL_RUNSTDBY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_OSC16MCTRL_RUNSTDBY_Msk instead */
#define OSCCTRL_OSC16MCTRL_ONDEMAND_Pos 7 /**< (OSCCTRL_OSC16MCTRL) On Demand Control Position */
#define OSCCTRL_OSC16MCTRL_ONDEMAND_Msk (_U_(0x1) << OSCCTRL_OSC16MCTRL_ONDEMAND_Pos) /**< (OSCCTRL_OSC16MCTRL) On Demand Control Mask */
#define OSCCTRL_OSC16MCTRL_ONDEMAND OSCCTRL_OSC16MCTRL_ONDEMAND_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_OSC16MCTRL_ONDEMAND_Msk instead */
#define OSCCTRL_OSC16MCTRL_MASK _U_(0xCE) /**< \deprecated (OSCCTRL_OSC16MCTRL) Register MASK (Use OSCCTRL_OSC16MCTRL_Msk instead) */
#define OSCCTRL_OSC16MCTRL_Msk _U_(0xCE) /**< (OSCCTRL_OSC16MCTRL) Register Mask */
/* -------- OSCCTRL_DFLLULPCTRL : (OSCCTRL Offset: 0x1c) (R/W 16) DFLLULP Control -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint16_t :1; /**< bit: 0 Reserved */
uint16_t ENABLE:1; /**< bit: 1 Enable */
uint16_t :1; /**< bit: 2 Reserved */
uint16_t BINSE:1; /**< bit: 3 Binary Search Enable */
uint16_t SAFE:1; /**< bit: 4 Tuner Safe Mode */
uint16_t DITHER:1; /**< bit: 5 Tuner Dither Mode */
uint16_t RUNSTDBY:1; /**< bit: 6 Run in Standby */
uint16_t ONDEMAND:1; /**< bit: 7 On Demand */
uint16_t DIV:3; /**< bit: 8..10 Division Factor */
uint16_t :5; /**< bit: 11..15 Reserved */
} bit; /**< Structure used for bit access */
uint16_t reg; /**< Type used for register access */
} OSCCTRL_DFLLULPCTRL_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define OSCCTRL_DFLLULPCTRL_OFFSET (0x1C) /**< (OSCCTRL_DFLLULPCTRL) DFLLULP Control Offset */
#define OSCCTRL_DFLLULPCTRL_RESETVALUE _U_(0x504) /**< (OSCCTRL_DFLLULPCTRL) DFLLULP Control Reset Value */
#define OSCCTRL_DFLLULPCTRL_ENABLE_Pos 1 /**< (OSCCTRL_DFLLULPCTRL) Enable Position */
#define OSCCTRL_DFLLULPCTRL_ENABLE_Msk (_U_(0x1) << OSCCTRL_DFLLULPCTRL_ENABLE_Pos) /**< (OSCCTRL_DFLLULPCTRL) Enable Mask */
#define OSCCTRL_DFLLULPCTRL_ENABLE OSCCTRL_DFLLULPCTRL_ENABLE_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_DFLLULPCTRL_ENABLE_Msk instead */
#define OSCCTRL_DFLLULPCTRL_BINSE_Pos 3 /**< (OSCCTRL_DFLLULPCTRL) Binary Search Enable Position */
#define OSCCTRL_DFLLULPCTRL_BINSE_Msk (_U_(0x1) << OSCCTRL_DFLLULPCTRL_BINSE_Pos) /**< (OSCCTRL_DFLLULPCTRL) Binary Search Enable Mask */
#define OSCCTRL_DFLLULPCTRL_BINSE OSCCTRL_DFLLULPCTRL_BINSE_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_DFLLULPCTRL_BINSE_Msk instead */
#define OSCCTRL_DFLLULPCTRL_SAFE_Pos 4 /**< (OSCCTRL_DFLLULPCTRL) Tuner Safe Mode Position */
#define OSCCTRL_DFLLULPCTRL_SAFE_Msk (_U_(0x1) << OSCCTRL_DFLLULPCTRL_SAFE_Pos) /**< (OSCCTRL_DFLLULPCTRL) Tuner Safe Mode Mask */
#define OSCCTRL_DFLLULPCTRL_SAFE OSCCTRL_DFLLULPCTRL_SAFE_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_DFLLULPCTRL_SAFE_Msk instead */
#define OSCCTRL_DFLLULPCTRL_DITHER_Pos 5 /**< (OSCCTRL_DFLLULPCTRL) Tuner Dither Mode Position */
#define OSCCTRL_DFLLULPCTRL_DITHER_Msk (_U_(0x1) << OSCCTRL_DFLLULPCTRL_DITHER_Pos) /**< (OSCCTRL_DFLLULPCTRL) Tuner Dither Mode Mask */
#define OSCCTRL_DFLLULPCTRL_DITHER OSCCTRL_DFLLULPCTRL_DITHER_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_DFLLULPCTRL_DITHER_Msk instead */
#define OSCCTRL_DFLLULPCTRL_RUNSTDBY_Pos 6 /**< (OSCCTRL_DFLLULPCTRL) Run in Standby Position */
#define OSCCTRL_DFLLULPCTRL_RUNSTDBY_Msk (_U_(0x1) << OSCCTRL_DFLLULPCTRL_RUNSTDBY_Pos) /**< (OSCCTRL_DFLLULPCTRL) Run in Standby Mask */
#define OSCCTRL_DFLLULPCTRL_RUNSTDBY OSCCTRL_DFLLULPCTRL_RUNSTDBY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_DFLLULPCTRL_RUNSTDBY_Msk instead */
#define OSCCTRL_DFLLULPCTRL_ONDEMAND_Pos 7 /**< (OSCCTRL_DFLLULPCTRL) On Demand Position */
#define OSCCTRL_DFLLULPCTRL_ONDEMAND_Msk (_U_(0x1) << OSCCTRL_DFLLULPCTRL_ONDEMAND_Pos) /**< (OSCCTRL_DFLLULPCTRL) On Demand Mask */
#define OSCCTRL_DFLLULPCTRL_ONDEMAND OSCCTRL_DFLLULPCTRL_ONDEMAND_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_DFLLULPCTRL_ONDEMAND_Msk instead */
#define OSCCTRL_DFLLULPCTRL_DIV_Pos 8 /**< (OSCCTRL_DFLLULPCTRL) Division Factor Position */
#define OSCCTRL_DFLLULPCTRL_DIV_Msk (_U_(0x7) << OSCCTRL_DFLLULPCTRL_DIV_Pos) /**< (OSCCTRL_DFLLULPCTRL) Division Factor Mask */
#define OSCCTRL_DFLLULPCTRL_DIV(value) (OSCCTRL_DFLLULPCTRL_DIV_Msk & ((value) << OSCCTRL_DFLLULPCTRL_DIV_Pos))
#define OSCCTRL_DFLLULPCTRL_DIV_DIV1_Val _U_(0x0) /**< (OSCCTRL_DFLLULPCTRL) Frequency Divided by 1 */
#define OSCCTRL_DFLLULPCTRL_DIV_DIV2_Val _U_(0x1) /**< (OSCCTRL_DFLLULPCTRL) Frequency Divided by 2 */
#define OSCCTRL_DFLLULPCTRL_DIV_DIV4_Val _U_(0x2) /**< (OSCCTRL_DFLLULPCTRL) Frequency Divided by 4 */
#define OSCCTRL_DFLLULPCTRL_DIV_DIV8_Val _U_(0x3) /**< (OSCCTRL_DFLLULPCTRL) Frequency Divided by 8 */
#define OSCCTRL_DFLLULPCTRL_DIV_DIV16_Val _U_(0x4) /**< (OSCCTRL_DFLLULPCTRL) Frequency Divided by 16 */
#define OSCCTRL_DFLLULPCTRL_DIV_DIV32_Val _U_(0x5) /**< (OSCCTRL_DFLLULPCTRL) Frequency Divided by 32 */
#define OSCCTRL_DFLLULPCTRL_DIV_DIV1 (OSCCTRL_DFLLULPCTRL_DIV_DIV1_Val << OSCCTRL_DFLLULPCTRL_DIV_Pos) /**< (OSCCTRL_DFLLULPCTRL) Frequency Divided by 1 Position */
#define OSCCTRL_DFLLULPCTRL_DIV_DIV2 (OSCCTRL_DFLLULPCTRL_DIV_DIV2_Val << OSCCTRL_DFLLULPCTRL_DIV_Pos) /**< (OSCCTRL_DFLLULPCTRL) Frequency Divided by 2 Position */
#define OSCCTRL_DFLLULPCTRL_DIV_DIV4 (OSCCTRL_DFLLULPCTRL_DIV_DIV4_Val << OSCCTRL_DFLLULPCTRL_DIV_Pos) /**< (OSCCTRL_DFLLULPCTRL) Frequency Divided by 4 Position */
#define OSCCTRL_DFLLULPCTRL_DIV_DIV8 (OSCCTRL_DFLLULPCTRL_DIV_DIV8_Val << OSCCTRL_DFLLULPCTRL_DIV_Pos) /**< (OSCCTRL_DFLLULPCTRL) Frequency Divided by 8 Position */
#define OSCCTRL_DFLLULPCTRL_DIV_DIV16 (OSCCTRL_DFLLULPCTRL_DIV_DIV16_Val << OSCCTRL_DFLLULPCTRL_DIV_Pos) /**< (OSCCTRL_DFLLULPCTRL) Frequency Divided by 16 Position */
#define OSCCTRL_DFLLULPCTRL_DIV_DIV32 (OSCCTRL_DFLLULPCTRL_DIV_DIV32_Val << OSCCTRL_DFLLULPCTRL_DIV_Pos) /**< (OSCCTRL_DFLLULPCTRL) Frequency Divided by 32 Position */
#define OSCCTRL_DFLLULPCTRL_MASK _U_(0x7FA) /**< \deprecated (OSCCTRL_DFLLULPCTRL) Register MASK (Use OSCCTRL_DFLLULPCTRL_Msk instead) */
#define OSCCTRL_DFLLULPCTRL_Msk _U_(0x7FA) /**< (OSCCTRL_DFLLULPCTRL) Register Mask */
/* -------- OSCCTRL_DFLLULPDITHER : (OSCCTRL Offset: 0x1e) (R/W 8) DFLLULP Dither Control -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t STEP:3; /**< bit: 0..2 Dither Step */
uint8_t :1; /**< bit: 3 Reserved */
uint8_t PER:3; /**< bit: 4..6 Dither Period */
uint8_t :1; /**< bit: 7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} OSCCTRL_DFLLULPDITHER_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define OSCCTRL_DFLLULPDITHER_OFFSET (0x1E) /**< (OSCCTRL_DFLLULPDITHER) DFLLULP Dither Control Offset */
#define OSCCTRL_DFLLULPDITHER_RESETVALUE _U_(0x00) /**< (OSCCTRL_DFLLULPDITHER) DFLLULP Dither Control Reset Value */
#define OSCCTRL_DFLLULPDITHER_STEP_Pos 0 /**< (OSCCTRL_DFLLULPDITHER) Dither Step Position */
#define OSCCTRL_DFLLULPDITHER_STEP_Msk (_U_(0x7) << OSCCTRL_DFLLULPDITHER_STEP_Pos) /**< (OSCCTRL_DFLLULPDITHER) Dither Step Mask */
#define OSCCTRL_DFLLULPDITHER_STEP(value) (OSCCTRL_DFLLULPDITHER_STEP_Msk & ((value) << OSCCTRL_DFLLULPDITHER_STEP_Pos))
#define OSCCTRL_DFLLULPDITHER_STEP_STEP1_Val _U_(0x0) /**< (OSCCTRL_DFLLULPDITHER) Dither Step = 1 */
#define OSCCTRL_DFLLULPDITHER_STEP_STEP2_Val _U_(0x1) /**< (OSCCTRL_DFLLULPDITHER) Dither Step = 2 */
#define OSCCTRL_DFLLULPDITHER_STEP_STEP4_Val _U_(0x2) /**< (OSCCTRL_DFLLULPDITHER) Dither Step = 4 */
#define OSCCTRL_DFLLULPDITHER_STEP_STEP8_Val _U_(0x3) /**< (OSCCTRL_DFLLULPDITHER) Dither Step = 8 */
#define OSCCTRL_DFLLULPDITHER_STEP_STEP1 (OSCCTRL_DFLLULPDITHER_STEP_STEP1_Val << OSCCTRL_DFLLULPDITHER_STEP_Pos) /**< (OSCCTRL_DFLLULPDITHER) Dither Step = 1 Position */
#define OSCCTRL_DFLLULPDITHER_STEP_STEP2 (OSCCTRL_DFLLULPDITHER_STEP_STEP2_Val << OSCCTRL_DFLLULPDITHER_STEP_Pos) /**< (OSCCTRL_DFLLULPDITHER) Dither Step = 2 Position */
#define OSCCTRL_DFLLULPDITHER_STEP_STEP4 (OSCCTRL_DFLLULPDITHER_STEP_STEP4_Val << OSCCTRL_DFLLULPDITHER_STEP_Pos) /**< (OSCCTRL_DFLLULPDITHER) Dither Step = 4 Position */
#define OSCCTRL_DFLLULPDITHER_STEP_STEP8 (OSCCTRL_DFLLULPDITHER_STEP_STEP8_Val << OSCCTRL_DFLLULPDITHER_STEP_Pos) /**< (OSCCTRL_DFLLULPDITHER) Dither Step = 8 Position */
#define OSCCTRL_DFLLULPDITHER_PER_Pos 4 /**< (OSCCTRL_DFLLULPDITHER) Dither Period Position */
#define OSCCTRL_DFLLULPDITHER_PER_Msk (_U_(0x7) << OSCCTRL_DFLLULPDITHER_PER_Pos) /**< (OSCCTRL_DFLLULPDITHER) Dither Period Mask */
#define OSCCTRL_DFLLULPDITHER_PER(value) (OSCCTRL_DFLLULPDITHER_PER_Msk & ((value) << OSCCTRL_DFLLULPDITHER_PER_Pos))
#define OSCCTRL_DFLLULPDITHER_PER_PER1_Val _U_(0x0) /**< (OSCCTRL_DFLLULPDITHER) Dither Over 1 Reference Clock Period */
#define OSCCTRL_DFLLULPDITHER_PER_PER2_Val _U_(0x1) /**< (OSCCTRL_DFLLULPDITHER) Dither Over 2 Reference Clock Period */
#define OSCCTRL_DFLLULPDITHER_PER_PER4_Val _U_(0x2) /**< (OSCCTRL_DFLLULPDITHER) Dither Over 4 Reference Clock Period */
#define OSCCTRL_DFLLULPDITHER_PER_PER8_Val _U_(0x3) /**< (OSCCTRL_DFLLULPDITHER) Dither Over 8 Reference Clock Period */
#define OSCCTRL_DFLLULPDITHER_PER_PER16_Val _U_(0x4) /**< (OSCCTRL_DFLLULPDITHER) Dither Over 16 Reference Clock Period */
#define OSCCTRL_DFLLULPDITHER_PER_PER32_Val _U_(0x5) /**< (OSCCTRL_DFLLULPDITHER) Dither Over 32 Reference Clock Period */
#define OSCCTRL_DFLLULPDITHER_PER_PER1 (OSCCTRL_DFLLULPDITHER_PER_PER1_Val << OSCCTRL_DFLLULPDITHER_PER_Pos) /**< (OSCCTRL_DFLLULPDITHER) Dither Over 1 Reference Clock Period Position */
#define OSCCTRL_DFLLULPDITHER_PER_PER2 (OSCCTRL_DFLLULPDITHER_PER_PER2_Val << OSCCTRL_DFLLULPDITHER_PER_Pos) /**< (OSCCTRL_DFLLULPDITHER) Dither Over 2 Reference Clock Period Position */
#define OSCCTRL_DFLLULPDITHER_PER_PER4 (OSCCTRL_DFLLULPDITHER_PER_PER4_Val << OSCCTRL_DFLLULPDITHER_PER_Pos) /**< (OSCCTRL_DFLLULPDITHER) Dither Over 4 Reference Clock Period Position */
#define OSCCTRL_DFLLULPDITHER_PER_PER8 (OSCCTRL_DFLLULPDITHER_PER_PER8_Val << OSCCTRL_DFLLULPDITHER_PER_Pos) /**< (OSCCTRL_DFLLULPDITHER) Dither Over 8 Reference Clock Period Position */
#define OSCCTRL_DFLLULPDITHER_PER_PER16 (OSCCTRL_DFLLULPDITHER_PER_PER16_Val << OSCCTRL_DFLLULPDITHER_PER_Pos) /**< (OSCCTRL_DFLLULPDITHER) Dither Over 16 Reference Clock Period Position */
#define OSCCTRL_DFLLULPDITHER_PER_PER32 (OSCCTRL_DFLLULPDITHER_PER_PER32_Val << OSCCTRL_DFLLULPDITHER_PER_Pos) /**< (OSCCTRL_DFLLULPDITHER) Dither Over 32 Reference Clock Period Position */
#define OSCCTRL_DFLLULPDITHER_MASK _U_(0x77) /**< \deprecated (OSCCTRL_DFLLULPDITHER) Register MASK (Use OSCCTRL_DFLLULPDITHER_Msk instead) */
#define OSCCTRL_DFLLULPDITHER_Msk _U_(0x77) /**< (OSCCTRL_DFLLULPDITHER) Register Mask */
/* -------- OSCCTRL_DFLLULPRREQ : (OSCCTRL Offset: 0x1f) (R/W 8) DFLLULP Read Request -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t :7; /**< bit: 0..6 Reserved */
uint8_t RREQ:1; /**< bit: 7 Read Request */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} OSCCTRL_DFLLULPRREQ_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define OSCCTRL_DFLLULPRREQ_OFFSET (0x1F) /**< (OSCCTRL_DFLLULPRREQ) DFLLULP Read Request Offset */
#define OSCCTRL_DFLLULPRREQ_RESETVALUE _U_(0x00) /**< (OSCCTRL_DFLLULPRREQ) DFLLULP Read Request Reset Value */
#define OSCCTRL_DFLLULPRREQ_RREQ_Pos 7 /**< (OSCCTRL_DFLLULPRREQ) Read Request Position */
#define OSCCTRL_DFLLULPRREQ_RREQ_Msk (_U_(0x1) << OSCCTRL_DFLLULPRREQ_RREQ_Pos) /**< (OSCCTRL_DFLLULPRREQ) Read Request Mask */
#define OSCCTRL_DFLLULPRREQ_RREQ OSCCTRL_DFLLULPRREQ_RREQ_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_DFLLULPRREQ_RREQ_Msk instead */
#define OSCCTRL_DFLLULPRREQ_MASK _U_(0x80) /**< \deprecated (OSCCTRL_DFLLULPRREQ) Register MASK (Use OSCCTRL_DFLLULPRREQ_Msk instead) */
#define OSCCTRL_DFLLULPRREQ_Msk _U_(0x80) /**< (OSCCTRL_DFLLULPRREQ) Register Mask */
/* -------- OSCCTRL_DFLLULPDLY : (OSCCTRL Offset: 0x20) (R/W 32) DFLLULP Delay Value -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t DELAY:8; /**< bit: 0..7 Delay Value */
uint32_t :24; /**< bit: 8..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} OSCCTRL_DFLLULPDLY_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define OSCCTRL_DFLLULPDLY_OFFSET (0x20) /**< (OSCCTRL_DFLLULPDLY) DFLLULP Delay Value Offset */
#define OSCCTRL_DFLLULPDLY_RESETVALUE _U_(0x80) /**< (OSCCTRL_DFLLULPDLY) DFLLULP Delay Value Reset Value */
#define OSCCTRL_DFLLULPDLY_DELAY_Pos 0 /**< (OSCCTRL_DFLLULPDLY) Delay Value Position */
#define OSCCTRL_DFLLULPDLY_DELAY_Msk (_U_(0xFF) << OSCCTRL_DFLLULPDLY_DELAY_Pos) /**< (OSCCTRL_DFLLULPDLY) Delay Value Mask */
#define OSCCTRL_DFLLULPDLY_DELAY(value) (OSCCTRL_DFLLULPDLY_DELAY_Msk & ((value) << OSCCTRL_DFLLULPDLY_DELAY_Pos))
#define OSCCTRL_DFLLULPDLY_MASK _U_(0xFF) /**< \deprecated (OSCCTRL_DFLLULPDLY) Register MASK (Use OSCCTRL_DFLLULPDLY_Msk instead) */
#define OSCCTRL_DFLLULPDLY_Msk _U_(0xFF) /**< (OSCCTRL_DFLLULPDLY) Register Mask */
/* -------- OSCCTRL_DFLLULPRATIO : (OSCCTRL Offset: 0x24) (R/W 32) DFLLULP Target Ratio -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t RATIO:11; /**< bit: 0..10 Target Tuner Ratio */
uint32_t :21; /**< bit: 11..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} OSCCTRL_DFLLULPRATIO_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define OSCCTRL_DFLLULPRATIO_OFFSET (0x24) /**< (OSCCTRL_DFLLULPRATIO) DFLLULP Target Ratio Offset */
#define OSCCTRL_DFLLULPRATIO_RESETVALUE _U_(0x00) /**< (OSCCTRL_DFLLULPRATIO) DFLLULP Target Ratio Reset Value */
#define OSCCTRL_DFLLULPRATIO_RATIO_Pos 0 /**< (OSCCTRL_DFLLULPRATIO) Target Tuner Ratio Position */
#define OSCCTRL_DFLLULPRATIO_RATIO_Msk (_U_(0x7FF) << OSCCTRL_DFLLULPRATIO_RATIO_Pos) /**< (OSCCTRL_DFLLULPRATIO) Target Tuner Ratio Mask */
#define OSCCTRL_DFLLULPRATIO_RATIO(value) (OSCCTRL_DFLLULPRATIO_RATIO_Msk & ((value) << OSCCTRL_DFLLULPRATIO_RATIO_Pos))
#define OSCCTRL_DFLLULPRATIO_MASK _U_(0x7FF) /**< \deprecated (OSCCTRL_DFLLULPRATIO) Register MASK (Use OSCCTRL_DFLLULPRATIO_Msk instead) */
#define OSCCTRL_DFLLULPRATIO_Msk _U_(0x7FF) /**< (OSCCTRL_DFLLULPRATIO) Register Mask */
/* -------- OSCCTRL_DFLLULPSYNCBUSY : (OSCCTRL Offset: 0x28) (R/ 32) DFLLULP Synchronization Busy -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t :1; /**< bit: 0 Reserved */
uint32_t ENABLE:1; /**< bit: 1 Enable Bit Synchronization Busy */
uint32_t TUNE:1; /**< bit: 2 Tune Bit Synchronization Busy */
uint32_t DELAY:1; /**< bit: 3 Delay Register Synchronization Busy */
uint32_t :28; /**< bit: 4..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} OSCCTRL_DFLLULPSYNCBUSY_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define OSCCTRL_DFLLULPSYNCBUSY_OFFSET (0x28) /**< (OSCCTRL_DFLLULPSYNCBUSY) DFLLULP Synchronization Busy Offset */
#define OSCCTRL_DFLLULPSYNCBUSY_RESETVALUE _U_(0x00) /**< (OSCCTRL_DFLLULPSYNCBUSY) DFLLULP Synchronization Busy Reset Value */
#define OSCCTRL_DFLLULPSYNCBUSY_ENABLE_Pos 1 /**< (OSCCTRL_DFLLULPSYNCBUSY) Enable Bit Synchronization Busy Position */
#define OSCCTRL_DFLLULPSYNCBUSY_ENABLE_Msk (_U_(0x1) << OSCCTRL_DFLLULPSYNCBUSY_ENABLE_Pos) /**< (OSCCTRL_DFLLULPSYNCBUSY) Enable Bit Synchronization Busy Mask */
#define OSCCTRL_DFLLULPSYNCBUSY_ENABLE OSCCTRL_DFLLULPSYNCBUSY_ENABLE_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_DFLLULPSYNCBUSY_ENABLE_Msk instead */
#define OSCCTRL_DFLLULPSYNCBUSY_TUNE_Pos 2 /**< (OSCCTRL_DFLLULPSYNCBUSY) Tune Bit Synchronization Busy Position */
#define OSCCTRL_DFLLULPSYNCBUSY_TUNE_Msk (_U_(0x1) << OSCCTRL_DFLLULPSYNCBUSY_TUNE_Pos) /**< (OSCCTRL_DFLLULPSYNCBUSY) Tune Bit Synchronization Busy Mask */
#define OSCCTRL_DFLLULPSYNCBUSY_TUNE OSCCTRL_DFLLULPSYNCBUSY_TUNE_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_DFLLULPSYNCBUSY_TUNE_Msk instead */
#define OSCCTRL_DFLLULPSYNCBUSY_DELAY_Pos 3 /**< (OSCCTRL_DFLLULPSYNCBUSY) Delay Register Synchronization Busy Position */
#define OSCCTRL_DFLLULPSYNCBUSY_DELAY_Msk (_U_(0x1) << OSCCTRL_DFLLULPSYNCBUSY_DELAY_Pos) /**< (OSCCTRL_DFLLULPSYNCBUSY) Delay Register Synchronization Busy Mask */
#define OSCCTRL_DFLLULPSYNCBUSY_DELAY OSCCTRL_DFLLULPSYNCBUSY_DELAY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_DFLLULPSYNCBUSY_DELAY_Msk instead */
#define OSCCTRL_DFLLULPSYNCBUSY_MASK _U_(0x0E) /**< \deprecated (OSCCTRL_DFLLULPSYNCBUSY) Register MASK (Use OSCCTRL_DFLLULPSYNCBUSY_Msk instead) */
#define OSCCTRL_DFLLULPSYNCBUSY_Msk _U_(0x0E) /**< (OSCCTRL_DFLLULPSYNCBUSY) Register Mask */
/* -------- OSCCTRL_DPLLCTRLA : (OSCCTRL Offset: 0x2c) (R/W 8) DPLL Control A -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t :1; /**< bit: 0 Reserved */
uint8_t ENABLE:1; /**< bit: 1 DPLL Enable */
uint8_t :4; /**< bit: 2..5 Reserved */
uint8_t RUNSTDBY:1; /**< bit: 6 Run in Standby */
uint8_t ONDEMAND:1; /**< bit: 7 On Demand Clock Activation */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} OSCCTRL_DPLLCTRLA_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define OSCCTRL_DPLLCTRLA_OFFSET (0x2C) /**< (OSCCTRL_DPLLCTRLA) DPLL Control A Offset */
#define OSCCTRL_DPLLCTRLA_RESETVALUE _U_(0x80) /**< (OSCCTRL_DPLLCTRLA) DPLL Control A Reset Value */
#define OSCCTRL_DPLLCTRLA_ENABLE_Pos 1 /**< (OSCCTRL_DPLLCTRLA) DPLL Enable Position */
#define OSCCTRL_DPLLCTRLA_ENABLE_Msk (_U_(0x1) << OSCCTRL_DPLLCTRLA_ENABLE_Pos) /**< (OSCCTRL_DPLLCTRLA) DPLL Enable Mask */
#define OSCCTRL_DPLLCTRLA_ENABLE OSCCTRL_DPLLCTRLA_ENABLE_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_DPLLCTRLA_ENABLE_Msk instead */
#define OSCCTRL_DPLLCTRLA_RUNSTDBY_Pos 6 /**< (OSCCTRL_DPLLCTRLA) Run in Standby Position */
#define OSCCTRL_DPLLCTRLA_RUNSTDBY_Msk (_U_(0x1) << OSCCTRL_DPLLCTRLA_RUNSTDBY_Pos) /**< (OSCCTRL_DPLLCTRLA) Run in Standby Mask */
#define OSCCTRL_DPLLCTRLA_RUNSTDBY OSCCTRL_DPLLCTRLA_RUNSTDBY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_DPLLCTRLA_RUNSTDBY_Msk instead */
#define OSCCTRL_DPLLCTRLA_ONDEMAND_Pos 7 /**< (OSCCTRL_DPLLCTRLA) On Demand Clock Activation Position */
#define OSCCTRL_DPLLCTRLA_ONDEMAND_Msk (_U_(0x1) << OSCCTRL_DPLLCTRLA_ONDEMAND_Pos) /**< (OSCCTRL_DPLLCTRLA) On Demand Clock Activation Mask */
#define OSCCTRL_DPLLCTRLA_ONDEMAND OSCCTRL_DPLLCTRLA_ONDEMAND_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_DPLLCTRLA_ONDEMAND_Msk instead */
#define OSCCTRL_DPLLCTRLA_MASK _U_(0xC2) /**< \deprecated (OSCCTRL_DPLLCTRLA) Register MASK (Use OSCCTRL_DPLLCTRLA_Msk instead) */
#define OSCCTRL_DPLLCTRLA_Msk _U_(0xC2) /**< (OSCCTRL_DPLLCTRLA) Register Mask */
/* -------- OSCCTRL_DPLLRATIO : (OSCCTRL Offset: 0x30) (R/W 32) DPLL Ratio Control -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t LDR:12; /**< bit: 0..11 Loop Divider Ratio */
uint32_t :4; /**< bit: 12..15 Reserved */
uint32_t LDRFRAC:4; /**< bit: 16..19 Loop Divider Ratio Fractional Part */
uint32_t :12; /**< bit: 20..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} OSCCTRL_DPLLRATIO_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define OSCCTRL_DPLLRATIO_OFFSET (0x30) /**< (OSCCTRL_DPLLRATIO) DPLL Ratio Control Offset */
#define OSCCTRL_DPLLRATIO_RESETVALUE _U_(0x00) /**< (OSCCTRL_DPLLRATIO) DPLL Ratio Control Reset Value */
#define OSCCTRL_DPLLRATIO_LDR_Pos 0 /**< (OSCCTRL_DPLLRATIO) Loop Divider Ratio Position */
#define OSCCTRL_DPLLRATIO_LDR_Msk (_U_(0xFFF) << OSCCTRL_DPLLRATIO_LDR_Pos) /**< (OSCCTRL_DPLLRATIO) Loop Divider Ratio Mask */
#define OSCCTRL_DPLLRATIO_LDR(value) (OSCCTRL_DPLLRATIO_LDR_Msk & ((value) << OSCCTRL_DPLLRATIO_LDR_Pos))
#define OSCCTRL_DPLLRATIO_LDRFRAC_Pos 16 /**< (OSCCTRL_DPLLRATIO) Loop Divider Ratio Fractional Part Position */
#define OSCCTRL_DPLLRATIO_LDRFRAC_Msk (_U_(0xF) << OSCCTRL_DPLLRATIO_LDRFRAC_Pos) /**< (OSCCTRL_DPLLRATIO) Loop Divider Ratio Fractional Part Mask */
#define OSCCTRL_DPLLRATIO_LDRFRAC(value) (OSCCTRL_DPLLRATIO_LDRFRAC_Msk & ((value) << OSCCTRL_DPLLRATIO_LDRFRAC_Pos))
#define OSCCTRL_DPLLRATIO_MASK _U_(0xF0FFF) /**< \deprecated (OSCCTRL_DPLLRATIO) Register MASK (Use OSCCTRL_DPLLRATIO_Msk instead) */
#define OSCCTRL_DPLLRATIO_Msk _U_(0xF0FFF) /**< (OSCCTRL_DPLLRATIO) Register Mask */
/* -------- OSCCTRL_DPLLCTRLB : (OSCCTRL Offset: 0x34) (R/W 32) DPLL Control B -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t FILTER:2; /**< bit: 0..1 Proportional Integral Filter Selection */
uint32_t LPEN:1; /**< bit: 2 Low-Power Enable */
uint32_t WUF:1; /**< bit: 3 Wake Up Fast */
uint32_t REFCLK:2; /**< bit: 4..5 Reference Clock Selection */
uint32_t :2; /**< bit: 6..7 Reserved */
uint32_t LTIME:3; /**< bit: 8..10 Lock Time */
uint32_t :1; /**< bit: 11 Reserved */
uint32_t LBYPASS:1; /**< bit: 12 Lock Bypass */
uint32_t :3; /**< bit: 13..15 Reserved */
uint32_t DIV:11; /**< bit: 16..26 Clock Divider */
uint32_t :5; /**< bit: 27..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} OSCCTRL_DPLLCTRLB_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define OSCCTRL_DPLLCTRLB_OFFSET (0x34) /**< (OSCCTRL_DPLLCTRLB) DPLL Control B Offset */
#define OSCCTRL_DPLLCTRLB_RESETVALUE _U_(0x00) /**< (OSCCTRL_DPLLCTRLB) DPLL Control B Reset Value */
#define OSCCTRL_DPLLCTRLB_FILTER_Pos 0 /**< (OSCCTRL_DPLLCTRLB) Proportional Integral Filter Selection Position */
#define OSCCTRL_DPLLCTRLB_FILTER_Msk (_U_(0x3) << OSCCTRL_DPLLCTRLB_FILTER_Pos) /**< (OSCCTRL_DPLLCTRLB) Proportional Integral Filter Selection Mask */
#define OSCCTRL_DPLLCTRLB_FILTER(value) (OSCCTRL_DPLLCTRLB_FILTER_Msk & ((value) << OSCCTRL_DPLLCTRLB_FILTER_Pos))
#define OSCCTRL_DPLLCTRLB_FILTER_Default_Val _U_(0x0) /**< (OSCCTRL_DPLLCTRLB) Default Filter Mode */
#define OSCCTRL_DPLLCTRLB_FILTER_LBFILT_Val _U_(0x1) /**< (OSCCTRL_DPLLCTRLB) Low Bandwidth Filter */
#define OSCCTRL_DPLLCTRLB_FILTER_HBFILT_Val _U_(0x2) /**< (OSCCTRL_DPLLCTRLB) High Bandwidth Filter */
#define OSCCTRL_DPLLCTRLB_FILTER_HDFILT_Val _U_(0x3) /**< (OSCCTRL_DPLLCTRLB) High Damping Filter */
#define OSCCTRL_DPLLCTRLB_FILTER_Default (OSCCTRL_DPLLCTRLB_FILTER_Default_Val << OSCCTRL_DPLLCTRLB_FILTER_Pos) /**< (OSCCTRL_DPLLCTRLB) Default Filter Mode Position */
#define OSCCTRL_DPLLCTRLB_FILTER_LBFILT (OSCCTRL_DPLLCTRLB_FILTER_LBFILT_Val << OSCCTRL_DPLLCTRLB_FILTER_Pos) /**< (OSCCTRL_DPLLCTRLB) Low Bandwidth Filter Position */
#define OSCCTRL_DPLLCTRLB_FILTER_HBFILT (OSCCTRL_DPLLCTRLB_FILTER_HBFILT_Val << OSCCTRL_DPLLCTRLB_FILTER_Pos) /**< (OSCCTRL_DPLLCTRLB) High Bandwidth Filter Position */
#define OSCCTRL_DPLLCTRLB_FILTER_HDFILT (OSCCTRL_DPLLCTRLB_FILTER_HDFILT_Val << OSCCTRL_DPLLCTRLB_FILTER_Pos) /**< (OSCCTRL_DPLLCTRLB) High Damping Filter Position */
#define OSCCTRL_DPLLCTRLB_LPEN_Pos 2 /**< (OSCCTRL_DPLLCTRLB) Low-Power Enable Position */
#define OSCCTRL_DPLLCTRLB_LPEN_Msk (_U_(0x1) << OSCCTRL_DPLLCTRLB_LPEN_Pos) /**< (OSCCTRL_DPLLCTRLB) Low-Power Enable Mask */
#define OSCCTRL_DPLLCTRLB_LPEN OSCCTRL_DPLLCTRLB_LPEN_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_DPLLCTRLB_LPEN_Msk instead */
#define OSCCTRL_DPLLCTRLB_WUF_Pos 3 /**< (OSCCTRL_DPLLCTRLB) Wake Up Fast Position */
#define OSCCTRL_DPLLCTRLB_WUF_Msk (_U_(0x1) << OSCCTRL_DPLLCTRLB_WUF_Pos) /**< (OSCCTRL_DPLLCTRLB) Wake Up Fast Mask */
#define OSCCTRL_DPLLCTRLB_WUF OSCCTRL_DPLLCTRLB_WUF_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_DPLLCTRLB_WUF_Msk instead */
#define OSCCTRL_DPLLCTRLB_REFCLK_Pos 4 /**< (OSCCTRL_DPLLCTRLB) Reference Clock Selection Position */
#define OSCCTRL_DPLLCTRLB_REFCLK_Msk (_U_(0x3) << OSCCTRL_DPLLCTRLB_REFCLK_Pos) /**< (OSCCTRL_DPLLCTRLB) Reference Clock Selection Mask */
#define OSCCTRL_DPLLCTRLB_REFCLK(value) (OSCCTRL_DPLLCTRLB_REFCLK_Msk & ((value) << OSCCTRL_DPLLCTRLB_REFCLK_Pos))
#define OSCCTRL_DPLLCTRLB_REFCLK_XOSC32K_Val _U_(0x0) /**< (OSCCTRL_DPLLCTRLB) XOSC32K Clock Reference */
#define OSCCTRL_DPLLCTRLB_REFCLK_XOSC_Val _U_(0x1) /**< (OSCCTRL_DPLLCTRLB) XOSC Clock Reference */
#define OSCCTRL_DPLLCTRLB_REFCLK_GCLK_Val _U_(0x2) /**< (OSCCTRL_DPLLCTRLB) GCLK Clock Reference */
#define OSCCTRL_DPLLCTRLB_REFCLK_XOSC32K (OSCCTRL_DPLLCTRLB_REFCLK_XOSC32K_Val << OSCCTRL_DPLLCTRLB_REFCLK_Pos) /**< (OSCCTRL_DPLLCTRLB) XOSC32K Clock Reference Position */
#define OSCCTRL_DPLLCTRLB_REFCLK_XOSC (OSCCTRL_DPLLCTRLB_REFCLK_XOSC_Val << OSCCTRL_DPLLCTRLB_REFCLK_Pos) /**< (OSCCTRL_DPLLCTRLB) XOSC Clock Reference Position */
#define OSCCTRL_DPLLCTRLB_REFCLK_GCLK (OSCCTRL_DPLLCTRLB_REFCLK_GCLK_Val << OSCCTRL_DPLLCTRLB_REFCLK_Pos) /**< (OSCCTRL_DPLLCTRLB) GCLK Clock Reference Position */
#define OSCCTRL_DPLLCTRLB_LTIME_Pos 8 /**< (OSCCTRL_DPLLCTRLB) Lock Time Position */
#define OSCCTRL_DPLLCTRLB_LTIME_Msk (_U_(0x7) << OSCCTRL_DPLLCTRLB_LTIME_Pos) /**< (OSCCTRL_DPLLCTRLB) Lock Time Mask */
#define OSCCTRL_DPLLCTRLB_LTIME(value) (OSCCTRL_DPLLCTRLB_LTIME_Msk & ((value) << OSCCTRL_DPLLCTRLB_LTIME_Pos))
#define OSCCTRL_DPLLCTRLB_LTIME_Default_Val _U_(0x0) /**< (OSCCTRL_DPLLCTRLB) No time-out. Automatic lock */
#define OSCCTRL_DPLLCTRLB_LTIME_8MS_Val _U_(0x4) /**< (OSCCTRL_DPLLCTRLB) Time-out if no lock within 8 ms */
#define OSCCTRL_DPLLCTRLB_LTIME_9MS_Val _U_(0x5) /**< (OSCCTRL_DPLLCTRLB) Time-out if no lock within 9 ms */
#define OSCCTRL_DPLLCTRLB_LTIME_10MS_Val _U_(0x6) /**< (OSCCTRL_DPLLCTRLB) Time-out if no lock within 10 ms */
#define OSCCTRL_DPLLCTRLB_LTIME_11MS_Val _U_(0x7) /**< (OSCCTRL_DPLLCTRLB) Time-out if no lock within 11 ms */
#define OSCCTRL_DPLLCTRLB_LTIME_Default (OSCCTRL_DPLLCTRLB_LTIME_Default_Val << OSCCTRL_DPLLCTRLB_LTIME_Pos) /**< (OSCCTRL_DPLLCTRLB) No time-out. Automatic lock Position */
#define OSCCTRL_DPLLCTRLB_LTIME_8MS (OSCCTRL_DPLLCTRLB_LTIME_8MS_Val << OSCCTRL_DPLLCTRLB_LTIME_Pos) /**< (OSCCTRL_DPLLCTRLB) Time-out if no lock within 8 ms Position */
#define OSCCTRL_DPLLCTRLB_LTIME_9MS (OSCCTRL_DPLLCTRLB_LTIME_9MS_Val << OSCCTRL_DPLLCTRLB_LTIME_Pos) /**< (OSCCTRL_DPLLCTRLB) Time-out if no lock within 9 ms Position */
#define OSCCTRL_DPLLCTRLB_LTIME_10MS (OSCCTRL_DPLLCTRLB_LTIME_10MS_Val << OSCCTRL_DPLLCTRLB_LTIME_Pos) /**< (OSCCTRL_DPLLCTRLB) Time-out if no lock within 10 ms Position */
#define OSCCTRL_DPLLCTRLB_LTIME_11MS (OSCCTRL_DPLLCTRLB_LTIME_11MS_Val << OSCCTRL_DPLLCTRLB_LTIME_Pos) /**< (OSCCTRL_DPLLCTRLB) Time-out if no lock within 11 ms Position */
#define OSCCTRL_DPLLCTRLB_LBYPASS_Pos 12 /**< (OSCCTRL_DPLLCTRLB) Lock Bypass Position */
#define OSCCTRL_DPLLCTRLB_LBYPASS_Msk (_U_(0x1) << OSCCTRL_DPLLCTRLB_LBYPASS_Pos) /**< (OSCCTRL_DPLLCTRLB) Lock Bypass Mask */
#define OSCCTRL_DPLLCTRLB_LBYPASS OSCCTRL_DPLLCTRLB_LBYPASS_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_DPLLCTRLB_LBYPASS_Msk instead */
#define OSCCTRL_DPLLCTRLB_DIV_Pos 16 /**< (OSCCTRL_DPLLCTRLB) Clock Divider Position */
#define OSCCTRL_DPLLCTRLB_DIV_Msk (_U_(0x7FF) << OSCCTRL_DPLLCTRLB_DIV_Pos) /**< (OSCCTRL_DPLLCTRLB) Clock Divider Mask */
#define OSCCTRL_DPLLCTRLB_DIV(value) (OSCCTRL_DPLLCTRLB_DIV_Msk & ((value) << OSCCTRL_DPLLCTRLB_DIV_Pos))
#define OSCCTRL_DPLLCTRLB_MASK _U_(0x7FF173F) /**< \deprecated (OSCCTRL_DPLLCTRLB) Register MASK (Use OSCCTRL_DPLLCTRLB_Msk instead) */
#define OSCCTRL_DPLLCTRLB_Msk _U_(0x7FF173F) /**< (OSCCTRL_DPLLCTRLB) Register Mask */
/* -------- OSCCTRL_DPLLPRESC : (OSCCTRL Offset: 0x38) (R/W 8) DPLL Prescaler -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t PRESC:2; /**< bit: 0..1 Output Clock Prescaler */
uint8_t :6; /**< bit: 2..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} OSCCTRL_DPLLPRESC_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define OSCCTRL_DPLLPRESC_OFFSET (0x38) /**< (OSCCTRL_DPLLPRESC) DPLL Prescaler Offset */
#define OSCCTRL_DPLLPRESC_RESETVALUE _U_(0x00) /**< (OSCCTRL_DPLLPRESC) DPLL Prescaler Reset Value */
#define OSCCTRL_DPLLPRESC_PRESC_Pos 0 /**< (OSCCTRL_DPLLPRESC) Output Clock Prescaler Position */
#define OSCCTRL_DPLLPRESC_PRESC_Msk (_U_(0x3) << OSCCTRL_DPLLPRESC_PRESC_Pos) /**< (OSCCTRL_DPLLPRESC) Output Clock Prescaler Mask */
#define OSCCTRL_DPLLPRESC_PRESC(value) (OSCCTRL_DPLLPRESC_PRESC_Msk & ((value) << OSCCTRL_DPLLPRESC_PRESC_Pos))
#define OSCCTRL_DPLLPRESC_PRESC_DIV1_Val _U_(0x0) /**< (OSCCTRL_DPLLPRESC) DPLL output is divided by 1 */
#define OSCCTRL_DPLLPRESC_PRESC_DIV2_Val _U_(0x1) /**< (OSCCTRL_DPLLPRESC) DPLL output is divided by 2 */
#define OSCCTRL_DPLLPRESC_PRESC_DIV4_Val _U_(0x2) /**< (OSCCTRL_DPLLPRESC) DPLL output is divided by 4 */
#define OSCCTRL_DPLLPRESC_PRESC_DIV1 (OSCCTRL_DPLLPRESC_PRESC_DIV1_Val << OSCCTRL_DPLLPRESC_PRESC_Pos) /**< (OSCCTRL_DPLLPRESC) DPLL output is divided by 1 Position */
#define OSCCTRL_DPLLPRESC_PRESC_DIV2 (OSCCTRL_DPLLPRESC_PRESC_DIV2_Val << OSCCTRL_DPLLPRESC_PRESC_Pos) /**< (OSCCTRL_DPLLPRESC) DPLL output is divided by 2 Position */
#define OSCCTRL_DPLLPRESC_PRESC_DIV4 (OSCCTRL_DPLLPRESC_PRESC_DIV4_Val << OSCCTRL_DPLLPRESC_PRESC_Pos) /**< (OSCCTRL_DPLLPRESC) DPLL output is divided by 4 Position */
#define OSCCTRL_DPLLPRESC_MASK _U_(0x03) /**< \deprecated (OSCCTRL_DPLLPRESC) Register MASK (Use OSCCTRL_DPLLPRESC_Msk instead) */
#define OSCCTRL_DPLLPRESC_Msk _U_(0x03) /**< (OSCCTRL_DPLLPRESC) Register Mask */
/* -------- OSCCTRL_DPLLSYNCBUSY : (OSCCTRL Offset: 0x3c) (R/ 8) DPLL Synchronization Busy -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t :1; /**< bit: 0 Reserved */
uint8_t ENABLE:1; /**< bit: 1 DPLL Enable Synchronization Status */
uint8_t DPLLRATIO:1; /**< bit: 2 DPLL Loop Divider Ratio Synchronization Status */
uint8_t DPLLPRESC:1; /**< bit: 3 DPLL Prescaler Synchronization Status */
uint8_t :4; /**< bit: 4..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} OSCCTRL_DPLLSYNCBUSY_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define OSCCTRL_DPLLSYNCBUSY_OFFSET (0x3C) /**< (OSCCTRL_DPLLSYNCBUSY) DPLL Synchronization Busy Offset */
#define OSCCTRL_DPLLSYNCBUSY_RESETVALUE _U_(0x00) /**< (OSCCTRL_DPLLSYNCBUSY) DPLL Synchronization Busy Reset Value */
#define OSCCTRL_DPLLSYNCBUSY_ENABLE_Pos 1 /**< (OSCCTRL_DPLLSYNCBUSY) DPLL Enable Synchronization Status Position */
#define OSCCTRL_DPLLSYNCBUSY_ENABLE_Msk (_U_(0x1) << OSCCTRL_DPLLSYNCBUSY_ENABLE_Pos) /**< (OSCCTRL_DPLLSYNCBUSY) DPLL Enable Synchronization Status Mask */
#define OSCCTRL_DPLLSYNCBUSY_ENABLE OSCCTRL_DPLLSYNCBUSY_ENABLE_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_DPLLSYNCBUSY_ENABLE_Msk instead */
#define OSCCTRL_DPLLSYNCBUSY_DPLLRATIO_Pos 2 /**< (OSCCTRL_DPLLSYNCBUSY) DPLL Loop Divider Ratio Synchronization Status Position */
#define OSCCTRL_DPLLSYNCBUSY_DPLLRATIO_Msk (_U_(0x1) << OSCCTRL_DPLLSYNCBUSY_DPLLRATIO_Pos) /**< (OSCCTRL_DPLLSYNCBUSY) DPLL Loop Divider Ratio Synchronization Status Mask */
#define OSCCTRL_DPLLSYNCBUSY_DPLLRATIO OSCCTRL_DPLLSYNCBUSY_DPLLRATIO_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_DPLLSYNCBUSY_DPLLRATIO_Msk instead */
#define OSCCTRL_DPLLSYNCBUSY_DPLLPRESC_Pos 3 /**< (OSCCTRL_DPLLSYNCBUSY) DPLL Prescaler Synchronization Status Position */
#define OSCCTRL_DPLLSYNCBUSY_DPLLPRESC_Msk (_U_(0x1) << OSCCTRL_DPLLSYNCBUSY_DPLLPRESC_Pos) /**< (OSCCTRL_DPLLSYNCBUSY) DPLL Prescaler Synchronization Status Mask */
#define OSCCTRL_DPLLSYNCBUSY_DPLLPRESC OSCCTRL_DPLLSYNCBUSY_DPLLPRESC_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_DPLLSYNCBUSY_DPLLPRESC_Msk instead */
#define OSCCTRL_DPLLSYNCBUSY_MASK _U_(0x0E) /**< \deprecated (OSCCTRL_DPLLSYNCBUSY) Register MASK (Use OSCCTRL_DPLLSYNCBUSY_Msk instead) */
#define OSCCTRL_DPLLSYNCBUSY_Msk _U_(0x0E) /**< (OSCCTRL_DPLLSYNCBUSY) Register Mask */
/* -------- OSCCTRL_DPLLSTATUS : (OSCCTRL Offset: 0x40) (R/ 8) DPLL Status -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t LOCK:1; /**< bit: 0 DPLL Lock */
uint8_t CLKRDY:1; /**< bit: 1 DPLL Clock Ready */
uint8_t :6; /**< bit: 2..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} OSCCTRL_DPLLSTATUS_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define OSCCTRL_DPLLSTATUS_OFFSET (0x40) /**< (OSCCTRL_DPLLSTATUS) DPLL Status Offset */
#define OSCCTRL_DPLLSTATUS_RESETVALUE _U_(0x00) /**< (OSCCTRL_DPLLSTATUS) DPLL Status Reset Value */
#define OSCCTRL_DPLLSTATUS_LOCK_Pos 0 /**< (OSCCTRL_DPLLSTATUS) DPLL Lock Position */
#define OSCCTRL_DPLLSTATUS_LOCK_Msk (_U_(0x1) << OSCCTRL_DPLLSTATUS_LOCK_Pos) /**< (OSCCTRL_DPLLSTATUS) DPLL Lock Mask */
#define OSCCTRL_DPLLSTATUS_LOCK OSCCTRL_DPLLSTATUS_LOCK_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_DPLLSTATUS_LOCK_Msk instead */
#define OSCCTRL_DPLLSTATUS_CLKRDY_Pos 1 /**< (OSCCTRL_DPLLSTATUS) DPLL Clock Ready Position */
#define OSCCTRL_DPLLSTATUS_CLKRDY_Msk (_U_(0x1) << OSCCTRL_DPLLSTATUS_CLKRDY_Pos) /**< (OSCCTRL_DPLLSTATUS) DPLL Clock Ready Mask */
#define OSCCTRL_DPLLSTATUS_CLKRDY OSCCTRL_DPLLSTATUS_CLKRDY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use OSCCTRL_DPLLSTATUS_CLKRDY_Msk instead */
#define OSCCTRL_DPLLSTATUS_MASK _U_(0x03) /**< \deprecated (OSCCTRL_DPLLSTATUS) Register MASK (Use OSCCTRL_DPLLSTATUS_Msk instead) */
#define OSCCTRL_DPLLSTATUS_Msk _U_(0x03) /**< (OSCCTRL_DPLLSTATUS) Register Mask */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
/** \brief OSCCTRL hardware registers */
typedef struct { /* Oscillators Control */
__IO OSCCTRL_EVCTRL_Type EVCTRL; /**< Offset: 0x00 (R/W 8) Event Control */
__I uint8_t Reserved1[3];
__IO OSCCTRL_INTENCLR_Type INTENCLR; /**< Offset: 0x04 (R/W 32) Interrupt Enable Clear */
__IO OSCCTRL_INTENSET_Type INTENSET; /**< Offset: 0x08 (R/W 32) Interrupt Enable Set */
__IO OSCCTRL_INTFLAG_Type INTFLAG; /**< Offset: 0x0C (R/W 32) Interrupt Flag Status and Clear */
__I OSCCTRL_STATUS_Type STATUS; /**< Offset: 0x10 (R/ 32) Status */
__IO OSCCTRL_XOSCCTRL_Type XOSCCTRL; /**< Offset: 0x14 (R/W 16) External Multipurpose Crystal Oscillator (XOSC) Control */
__IO OSCCTRL_CFDPRESC_Type CFDPRESC; /**< Offset: 0x16 (R/W 8) Clock Failure Detector Prescaler */
__I uint8_t Reserved2[1];
__IO OSCCTRL_OSC16MCTRL_Type OSC16MCTRL; /**< Offset: 0x18 (R/W 8) 16MHz Internal Oscillator (OSC16M) Control */
__I uint8_t Reserved3[3];
__IO OSCCTRL_DFLLULPCTRL_Type DFLLULPCTRL; /**< Offset: 0x1C (R/W 16) DFLLULP Control */
__IO OSCCTRL_DFLLULPDITHER_Type DFLLULPDITHER; /**< Offset: 0x1E (R/W 8) DFLLULP Dither Control */
__IO OSCCTRL_DFLLULPRREQ_Type DFLLULPRREQ; /**< Offset: 0x1F (R/W 8) DFLLULP Read Request */
__IO OSCCTRL_DFLLULPDLY_Type DFLLULPDLY; /**< Offset: 0x20 (R/W 32) DFLLULP Delay Value */
__IO OSCCTRL_DFLLULPRATIO_Type DFLLULPRATIO; /**< Offset: 0x24 (R/W 32) DFLLULP Target Ratio */
__I OSCCTRL_DFLLULPSYNCBUSY_Type DFLLULPSYNCBUSY; /**< Offset: 0x28 (R/ 32) DFLLULP Synchronization Busy */
__IO OSCCTRL_DPLLCTRLA_Type DPLLCTRLA; /**< Offset: 0x2C (R/W 8) DPLL Control A */
__I uint8_t Reserved4[3];
__IO OSCCTRL_DPLLRATIO_Type DPLLRATIO; /**< Offset: 0x30 (R/W 32) DPLL Ratio Control */
__IO OSCCTRL_DPLLCTRLB_Type DPLLCTRLB; /**< Offset: 0x34 (R/W 32) DPLL Control B */
__IO OSCCTRL_DPLLPRESC_Type DPLLPRESC; /**< Offset: 0x38 (R/W 8) DPLL Prescaler */
__I uint8_t Reserved5[3];
__I OSCCTRL_DPLLSYNCBUSY_Type DPLLSYNCBUSY; /**< Offset: 0x3C (R/ 8) DPLL Synchronization Busy */
__I uint8_t Reserved6[3];
__I OSCCTRL_DPLLSTATUS_Type DPLLSTATUS; /**< Offset: 0x40 (R/ 8) DPLL Status */
} Oscctrl;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/** @} end of Oscillators Control */
#endif /* _SAML10_OSCCTRL_COMPONENT_H_ */

View File

@ -0,0 +1,966 @@
/**
* \file
*
* \brief Component description for PAC
*
* Copyright (c) 2018 Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* 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
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
/* file generated from device description version 2018-08-31T13:51:50Z */
#ifndef _SAML10_PAC_COMPONENT_H_
#define _SAML10_PAC_COMPONENT_H_
#define _SAML10_PAC_COMPONENT_ /**< \deprecated Backward compatibility for ASF */
/** \addtogroup SAML_SAML10 Peripheral Access Controller
* @{
*/
/* ========================================================================== */
/** SOFTWARE API DEFINITION FOR PAC */
/* ========================================================================== */
#define PAC_U2120 /**< (PAC) Module ID */
#define REV_PAC 0x200 /**< (PAC) Module revision */
/* -------- PAC_WRCTRL : (PAC Offset: 0x00) (R/W 32) Write control -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t PERID:16; /**< bit: 0..15 Peripheral identifier */
uint32_t KEY:8; /**< bit: 16..23 Peripheral access control key */
uint32_t :8; /**< bit: 24..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} PAC_WRCTRL_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define PAC_WRCTRL_OFFSET (0x00) /**< (PAC_WRCTRL) Write control Offset */
#define PAC_WRCTRL_RESETVALUE _U_(0x00) /**< (PAC_WRCTRL) Write control Reset Value */
#define PAC_WRCTRL_PERID_Pos 0 /**< (PAC_WRCTRL) Peripheral identifier Position */
#define PAC_WRCTRL_PERID_Msk (_U_(0xFFFF) << PAC_WRCTRL_PERID_Pos) /**< (PAC_WRCTRL) Peripheral identifier Mask */
#define PAC_WRCTRL_PERID(value) (PAC_WRCTRL_PERID_Msk & ((value) << PAC_WRCTRL_PERID_Pos))
#define PAC_WRCTRL_KEY_Pos 16 /**< (PAC_WRCTRL) Peripheral access control key Position */
#define PAC_WRCTRL_KEY_Msk (_U_(0xFF) << PAC_WRCTRL_KEY_Pos) /**< (PAC_WRCTRL) Peripheral access control key Mask */
#define PAC_WRCTRL_KEY(value) (PAC_WRCTRL_KEY_Msk & ((value) << PAC_WRCTRL_KEY_Pos))
#define PAC_WRCTRL_KEY_OFF_Val _U_(0x0) /**< (PAC_WRCTRL) No action */
#define PAC_WRCTRL_KEY_CLR_Val _U_(0x1) /**< (PAC_WRCTRL) Clear protection */
#define PAC_WRCTRL_KEY_SET_Val _U_(0x2) /**< (PAC_WRCTRL) Set protection */
#define PAC_WRCTRL_KEY_SETLCK_Val _U_(0x3) /**< (PAC_WRCTRL) Set and lock protection */
#define PAC_WRCTRL_KEY_SETSEC_Val _U_(0x4) /**< (PAC_WRCTRL) Set IP secure */
#define PAC_WRCTRL_KEY_SETNONSEC_Val _U_(0x5) /**< (PAC_WRCTRL) Set IP non-secure */
#define PAC_WRCTRL_KEY_SECLOCK_Val _U_(0x6) /**< (PAC_WRCTRL) Lock IP security value */
#define PAC_WRCTRL_KEY_OFF (PAC_WRCTRL_KEY_OFF_Val << PAC_WRCTRL_KEY_Pos) /**< (PAC_WRCTRL) No action Position */
#define PAC_WRCTRL_KEY_CLR (PAC_WRCTRL_KEY_CLR_Val << PAC_WRCTRL_KEY_Pos) /**< (PAC_WRCTRL) Clear protection Position */
#define PAC_WRCTRL_KEY_SET (PAC_WRCTRL_KEY_SET_Val << PAC_WRCTRL_KEY_Pos) /**< (PAC_WRCTRL) Set protection Position */
#define PAC_WRCTRL_KEY_SETLCK (PAC_WRCTRL_KEY_SETLCK_Val << PAC_WRCTRL_KEY_Pos) /**< (PAC_WRCTRL) Set and lock protection Position */
#define PAC_WRCTRL_KEY_SETSEC (PAC_WRCTRL_KEY_SETSEC_Val << PAC_WRCTRL_KEY_Pos) /**< (PAC_WRCTRL) Set IP secure Position */
#define PAC_WRCTRL_KEY_SETNONSEC (PAC_WRCTRL_KEY_SETNONSEC_Val << PAC_WRCTRL_KEY_Pos) /**< (PAC_WRCTRL) Set IP non-secure Position */
#define PAC_WRCTRL_KEY_SECLOCK (PAC_WRCTRL_KEY_SECLOCK_Val << PAC_WRCTRL_KEY_Pos) /**< (PAC_WRCTRL) Lock IP security value Position */
#define PAC_WRCTRL_MASK _U_(0xFFFFFF) /**< \deprecated (PAC_WRCTRL) Register MASK (Use PAC_WRCTRL_Msk instead) */
#define PAC_WRCTRL_Msk _U_(0xFFFFFF) /**< (PAC_WRCTRL) Register Mask */
/* -------- PAC_EVCTRL : (PAC Offset: 0x04) (R/W 8) Event control -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t ERREO:1; /**< bit: 0 Peripheral acess error event output */
uint8_t :7; /**< bit: 1..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} PAC_EVCTRL_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define PAC_EVCTRL_OFFSET (0x04) /**< (PAC_EVCTRL) Event control Offset */
#define PAC_EVCTRL_RESETVALUE _U_(0x00) /**< (PAC_EVCTRL) Event control Reset Value */
#define PAC_EVCTRL_ERREO_Pos 0 /**< (PAC_EVCTRL) Peripheral acess error event output Position */
#define PAC_EVCTRL_ERREO_Msk (_U_(0x1) << PAC_EVCTRL_ERREO_Pos) /**< (PAC_EVCTRL) Peripheral acess error event output Mask */
#define PAC_EVCTRL_ERREO PAC_EVCTRL_ERREO_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_EVCTRL_ERREO_Msk instead */
#define PAC_EVCTRL_MASK _U_(0x01) /**< \deprecated (PAC_EVCTRL) Register MASK (Use PAC_EVCTRL_Msk instead) */
#define PAC_EVCTRL_Msk _U_(0x01) /**< (PAC_EVCTRL) Register Mask */
/* -------- PAC_INTENCLR : (PAC Offset: 0x08) (R/W 8) Interrupt enable clear -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t ERR:1; /**< bit: 0 Peripheral access error interrupt disable */
uint8_t :7; /**< bit: 1..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} PAC_INTENCLR_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define PAC_INTENCLR_OFFSET (0x08) /**< (PAC_INTENCLR) Interrupt enable clear Offset */
#define PAC_INTENCLR_RESETVALUE _U_(0x00) /**< (PAC_INTENCLR) Interrupt enable clear Reset Value */
#define PAC_INTENCLR_ERR_Pos 0 /**< (PAC_INTENCLR) Peripheral access error interrupt disable Position */
#define PAC_INTENCLR_ERR_Msk (_U_(0x1) << PAC_INTENCLR_ERR_Pos) /**< (PAC_INTENCLR) Peripheral access error interrupt disable Mask */
#define PAC_INTENCLR_ERR PAC_INTENCLR_ERR_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_INTENCLR_ERR_Msk instead */
#define PAC_INTENCLR_MASK _U_(0x01) /**< \deprecated (PAC_INTENCLR) Register MASK (Use PAC_INTENCLR_Msk instead) */
#define PAC_INTENCLR_Msk _U_(0x01) /**< (PAC_INTENCLR) Register Mask */
/* -------- PAC_INTENSET : (PAC Offset: 0x09) (R/W 8) Interrupt enable set -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t ERR:1; /**< bit: 0 Peripheral access error interrupt enable */
uint8_t :7; /**< bit: 1..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} PAC_INTENSET_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define PAC_INTENSET_OFFSET (0x09) /**< (PAC_INTENSET) Interrupt enable set Offset */
#define PAC_INTENSET_RESETVALUE _U_(0x00) /**< (PAC_INTENSET) Interrupt enable set Reset Value */
#define PAC_INTENSET_ERR_Pos 0 /**< (PAC_INTENSET) Peripheral access error interrupt enable Position */
#define PAC_INTENSET_ERR_Msk (_U_(0x1) << PAC_INTENSET_ERR_Pos) /**< (PAC_INTENSET) Peripheral access error interrupt enable Mask */
#define PAC_INTENSET_ERR PAC_INTENSET_ERR_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_INTENSET_ERR_Msk instead */
#define PAC_INTENSET_MASK _U_(0x01) /**< \deprecated (PAC_INTENSET) Register MASK (Use PAC_INTENSET_Msk instead) */
#define PAC_INTENSET_Msk _U_(0x01) /**< (PAC_INTENSET) Register Mask */
/* -------- PAC_INTFLAGAHB : (PAC Offset: 0x10) (R/W 32) Bridge interrupt flag status -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union { // __I to avoid read-modify-write on write-to-clear register
struct {
__I uint32_t FLASH_:1; /**< bit: 0 FLASH */
__I uint32_t HPB0_:1; /**< bit: 1 HPB0 */
__I uint32_t HPB1_:1; /**< bit: 2 HPB1 */
__I uint32_t HPB2_:1; /**< bit: 3 HPB2 */
__I uint32_t HSRAMCPU_:1; /**< bit: 4 HSRAMCPU */
__I uint32_t HSRAMDMAC_:1; /**< bit: 5 HSRAMDMAC */
__I uint32_t HSRAMDSU_:1; /**< bit: 6 HSRAMDSU */
__I uint32_t :25; /**< bit: 7..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} PAC_INTFLAGAHB_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define PAC_INTFLAGAHB_OFFSET (0x10) /**< (PAC_INTFLAGAHB) Bridge interrupt flag status Offset */
#define PAC_INTFLAGAHB_RESETVALUE _U_(0x00) /**< (PAC_INTFLAGAHB) Bridge interrupt flag status Reset Value */
#define PAC_INTFLAGAHB_FLASH_Pos 0 /**< (PAC_INTFLAGAHB) FLASH Position */
#define PAC_INTFLAGAHB_FLASH_Msk (_U_(0x1) << PAC_INTFLAGAHB_FLASH_Pos) /**< (PAC_INTFLAGAHB) FLASH Mask */
#define PAC_INTFLAGAHB_FLASH PAC_INTFLAGAHB_FLASH_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_INTFLAGAHB_FLASH_Msk instead */
#define PAC_INTFLAGAHB_HPB0_Pos 1 /**< (PAC_INTFLAGAHB) HPB0 Position */
#define PAC_INTFLAGAHB_HPB0_Msk (_U_(0x1) << PAC_INTFLAGAHB_HPB0_Pos) /**< (PAC_INTFLAGAHB) HPB0 Mask */
#define PAC_INTFLAGAHB_HPB0 PAC_INTFLAGAHB_HPB0_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_INTFLAGAHB_HPB0_Msk instead */
#define PAC_INTFLAGAHB_HPB1_Pos 2 /**< (PAC_INTFLAGAHB) HPB1 Position */
#define PAC_INTFLAGAHB_HPB1_Msk (_U_(0x1) << PAC_INTFLAGAHB_HPB1_Pos) /**< (PAC_INTFLAGAHB) HPB1 Mask */
#define PAC_INTFLAGAHB_HPB1 PAC_INTFLAGAHB_HPB1_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_INTFLAGAHB_HPB1_Msk instead */
#define PAC_INTFLAGAHB_HPB2_Pos 3 /**< (PAC_INTFLAGAHB) HPB2 Position */
#define PAC_INTFLAGAHB_HPB2_Msk (_U_(0x1) << PAC_INTFLAGAHB_HPB2_Pos) /**< (PAC_INTFLAGAHB) HPB2 Mask */
#define PAC_INTFLAGAHB_HPB2 PAC_INTFLAGAHB_HPB2_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_INTFLAGAHB_HPB2_Msk instead */
#define PAC_INTFLAGAHB_HSRAMCPU_Pos 4 /**< (PAC_INTFLAGAHB) HSRAMCPU Position */
#define PAC_INTFLAGAHB_HSRAMCPU_Msk (_U_(0x1) << PAC_INTFLAGAHB_HSRAMCPU_Pos) /**< (PAC_INTFLAGAHB) HSRAMCPU Mask */
#define PAC_INTFLAGAHB_HSRAMCPU PAC_INTFLAGAHB_HSRAMCPU_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_INTFLAGAHB_HSRAMCPU_Msk instead */
#define PAC_INTFLAGAHB_HSRAMDMAC_Pos 5 /**< (PAC_INTFLAGAHB) HSRAMDMAC Position */
#define PAC_INTFLAGAHB_HSRAMDMAC_Msk (_U_(0x1) << PAC_INTFLAGAHB_HSRAMDMAC_Pos) /**< (PAC_INTFLAGAHB) HSRAMDMAC Mask */
#define PAC_INTFLAGAHB_HSRAMDMAC PAC_INTFLAGAHB_HSRAMDMAC_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_INTFLAGAHB_HSRAMDMAC_Msk instead */
#define PAC_INTFLAGAHB_HSRAMDSU_Pos 6 /**< (PAC_INTFLAGAHB) HSRAMDSU Position */
#define PAC_INTFLAGAHB_HSRAMDSU_Msk (_U_(0x1) << PAC_INTFLAGAHB_HSRAMDSU_Pos) /**< (PAC_INTFLAGAHB) HSRAMDSU Mask */
#define PAC_INTFLAGAHB_HSRAMDSU PAC_INTFLAGAHB_HSRAMDSU_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_INTFLAGAHB_HSRAMDSU_Msk instead */
#define PAC_INTFLAGAHB_MASK _U_(0x7F) /**< \deprecated (PAC_INTFLAGAHB) Register MASK (Use PAC_INTFLAGAHB_Msk instead) */
#define PAC_INTFLAGAHB_Msk _U_(0x7F) /**< (PAC_INTFLAGAHB) Register Mask */
#define PAC_INTFLAGAHB_HPB_Pos 1 /**< (PAC_INTFLAGAHB Position) HPBx */
#define PAC_INTFLAGAHB_HPB_Msk (_U_(0x7) << PAC_INTFLAGAHB_HPB_Pos) /**< (PAC_INTFLAGAHB Mask) HPB */
#define PAC_INTFLAGAHB_HPB(value) (PAC_INTFLAGAHB_HPB_Msk & ((value) << PAC_INTFLAGAHB_HPB_Pos))
/* -------- PAC_INTFLAGA : (PAC Offset: 0x14) (R/W 32) Peripheral interrupt flag status - Bridge A -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union { // __I to avoid read-modify-write on write-to-clear register
struct {
__I uint32_t PAC_:1; /**< bit: 0 PAC */
__I uint32_t PM_:1; /**< bit: 1 PM */
__I uint32_t MCLK_:1; /**< bit: 2 MCLK */
__I uint32_t RSTC_:1; /**< bit: 3 RSTC */
__I uint32_t OSCCTRL_:1; /**< bit: 4 OSCCTRL */
__I uint32_t OSC32KCTRL_:1; /**< bit: 5 OSC32KCTRL */
__I uint32_t SUPC_:1; /**< bit: 6 SUPC */
__I uint32_t GCLK_:1; /**< bit: 7 GCLK */
__I uint32_t WDT_:1; /**< bit: 8 WDT */
__I uint32_t RTC_:1; /**< bit: 9 RTC */
__I uint32_t EIC_:1; /**< bit: 10 EIC */
__I uint32_t FREQM_:1; /**< bit: 11 FREQM */
__I uint32_t PORT_:1; /**< bit: 12 PORT */
__I uint32_t AC_:1; /**< bit: 13 AC */
__I uint32_t :18; /**< bit: 14..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} PAC_INTFLAGA_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define PAC_INTFLAGA_OFFSET (0x14) /**< (PAC_INTFLAGA) Peripheral interrupt flag status - Bridge A Offset */
#define PAC_INTFLAGA_RESETVALUE _U_(0x00) /**< (PAC_INTFLAGA) Peripheral interrupt flag status - Bridge A Reset Value */
#define PAC_INTFLAGA_PAC_Pos 0 /**< (PAC_INTFLAGA) PAC Position */
#define PAC_INTFLAGA_PAC_Msk (_U_(0x1) << PAC_INTFLAGA_PAC_Pos) /**< (PAC_INTFLAGA) PAC Mask */
#define PAC_INTFLAGA_PAC PAC_INTFLAGA_PAC_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_INTFLAGA_PAC_Msk instead */
#define PAC_INTFLAGA_PM_Pos 1 /**< (PAC_INTFLAGA) PM Position */
#define PAC_INTFLAGA_PM_Msk (_U_(0x1) << PAC_INTFLAGA_PM_Pos) /**< (PAC_INTFLAGA) PM Mask */
#define PAC_INTFLAGA_PM PAC_INTFLAGA_PM_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_INTFLAGA_PM_Msk instead */
#define PAC_INTFLAGA_MCLK_Pos 2 /**< (PAC_INTFLAGA) MCLK Position */
#define PAC_INTFLAGA_MCLK_Msk (_U_(0x1) << PAC_INTFLAGA_MCLK_Pos) /**< (PAC_INTFLAGA) MCLK Mask */
#define PAC_INTFLAGA_MCLK PAC_INTFLAGA_MCLK_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_INTFLAGA_MCLK_Msk instead */
#define PAC_INTFLAGA_RSTC_Pos 3 /**< (PAC_INTFLAGA) RSTC Position */
#define PAC_INTFLAGA_RSTC_Msk (_U_(0x1) << PAC_INTFLAGA_RSTC_Pos) /**< (PAC_INTFLAGA) RSTC Mask */
#define PAC_INTFLAGA_RSTC PAC_INTFLAGA_RSTC_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_INTFLAGA_RSTC_Msk instead */
#define PAC_INTFLAGA_OSCCTRL_Pos 4 /**< (PAC_INTFLAGA) OSCCTRL Position */
#define PAC_INTFLAGA_OSCCTRL_Msk (_U_(0x1) << PAC_INTFLAGA_OSCCTRL_Pos) /**< (PAC_INTFLAGA) OSCCTRL Mask */
#define PAC_INTFLAGA_OSCCTRL PAC_INTFLAGA_OSCCTRL_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_INTFLAGA_OSCCTRL_Msk instead */
#define PAC_INTFLAGA_OSC32KCTRL_Pos 5 /**< (PAC_INTFLAGA) OSC32KCTRL Position */
#define PAC_INTFLAGA_OSC32KCTRL_Msk (_U_(0x1) << PAC_INTFLAGA_OSC32KCTRL_Pos) /**< (PAC_INTFLAGA) OSC32KCTRL Mask */
#define PAC_INTFLAGA_OSC32KCTRL PAC_INTFLAGA_OSC32KCTRL_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_INTFLAGA_OSC32KCTRL_Msk instead */
#define PAC_INTFLAGA_SUPC_Pos 6 /**< (PAC_INTFLAGA) SUPC Position */
#define PAC_INTFLAGA_SUPC_Msk (_U_(0x1) << PAC_INTFLAGA_SUPC_Pos) /**< (PAC_INTFLAGA) SUPC Mask */
#define PAC_INTFLAGA_SUPC PAC_INTFLAGA_SUPC_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_INTFLAGA_SUPC_Msk instead */
#define PAC_INTFLAGA_GCLK_Pos 7 /**< (PAC_INTFLAGA) GCLK Position */
#define PAC_INTFLAGA_GCLK_Msk (_U_(0x1) << PAC_INTFLAGA_GCLK_Pos) /**< (PAC_INTFLAGA) GCLK Mask */
#define PAC_INTFLAGA_GCLK PAC_INTFLAGA_GCLK_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_INTFLAGA_GCLK_Msk instead */
#define PAC_INTFLAGA_WDT_Pos 8 /**< (PAC_INTFLAGA) WDT Position */
#define PAC_INTFLAGA_WDT_Msk (_U_(0x1) << PAC_INTFLAGA_WDT_Pos) /**< (PAC_INTFLAGA) WDT Mask */
#define PAC_INTFLAGA_WDT PAC_INTFLAGA_WDT_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_INTFLAGA_WDT_Msk instead */
#define PAC_INTFLAGA_RTC_Pos 9 /**< (PAC_INTFLAGA) RTC Position */
#define PAC_INTFLAGA_RTC_Msk (_U_(0x1) << PAC_INTFLAGA_RTC_Pos) /**< (PAC_INTFLAGA) RTC Mask */
#define PAC_INTFLAGA_RTC PAC_INTFLAGA_RTC_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_INTFLAGA_RTC_Msk instead */
#define PAC_INTFLAGA_EIC_Pos 10 /**< (PAC_INTFLAGA) EIC Position */
#define PAC_INTFLAGA_EIC_Msk (_U_(0x1) << PAC_INTFLAGA_EIC_Pos) /**< (PAC_INTFLAGA) EIC Mask */
#define PAC_INTFLAGA_EIC PAC_INTFLAGA_EIC_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_INTFLAGA_EIC_Msk instead */
#define PAC_INTFLAGA_FREQM_Pos 11 /**< (PAC_INTFLAGA) FREQM Position */
#define PAC_INTFLAGA_FREQM_Msk (_U_(0x1) << PAC_INTFLAGA_FREQM_Pos) /**< (PAC_INTFLAGA) FREQM Mask */
#define PAC_INTFLAGA_FREQM PAC_INTFLAGA_FREQM_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_INTFLAGA_FREQM_Msk instead */
#define PAC_INTFLAGA_PORT_Pos 12 /**< (PAC_INTFLAGA) PORT Position */
#define PAC_INTFLAGA_PORT_Msk (_U_(0x1) << PAC_INTFLAGA_PORT_Pos) /**< (PAC_INTFLAGA) PORT Mask */
#define PAC_INTFLAGA_PORT PAC_INTFLAGA_PORT_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_INTFLAGA_PORT_Msk instead */
#define PAC_INTFLAGA_AC_Pos 13 /**< (PAC_INTFLAGA) AC Position */
#define PAC_INTFLAGA_AC_Msk (_U_(0x1) << PAC_INTFLAGA_AC_Pos) /**< (PAC_INTFLAGA) AC Mask */
#define PAC_INTFLAGA_AC PAC_INTFLAGA_AC_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_INTFLAGA_AC_Msk instead */
#define PAC_INTFLAGA_MASK _U_(0x3FFF) /**< \deprecated (PAC_INTFLAGA) Register MASK (Use PAC_INTFLAGA_Msk instead) */
#define PAC_INTFLAGA_Msk _U_(0x3FFF) /**< (PAC_INTFLAGA) Register Mask */
/* -------- PAC_INTFLAGB : (PAC Offset: 0x18) (R/W 32) Peripheral interrupt flag status - Bridge B -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union { // __I to avoid read-modify-write on write-to-clear register
struct {
__I uint32_t IDAU_:1; /**< bit: 0 IDAU */
__I uint32_t DSU_:1; /**< bit: 1 DSU */
__I uint32_t NVMCTRL_:1; /**< bit: 2 NVMCTRL */
__I uint32_t DMAC_:1; /**< bit: 3 DMAC */
__I uint32_t :28; /**< bit: 4..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} PAC_INTFLAGB_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define PAC_INTFLAGB_OFFSET (0x18) /**< (PAC_INTFLAGB) Peripheral interrupt flag status - Bridge B Offset */
#define PAC_INTFLAGB_RESETVALUE _U_(0x00) /**< (PAC_INTFLAGB) Peripheral interrupt flag status - Bridge B Reset Value */
#define PAC_INTFLAGB_IDAU_Pos 0 /**< (PAC_INTFLAGB) IDAU Position */
#define PAC_INTFLAGB_IDAU_Msk (_U_(0x1) << PAC_INTFLAGB_IDAU_Pos) /**< (PAC_INTFLAGB) IDAU Mask */
#define PAC_INTFLAGB_IDAU PAC_INTFLAGB_IDAU_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_INTFLAGB_IDAU_Msk instead */
#define PAC_INTFLAGB_DSU_Pos 1 /**< (PAC_INTFLAGB) DSU Position */
#define PAC_INTFLAGB_DSU_Msk (_U_(0x1) << PAC_INTFLAGB_DSU_Pos) /**< (PAC_INTFLAGB) DSU Mask */
#define PAC_INTFLAGB_DSU PAC_INTFLAGB_DSU_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_INTFLAGB_DSU_Msk instead */
#define PAC_INTFLAGB_NVMCTRL_Pos 2 /**< (PAC_INTFLAGB) NVMCTRL Position */
#define PAC_INTFLAGB_NVMCTRL_Msk (_U_(0x1) << PAC_INTFLAGB_NVMCTRL_Pos) /**< (PAC_INTFLAGB) NVMCTRL Mask */
#define PAC_INTFLAGB_NVMCTRL PAC_INTFLAGB_NVMCTRL_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_INTFLAGB_NVMCTRL_Msk instead */
#define PAC_INTFLAGB_DMAC_Pos 3 /**< (PAC_INTFLAGB) DMAC Position */
#define PAC_INTFLAGB_DMAC_Msk (_U_(0x1) << PAC_INTFLAGB_DMAC_Pos) /**< (PAC_INTFLAGB) DMAC Mask */
#define PAC_INTFLAGB_DMAC PAC_INTFLAGB_DMAC_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_INTFLAGB_DMAC_Msk instead */
#define PAC_INTFLAGB_MASK _U_(0x0F) /**< \deprecated (PAC_INTFLAGB) Register MASK (Use PAC_INTFLAGB_Msk instead) */
#define PAC_INTFLAGB_Msk _U_(0x0F) /**< (PAC_INTFLAGB) Register Mask */
/* -------- PAC_INTFLAGC : (PAC Offset: 0x1c) (R/W 32) Peripheral interrupt flag status - Bridge C -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union { // __I to avoid read-modify-write on write-to-clear register
struct {
__I uint32_t EVSYS_:1; /**< bit: 0 EVSYS */
__I uint32_t SERCOM0_:1; /**< bit: 1 SERCOM0 */
__I uint32_t SERCOM1_:1; /**< bit: 2 SERCOM1 */
__I uint32_t SERCOM2_:1; /**< bit: 3 SERCOM2 */
__I uint32_t TC0_:1; /**< bit: 4 TC0 */
__I uint32_t TC1_:1; /**< bit: 5 TC1 */
__I uint32_t TC2_:1; /**< bit: 6 TC2 */
__I uint32_t ADC_:1; /**< bit: 7 ADC */
__I uint32_t DAC_:1; /**< bit: 8 DAC */
__I uint32_t PTC_:1; /**< bit: 9 PTC */
__I uint32_t TRNG_:1; /**< bit: 10 TRNG */
__I uint32_t CCL_:1; /**< bit: 11 CCL */
__I uint32_t OPAMP_:1; /**< bit: 12 OPAMP */
__I uint32_t TRAM_:1; /**< bit: 13 TRAM */
__I uint32_t :18; /**< bit: 14..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} PAC_INTFLAGC_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define PAC_INTFLAGC_OFFSET (0x1C) /**< (PAC_INTFLAGC) Peripheral interrupt flag status - Bridge C Offset */
#define PAC_INTFLAGC_RESETVALUE _U_(0x00) /**< (PAC_INTFLAGC) Peripheral interrupt flag status - Bridge C Reset Value */
#define PAC_INTFLAGC_EVSYS_Pos 0 /**< (PAC_INTFLAGC) EVSYS Position */
#define PAC_INTFLAGC_EVSYS_Msk (_U_(0x1) << PAC_INTFLAGC_EVSYS_Pos) /**< (PAC_INTFLAGC) EVSYS Mask */
#define PAC_INTFLAGC_EVSYS PAC_INTFLAGC_EVSYS_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_INTFLAGC_EVSYS_Msk instead */
#define PAC_INTFLAGC_SERCOM0_Pos 1 /**< (PAC_INTFLAGC) SERCOM0 Position */
#define PAC_INTFLAGC_SERCOM0_Msk (_U_(0x1) << PAC_INTFLAGC_SERCOM0_Pos) /**< (PAC_INTFLAGC) SERCOM0 Mask */
#define PAC_INTFLAGC_SERCOM0 PAC_INTFLAGC_SERCOM0_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_INTFLAGC_SERCOM0_Msk instead */
#define PAC_INTFLAGC_SERCOM1_Pos 2 /**< (PAC_INTFLAGC) SERCOM1 Position */
#define PAC_INTFLAGC_SERCOM1_Msk (_U_(0x1) << PAC_INTFLAGC_SERCOM1_Pos) /**< (PAC_INTFLAGC) SERCOM1 Mask */
#define PAC_INTFLAGC_SERCOM1 PAC_INTFLAGC_SERCOM1_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_INTFLAGC_SERCOM1_Msk instead */
#define PAC_INTFLAGC_SERCOM2_Pos 3 /**< (PAC_INTFLAGC) SERCOM2 Position */
#define PAC_INTFLAGC_SERCOM2_Msk (_U_(0x1) << PAC_INTFLAGC_SERCOM2_Pos) /**< (PAC_INTFLAGC) SERCOM2 Mask */
#define PAC_INTFLAGC_SERCOM2 PAC_INTFLAGC_SERCOM2_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_INTFLAGC_SERCOM2_Msk instead */
#define PAC_INTFLAGC_TC0_Pos 4 /**< (PAC_INTFLAGC) TC0 Position */
#define PAC_INTFLAGC_TC0_Msk (_U_(0x1) << PAC_INTFLAGC_TC0_Pos) /**< (PAC_INTFLAGC) TC0 Mask */
#define PAC_INTFLAGC_TC0 PAC_INTFLAGC_TC0_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_INTFLAGC_TC0_Msk instead */
#define PAC_INTFLAGC_TC1_Pos 5 /**< (PAC_INTFLAGC) TC1 Position */
#define PAC_INTFLAGC_TC1_Msk (_U_(0x1) << PAC_INTFLAGC_TC1_Pos) /**< (PAC_INTFLAGC) TC1 Mask */
#define PAC_INTFLAGC_TC1 PAC_INTFLAGC_TC1_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_INTFLAGC_TC1_Msk instead */
#define PAC_INTFLAGC_TC2_Pos 6 /**< (PAC_INTFLAGC) TC2 Position */
#define PAC_INTFLAGC_TC2_Msk (_U_(0x1) << PAC_INTFLAGC_TC2_Pos) /**< (PAC_INTFLAGC) TC2 Mask */
#define PAC_INTFLAGC_TC2 PAC_INTFLAGC_TC2_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_INTFLAGC_TC2_Msk instead */
#define PAC_INTFLAGC_ADC_Pos 7 /**< (PAC_INTFLAGC) ADC Position */
#define PAC_INTFLAGC_ADC_Msk (_U_(0x1) << PAC_INTFLAGC_ADC_Pos) /**< (PAC_INTFLAGC) ADC Mask */
#define PAC_INTFLAGC_ADC PAC_INTFLAGC_ADC_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_INTFLAGC_ADC_Msk instead */
#define PAC_INTFLAGC_DAC_Pos 8 /**< (PAC_INTFLAGC) DAC Position */
#define PAC_INTFLAGC_DAC_Msk (_U_(0x1) << PAC_INTFLAGC_DAC_Pos) /**< (PAC_INTFLAGC) DAC Mask */
#define PAC_INTFLAGC_DAC PAC_INTFLAGC_DAC_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_INTFLAGC_DAC_Msk instead */
#define PAC_INTFLAGC_PTC_Pos 9 /**< (PAC_INTFLAGC) PTC Position */
#define PAC_INTFLAGC_PTC_Msk (_U_(0x1) << PAC_INTFLAGC_PTC_Pos) /**< (PAC_INTFLAGC) PTC Mask */
#define PAC_INTFLAGC_PTC PAC_INTFLAGC_PTC_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_INTFLAGC_PTC_Msk instead */
#define PAC_INTFLAGC_TRNG_Pos 10 /**< (PAC_INTFLAGC) TRNG Position */
#define PAC_INTFLAGC_TRNG_Msk (_U_(0x1) << PAC_INTFLAGC_TRNG_Pos) /**< (PAC_INTFLAGC) TRNG Mask */
#define PAC_INTFLAGC_TRNG PAC_INTFLAGC_TRNG_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_INTFLAGC_TRNG_Msk instead */
#define PAC_INTFLAGC_CCL_Pos 11 /**< (PAC_INTFLAGC) CCL Position */
#define PAC_INTFLAGC_CCL_Msk (_U_(0x1) << PAC_INTFLAGC_CCL_Pos) /**< (PAC_INTFLAGC) CCL Mask */
#define PAC_INTFLAGC_CCL PAC_INTFLAGC_CCL_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_INTFLAGC_CCL_Msk instead */
#define PAC_INTFLAGC_OPAMP_Pos 12 /**< (PAC_INTFLAGC) OPAMP Position */
#define PAC_INTFLAGC_OPAMP_Msk (_U_(0x1) << PAC_INTFLAGC_OPAMP_Pos) /**< (PAC_INTFLAGC) OPAMP Mask */
#define PAC_INTFLAGC_OPAMP PAC_INTFLAGC_OPAMP_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_INTFLAGC_OPAMP_Msk instead */
#define PAC_INTFLAGC_TRAM_Pos 13 /**< (PAC_INTFLAGC) TRAM Position */
#define PAC_INTFLAGC_TRAM_Msk (_U_(0x1) << PAC_INTFLAGC_TRAM_Pos) /**< (PAC_INTFLAGC) TRAM Mask */
#define PAC_INTFLAGC_TRAM PAC_INTFLAGC_TRAM_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_INTFLAGC_TRAM_Msk instead */
#define PAC_INTFLAGC_MASK _U_(0x3FFF) /**< \deprecated (PAC_INTFLAGC) Register MASK (Use PAC_INTFLAGC_Msk instead) */
#define PAC_INTFLAGC_Msk _U_(0x3FFF) /**< (PAC_INTFLAGC) Register Mask */
#define PAC_INTFLAGC_SERCOM_Pos 1 /**< (PAC_INTFLAGC Position) SERCOMx */
#define PAC_INTFLAGC_SERCOM_Msk (_U_(0x7) << PAC_INTFLAGC_SERCOM_Pos) /**< (PAC_INTFLAGC Mask) SERCOM */
#define PAC_INTFLAGC_SERCOM(value) (PAC_INTFLAGC_SERCOM_Msk & ((value) << PAC_INTFLAGC_SERCOM_Pos))
#define PAC_INTFLAGC_TC_Pos 4 /**< (PAC_INTFLAGC Position) TCx */
#define PAC_INTFLAGC_TC_Msk (_U_(0x7) << PAC_INTFLAGC_TC_Pos) /**< (PAC_INTFLAGC Mask) TC */
#define PAC_INTFLAGC_TC(value) (PAC_INTFLAGC_TC_Msk & ((value) << PAC_INTFLAGC_TC_Pos))
/* -------- PAC_STATUSA : (PAC Offset: 0x34) (R/ 32) Peripheral write protection status - Bridge A -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t PAC_:1; /**< bit: 0 PAC APB Protect Enable */
uint32_t PM_:1; /**< bit: 1 PM APB Protect Enable */
uint32_t MCLK_:1; /**< bit: 2 MCLK APB Protect Enable */
uint32_t RSTC_:1; /**< bit: 3 RSTC APB Protect Enable */
uint32_t OSCCTRL_:1; /**< bit: 4 OSCCTRL APB Protect Enable */
uint32_t OSC32KCTRL_:1; /**< bit: 5 OSC32KCTRL APB Protect Enable */
uint32_t SUPC_:1; /**< bit: 6 SUPC APB Protect Enable */
uint32_t GCLK_:1; /**< bit: 7 GCLK APB Protect Enable */
uint32_t WDT_:1; /**< bit: 8 WDT APB Protect Enable */
uint32_t RTC_:1; /**< bit: 9 RTC APB Protect Enable */
uint32_t EIC_:1; /**< bit: 10 EIC APB Protect Enable */
uint32_t FREQM_:1; /**< bit: 11 FREQM APB Protect Enable */
uint32_t PORT_:1; /**< bit: 12 PORT APB Protect Enable */
uint32_t AC_:1; /**< bit: 13 AC APB Protect Enable */
uint32_t :18; /**< bit: 14..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} PAC_STATUSA_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define PAC_STATUSA_OFFSET (0x34) /**< (PAC_STATUSA) Peripheral write protection status - Bridge A Offset */
#define PAC_STATUSA_RESETVALUE _U_(0xC000) /**< (PAC_STATUSA) Peripheral write protection status - Bridge A Reset Value */
#define PAC_STATUSA_PAC_Pos 0 /**< (PAC_STATUSA) PAC APB Protect Enable Position */
#define PAC_STATUSA_PAC_Msk (_U_(0x1) << PAC_STATUSA_PAC_Pos) /**< (PAC_STATUSA) PAC APB Protect Enable Mask */
#define PAC_STATUSA_PAC PAC_STATUSA_PAC_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_STATUSA_PAC_Msk instead */
#define PAC_STATUSA_PM_Pos 1 /**< (PAC_STATUSA) PM APB Protect Enable Position */
#define PAC_STATUSA_PM_Msk (_U_(0x1) << PAC_STATUSA_PM_Pos) /**< (PAC_STATUSA) PM APB Protect Enable Mask */
#define PAC_STATUSA_PM PAC_STATUSA_PM_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_STATUSA_PM_Msk instead */
#define PAC_STATUSA_MCLK_Pos 2 /**< (PAC_STATUSA) MCLK APB Protect Enable Position */
#define PAC_STATUSA_MCLK_Msk (_U_(0x1) << PAC_STATUSA_MCLK_Pos) /**< (PAC_STATUSA) MCLK APB Protect Enable Mask */
#define PAC_STATUSA_MCLK PAC_STATUSA_MCLK_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_STATUSA_MCLK_Msk instead */
#define PAC_STATUSA_RSTC_Pos 3 /**< (PAC_STATUSA) RSTC APB Protect Enable Position */
#define PAC_STATUSA_RSTC_Msk (_U_(0x1) << PAC_STATUSA_RSTC_Pos) /**< (PAC_STATUSA) RSTC APB Protect Enable Mask */
#define PAC_STATUSA_RSTC PAC_STATUSA_RSTC_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_STATUSA_RSTC_Msk instead */
#define PAC_STATUSA_OSCCTRL_Pos 4 /**< (PAC_STATUSA) OSCCTRL APB Protect Enable Position */
#define PAC_STATUSA_OSCCTRL_Msk (_U_(0x1) << PAC_STATUSA_OSCCTRL_Pos) /**< (PAC_STATUSA) OSCCTRL APB Protect Enable Mask */
#define PAC_STATUSA_OSCCTRL PAC_STATUSA_OSCCTRL_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_STATUSA_OSCCTRL_Msk instead */
#define PAC_STATUSA_OSC32KCTRL_Pos 5 /**< (PAC_STATUSA) OSC32KCTRL APB Protect Enable Position */
#define PAC_STATUSA_OSC32KCTRL_Msk (_U_(0x1) << PAC_STATUSA_OSC32KCTRL_Pos) /**< (PAC_STATUSA) OSC32KCTRL APB Protect Enable Mask */
#define PAC_STATUSA_OSC32KCTRL PAC_STATUSA_OSC32KCTRL_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_STATUSA_OSC32KCTRL_Msk instead */
#define PAC_STATUSA_SUPC_Pos 6 /**< (PAC_STATUSA) SUPC APB Protect Enable Position */
#define PAC_STATUSA_SUPC_Msk (_U_(0x1) << PAC_STATUSA_SUPC_Pos) /**< (PAC_STATUSA) SUPC APB Protect Enable Mask */
#define PAC_STATUSA_SUPC PAC_STATUSA_SUPC_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_STATUSA_SUPC_Msk instead */
#define PAC_STATUSA_GCLK_Pos 7 /**< (PAC_STATUSA) GCLK APB Protect Enable Position */
#define PAC_STATUSA_GCLK_Msk (_U_(0x1) << PAC_STATUSA_GCLK_Pos) /**< (PAC_STATUSA) GCLK APB Protect Enable Mask */
#define PAC_STATUSA_GCLK PAC_STATUSA_GCLK_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_STATUSA_GCLK_Msk instead */
#define PAC_STATUSA_WDT_Pos 8 /**< (PAC_STATUSA) WDT APB Protect Enable Position */
#define PAC_STATUSA_WDT_Msk (_U_(0x1) << PAC_STATUSA_WDT_Pos) /**< (PAC_STATUSA) WDT APB Protect Enable Mask */
#define PAC_STATUSA_WDT PAC_STATUSA_WDT_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_STATUSA_WDT_Msk instead */
#define PAC_STATUSA_RTC_Pos 9 /**< (PAC_STATUSA) RTC APB Protect Enable Position */
#define PAC_STATUSA_RTC_Msk (_U_(0x1) << PAC_STATUSA_RTC_Pos) /**< (PAC_STATUSA) RTC APB Protect Enable Mask */
#define PAC_STATUSA_RTC PAC_STATUSA_RTC_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_STATUSA_RTC_Msk instead */
#define PAC_STATUSA_EIC_Pos 10 /**< (PAC_STATUSA) EIC APB Protect Enable Position */
#define PAC_STATUSA_EIC_Msk (_U_(0x1) << PAC_STATUSA_EIC_Pos) /**< (PAC_STATUSA) EIC APB Protect Enable Mask */
#define PAC_STATUSA_EIC PAC_STATUSA_EIC_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_STATUSA_EIC_Msk instead */
#define PAC_STATUSA_FREQM_Pos 11 /**< (PAC_STATUSA) FREQM APB Protect Enable Position */
#define PAC_STATUSA_FREQM_Msk (_U_(0x1) << PAC_STATUSA_FREQM_Pos) /**< (PAC_STATUSA) FREQM APB Protect Enable Mask */
#define PAC_STATUSA_FREQM PAC_STATUSA_FREQM_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_STATUSA_FREQM_Msk instead */
#define PAC_STATUSA_PORT_Pos 12 /**< (PAC_STATUSA) PORT APB Protect Enable Position */
#define PAC_STATUSA_PORT_Msk (_U_(0x1) << PAC_STATUSA_PORT_Pos) /**< (PAC_STATUSA) PORT APB Protect Enable Mask */
#define PAC_STATUSA_PORT PAC_STATUSA_PORT_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_STATUSA_PORT_Msk instead */
#define PAC_STATUSA_AC_Pos 13 /**< (PAC_STATUSA) AC APB Protect Enable Position */
#define PAC_STATUSA_AC_Msk (_U_(0x1) << PAC_STATUSA_AC_Pos) /**< (PAC_STATUSA) AC APB Protect Enable Mask */
#define PAC_STATUSA_AC PAC_STATUSA_AC_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_STATUSA_AC_Msk instead */
#define PAC_STATUSA_MASK _U_(0x3FFF) /**< \deprecated (PAC_STATUSA) Register MASK (Use PAC_STATUSA_Msk instead) */
#define PAC_STATUSA_Msk _U_(0x3FFF) /**< (PAC_STATUSA) Register Mask */
/* -------- PAC_STATUSB : (PAC Offset: 0x38) (R/ 32) Peripheral write protection status - Bridge B -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t IDAU_:1; /**< bit: 0 IDAU APB Protect Enable */
uint32_t DSU_:1; /**< bit: 1 DSU APB Protect Enable */
uint32_t NVMCTRL_:1; /**< bit: 2 NVMCTRL APB Protect Enable */
uint32_t DMAC_:1; /**< bit: 3 DMAC APB Protect Enable */
uint32_t :28; /**< bit: 4..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} PAC_STATUSB_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define PAC_STATUSB_OFFSET (0x38) /**< (PAC_STATUSB) Peripheral write protection status - Bridge B Offset */
#define PAC_STATUSB_RESETVALUE _U_(0x02) /**< (PAC_STATUSB) Peripheral write protection status - Bridge B Reset Value */
#define PAC_STATUSB_IDAU_Pos 0 /**< (PAC_STATUSB) IDAU APB Protect Enable Position */
#define PAC_STATUSB_IDAU_Msk (_U_(0x1) << PAC_STATUSB_IDAU_Pos) /**< (PAC_STATUSB) IDAU APB Protect Enable Mask */
#define PAC_STATUSB_IDAU PAC_STATUSB_IDAU_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_STATUSB_IDAU_Msk instead */
#define PAC_STATUSB_DSU_Pos 1 /**< (PAC_STATUSB) DSU APB Protect Enable Position */
#define PAC_STATUSB_DSU_Msk (_U_(0x1) << PAC_STATUSB_DSU_Pos) /**< (PAC_STATUSB) DSU APB Protect Enable Mask */
#define PAC_STATUSB_DSU PAC_STATUSB_DSU_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_STATUSB_DSU_Msk instead */
#define PAC_STATUSB_NVMCTRL_Pos 2 /**< (PAC_STATUSB) NVMCTRL APB Protect Enable Position */
#define PAC_STATUSB_NVMCTRL_Msk (_U_(0x1) << PAC_STATUSB_NVMCTRL_Pos) /**< (PAC_STATUSB) NVMCTRL APB Protect Enable Mask */
#define PAC_STATUSB_NVMCTRL PAC_STATUSB_NVMCTRL_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_STATUSB_NVMCTRL_Msk instead */
#define PAC_STATUSB_DMAC_Pos 3 /**< (PAC_STATUSB) DMAC APB Protect Enable Position */
#define PAC_STATUSB_DMAC_Msk (_U_(0x1) << PAC_STATUSB_DMAC_Pos) /**< (PAC_STATUSB) DMAC APB Protect Enable Mask */
#define PAC_STATUSB_DMAC PAC_STATUSB_DMAC_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_STATUSB_DMAC_Msk instead */
#define PAC_STATUSB_MASK _U_(0x0F) /**< \deprecated (PAC_STATUSB) Register MASK (Use PAC_STATUSB_Msk instead) */
#define PAC_STATUSB_Msk _U_(0x0F) /**< (PAC_STATUSB) Register Mask */
/* -------- PAC_STATUSC : (PAC Offset: 0x3c) (R/ 32) Peripheral write protection status - Bridge C -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t EVSYS_:1; /**< bit: 0 EVSYS APB Protect Enable */
uint32_t SERCOM0_:1; /**< bit: 1 SERCOM0 APB Protect Enable */
uint32_t SERCOM1_:1; /**< bit: 2 SERCOM1 APB Protect Enable */
uint32_t SERCOM2_:1; /**< bit: 3 SERCOM2 APB Protect Enable */
uint32_t TC0_:1; /**< bit: 4 TC0 APB Protect Enable */
uint32_t TC1_:1; /**< bit: 5 TC1 APB Protect Enable */
uint32_t TC2_:1; /**< bit: 6 TC2 APB Protect Enable */
uint32_t ADC_:1; /**< bit: 7 ADC APB Protect Enable */
uint32_t DAC_:1; /**< bit: 8 DAC APB Protect Enable */
uint32_t PTC_:1; /**< bit: 9 PTC APB Protect Enable */
uint32_t TRNG_:1; /**< bit: 10 TRNG APB Protect Enable */
uint32_t CCL_:1; /**< bit: 11 CCL APB Protect Enable */
uint32_t OPAMP_:1; /**< bit: 12 OPAMP APB Protect Enable */
uint32_t TRAM_:1; /**< bit: 13 TRAM APB Protect Enable */
uint32_t :18; /**< bit: 14..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} PAC_STATUSC_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define PAC_STATUSC_OFFSET (0x3C) /**< (PAC_STATUSC) Peripheral write protection status - Bridge C Offset */
#define PAC_STATUSC_RESETVALUE _U_(0x00) /**< (PAC_STATUSC) Peripheral write protection status - Bridge C Reset Value */
#define PAC_STATUSC_EVSYS_Pos 0 /**< (PAC_STATUSC) EVSYS APB Protect Enable Position */
#define PAC_STATUSC_EVSYS_Msk (_U_(0x1) << PAC_STATUSC_EVSYS_Pos) /**< (PAC_STATUSC) EVSYS APB Protect Enable Mask */
#define PAC_STATUSC_EVSYS PAC_STATUSC_EVSYS_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_STATUSC_EVSYS_Msk instead */
#define PAC_STATUSC_SERCOM0_Pos 1 /**< (PAC_STATUSC) SERCOM0 APB Protect Enable Position */
#define PAC_STATUSC_SERCOM0_Msk (_U_(0x1) << PAC_STATUSC_SERCOM0_Pos) /**< (PAC_STATUSC) SERCOM0 APB Protect Enable Mask */
#define PAC_STATUSC_SERCOM0 PAC_STATUSC_SERCOM0_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_STATUSC_SERCOM0_Msk instead */
#define PAC_STATUSC_SERCOM1_Pos 2 /**< (PAC_STATUSC) SERCOM1 APB Protect Enable Position */
#define PAC_STATUSC_SERCOM1_Msk (_U_(0x1) << PAC_STATUSC_SERCOM1_Pos) /**< (PAC_STATUSC) SERCOM1 APB Protect Enable Mask */
#define PAC_STATUSC_SERCOM1 PAC_STATUSC_SERCOM1_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_STATUSC_SERCOM1_Msk instead */
#define PAC_STATUSC_SERCOM2_Pos 3 /**< (PAC_STATUSC) SERCOM2 APB Protect Enable Position */
#define PAC_STATUSC_SERCOM2_Msk (_U_(0x1) << PAC_STATUSC_SERCOM2_Pos) /**< (PAC_STATUSC) SERCOM2 APB Protect Enable Mask */
#define PAC_STATUSC_SERCOM2 PAC_STATUSC_SERCOM2_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_STATUSC_SERCOM2_Msk instead */
#define PAC_STATUSC_TC0_Pos 4 /**< (PAC_STATUSC) TC0 APB Protect Enable Position */
#define PAC_STATUSC_TC0_Msk (_U_(0x1) << PAC_STATUSC_TC0_Pos) /**< (PAC_STATUSC) TC0 APB Protect Enable Mask */
#define PAC_STATUSC_TC0 PAC_STATUSC_TC0_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_STATUSC_TC0_Msk instead */
#define PAC_STATUSC_TC1_Pos 5 /**< (PAC_STATUSC) TC1 APB Protect Enable Position */
#define PAC_STATUSC_TC1_Msk (_U_(0x1) << PAC_STATUSC_TC1_Pos) /**< (PAC_STATUSC) TC1 APB Protect Enable Mask */
#define PAC_STATUSC_TC1 PAC_STATUSC_TC1_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_STATUSC_TC1_Msk instead */
#define PAC_STATUSC_TC2_Pos 6 /**< (PAC_STATUSC) TC2 APB Protect Enable Position */
#define PAC_STATUSC_TC2_Msk (_U_(0x1) << PAC_STATUSC_TC2_Pos) /**< (PAC_STATUSC) TC2 APB Protect Enable Mask */
#define PAC_STATUSC_TC2 PAC_STATUSC_TC2_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_STATUSC_TC2_Msk instead */
#define PAC_STATUSC_ADC_Pos 7 /**< (PAC_STATUSC) ADC APB Protect Enable Position */
#define PAC_STATUSC_ADC_Msk (_U_(0x1) << PAC_STATUSC_ADC_Pos) /**< (PAC_STATUSC) ADC APB Protect Enable Mask */
#define PAC_STATUSC_ADC PAC_STATUSC_ADC_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_STATUSC_ADC_Msk instead */
#define PAC_STATUSC_DAC_Pos 8 /**< (PAC_STATUSC) DAC APB Protect Enable Position */
#define PAC_STATUSC_DAC_Msk (_U_(0x1) << PAC_STATUSC_DAC_Pos) /**< (PAC_STATUSC) DAC APB Protect Enable Mask */
#define PAC_STATUSC_DAC PAC_STATUSC_DAC_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_STATUSC_DAC_Msk instead */
#define PAC_STATUSC_PTC_Pos 9 /**< (PAC_STATUSC) PTC APB Protect Enable Position */
#define PAC_STATUSC_PTC_Msk (_U_(0x1) << PAC_STATUSC_PTC_Pos) /**< (PAC_STATUSC) PTC APB Protect Enable Mask */
#define PAC_STATUSC_PTC PAC_STATUSC_PTC_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_STATUSC_PTC_Msk instead */
#define PAC_STATUSC_TRNG_Pos 10 /**< (PAC_STATUSC) TRNG APB Protect Enable Position */
#define PAC_STATUSC_TRNG_Msk (_U_(0x1) << PAC_STATUSC_TRNG_Pos) /**< (PAC_STATUSC) TRNG APB Protect Enable Mask */
#define PAC_STATUSC_TRNG PAC_STATUSC_TRNG_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_STATUSC_TRNG_Msk instead */
#define PAC_STATUSC_CCL_Pos 11 /**< (PAC_STATUSC) CCL APB Protect Enable Position */
#define PAC_STATUSC_CCL_Msk (_U_(0x1) << PAC_STATUSC_CCL_Pos) /**< (PAC_STATUSC) CCL APB Protect Enable Mask */
#define PAC_STATUSC_CCL PAC_STATUSC_CCL_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_STATUSC_CCL_Msk instead */
#define PAC_STATUSC_OPAMP_Pos 12 /**< (PAC_STATUSC) OPAMP APB Protect Enable Position */
#define PAC_STATUSC_OPAMP_Msk (_U_(0x1) << PAC_STATUSC_OPAMP_Pos) /**< (PAC_STATUSC) OPAMP APB Protect Enable Mask */
#define PAC_STATUSC_OPAMP PAC_STATUSC_OPAMP_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_STATUSC_OPAMP_Msk instead */
#define PAC_STATUSC_TRAM_Pos 13 /**< (PAC_STATUSC) TRAM APB Protect Enable Position */
#define PAC_STATUSC_TRAM_Msk (_U_(0x1) << PAC_STATUSC_TRAM_Pos) /**< (PAC_STATUSC) TRAM APB Protect Enable Mask */
#define PAC_STATUSC_TRAM PAC_STATUSC_TRAM_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_STATUSC_TRAM_Msk instead */
#define PAC_STATUSC_MASK _U_(0x3FFF) /**< \deprecated (PAC_STATUSC) Register MASK (Use PAC_STATUSC_Msk instead) */
#define PAC_STATUSC_Msk _U_(0x3FFF) /**< (PAC_STATUSC) Register Mask */
#define PAC_STATUSC_SERCOM_Pos 1 /**< (PAC_STATUSC Position) SERCOMx APB Protect Enable */
#define PAC_STATUSC_SERCOM_Msk (_U_(0x7) << PAC_STATUSC_SERCOM_Pos) /**< (PAC_STATUSC Mask) SERCOM */
#define PAC_STATUSC_SERCOM(value) (PAC_STATUSC_SERCOM_Msk & ((value) << PAC_STATUSC_SERCOM_Pos))
#define PAC_STATUSC_TC_Pos 4 /**< (PAC_STATUSC Position) TCx APB Protect Enable */
#define PAC_STATUSC_TC_Msk (_U_(0x7) << PAC_STATUSC_TC_Pos) /**< (PAC_STATUSC Mask) TC */
#define PAC_STATUSC_TC(value) (PAC_STATUSC_TC_Msk & ((value) << PAC_STATUSC_TC_Pos))
/* -------- PAC_NONSECA : (PAC Offset: 0x54) (R/ 32) Peripheral non-secure status - Bridge A -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t PAC_:1; /**< bit: 0 PAC Non-Secure */
uint32_t PM_:1; /**< bit: 1 PM Non-Secure */
uint32_t MCLK_:1; /**< bit: 2 MCLK Non-Secure */
uint32_t RSTC_:1; /**< bit: 3 RSTC Non-Secure */
uint32_t OSCCTRL_:1; /**< bit: 4 OSCCTRL Non-Secure */
uint32_t OSC32KCTRL_:1; /**< bit: 5 OSC32KCTRL Non-Secure */
uint32_t SUPC_:1; /**< bit: 6 SUPC Non-Secure */
uint32_t GCLK_:1; /**< bit: 7 GCLK Non-Secure */
uint32_t WDT_:1; /**< bit: 8 WDT Non-Secure */
uint32_t RTC_:1; /**< bit: 9 RTC Non-Secure */
uint32_t EIC_:1; /**< bit: 10 EIC Non-Secure */
uint32_t FREQM_:1; /**< bit: 11 FREQM Non-Secure */
uint32_t PORT_:1; /**< bit: 12 PORT Non-Secure */
uint32_t AC_:1; /**< bit: 13 AC Non-Secure */
uint32_t :18; /**< bit: 14..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} PAC_NONSECA_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define PAC_NONSECA_OFFSET (0x54) /**< (PAC_NONSECA) Peripheral non-secure status - Bridge A Offset */
#define PAC_NONSECA_RESETVALUE _U_(0x00) /**< (PAC_NONSECA) Peripheral non-secure status - Bridge A Reset Value */
#define PAC_NONSECA_PAC_Pos 0 /**< (PAC_NONSECA) PAC Non-Secure Position */
#define PAC_NONSECA_PAC_Msk (_U_(0x1) << PAC_NONSECA_PAC_Pos) /**< (PAC_NONSECA) PAC Non-Secure Mask */
#define PAC_NONSECA_PAC PAC_NONSECA_PAC_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_NONSECA_PAC_Msk instead */
#define PAC_NONSECA_PM_Pos 1 /**< (PAC_NONSECA) PM Non-Secure Position */
#define PAC_NONSECA_PM_Msk (_U_(0x1) << PAC_NONSECA_PM_Pos) /**< (PAC_NONSECA) PM Non-Secure Mask */
#define PAC_NONSECA_PM PAC_NONSECA_PM_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_NONSECA_PM_Msk instead */
#define PAC_NONSECA_MCLK_Pos 2 /**< (PAC_NONSECA) MCLK Non-Secure Position */
#define PAC_NONSECA_MCLK_Msk (_U_(0x1) << PAC_NONSECA_MCLK_Pos) /**< (PAC_NONSECA) MCLK Non-Secure Mask */
#define PAC_NONSECA_MCLK PAC_NONSECA_MCLK_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_NONSECA_MCLK_Msk instead */
#define PAC_NONSECA_RSTC_Pos 3 /**< (PAC_NONSECA) RSTC Non-Secure Position */
#define PAC_NONSECA_RSTC_Msk (_U_(0x1) << PAC_NONSECA_RSTC_Pos) /**< (PAC_NONSECA) RSTC Non-Secure Mask */
#define PAC_NONSECA_RSTC PAC_NONSECA_RSTC_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_NONSECA_RSTC_Msk instead */
#define PAC_NONSECA_OSCCTRL_Pos 4 /**< (PAC_NONSECA) OSCCTRL Non-Secure Position */
#define PAC_NONSECA_OSCCTRL_Msk (_U_(0x1) << PAC_NONSECA_OSCCTRL_Pos) /**< (PAC_NONSECA) OSCCTRL Non-Secure Mask */
#define PAC_NONSECA_OSCCTRL PAC_NONSECA_OSCCTRL_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_NONSECA_OSCCTRL_Msk instead */
#define PAC_NONSECA_OSC32KCTRL_Pos 5 /**< (PAC_NONSECA) OSC32KCTRL Non-Secure Position */
#define PAC_NONSECA_OSC32KCTRL_Msk (_U_(0x1) << PAC_NONSECA_OSC32KCTRL_Pos) /**< (PAC_NONSECA) OSC32KCTRL Non-Secure Mask */
#define PAC_NONSECA_OSC32KCTRL PAC_NONSECA_OSC32KCTRL_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_NONSECA_OSC32KCTRL_Msk instead */
#define PAC_NONSECA_SUPC_Pos 6 /**< (PAC_NONSECA) SUPC Non-Secure Position */
#define PAC_NONSECA_SUPC_Msk (_U_(0x1) << PAC_NONSECA_SUPC_Pos) /**< (PAC_NONSECA) SUPC Non-Secure Mask */
#define PAC_NONSECA_SUPC PAC_NONSECA_SUPC_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_NONSECA_SUPC_Msk instead */
#define PAC_NONSECA_GCLK_Pos 7 /**< (PAC_NONSECA) GCLK Non-Secure Position */
#define PAC_NONSECA_GCLK_Msk (_U_(0x1) << PAC_NONSECA_GCLK_Pos) /**< (PAC_NONSECA) GCLK Non-Secure Mask */
#define PAC_NONSECA_GCLK PAC_NONSECA_GCLK_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_NONSECA_GCLK_Msk instead */
#define PAC_NONSECA_WDT_Pos 8 /**< (PAC_NONSECA) WDT Non-Secure Position */
#define PAC_NONSECA_WDT_Msk (_U_(0x1) << PAC_NONSECA_WDT_Pos) /**< (PAC_NONSECA) WDT Non-Secure Mask */
#define PAC_NONSECA_WDT PAC_NONSECA_WDT_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_NONSECA_WDT_Msk instead */
#define PAC_NONSECA_RTC_Pos 9 /**< (PAC_NONSECA) RTC Non-Secure Position */
#define PAC_NONSECA_RTC_Msk (_U_(0x1) << PAC_NONSECA_RTC_Pos) /**< (PAC_NONSECA) RTC Non-Secure Mask */
#define PAC_NONSECA_RTC PAC_NONSECA_RTC_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_NONSECA_RTC_Msk instead */
#define PAC_NONSECA_EIC_Pos 10 /**< (PAC_NONSECA) EIC Non-Secure Position */
#define PAC_NONSECA_EIC_Msk (_U_(0x1) << PAC_NONSECA_EIC_Pos) /**< (PAC_NONSECA) EIC Non-Secure Mask */
#define PAC_NONSECA_EIC PAC_NONSECA_EIC_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_NONSECA_EIC_Msk instead */
#define PAC_NONSECA_FREQM_Pos 11 /**< (PAC_NONSECA) FREQM Non-Secure Position */
#define PAC_NONSECA_FREQM_Msk (_U_(0x1) << PAC_NONSECA_FREQM_Pos) /**< (PAC_NONSECA) FREQM Non-Secure Mask */
#define PAC_NONSECA_FREQM PAC_NONSECA_FREQM_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_NONSECA_FREQM_Msk instead */
#define PAC_NONSECA_PORT_Pos 12 /**< (PAC_NONSECA) PORT Non-Secure Position */
#define PAC_NONSECA_PORT_Msk (_U_(0x1) << PAC_NONSECA_PORT_Pos) /**< (PAC_NONSECA) PORT Non-Secure Mask */
#define PAC_NONSECA_PORT PAC_NONSECA_PORT_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_NONSECA_PORT_Msk instead */
#define PAC_NONSECA_AC_Pos 13 /**< (PAC_NONSECA) AC Non-Secure Position */
#define PAC_NONSECA_AC_Msk (_U_(0x1) << PAC_NONSECA_AC_Pos) /**< (PAC_NONSECA) AC Non-Secure Mask */
#define PAC_NONSECA_AC PAC_NONSECA_AC_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_NONSECA_AC_Msk instead */
#define PAC_NONSECA_MASK _U_(0x3FFF) /**< \deprecated (PAC_NONSECA) Register MASK (Use PAC_NONSECA_Msk instead) */
#define PAC_NONSECA_Msk _U_(0x3FFF) /**< (PAC_NONSECA) Register Mask */
/* -------- PAC_NONSECB : (PAC Offset: 0x58) (R/ 32) Peripheral non-secure status - Bridge B -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t IDAU_:1; /**< bit: 0 IDAU Non-Secure */
uint32_t DSU_:1; /**< bit: 1 DSU Non-Secure */
uint32_t NVMCTRL_:1; /**< bit: 2 NVMCTRL Non-Secure */
uint32_t DMAC_:1; /**< bit: 3 DMAC Non-Secure */
uint32_t :28; /**< bit: 4..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} PAC_NONSECB_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define PAC_NONSECB_OFFSET (0x58) /**< (PAC_NONSECB) Peripheral non-secure status - Bridge B Offset */
#define PAC_NONSECB_RESETVALUE _U_(0x02) /**< (PAC_NONSECB) Peripheral non-secure status - Bridge B Reset Value */
#define PAC_NONSECB_IDAU_Pos 0 /**< (PAC_NONSECB) IDAU Non-Secure Position */
#define PAC_NONSECB_IDAU_Msk (_U_(0x1) << PAC_NONSECB_IDAU_Pos) /**< (PAC_NONSECB) IDAU Non-Secure Mask */
#define PAC_NONSECB_IDAU PAC_NONSECB_IDAU_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_NONSECB_IDAU_Msk instead */
#define PAC_NONSECB_DSU_Pos 1 /**< (PAC_NONSECB) DSU Non-Secure Position */
#define PAC_NONSECB_DSU_Msk (_U_(0x1) << PAC_NONSECB_DSU_Pos) /**< (PAC_NONSECB) DSU Non-Secure Mask */
#define PAC_NONSECB_DSU PAC_NONSECB_DSU_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_NONSECB_DSU_Msk instead */
#define PAC_NONSECB_NVMCTRL_Pos 2 /**< (PAC_NONSECB) NVMCTRL Non-Secure Position */
#define PAC_NONSECB_NVMCTRL_Msk (_U_(0x1) << PAC_NONSECB_NVMCTRL_Pos) /**< (PAC_NONSECB) NVMCTRL Non-Secure Mask */
#define PAC_NONSECB_NVMCTRL PAC_NONSECB_NVMCTRL_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_NONSECB_NVMCTRL_Msk instead */
#define PAC_NONSECB_DMAC_Pos 3 /**< (PAC_NONSECB) DMAC Non-Secure Position */
#define PAC_NONSECB_DMAC_Msk (_U_(0x1) << PAC_NONSECB_DMAC_Pos) /**< (PAC_NONSECB) DMAC Non-Secure Mask */
#define PAC_NONSECB_DMAC PAC_NONSECB_DMAC_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_NONSECB_DMAC_Msk instead */
#define PAC_NONSECB_MASK _U_(0x0F) /**< \deprecated (PAC_NONSECB) Register MASK (Use PAC_NONSECB_Msk instead) */
#define PAC_NONSECB_Msk _U_(0x0F) /**< (PAC_NONSECB) Register Mask */
/* -------- PAC_NONSECC : (PAC Offset: 0x5c) (R/ 32) Peripheral non-secure status - Bridge C -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t EVSYS_:1; /**< bit: 0 EVSYS Non-Secure */
uint32_t SERCOM0_:1; /**< bit: 1 SERCOM0 Non-Secure */
uint32_t SERCOM1_:1; /**< bit: 2 SERCOM1 Non-Secure */
uint32_t SERCOM2_:1; /**< bit: 3 SERCOM2 Non-Secure */
uint32_t TC0_:1; /**< bit: 4 TC0 Non-Secure */
uint32_t TC1_:1; /**< bit: 5 TC1 Non-Secure */
uint32_t TC2_:1; /**< bit: 6 TC2 Non-Secure */
uint32_t ADC_:1; /**< bit: 7 ADC Non-Secure */
uint32_t DAC_:1; /**< bit: 8 DAC Non-Secure */
uint32_t PTC_:1; /**< bit: 9 PTC Non-Secure */
uint32_t TRNG_:1; /**< bit: 10 TRNG Non-Secure */
uint32_t CCL_:1; /**< bit: 11 CCL Non-Secure */
uint32_t OPAMP_:1; /**< bit: 12 OPAMP Non-Secure */
uint32_t TRAM_:1; /**< bit: 13 TRAM Non-Secure */
uint32_t :18; /**< bit: 14..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} PAC_NONSECC_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define PAC_NONSECC_OFFSET (0x5C) /**< (PAC_NONSECC) Peripheral non-secure status - Bridge C Offset */
#define PAC_NONSECC_RESETVALUE _U_(0x00) /**< (PAC_NONSECC) Peripheral non-secure status - Bridge C Reset Value */
#define PAC_NONSECC_EVSYS_Pos 0 /**< (PAC_NONSECC) EVSYS Non-Secure Position */
#define PAC_NONSECC_EVSYS_Msk (_U_(0x1) << PAC_NONSECC_EVSYS_Pos) /**< (PAC_NONSECC) EVSYS Non-Secure Mask */
#define PAC_NONSECC_EVSYS PAC_NONSECC_EVSYS_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_NONSECC_EVSYS_Msk instead */
#define PAC_NONSECC_SERCOM0_Pos 1 /**< (PAC_NONSECC) SERCOM0 Non-Secure Position */
#define PAC_NONSECC_SERCOM0_Msk (_U_(0x1) << PAC_NONSECC_SERCOM0_Pos) /**< (PAC_NONSECC) SERCOM0 Non-Secure Mask */
#define PAC_NONSECC_SERCOM0 PAC_NONSECC_SERCOM0_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_NONSECC_SERCOM0_Msk instead */
#define PAC_NONSECC_SERCOM1_Pos 2 /**< (PAC_NONSECC) SERCOM1 Non-Secure Position */
#define PAC_NONSECC_SERCOM1_Msk (_U_(0x1) << PAC_NONSECC_SERCOM1_Pos) /**< (PAC_NONSECC) SERCOM1 Non-Secure Mask */
#define PAC_NONSECC_SERCOM1 PAC_NONSECC_SERCOM1_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_NONSECC_SERCOM1_Msk instead */
#define PAC_NONSECC_SERCOM2_Pos 3 /**< (PAC_NONSECC) SERCOM2 Non-Secure Position */
#define PAC_NONSECC_SERCOM2_Msk (_U_(0x1) << PAC_NONSECC_SERCOM2_Pos) /**< (PAC_NONSECC) SERCOM2 Non-Secure Mask */
#define PAC_NONSECC_SERCOM2 PAC_NONSECC_SERCOM2_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_NONSECC_SERCOM2_Msk instead */
#define PAC_NONSECC_TC0_Pos 4 /**< (PAC_NONSECC) TC0 Non-Secure Position */
#define PAC_NONSECC_TC0_Msk (_U_(0x1) << PAC_NONSECC_TC0_Pos) /**< (PAC_NONSECC) TC0 Non-Secure Mask */
#define PAC_NONSECC_TC0 PAC_NONSECC_TC0_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_NONSECC_TC0_Msk instead */
#define PAC_NONSECC_TC1_Pos 5 /**< (PAC_NONSECC) TC1 Non-Secure Position */
#define PAC_NONSECC_TC1_Msk (_U_(0x1) << PAC_NONSECC_TC1_Pos) /**< (PAC_NONSECC) TC1 Non-Secure Mask */
#define PAC_NONSECC_TC1 PAC_NONSECC_TC1_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_NONSECC_TC1_Msk instead */
#define PAC_NONSECC_TC2_Pos 6 /**< (PAC_NONSECC) TC2 Non-Secure Position */
#define PAC_NONSECC_TC2_Msk (_U_(0x1) << PAC_NONSECC_TC2_Pos) /**< (PAC_NONSECC) TC2 Non-Secure Mask */
#define PAC_NONSECC_TC2 PAC_NONSECC_TC2_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_NONSECC_TC2_Msk instead */
#define PAC_NONSECC_ADC_Pos 7 /**< (PAC_NONSECC) ADC Non-Secure Position */
#define PAC_NONSECC_ADC_Msk (_U_(0x1) << PAC_NONSECC_ADC_Pos) /**< (PAC_NONSECC) ADC Non-Secure Mask */
#define PAC_NONSECC_ADC PAC_NONSECC_ADC_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_NONSECC_ADC_Msk instead */
#define PAC_NONSECC_DAC_Pos 8 /**< (PAC_NONSECC) DAC Non-Secure Position */
#define PAC_NONSECC_DAC_Msk (_U_(0x1) << PAC_NONSECC_DAC_Pos) /**< (PAC_NONSECC) DAC Non-Secure Mask */
#define PAC_NONSECC_DAC PAC_NONSECC_DAC_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_NONSECC_DAC_Msk instead */
#define PAC_NONSECC_PTC_Pos 9 /**< (PAC_NONSECC) PTC Non-Secure Position */
#define PAC_NONSECC_PTC_Msk (_U_(0x1) << PAC_NONSECC_PTC_Pos) /**< (PAC_NONSECC) PTC Non-Secure Mask */
#define PAC_NONSECC_PTC PAC_NONSECC_PTC_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_NONSECC_PTC_Msk instead */
#define PAC_NONSECC_TRNG_Pos 10 /**< (PAC_NONSECC) TRNG Non-Secure Position */
#define PAC_NONSECC_TRNG_Msk (_U_(0x1) << PAC_NONSECC_TRNG_Pos) /**< (PAC_NONSECC) TRNG Non-Secure Mask */
#define PAC_NONSECC_TRNG PAC_NONSECC_TRNG_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_NONSECC_TRNG_Msk instead */
#define PAC_NONSECC_CCL_Pos 11 /**< (PAC_NONSECC) CCL Non-Secure Position */
#define PAC_NONSECC_CCL_Msk (_U_(0x1) << PAC_NONSECC_CCL_Pos) /**< (PAC_NONSECC) CCL Non-Secure Mask */
#define PAC_NONSECC_CCL PAC_NONSECC_CCL_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_NONSECC_CCL_Msk instead */
#define PAC_NONSECC_OPAMP_Pos 12 /**< (PAC_NONSECC) OPAMP Non-Secure Position */
#define PAC_NONSECC_OPAMP_Msk (_U_(0x1) << PAC_NONSECC_OPAMP_Pos) /**< (PAC_NONSECC) OPAMP Non-Secure Mask */
#define PAC_NONSECC_OPAMP PAC_NONSECC_OPAMP_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_NONSECC_OPAMP_Msk instead */
#define PAC_NONSECC_TRAM_Pos 13 /**< (PAC_NONSECC) TRAM Non-Secure Position */
#define PAC_NONSECC_TRAM_Msk (_U_(0x1) << PAC_NONSECC_TRAM_Pos) /**< (PAC_NONSECC) TRAM Non-Secure Mask */
#define PAC_NONSECC_TRAM PAC_NONSECC_TRAM_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_NONSECC_TRAM_Msk instead */
#define PAC_NONSECC_MASK _U_(0x3FFF) /**< \deprecated (PAC_NONSECC) Register MASK (Use PAC_NONSECC_Msk instead) */
#define PAC_NONSECC_Msk _U_(0x3FFF) /**< (PAC_NONSECC) Register Mask */
#define PAC_NONSECC_SERCOM_Pos 1 /**< (PAC_NONSECC Position) SERCOMx Non-Secure */
#define PAC_NONSECC_SERCOM_Msk (_U_(0x7) << PAC_NONSECC_SERCOM_Pos) /**< (PAC_NONSECC Mask) SERCOM */
#define PAC_NONSECC_SERCOM(value) (PAC_NONSECC_SERCOM_Msk & ((value) << PAC_NONSECC_SERCOM_Pos))
#define PAC_NONSECC_TC_Pos 4 /**< (PAC_NONSECC Position) TCx Non-Secure */
#define PAC_NONSECC_TC_Msk (_U_(0x7) << PAC_NONSECC_TC_Pos) /**< (PAC_NONSECC Mask) TC */
#define PAC_NONSECC_TC(value) (PAC_NONSECC_TC_Msk & ((value) << PAC_NONSECC_TC_Pos))
/* -------- PAC_SECLOCKA : (PAC Offset: 0x74) (R/ 32) Peripheral secure status locked - Bridge A -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t PAC_:1; /**< bit: 0 PAC Secure Status Locked */
uint32_t PM_:1; /**< bit: 1 PM Secure Status Locked */
uint32_t MCLK_:1; /**< bit: 2 MCLK Secure Status Locked */
uint32_t RSTC_:1; /**< bit: 3 RSTC Secure Status Locked */
uint32_t OSCCTRL_:1; /**< bit: 4 OSCCTRL Secure Status Locked */
uint32_t OSC32KCTRL_:1; /**< bit: 5 OSC32KCTRL Secure Status Locked */
uint32_t SUPC_:1; /**< bit: 6 SUPC Secure Status Locked */
uint32_t GCLK_:1; /**< bit: 7 GCLK Secure Status Locked */
uint32_t WDT_:1; /**< bit: 8 WDT Secure Status Locked */
uint32_t RTC_:1; /**< bit: 9 RTC Secure Status Locked */
uint32_t EIC_:1; /**< bit: 10 EIC Secure Status Locked */
uint32_t FREQM_:1; /**< bit: 11 FREQM Secure Status Locked */
uint32_t PORT_:1; /**< bit: 12 PORT Secure Status Locked */
uint32_t AC_:1; /**< bit: 13 AC Secure Status Locked */
uint32_t :18; /**< bit: 14..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} PAC_SECLOCKA_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define PAC_SECLOCKA_OFFSET (0x74) /**< (PAC_SECLOCKA) Peripheral secure status locked - Bridge A Offset */
#define PAC_SECLOCKA_RESETVALUE _U_(0x00) /**< (PAC_SECLOCKA) Peripheral secure status locked - Bridge A Reset Value */
#define PAC_SECLOCKA_PAC_Pos 0 /**< (PAC_SECLOCKA) PAC Secure Status Locked Position */
#define PAC_SECLOCKA_PAC_Msk (_U_(0x1) << PAC_SECLOCKA_PAC_Pos) /**< (PAC_SECLOCKA) PAC Secure Status Locked Mask */
#define PAC_SECLOCKA_PAC PAC_SECLOCKA_PAC_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_SECLOCKA_PAC_Msk instead */
#define PAC_SECLOCKA_PM_Pos 1 /**< (PAC_SECLOCKA) PM Secure Status Locked Position */
#define PAC_SECLOCKA_PM_Msk (_U_(0x1) << PAC_SECLOCKA_PM_Pos) /**< (PAC_SECLOCKA) PM Secure Status Locked Mask */
#define PAC_SECLOCKA_PM PAC_SECLOCKA_PM_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_SECLOCKA_PM_Msk instead */
#define PAC_SECLOCKA_MCLK_Pos 2 /**< (PAC_SECLOCKA) MCLK Secure Status Locked Position */
#define PAC_SECLOCKA_MCLK_Msk (_U_(0x1) << PAC_SECLOCKA_MCLK_Pos) /**< (PAC_SECLOCKA) MCLK Secure Status Locked Mask */
#define PAC_SECLOCKA_MCLK PAC_SECLOCKA_MCLK_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_SECLOCKA_MCLK_Msk instead */
#define PAC_SECLOCKA_RSTC_Pos 3 /**< (PAC_SECLOCKA) RSTC Secure Status Locked Position */
#define PAC_SECLOCKA_RSTC_Msk (_U_(0x1) << PAC_SECLOCKA_RSTC_Pos) /**< (PAC_SECLOCKA) RSTC Secure Status Locked Mask */
#define PAC_SECLOCKA_RSTC PAC_SECLOCKA_RSTC_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_SECLOCKA_RSTC_Msk instead */
#define PAC_SECLOCKA_OSCCTRL_Pos 4 /**< (PAC_SECLOCKA) OSCCTRL Secure Status Locked Position */
#define PAC_SECLOCKA_OSCCTRL_Msk (_U_(0x1) << PAC_SECLOCKA_OSCCTRL_Pos) /**< (PAC_SECLOCKA) OSCCTRL Secure Status Locked Mask */
#define PAC_SECLOCKA_OSCCTRL PAC_SECLOCKA_OSCCTRL_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_SECLOCKA_OSCCTRL_Msk instead */
#define PAC_SECLOCKA_OSC32KCTRL_Pos 5 /**< (PAC_SECLOCKA) OSC32KCTRL Secure Status Locked Position */
#define PAC_SECLOCKA_OSC32KCTRL_Msk (_U_(0x1) << PAC_SECLOCKA_OSC32KCTRL_Pos) /**< (PAC_SECLOCKA) OSC32KCTRL Secure Status Locked Mask */
#define PAC_SECLOCKA_OSC32KCTRL PAC_SECLOCKA_OSC32KCTRL_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_SECLOCKA_OSC32KCTRL_Msk instead */
#define PAC_SECLOCKA_SUPC_Pos 6 /**< (PAC_SECLOCKA) SUPC Secure Status Locked Position */
#define PAC_SECLOCKA_SUPC_Msk (_U_(0x1) << PAC_SECLOCKA_SUPC_Pos) /**< (PAC_SECLOCKA) SUPC Secure Status Locked Mask */
#define PAC_SECLOCKA_SUPC PAC_SECLOCKA_SUPC_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_SECLOCKA_SUPC_Msk instead */
#define PAC_SECLOCKA_GCLK_Pos 7 /**< (PAC_SECLOCKA) GCLK Secure Status Locked Position */
#define PAC_SECLOCKA_GCLK_Msk (_U_(0x1) << PAC_SECLOCKA_GCLK_Pos) /**< (PAC_SECLOCKA) GCLK Secure Status Locked Mask */
#define PAC_SECLOCKA_GCLK PAC_SECLOCKA_GCLK_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_SECLOCKA_GCLK_Msk instead */
#define PAC_SECLOCKA_WDT_Pos 8 /**< (PAC_SECLOCKA) WDT Secure Status Locked Position */
#define PAC_SECLOCKA_WDT_Msk (_U_(0x1) << PAC_SECLOCKA_WDT_Pos) /**< (PAC_SECLOCKA) WDT Secure Status Locked Mask */
#define PAC_SECLOCKA_WDT PAC_SECLOCKA_WDT_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_SECLOCKA_WDT_Msk instead */
#define PAC_SECLOCKA_RTC_Pos 9 /**< (PAC_SECLOCKA) RTC Secure Status Locked Position */
#define PAC_SECLOCKA_RTC_Msk (_U_(0x1) << PAC_SECLOCKA_RTC_Pos) /**< (PAC_SECLOCKA) RTC Secure Status Locked Mask */
#define PAC_SECLOCKA_RTC PAC_SECLOCKA_RTC_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_SECLOCKA_RTC_Msk instead */
#define PAC_SECLOCKA_EIC_Pos 10 /**< (PAC_SECLOCKA) EIC Secure Status Locked Position */
#define PAC_SECLOCKA_EIC_Msk (_U_(0x1) << PAC_SECLOCKA_EIC_Pos) /**< (PAC_SECLOCKA) EIC Secure Status Locked Mask */
#define PAC_SECLOCKA_EIC PAC_SECLOCKA_EIC_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_SECLOCKA_EIC_Msk instead */
#define PAC_SECLOCKA_FREQM_Pos 11 /**< (PAC_SECLOCKA) FREQM Secure Status Locked Position */
#define PAC_SECLOCKA_FREQM_Msk (_U_(0x1) << PAC_SECLOCKA_FREQM_Pos) /**< (PAC_SECLOCKA) FREQM Secure Status Locked Mask */
#define PAC_SECLOCKA_FREQM PAC_SECLOCKA_FREQM_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_SECLOCKA_FREQM_Msk instead */
#define PAC_SECLOCKA_PORT_Pos 12 /**< (PAC_SECLOCKA) PORT Secure Status Locked Position */
#define PAC_SECLOCKA_PORT_Msk (_U_(0x1) << PAC_SECLOCKA_PORT_Pos) /**< (PAC_SECLOCKA) PORT Secure Status Locked Mask */
#define PAC_SECLOCKA_PORT PAC_SECLOCKA_PORT_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_SECLOCKA_PORT_Msk instead */
#define PAC_SECLOCKA_AC_Pos 13 /**< (PAC_SECLOCKA) AC Secure Status Locked Position */
#define PAC_SECLOCKA_AC_Msk (_U_(0x1) << PAC_SECLOCKA_AC_Pos) /**< (PAC_SECLOCKA) AC Secure Status Locked Mask */
#define PAC_SECLOCKA_AC PAC_SECLOCKA_AC_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_SECLOCKA_AC_Msk instead */
#define PAC_SECLOCKA_MASK _U_(0x3FFF) /**< \deprecated (PAC_SECLOCKA) Register MASK (Use PAC_SECLOCKA_Msk instead) */
#define PAC_SECLOCKA_Msk _U_(0x3FFF) /**< (PAC_SECLOCKA) Register Mask */
/* -------- PAC_SECLOCKB : (PAC Offset: 0x78) (R/ 32) Peripheral secure status locked - Bridge B -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t IDAU_:1; /**< bit: 0 IDAU Secure Status Locked */
uint32_t DSU_:1; /**< bit: 1 DSU Secure Status Locked */
uint32_t NVMCTRL_:1; /**< bit: 2 NVMCTRL Secure Status Locked */
uint32_t DMAC_:1; /**< bit: 3 DMAC Secure Status Locked */
uint32_t :28; /**< bit: 4..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} PAC_SECLOCKB_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define PAC_SECLOCKB_OFFSET (0x78) /**< (PAC_SECLOCKB) Peripheral secure status locked - Bridge B Offset */
#define PAC_SECLOCKB_RESETVALUE _U_(0x03) /**< (PAC_SECLOCKB) Peripheral secure status locked - Bridge B Reset Value */
#define PAC_SECLOCKB_IDAU_Pos 0 /**< (PAC_SECLOCKB) IDAU Secure Status Locked Position */
#define PAC_SECLOCKB_IDAU_Msk (_U_(0x1) << PAC_SECLOCKB_IDAU_Pos) /**< (PAC_SECLOCKB) IDAU Secure Status Locked Mask */
#define PAC_SECLOCKB_IDAU PAC_SECLOCKB_IDAU_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_SECLOCKB_IDAU_Msk instead */
#define PAC_SECLOCKB_DSU_Pos 1 /**< (PAC_SECLOCKB) DSU Secure Status Locked Position */
#define PAC_SECLOCKB_DSU_Msk (_U_(0x1) << PAC_SECLOCKB_DSU_Pos) /**< (PAC_SECLOCKB) DSU Secure Status Locked Mask */
#define PAC_SECLOCKB_DSU PAC_SECLOCKB_DSU_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_SECLOCKB_DSU_Msk instead */
#define PAC_SECLOCKB_NVMCTRL_Pos 2 /**< (PAC_SECLOCKB) NVMCTRL Secure Status Locked Position */
#define PAC_SECLOCKB_NVMCTRL_Msk (_U_(0x1) << PAC_SECLOCKB_NVMCTRL_Pos) /**< (PAC_SECLOCKB) NVMCTRL Secure Status Locked Mask */
#define PAC_SECLOCKB_NVMCTRL PAC_SECLOCKB_NVMCTRL_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_SECLOCKB_NVMCTRL_Msk instead */
#define PAC_SECLOCKB_DMAC_Pos 3 /**< (PAC_SECLOCKB) DMAC Secure Status Locked Position */
#define PAC_SECLOCKB_DMAC_Msk (_U_(0x1) << PAC_SECLOCKB_DMAC_Pos) /**< (PAC_SECLOCKB) DMAC Secure Status Locked Mask */
#define PAC_SECLOCKB_DMAC PAC_SECLOCKB_DMAC_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_SECLOCKB_DMAC_Msk instead */
#define PAC_SECLOCKB_MASK _U_(0x0F) /**< \deprecated (PAC_SECLOCKB) Register MASK (Use PAC_SECLOCKB_Msk instead) */
#define PAC_SECLOCKB_Msk _U_(0x0F) /**< (PAC_SECLOCKB) Register Mask */
/* -------- PAC_SECLOCKC : (PAC Offset: 0x7c) (R/ 32) Peripheral secure status locked - Bridge C -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t EVSYS_:1; /**< bit: 0 EVSYS Secure Status Locked */
uint32_t SERCOM0_:1; /**< bit: 1 SERCOM0 Secure Status Locked */
uint32_t SERCOM1_:1; /**< bit: 2 SERCOM1 Secure Status Locked */
uint32_t SERCOM2_:1; /**< bit: 3 SERCOM2 Secure Status Locked */
uint32_t TC0_:1; /**< bit: 4 TC0 Secure Status Locked */
uint32_t TC1_:1; /**< bit: 5 TC1 Secure Status Locked */
uint32_t TC2_:1; /**< bit: 6 TC2 Secure Status Locked */
uint32_t ADC_:1; /**< bit: 7 ADC Secure Status Locked */
uint32_t DAC_:1; /**< bit: 8 DAC Secure Status Locked */
uint32_t PTC_:1; /**< bit: 9 PTC Secure Status Locked */
uint32_t TRNG_:1; /**< bit: 10 TRNG Secure Status Locked */
uint32_t CCL_:1; /**< bit: 11 CCL Secure Status Locked */
uint32_t OPAMP_:1; /**< bit: 12 OPAMP Secure Status Locked */
uint32_t TRAM_:1; /**< bit: 13 TRAM Secure Status Locked */
uint32_t :18; /**< bit: 14..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} PAC_SECLOCKC_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define PAC_SECLOCKC_OFFSET (0x7C) /**< (PAC_SECLOCKC) Peripheral secure status locked - Bridge C Offset */
#define PAC_SECLOCKC_RESETVALUE _U_(0x00) /**< (PAC_SECLOCKC) Peripheral secure status locked - Bridge C Reset Value */
#define PAC_SECLOCKC_EVSYS_Pos 0 /**< (PAC_SECLOCKC) EVSYS Secure Status Locked Position */
#define PAC_SECLOCKC_EVSYS_Msk (_U_(0x1) << PAC_SECLOCKC_EVSYS_Pos) /**< (PAC_SECLOCKC) EVSYS Secure Status Locked Mask */
#define PAC_SECLOCKC_EVSYS PAC_SECLOCKC_EVSYS_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_SECLOCKC_EVSYS_Msk instead */
#define PAC_SECLOCKC_SERCOM0_Pos 1 /**< (PAC_SECLOCKC) SERCOM0 Secure Status Locked Position */
#define PAC_SECLOCKC_SERCOM0_Msk (_U_(0x1) << PAC_SECLOCKC_SERCOM0_Pos) /**< (PAC_SECLOCKC) SERCOM0 Secure Status Locked Mask */
#define PAC_SECLOCKC_SERCOM0 PAC_SECLOCKC_SERCOM0_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_SECLOCKC_SERCOM0_Msk instead */
#define PAC_SECLOCKC_SERCOM1_Pos 2 /**< (PAC_SECLOCKC) SERCOM1 Secure Status Locked Position */
#define PAC_SECLOCKC_SERCOM1_Msk (_U_(0x1) << PAC_SECLOCKC_SERCOM1_Pos) /**< (PAC_SECLOCKC) SERCOM1 Secure Status Locked Mask */
#define PAC_SECLOCKC_SERCOM1 PAC_SECLOCKC_SERCOM1_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_SECLOCKC_SERCOM1_Msk instead */
#define PAC_SECLOCKC_SERCOM2_Pos 3 /**< (PAC_SECLOCKC) SERCOM2 Secure Status Locked Position */
#define PAC_SECLOCKC_SERCOM2_Msk (_U_(0x1) << PAC_SECLOCKC_SERCOM2_Pos) /**< (PAC_SECLOCKC) SERCOM2 Secure Status Locked Mask */
#define PAC_SECLOCKC_SERCOM2 PAC_SECLOCKC_SERCOM2_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_SECLOCKC_SERCOM2_Msk instead */
#define PAC_SECLOCKC_TC0_Pos 4 /**< (PAC_SECLOCKC) TC0 Secure Status Locked Position */
#define PAC_SECLOCKC_TC0_Msk (_U_(0x1) << PAC_SECLOCKC_TC0_Pos) /**< (PAC_SECLOCKC) TC0 Secure Status Locked Mask */
#define PAC_SECLOCKC_TC0 PAC_SECLOCKC_TC0_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_SECLOCKC_TC0_Msk instead */
#define PAC_SECLOCKC_TC1_Pos 5 /**< (PAC_SECLOCKC) TC1 Secure Status Locked Position */
#define PAC_SECLOCKC_TC1_Msk (_U_(0x1) << PAC_SECLOCKC_TC1_Pos) /**< (PAC_SECLOCKC) TC1 Secure Status Locked Mask */
#define PAC_SECLOCKC_TC1 PAC_SECLOCKC_TC1_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_SECLOCKC_TC1_Msk instead */
#define PAC_SECLOCKC_TC2_Pos 6 /**< (PAC_SECLOCKC) TC2 Secure Status Locked Position */
#define PAC_SECLOCKC_TC2_Msk (_U_(0x1) << PAC_SECLOCKC_TC2_Pos) /**< (PAC_SECLOCKC) TC2 Secure Status Locked Mask */
#define PAC_SECLOCKC_TC2 PAC_SECLOCKC_TC2_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_SECLOCKC_TC2_Msk instead */
#define PAC_SECLOCKC_ADC_Pos 7 /**< (PAC_SECLOCKC) ADC Secure Status Locked Position */
#define PAC_SECLOCKC_ADC_Msk (_U_(0x1) << PAC_SECLOCKC_ADC_Pos) /**< (PAC_SECLOCKC) ADC Secure Status Locked Mask */
#define PAC_SECLOCKC_ADC PAC_SECLOCKC_ADC_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_SECLOCKC_ADC_Msk instead */
#define PAC_SECLOCKC_DAC_Pos 8 /**< (PAC_SECLOCKC) DAC Secure Status Locked Position */
#define PAC_SECLOCKC_DAC_Msk (_U_(0x1) << PAC_SECLOCKC_DAC_Pos) /**< (PAC_SECLOCKC) DAC Secure Status Locked Mask */
#define PAC_SECLOCKC_DAC PAC_SECLOCKC_DAC_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_SECLOCKC_DAC_Msk instead */
#define PAC_SECLOCKC_PTC_Pos 9 /**< (PAC_SECLOCKC) PTC Secure Status Locked Position */
#define PAC_SECLOCKC_PTC_Msk (_U_(0x1) << PAC_SECLOCKC_PTC_Pos) /**< (PAC_SECLOCKC) PTC Secure Status Locked Mask */
#define PAC_SECLOCKC_PTC PAC_SECLOCKC_PTC_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_SECLOCKC_PTC_Msk instead */
#define PAC_SECLOCKC_TRNG_Pos 10 /**< (PAC_SECLOCKC) TRNG Secure Status Locked Position */
#define PAC_SECLOCKC_TRNG_Msk (_U_(0x1) << PAC_SECLOCKC_TRNG_Pos) /**< (PAC_SECLOCKC) TRNG Secure Status Locked Mask */
#define PAC_SECLOCKC_TRNG PAC_SECLOCKC_TRNG_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_SECLOCKC_TRNG_Msk instead */
#define PAC_SECLOCKC_CCL_Pos 11 /**< (PAC_SECLOCKC) CCL Secure Status Locked Position */
#define PAC_SECLOCKC_CCL_Msk (_U_(0x1) << PAC_SECLOCKC_CCL_Pos) /**< (PAC_SECLOCKC) CCL Secure Status Locked Mask */
#define PAC_SECLOCKC_CCL PAC_SECLOCKC_CCL_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_SECLOCKC_CCL_Msk instead */
#define PAC_SECLOCKC_OPAMP_Pos 12 /**< (PAC_SECLOCKC) OPAMP Secure Status Locked Position */
#define PAC_SECLOCKC_OPAMP_Msk (_U_(0x1) << PAC_SECLOCKC_OPAMP_Pos) /**< (PAC_SECLOCKC) OPAMP Secure Status Locked Mask */
#define PAC_SECLOCKC_OPAMP PAC_SECLOCKC_OPAMP_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_SECLOCKC_OPAMP_Msk instead */
#define PAC_SECLOCKC_TRAM_Pos 13 /**< (PAC_SECLOCKC) TRAM Secure Status Locked Position */
#define PAC_SECLOCKC_TRAM_Msk (_U_(0x1) << PAC_SECLOCKC_TRAM_Pos) /**< (PAC_SECLOCKC) TRAM Secure Status Locked Mask */
#define PAC_SECLOCKC_TRAM PAC_SECLOCKC_TRAM_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PAC_SECLOCKC_TRAM_Msk instead */
#define PAC_SECLOCKC_MASK _U_(0x3FFF) /**< \deprecated (PAC_SECLOCKC) Register MASK (Use PAC_SECLOCKC_Msk instead) */
#define PAC_SECLOCKC_Msk _U_(0x3FFF) /**< (PAC_SECLOCKC) Register Mask */
#define PAC_SECLOCKC_SERCOM_Pos 1 /**< (PAC_SECLOCKC Position) SERCOMx Secure Status Locked */
#define PAC_SECLOCKC_SERCOM_Msk (_U_(0x7) << PAC_SECLOCKC_SERCOM_Pos) /**< (PAC_SECLOCKC Mask) SERCOM */
#define PAC_SECLOCKC_SERCOM(value) (PAC_SECLOCKC_SERCOM_Msk & ((value) << PAC_SECLOCKC_SERCOM_Pos))
#define PAC_SECLOCKC_TC_Pos 4 /**< (PAC_SECLOCKC Position) TCx Secure Status Locked */
#define PAC_SECLOCKC_TC_Msk (_U_(0x7) << PAC_SECLOCKC_TC_Pos) /**< (PAC_SECLOCKC Mask) TC */
#define PAC_SECLOCKC_TC(value) (PAC_SECLOCKC_TC_Msk & ((value) << PAC_SECLOCKC_TC_Pos))
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
/** \brief PAC hardware registers */
typedef struct { /* Peripheral Access Controller */
__IO PAC_WRCTRL_Type WRCTRL; /**< Offset: 0x00 (R/W 32) Write control */
__IO PAC_EVCTRL_Type EVCTRL; /**< Offset: 0x04 (R/W 8) Event control */
__I uint8_t Reserved1[3];
__IO PAC_INTENCLR_Type INTENCLR; /**< Offset: 0x08 (R/W 8) Interrupt enable clear */
__IO PAC_INTENSET_Type INTENSET; /**< Offset: 0x09 (R/W 8) Interrupt enable set */
__I uint8_t Reserved2[6];
__IO PAC_INTFLAGAHB_Type INTFLAGAHB; /**< Offset: 0x10 (R/W 32) Bridge interrupt flag status */
__IO PAC_INTFLAGA_Type INTFLAGA; /**< Offset: 0x14 (R/W 32) Peripheral interrupt flag status - Bridge A */
__IO PAC_INTFLAGB_Type INTFLAGB; /**< Offset: 0x18 (R/W 32) Peripheral interrupt flag status - Bridge B */
__IO PAC_INTFLAGC_Type INTFLAGC; /**< Offset: 0x1C (R/W 32) Peripheral interrupt flag status - Bridge C */
__I uint8_t Reserved3[20];
__I PAC_STATUSA_Type STATUSA; /**< Offset: 0x34 (R/ 32) Peripheral write protection status - Bridge A */
__I PAC_STATUSB_Type STATUSB; /**< Offset: 0x38 (R/ 32) Peripheral write protection status - Bridge B */
__I PAC_STATUSC_Type STATUSC; /**< Offset: 0x3C (R/ 32) Peripheral write protection status - Bridge C */
__I uint8_t Reserved4[20];
__I PAC_NONSECA_Type NONSECA; /**< Offset: 0x54 (R/ 32) Peripheral non-secure status - Bridge A */
__I PAC_NONSECB_Type NONSECB; /**< Offset: 0x58 (R/ 32) Peripheral non-secure status - Bridge B */
__I PAC_NONSECC_Type NONSECC; /**< Offset: 0x5C (R/ 32) Peripheral non-secure status - Bridge C */
__I uint8_t Reserved5[20];
__I PAC_SECLOCKA_Type SECLOCKA; /**< Offset: 0x74 (R/ 32) Peripheral secure status locked - Bridge A */
__I PAC_SECLOCKB_Type SECLOCKB; /**< Offset: 0x78 (R/ 32) Peripheral secure status locked - Bridge B */
__I PAC_SECLOCKC_Type SECLOCKC; /**< Offset: 0x7C (R/ 32) Peripheral secure status locked - Bridge C */
} Pac;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/** @} end of Peripheral Access Controller */
#endif /* _SAML10_PAC_COMPONENT_H_ */

View File

@ -0,0 +1,266 @@
/**
* \file
*
* \brief Component description for PM
*
* Copyright (c) 2018 Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* 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
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
/* file generated from device description version 2018-08-31T13:51:50Z */
#ifndef _SAML10_PM_COMPONENT_H_
#define _SAML10_PM_COMPONENT_H_
#define _SAML10_PM_COMPONENT_ /**< \deprecated Backward compatibility for ASF */
/** \addtogroup SAML_SAML10 Power Manager
* @{
*/
/* ========================================================================== */
/** SOFTWARE API DEFINITION FOR PM */
/* ========================================================================== */
#define PM_U2240 /**< (PM) Module ID */
#define REV_PM 0x310 /**< (PM) Module revision */
/* -------- PM_SLEEPCFG : (PM Offset: 0x01) (R/W 8) Sleep Configuration -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t SLEEPMODE:3; /**< bit: 0..2 Sleep Mode */
uint8_t :5; /**< bit: 3..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} PM_SLEEPCFG_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define PM_SLEEPCFG_OFFSET (0x01) /**< (PM_SLEEPCFG) Sleep Configuration Offset */
#define PM_SLEEPCFG_RESETVALUE _U_(0x02) /**< (PM_SLEEPCFG) Sleep Configuration Reset Value */
#define PM_SLEEPCFG_SLEEPMODE_Pos 0 /**< (PM_SLEEPCFG) Sleep Mode Position */
#define PM_SLEEPCFG_SLEEPMODE_Msk (_U_(0x7) << PM_SLEEPCFG_SLEEPMODE_Pos) /**< (PM_SLEEPCFG) Sleep Mode Mask */
#define PM_SLEEPCFG_SLEEPMODE(value) (PM_SLEEPCFG_SLEEPMODE_Msk & ((value) << PM_SLEEPCFG_SLEEPMODE_Pos))
#define PM_SLEEPCFG_SLEEPMODE_IDLE_Val _U_(0x2) /**< (PM_SLEEPCFG) CPU, AHB, APB clocks are OFF */
#define PM_SLEEPCFG_SLEEPMODE_STANDBY_Val _U_(0x4) /**< (PM_SLEEPCFG) All Clocks are OFF */
#define PM_SLEEPCFG_SLEEPMODE_OFF_Val _U_(0x6) /**< (PM_SLEEPCFG) All power domains are powered OFF */
#define PM_SLEEPCFG_SLEEPMODE_IDLE (PM_SLEEPCFG_SLEEPMODE_IDLE_Val << PM_SLEEPCFG_SLEEPMODE_Pos) /**< (PM_SLEEPCFG) CPU, AHB, APB clocks are OFF Position */
#define PM_SLEEPCFG_SLEEPMODE_STANDBY (PM_SLEEPCFG_SLEEPMODE_STANDBY_Val << PM_SLEEPCFG_SLEEPMODE_Pos) /**< (PM_SLEEPCFG) All Clocks are OFF Position */
#define PM_SLEEPCFG_SLEEPMODE_OFF (PM_SLEEPCFG_SLEEPMODE_OFF_Val << PM_SLEEPCFG_SLEEPMODE_Pos) /**< (PM_SLEEPCFG) All power domains are powered OFF Position */
#define PM_SLEEPCFG_MASK _U_(0x07) /**< \deprecated (PM_SLEEPCFG) Register MASK (Use PM_SLEEPCFG_Msk instead) */
#define PM_SLEEPCFG_Msk _U_(0x07) /**< (PM_SLEEPCFG) Register Mask */
/* -------- PM_PLCFG : (PM Offset: 0x02) (R/W 8) Performance Level Configuration -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t PLSEL:2; /**< bit: 0..1 Performance Level Select */
uint8_t :5; /**< bit: 2..6 Reserved */
uint8_t PLDIS:1; /**< bit: 7 Performance Level Disable */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} PM_PLCFG_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define PM_PLCFG_OFFSET (0x02) /**< (PM_PLCFG) Performance Level Configuration Offset */
#define PM_PLCFG_RESETVALUE _U_(0x00) /**< (PM_PLCFG) Performance Level Configuration Reset Value */
#define PM_PLCFG_PLSEL_Pos 0 /**< (PM_PLCFG) Performance Level Select Position */
#define PM_PLCFG_PLSEL_Msk (_U_(0x3) << PM_PLCFG_PLSEL_Pos) /**< (PM_PLCFG) Performance Level Select Mask */
#define PM_PLCFG_PLSEL(value) (PM_PLCFG_PLSEL_Msk & ((value) << PM_PLCFG_PLSEL_Pos))
#define PM_PLCFG_PLSEL_PL0_Val _U_(0x0) /**< (PM_PLCFG) Performance Level 0 */
#define PM_PLCFG_PLSEL_PL2_Val _U_(0x2) /**< (PM_PLCFG) Performance Level 2 */
#define PM_PLCFG_PLSEL_PL0 (PM_PLCFG_PLSEL_PL0_Val << PM_PLCFG_PLSEL_Pos) /**< (PM_PLCFG) Performance Level 0 Position */
#define PM_PLCFG_PLSEL_PL2 (PM_PLCFG_PLSEL_PL2_Val << PM_PLCFG_PLSEL_Pos) /**< (PM_PLCFG) Performance Level 2 Position */
#define PM_PLCFG_PLDIS_Pos 7 /**< (PM_PLCFG) Performance Level Disable Position */
#define PM_PLCFG_PLDIS_Msk (_U_(0x1) << PM_PLCFG_PLDIS_Pos) /**< (PM_PLCFG) Performance Level Disable Mask */
#define PM_PLCFG_PLDIS PM_PLCFG_PLDIS_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PM_PLCFG_PLDIS_Msk instead */
#define PM_PLCFG_MASK _U_(0x83) /**< \deprecated (PM_PLCFG) Register MASK (Use PM_PLCFG_Msk instead) */
#define PM_PLCFG_Msk _U_(0x83) /**< (PM_PLCFG) Register Mask */
/* -------- PM_PWCFG : (PM Offset: 0x03) (R/W 8) Power Configuration -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t RAMPSWC:2; /**< bit: 0..1 RAM Power Switch Configuration */
uint8_t :6; /**< bit: 2..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} PM_PWCFG_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define PM_PWCFG_OFFSET (0x03) /**< (PM_PWCFG) Power Configuration Offset */
#define PM_PWCFG_RESETVALUE _U_(0x00) /**< (PM_PWCFG) Power Configuration Reset Value */
#define PM_PWCFG_RAMPSWC_Pos 0 /**< (PM_PWCFG) RAM Power Switch Configuration Position */
#define PM_PWCFG_RAMPSWC_Msk (_U_(0x3) << PM_PWCFG_RAMPSWC_Pos) /**< (PM_PWCFG) RAM Power Switch Configuration Mask */
#define PM_PWCFG_RAMPSWC(value) (PM_PWCFG_RAMPSWC_Msk & ((value) << PM_PWCFG_RAMPSWC_Pos))
#define PM_PWCFG_RAMPSWC_16KB_Val _U_(0x0) /**< (PM_PWCFG) 16KB Available */
#define PM_PWCFG_RAMPSWC_12KB_Val _U_(0x1) /**< (PM_PWCFG) 12KB Available */
#define PM_PWCFG_RAMPSWC_8KB_Val _U_(0x2) /**< (PM_PWCFG) 8KB Available */
#define PM_PWCFG_RAMPSWC_4KB_Val _U_(0x3) /**< (PM_PWCFG) 4KB Available */
#define PM_PWCFG_RAMPSWC_16KB (PM_PWCFG_RAMPSWC_16KB_Val << PM_PWCFG_RAMPSWC_Pos) /**< (PM_PWCFG) 16KB Available Position */
#define PM_PWCFG_RAMPSWC_12KB (PM_PWCFG_RAMPSWC_12KB_Val << PM_PWCFG_RAMPSWC_Pos) /**< (PM_PWCFG) 12KB Available Position */
#define PM_PWCFG_RAMPSWC_8KB (PM_PWCFG_RAMPSWC_8KB_Val << PM_PWCFG_RAMPSWC_Pos) /**< (PM_PWCFG) 8KB Available Position */
#define PM_PWCFG_RAMPSWC_4KB (PM_PWCFG_RAMPSWC_4KB_Val << PM_PWCFG_RAMPSWC_Pos) /**< (PM_PWCFG) 4KB Available Position */
#define PM_PWCFG_MASK _U_(0x03) /**< \deprecated (PM_PWCFG) Register MASK (Use PM_PWCFG_Msk instead) */
#define PM_PWCFG_Msk _U_(0x03) /**< (PM_PWCFG) Register Mask */
/* -------- PM_INTENCLR : (PM Offset: 0x04) (R/W 8) Interrupt Enable Clear -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t PLRDY:1; /**< bit: 0 Performance Level Interrupt Enable */
uint8_t :7; /**< bit: 1..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} PM_INTENCLR_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define PM_INTENCLR_OFFSET (0x04) /**< (PM_INTENCLR) Interrupt Enable Clear Offset */
#define PM_INTENCLR_RESETVALUE _U_(0x00) /**< (PM_INTENCLR) Interrupt Enable Clear Reset Value */
#define PM_INTENCLR_PLRDY_Pos 0 /**< (PM_INTENCLR) Performance Level Interrupt Enable Position */
#define PM_INTENCLR_PLRDY_Msk (_U_(0x1) << PM_INTENCLR_PLRDY_Pos) /**< (PM_INTENCLR) Performance Level Interrupt Enable Mask */
#define PM_INTENCLR_PLRDY PM_INTENCLR_PLRDY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PM_INTENCLR_PLRDY_Msk instead */
#define PM_INTENCLR_MASK _U_(0x01) /**< \deprecated (PM_INTENCLR) Register MASK (Use PM_INTENCLR_Msk instead) */
#define PM_INTENCLR_Msk _U_(0x01) /**< (PM_INTENCLR) Register Mask */
/* -------- PM_INTENSET : (PM Offset: 0x05) (R/W 8) Interrupt Enable Set -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t PLRDY:1; /**< bit: 0 Performance Level Ready interrupt Enable */
uint8_t :7; /**< bit: 1..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} PM_INTENSET_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define PM_INTENSET_OFFSET (0x05) /**< (PM_INTENSET) Interrupt Enable Set Offset */
#define PM_INTENSET_RESETVALUE _U_(0x00) /**< (PM_INTENSET) Interrupt Enable Set Reset Value */
#define PM_INTENSET_PLRDY_Pos 0 /**< (PM_INTENSET) Performance Level Ready interrupt Enable Position */
#define PM_INTENSET_PLRDY_Msk (_U_(0x1) << PM_INTENSET_PLRDY_Pos) /**< (PM_INTENSET) Performance Level Ready interrupt Enable Mask */
#define PM_INTENSET_PLRDY PM_INTENSET_PLRDY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PM_INTENSET_PLRDY_Msk instead */
#define PM_INTENSET_MASK _U_(0x01) /**< \deprecated (PM_INTENSET) Register MASK (Use PM_INTENSET_Msk instead) */
#define PM_INTENSET_Msk _U_(0x01) /**< (PM_INTENSET) Register Mask */
/* -------- PM_INTFLAG : (PM Offset: 0x06) (R/W 8) Interrupt Flag Status and Clear -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union { // __I to avoid read-modify-write on write-to-clear register
struct {
__I uint8_t PLRDY:1; /**< bit: 0 Performance Level Ready */
__I uint8_t :7; /**< bit: 1..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} PM_INTFLAG_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define PM_INTFLAG_OFFSET (0x06) /**< (PM_INTFLAG) Interrupt Flag Status and Clear Offset */
#define PM_INTFLAG_RESETVALUE _U_(0x00) /**< (PM_INTFLAG) Interrupt Flag Status and Clear Reset Value */
#define PM_INTFLAG_PLRDY_Pos 0 /**< (PM_INTFLAG) Performance Level Ready Position */
#define PM_INTFLAG_PLRDY_Msk (_U_(0x1) << PM_INTFLAG_PLRDY_Pos) /**< (PM_INTFLAG) Performance Level Ready Mask */
#define PM_INTFLAG_PLRDY PM_INTFLAG_PLRDY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PM_INTFLAG_PLRDY_Msk instead */
#define PM_INTFLAG_MASK _U_(0x01) /**< \deprecated (PM_INTFLAG) Register MASK (Use PM_INTFLAG_Msk instead) */
#define PM_INTFLAG_Msk _U_(0x01) /**< (PM_INTFLAG) Register Mask */
/* -------- PM_STDBYCFG : (PM Offset: 0x08) (R/W 16) Standby Configuration -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint16_t PDCFG:1; /**< bit: 0 Power Domain Configuration */
uint16_t :3; /**< bit: 1..3 Reserved */
uint16_t DPGPDSW:1; /**< bit: 4 Dynamic Power Gating for PDSW */
uint16_t :1; /**< bit: 5 Reserved */
uint16_t VREGSMOD:2; /**< bit: 6..7 Voltage Regulator Standby mode */
uint16_t :2; /**< bit: 8..9 Reserved */
uint16_t BBIASHS:1; /**< bit: 10 Back Bias for HSRAM */
uint16_t :1; /**< bit: 11 Reserved */
uint16_t BBIASTR:1; /**< bit: 12 Back Bias for Trust RAM */
uint16_t :3; /**< bit: 13..15 Reserved */
} bit; /**< Structure used for bit access */
uint16_t reg; /**< Type used for register access */
} PM_STDBYCFG_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define PM_STDBYCFG_OFFSET (0x08) /**< (PM_STDBYCFG) Standby Configuration Offset */
#define PM_STDBYCFG_RESETVALUE _U_(0x00) /**< (PM_STDBYCFG) Standby Configuration Reset Value */
#define PM_STDBYCFG_PDCFG_Pos 0 /**< (PM_STDBYCFG) Power Domain Configuration Position */
#define PM_STDBYCFG_PDCFG_Msk (_U_(0x1) << PM_STDBYCFG_PDCFG_Pos) /**< (PM_STDBYCFG) Power Domain Configuration Mask */
#define PM_STDBYCFG_PDCFG PM_STDBYCFG_PDCFG_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PM_STDBYCFG_PDCFG_Msk instead */
#define PM_STDBYCFG_PDCFG_DEFAULT_Val _U_(0x0) /**< (PM_STDBYCFG) PDSW power domain switching is handled by hardware. */
#define PM_STDBYCFG_PDCFG_PDSW_Val _U_(0x1) /**< (PM_STDBYCFG) PDSW is forced ACTIVE. */
#define PM_STDBYCFG_PDCFG_DEFAULT (PM_STDBYCFG_PDCFG_DEFAULT_Val << PM_STDBYCFG_PDCFG_Pos) /**< (PM_STDBYCFG) PDSW power domain switching is handled by hardware. Position */
#define PM_STDBYCFG_PDCFG_PDSW (PM_STDBYCFG_PDCFG_PDSW_Val << PM_STDBYCFG_PDCFG_Pos) /**< (PM_STDBYCFG) PDSW is forced ACTIVE. Position */
#define PM_STDBYCFG_DPGPDSW_Pos 4 /**< (PM_STDBYCFG) Dynamic Power Gating for PDSW Position */
#define PM_STDBYCFG_DPGPDSW_Msk (_U_(0x1) << PM_STDBYCFG_DPGPDSW_Pos) /**< (PM_STDBYCFG) Dynamic Power Gating for PDSW Mask */
#define PM_STDBYCFG_DPGPDSW PM_STDBYCFG_DPGPDSW_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PM_STDBYCFG_DPGPDSW_Msk instead */
#define PM_STDBYCFG_DPGPDSW_0_Val _U_(0x0) /**< (PM_STDBYCFG) Dynamic Power Gating disabled */
#define PM_STDBYCFG_DPGPDSW_1_Val _U_(0x1) /**< (PM_STDBYCFG) Dynamic Power Gating enabled */
#define PM_STDBYCFG_DPGPDSW_0 (PM_STDBYCFG_DPGPDSW_0_Val << PM_STDBYCFG_DPGPDSW_Pos) /**< (PM_STDBYCFG) Dynamic Power Gating disabled Position */
#define PM_STDBYCFG_DPGPDSW_1 (PM_STDBYCFG_DPGPDSW_1_Val << PM_STDBYCFG_DPGPDSW_Pos) /**< (PM_STDBYCFG) Dynamic Power Gating enabled Position */
#define PM_STDBYCFG_VREGSMOD_Pos 6 /**< (PM_STDBYCFG) Voltage Regulator Standby mode Position */
#define PM_STDBYCFG_VREGSMOD_Msk (_U_(0x3) << PM_STDBYCFG_VREGSMOD_Pos) /**< (PM_STDBYCFG) Voltage Regulator Standby mode Mask */
#define PM_STDBYCFG_VREGSMOD(value) (PM_STDBYCFG_VREGSMOD_Msk & ((value) << PM_STDBYCFG_VREGSMOD_Pos))
#define PM_STDBYCFG_VREGSMOD_AUTO_Val _U_(0x0) /**< (PM_STDBYCFG) Automatic mode */
#define PM_STDBYCFG_VREGSMOD_PERFORMANCE_Val _U_(0x1) /**< (PM_STDBYCFG) Performance oriented */
#define PM_STDBYCFG_VREGSMOD_LP_Val _U_(0x2) /**< (PM_STDBYCFG) Low Power oriented */
#define PM_STDBYCFG_VREGSMOD_AUTO (PM_STDBYCFG_VREGSMOD_AUTO_Val << PM_STDBYCFG_VREGSMOD_Pos) /**< (PM_STDBYCFG) Automatic mode Position */
#define PM_STDBYCFG_VREGSMOD_PERFORMANCE (PM_STDBYCFG_VREGSMOD_PERFORMANCE_Val << PM_STDBYCFG_VREGSMOD_Pos) /**< (PM_STDBYCFG) Performance oriented Position */
#define PM_STDBYCFG_VREGSMOD_LP (PM_STDBYCFG_VREGSMOD_LP_Val << PM_STDBYCFG_VREGSMOD_Pos) /**< (PM_STDBYCFG) Low Power oriented Position */
#define PM_STDBYCFG_BBIASHS_Pos 10 /**< (PM_STDBYCFG) Back Bias for HSRAM Position */
#define PM_STDBYCFG_BBIASHS_Msk (_U_(0x1) << PM_STDBYCFG_BBIASHS_Pos) /**< (PM_STDBYCFG) Back Bias for HSRAM Mask */
#define PM_STDBYCFG_BBIASHS PM_STDBYCFG_BBIASHS_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PM_STDBYCFG_BBIASHS_Msk instead */
#define PM_STDBYCFG_BBIASTR_Pos 12 /**< (PM_STDBYCFG) Back Bias for Trust RAM Position */
#define PM_STDBYCFG_BBIASTR_Msk (_U_(0x1) << PM_STDBYCFG_BBIASTR_Pos) /**< (PM_STDBYCFG) Back Bias for Trust RAM Mask */
#define PM_STDBYCFG_BBIASTR PM_STDBYCFG_BBIASTR_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PM_STDBYCFG_BBIASTR_Msk instead */
#define PM_STDBYCFG_MASK _U_(0x14D1) /**< \deprecated (PM_STDBYCFG) Register MASK (Use PM_STDBYCFG_Msk instead) */
#define PM_STDBYCFG_Msk _U_(0x14D1) /**< (PM_STDBYCFG) Register Mask */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
/** \brief PM hardware registers */
typedef struct { /* Power Manager */
__I uint8_t Reserved1[1];
__IO PM_SLEEPCFG_Type SLEEPCFG; /**< Offset: 0x01 (R/W 8) Sleep Configuration */
__IO PM_PLCFG_Type PLCFG; /**< Offset: 0x02 (R/W 8) Performance Level Configuration */
__IO PM_PWCFG_Type PWCFG; /**< Offset: 0x03 (R/W 8) Power Configuration */
__IO PM_INTENCLR_Type INTENCLR; /**< Offset: 0x04 (R/W 8) Interrupt Enable Clear */
__IO PM_INTENSET_Type INTENSET; /**< Offset: 0x05 (R/W 8) Interrupt Enable Set */
__IO PM_INTFLAG_Type INTFLAG; /**< Offset: 0x06 (R/W 8) Interrupt Flag Status and Clear */
__I uint8_t Reserved2[1];
__IO PM_STDBYCFG_Type STDBYCFG; /**< Offset: 0x08 (R/W 16) Standby Configuration */
} Pm;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/** @} end of Power Manager */
#endif /* _SAML10_PM_COMPONENT_H_ */

View File

@ -0,0 +1,566 @@
/**
* \file
*
* \brief Component description for PORT
*
* Copyright (c) 2018 Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* 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
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
/* file generated from device description version 2018-08-31T13:51:50Z */
#ifndef _SAML10_PORT_COMPONENT_H_
#define _SAML10_PORT_COMPONENT_H_
#define _SAML10_PORT_COMPONENT_ /**< \deprecated Backward compatibility for ASF */
/** \addtogroup SAML_SAML10 Port Module
* @{
*/
/* ========================================================================== */
/** SOFTWARE API DEFINITION FOR PORT */
/* ========================================================================== */
#define PORT_U2210 /**< (PORT) Module ID */
#define REV_PORT 0x300 /**< (PORT) Module revision */
/* -------- PORT_DIR : (PORT Offset: 0x00) (R/W 32) Data Direction -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t DIR:32; /**< bit: 0..31 Port Data Direction */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} PORT_DIR_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define PORT_DIR_OFFSET (0x00) /**< (PORT_DIR) Data Direction Offset */
#define PORT_DIR_RESETVALUE _U_(0x00) /**< (PORT_DIR) Data Direction Reset Value */
#define PORT_DIR_DIR_Pos 0 /**< (PORT_DIR) Port Data Direction Position */
#define PORT_DIR_DIR_Msk (_U_(0xFFFFFFFF) << PORT_DIR_DIR_Pos) /**< (PORT_DIR) Port Data Direction Mask */
#define PORT_DIR_DIR(value) (PORT_DIR_DIR_Msk & ((value) << PORT_DIR_DIR_Pos))
#define PORT_DIR_MASK _U_(0xFFFFFFFF) /**< \deprecated (PORT_DIR) Register MASK (Use PORT_DIR_Msk instead) */
#define PORT_DIR_Msk _U_(0xFFFFFFFF) /**< (PORT_DIR) Register Mask */
/* -------- PORT_DIRCLR : (PORT Offset: 0x04) (R/W 32) Data Direction Clear -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t DIRCLR:32; /**< bit: 0..31 Port Data Direction Clear */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} PORT_DIRCLR_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define PORT_DIRCLR_OFFSET (0x04) /**< (PORT_DIRCLR) Data Direction Clear Offset */
#define PORT_DIRCLR_RESETVALUE _U_(0x00) /**< (PORT_DIRCLR) Data Direction Clear Reset Value */
#define PORT_DIRCLR_DIRCLR_Pos 0 /**< (PORT_DIRCLR) Port Data Direction Clear Position */
#define PORT_DIRCLR_DIRCLR_Msk (_U_(0xFFFFFFFF) << PORT_DIRCLR_DIRCLR_Pos) /**< (PORT_DIRCLR) Port Data Direction Clear Mask */
#define PORT_DIRCLR_DIRCLR(value) (PORT_DIRCLR_DIRCLR_Msk & ((value) << PORT_DIRCLR_DIRCLR_Pos))
#define PORT_DIRCLR_MASK _U_(0xFFFFFFFF) /**< \deprecated (PORT_DIRCLR) Register MASK (Use PORT_DIRCLR_Msk instead) */
#define PORT_DIRCLR_Msk _U_(0xFFFFFFFF) /**< (PORT_DIRCLR) Register Mask */
/* -------- PORT_DIRSET : (PORT Offset: 0x08) (R/W 32) Data Direction Set -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t DIRSET:32; /**< bit: 0..31 Port Data Direction Set */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} PORT_DIRSET_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define PORT_DIRSET_OFFSET (0x08) /**< (PORT_DIRSET) Data Direction Set Offset */
#define PORT_DIRSET_RESETVALUE _U_(0x00) /**< (PORT_DIRSET) Data Direction Set Reset Value */
#define PORT_DIRSET_DIRSET_Pos 0 /**< (PORT_DIRSET) Port Data Direction Set Position */
#define PORT_DIRSET_DIRSET_Msk (_U_(0xFFFFFFFF) << PORT_DIRSET_DIRSET_Pos) /**< (PORT_DIRSET) Port Data Direction Set Mask */
#define PORT_DIRSET_DIRSET(value) (PORT_DIRSET_DIRSET_Msk & ((value) << PORT_DIRSET_DIRSET_Pos))
#define PORT_DIRSET_MASK _U_(0xFFFFFFFF) /**< \deprecated (PORT_DIRSET) Register MASK (Use PORT_DIRSET_Msk instead) */
#define PORT_DIRSET_Msk _U_(0xFFFFFFFF) /**< (PORT_DIRSET) Register Mask */
/* -------- PORT_DIRTGL : (PORT Offset: 0x0c) (R/W 32) Data Direction Toggle -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t DIRTGL:32; /**< bit: 0..31 Port Data Direction Toggle */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} PORT_DIRTGL_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define PORT_DIRTGL_OFFSET (0x0C) /**< (PORT_DIRTGL) Data Direction Toggle Offset */
#define PORT_DIRTGL_RESETVALUE _U_(0x00) /**< (PORT_DIRTGL) Data Direction Toggle Reset Value */
#define PORT_DIRTGL_DIRTGL_Pos 0 /**< (PORT_DIRTGL) Port Data Direction Toggle Position */
#define PORT_DIRTGL_DIRTGL_Msk (_U_(0xFFFFFFFF) << PORT_DIRTGL_DIRTGL_Pos) /**< (PORT_DIRTGL) Port Data Direction Toggle Mask */
#define PORT_DIRTGL_DIRTGL(value) (PORT_DIRTGL_DIRTGL_Msk & ((value) << PORT_DIRTGL_DIRTGL_Pos))
#define PORT_DIRTGL_MASK _U_(0xFFFFFFFF) /**< \deprecated (PORT_DIRTGL) Register MASK (Use PORT_DIRTGL_Msk instead) */
#define PORT_DIRTGL_Msk _U_(0xFFFFFFFF) /**< (PORT_DIRTGL) Register Mask */
/* -------- PORT_OUT : (PORT Offset: 0x10) (R/W 32) Data Output Value -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t OUT:32; /**< bit: 0..31 PORT Data Output Value */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} PORT_OUT_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define PORT_OUT_OFFSET (0x10) /**< (PORT_OUT) Data Output Value Offset */
#define PORT_OUT_RESETVALUE _U_(0x00) /**< (PORT_OUT) Data Output Value Reset Value */
#define PORT_OUT_OUT_Pos 0 /**< (PORT_OUT) PORT Data Output Value Position */
#define PORT_OUT_OUT_Msk (_U_(0xFFFFFFFF) << PORT_OUT_OUT_Pos) /**< (PORT_OUT) PORT Data Output Value Mask */
#define PORT_OUT_OUT(value) (PORT_OUT_OUT_Msk & ((value) << PORT_OUT_OUT_Pos))
#define PORT_OUT_MASK _U_(0xFFFFFFFF) /**< \deprecated (PORT_OUT) Register MASK (Use PORT_OUT_Msk instead) */
#define PORT_OUT_Msk _U_(0xFFFFFFFF) /**< (PORT_OUT) Register Mask */
/* -------- PORT_OUTCLR : (PORT Offset: 0x14) (R/W 32) Data Output Value Clear -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t OUTCLR:32; /**< bit: 0..31 PORT Data Output Value Clear */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} PORT_OUTCLR_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define PORT_OUTCLR_OFFSET (0x14) /**< (PORT_OUTCLR) Data Output Value Clear Offset */
#define PORT_OUTCLR_RESETVALUE _U_(0x00) /**< (PORT_OUTCLR) Data Output Value Clear Reset Value */
#define PORT_OUTCLR_OUTCLR_Pos 0 /**< (PORT_OUTCLR) PORT Data Output Value Clear Position */
#define PORT_OUTCLR_OUTCLR_Msk (_U_(0xFFFFFFFF) << PORT_OUTCLR_OUTCLR_Pos) /**< (PORT_OUTCLR) PORT Data Output Value Clear Mask */
#define PORT_OUTCLR_OUTCLR(value) (PORT_OUTCLR_OUTCLR_Msk & ((value) << PORT_OUTCLR_OUTCLR_Pos))
#define PORT_OUTCLR_MASK _U_(0xFFFFFFFF) /**< \deprecated (PORT_OUTCLR) Register MASK (Use PORT_OUTCLR_Msk instead) */
#define PORT_OUTCLR_Msk _U_(0xFFFFFFFF) /**< (PORT_OUTCLR) Register Mask */
/* -------- PORT_OUTSET : (PORT Offset: 0x18) (R/W 32) Data Output Value Set -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t OUTSET:32; /**< bit: 0..31 PORT Data Output Value Set */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} PORT_OUTSET_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define PORT_OUTSET_OFFSET (0x18) /**< (PORT_OUTSET) Data Output Value Set Offset */
#define PORT_OUTSET_RESETVALUE _U_(0x00) /**< (PORT_OUTSET) Data Output Value Set Reset Value */
#define PORT_OUTSET_OUTSET_Pos 0 /**< (PORT_OUTSET) PORT Data Output Value Set Position */
#define PORT_OUTSET_OUTSET_Msk (_U_(0xFFFFFFFF) << PORT_OUTSET_OUTSET_Pos) /**< (PORT_OUTSET) PORT Data Output Value Set Mask */
#define PORT_OUTSET_OUTSET(value) (PORT_OUTSET_OUTSET_Msk & ((value) << PORT_OUTSET_OUTSET_Pos))
#define PORT_OUTSET_MASK _U_(0xFFFFFFFF) /**< \deprecated (PORT_OUTSET) Register MASK (Use PORT_OUTSET_Msk instead) */
#define PORT_OUTSET_Msk _U_(0xFFFFFFFF) /**< (PORT_OUTSET) Register Mask */
/* -------- PORT_OUTTGL : (PORT Offset: 0x1c) (R/W 32) Data Output Value Toggle -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t OUTTGL:32; /**< bit: 0..31 PORT Data Output Value Toggle */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} PORT_OUTTGL_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define PORT_OUTTGL_OFFSET (0x1C) /**< (PORT_OUTTGL) Data Output Value Toggle Offset */
#define PORT_OUTTGL_RESETVALUE _U_(0x00) /**< (PORT_OUTTGL) Data Output Value Toggle Reset Value */
#define PORT_OUTTGL_OUTTGL_Pos 0 /**< (PORT_OUTTGL) PORT Data Output Value Toggle Position */
#define PORT_OUTTGL_OUTTGL_Msk (_U_(0xFFFFFFFF) << PORT_OUTTGL_OUTTGL_Pos) /**< (PORT_OUTTGL) PORT Data Output Value Toggle Mask */
#define PORT_OUTTGL_OUTTGL(value) (PORT_OUTTGL_OUTTGL_Msk & ((value) << PORT_OUTTGL_OUTTGL_Pos))
#define PORT_OUTTGL_MASK _U_(0xFFFFFFFF) /**< \deprecated (PORT_OUTTGL) Register MASK (Use PORT_OUTTGL_Msk instead) */
#define PORT_OUTTGL_Msk _U_(0xFFFFFFFF) /**< (PORT_OUTTGL) Register Mask */
/* -------- PORT_IN : (PORT Offset: 0x20) (R/ 32) Data Input Value -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t IN:32; /**< bit: 0..31 PORT Data Input Value */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} PORT_IN_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define PORT_IN_OFFSET (0x20) /**< (PORT_IN) Data Input Value Offset */
#define PORT_IN_RESETVALUE _U_(0x00) /**< (PORT_IN) Data Input Value Reset Value */
#define PORT_IN_IN_Pos 0 /**< (PORT_IN) PORT Data Input Value Position */
#define PORT_IN_IN_Msk (_U_(0xFFFFFFFF) << PORT_IN_IN_Pos) /**< (PORT_IN) PORT Data Input Value Mask */
#define PORT_IN_IN(value) (PORT_IN_IN_Msk & ((value) << PORT_IN_IN_Pos))
#define PORT_IN_MASK _U_(0xFFFFFFFF) /**< \deprecated (PORT_IN) Register MASK (Use PORT_IN_Msk instead) */
#define PORT_IN_Msk _U_(0xFFFFFFFF) /**< (PORT_IN) Register Mask */
/* -------- PORT_CTRL : (PORT Offset: 0x24) (R/W 32) Control -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t SAMPLING:32; /**< bit: 0..31 Input Sampling Mode */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} PORT_CTRL_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define PORT_CTRL_OFFSET (0x24) /**< (PORT_CTRL) Control Offset */
#define PORT_CTRL_RESETVALUE _U_(0x00) /**< (PORT_CTRL) Control Reset Value */
#define PORT_CTRL_SAMPLING_Pos 0 /**< (PORT_CTRL) Input Sampling Mode Position */
#define PORT_CTRL_SAMPLING_Msk (_U_(0xFFFFFFFF) << PORT_CTRL_SAMPLING_Pos) /**< (PORT_CTRL) Input Sampling Mode Mask */
#define PORT_CTRL_SAMPLING(value) (PORT_CTRL_SAMPLING_Msk & ((value) << PORT_CTRL_SAMPLING_Pos))
#define PORT_CTRL_MASK _U_(0xFFFFFFFF) /**< \deprecated (PORT_CTRL) Register MASK (Use PORT_CTRL_Msk instead) */
#define PORT_CTRL_Msk _U_(0xFFFFFFFF) /**< (PORT_CTRL) Register Mask */
/* -------- PORT_WRCONFIG : (PORT Offset: 0x28) (/W 32) Write Configuration -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t PINMASK:16; /**< bit: 0..15 Pin Mask for Multiple Pin Configuration */
uint32_t PMUXEN:1; /**< bit: 16 Peripheral Multiplexer Enable */
uint32_t INEN:1; /**< bit: 17 Input Enable */
uint32_t PULLEN:1; /**< bit: 18 Pull Enable */
uint32_t :3; /**< bit: 19..21 Reserved */
uint32_t DRVSTR:1; /**< bit: 22 Output Driver Strength Selection */
uint32_t :1; /**< bit: 23 Reserved */
uint32_t PMUX:4; /**< bit: 24..27 Peripheral Multiplexing */
uint32_t WRPMUX:1; /**< bit: 28 Write PMUX */
uint32_t :1; /**< bit: 29 Reserved */
uint32_t WRPINCFG:1; /**< bit: 30 Write PINCFG */
uint32_t HWSEL:1; /**< bit: 31 Half-Word Select */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} PORT_WRCONFIG_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define PORT_WRCONFIG_OFFSET (0x28) /**< (PORT_WRCONFIG) Write Configuration Offset */
#define PORT_WRCONFIG_RESETVALUE _U_(0x00) /**< (PORT_WRCONFIG) Write Configuration Reset Value */
#define PORT_WRCONFIG_PINMASK_Pos 0 /**< (PORT_WRCONFIG) Pin Mask for Multiple Pin Configuration Position */
#define PORT_WRCONFIG_PINMASK_Msk (_U_(0xFFFF) << PORT_WRCONFIG_PINMASK_Pos) /**< (PORT_WRCONFIG) Pin Mask for Multiple Pin Configuration Mask */
#define PORT_WRCONFIG_PINMASK(value) (PORT_WRCONFIG_PINMASK_Msk & ((value) << PORT_WRCONFIG_PINMASK_Pos))
#define PORT_WRCONFIG_PMUXEN_Pos 16 /**< (PORT_WRCONFIG) Peripheral Multiplexer Enable Position */
#define PORT_WRCONFIG_PMUXEN_Msk (_U_(0x1) << PORT_WRCONFIG_PMUXEN_Pos) /**< (PORT_WRCONFIG) Peripheral Multiplexer Enable Mask */
#define PORT_WRCONFIG_PMUXEN PORT_WRCONFIG_PMUXEN_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PORT_WRCONFIG_PMUXEN_Msk instead */
#define PORT_WRCONFIG_INEN_Pos 17 /**< (PORT_WRCONFIG) Input Enable Position */
#define PORT_WRCONFIG_INEN_Msk (_U_(0x1) << PORT_WRCONFIG_INEN_Pos) /**< (PORT_WRCONFIG) Input Enable Mask */
#define PORT_WRCONFIG_INEN PORT_WRCONFIG_INEN_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PORT_WRCONFIG_INEN_Msk instead */
#define PORT_WRCONFIG_PULLEN_Pos 18 /**< (PORT_WRCONFIG) Pull Enable Position */
#define PORT_WRCONFIG_PULLEN_Msk (_U_(0x1) << PORT_WRCONFIG_PULLEN_Pos) /**< (PORT_WRCONFIG) Pull Enable Mask */
#define PORT_WRCONFIG_PULLEN PORT_WRCONFIG_PULLEN_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PORT_WRCONFIG_PULLEN_Msk instead */
#define PORT_WRCONFIG_DRVSTR_Pos 22 /**< (PORT_WRCONFIG) Output Driver Strength Selection Position */
#define PORT_WRCONFIG_DRVSTR_Msk (_U_(0x1) << PORT_WRCONFIG_DRVSTR_Pos) /**< (PORT_WRCONFIG) Output Driver Strength Selection Mask */
#define PORT_WRCONFIG_DRVSTR PORT_WRCONFIG_DRVSTR_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PORT_WRCONFIG_DRVSTR_Msk instead */
#define PORT_WRCONFIG_PMUX_Pos 24 /**< (PORT_WRCONFIG) Peripheral Multiplexing Position */
#define PORT_WRCONFIG_PMUX_Msk (_U_(0xF) << PORT_WRCONFIG_PMUX_Pos) /**< (PORT_WRCONFIG) Peripheral Multiplexing Mask */
#define PORT_WRCONFIG_PMUX(value) (PORT_WRCONFIG_PMUX_Msk & ((value) << PORT_WRCONFIG_PMUX_Pos))
#define PORT_WRCONFIG_WRPMUX_Pos 28 /**< (PORT_WRCONFIG) Write PMUX Position */
#define PORT_WRCONFIG_WRPMUX_Msk (_U_(0x1) << PORT_WRCONFIG_WRPMUX_Pos) /**< (PORT_WRCONFIG) Write PMUX Mask */
#define PORT_WRCONFIG_WRPMUX PORT_WRCONFIG_WRPMUX_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PORT_WRCONFIG_WRPMUX_Msk instead */
#define PORT_WRCONFIG_WRPINCFG_Pos 30 /**< (PORT_WRCONFIG) Write PINCFG Position */
#define PORT_WRCONFIG_WRPINCFG_Msk (_U_(0x1) << PORT_WRCONFIG_WRPINCFG_Pos) /**< (PORT_WRCONFIG) Write PINCFG Mask */
#define PORT_WRCONFIG_WRPINCFG PORT_WRCONFIG_WRPINCFG_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PORT_WRCONFIG_WRPINCFG_Msk instead */
#define PORT_WRCONFIG_HWSEL_Pos 31 /**< (PORT_WRCONFIG) Half-Word Select Position */
#define PORT_WRCONFIG_HWSEL_Msk (_U_(0x1) << PORT_WRCONFIG_HWSEL_Pos) /**< (PORT_WRCONFIG) Half-Word Select Mask */
#define PORT_WRCONFIG_HWSEL PORT_WRCONFIG_HWSEL_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PORT_WRCONFIG_HWSEL_Msk instead */
#define PORT_WRCONFIG_Msk _U_(0xDF47FFFF) /**< (PORT_WRCONFIG) Register Mask */
/* -------- PORT_EVCTRL : (PORT Offset: 0x2c) (R/W 32) Event Input Control -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t PID0:5; /**< bit: 0..4 PORT Event Pin Identifier 0 */
uint32_t EVACT0:2; /**< bit: 5..6 PORT Event Action 0 */
uint32_t PORTEI0:1; /**< bit: 7 PORT Event Input Enable 0 */
uint32_t PID1:5; /**< bit: 8..12 PORT Event Pin Identifier 1 */
uint32_t EVACT1:2; /**< bit: 13..14 PORT Event Action 1 */
uint32_t PORTEI1:1; /**< bit: 15 PORT Event Input Enable 1 */
uint32_t PID2:5; /**< bit: 16..20 PORT Event Pin Identifier 2 */
uint32_t EVACT2:2; /**< bit: 21..22 PORT Event Action 2 */
uint32_t PORTEI2:1; /**< bit: 23 PORT Event Input Enable 2 */
uint32_t PID3:5; /**< bit: 24..28 PORT Event Pin Identifier 3 */
uint32_t EVACT3:2; /**< bit: 29..30 PORT Event Action 3 */
uint32_t PORTEI3:1; /**< bit: 31 PORT Event Input Enable 3 */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} PORT_EVCTRL_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define PORT_EVCTRL_OFFSET (0x2C) /**< (PORT_EVCTRL) Event Input Control Offset */
#define PORT_EVCTRL_RESETVALUE _U_(0x00) /**< (PORT_EVCTRL) Event Input Control Reset Value */
#define PORT_EVCTRL_PID0_Pos 0 /**< (PORT_EVCTRL) PORT Event Pin Identifier 0 Position */
#define PORT_EVCTRL_PID0_Msk (_U_(0x1F) << PORT_EVCTRL_PID0_Pos) /**< (PORT_EVCTRL) PORT Event Pin Identifier 0 Mask */
#define PORT_EVCTRL_PID0(value) (PORT_EVCTRL_PID0_Msk & ((value) << PORT_EVCTRL_PID0_Pos))
#define PORT_EVCTRL_EVACT0_Pos 5 /**< (PORT_EVCTRL) PORT Event Action 0 Position */
#define PORT_EVCTRL_EVACT0_Msk (_U_(0x3) << PORT_EVCTRL_EVACT0_Pos) /**< (PORT_EVCTRL) PORT Event Action 0 Mask */
#define PORT_EVCTRL_EVACT0(value) (PORT_EVCTRL_EVACT0_Msk & ((value) << PORT_EVCTRL_EVACT0_Pos))
#define PORT_EVCTRL_EVACT0_OUT_Val _U_(0x0) /**< (PORT_EVCTRL) Event output to pin */
#define PORT_EVCTRL_EVACT0_SET_Val _U_(0x1) /**< (PORT_EVCTRL) Set output register of pin on event */
#define PORT_EVCTRL_EVACT0_CLR_Val _U_(0x2) /**< (PORT_EVCTRL) Clear output register of pin on event */
#define PORT_EVCTRL_EVACT0_TGL_Val _U_(0x3) /**< (PORT_EVCTRL) Toggle output register of pin on event */
#define PORT_EVCTRL_EVACT0_OUT (PORT_EVCTRL_EVACT0_OUT_Val << PORT_EVCTRL_EVACT0_Pos) /**< (PORT_EVCTRL) Event output to pin Position */
#define PORT_EVCTRL_EVACT0_SET (PORT_EVCTRL_EVACT0_SET_Val << PORT_EVCTRL_EVACT0_Pos) /**< (PORT_EVCTRL) Set output register of pin on event Position */
#define PORT_EVCTRL_EVACT0_CLR (PORT_EVCTRL_EVACT0_CLR_Val << PORT_EVCTRL_EVACT0_Pos) /**< (PORT_EVCTRL) Clear output register of pin on event Position */
#define PORT_EVCTRL_EVACT0_TGL (PORT_EVCTRL_EVACT0_TGL_Val << PORT_EVCTRL_EVACT0_Pos) /**< (PORT_EVCTRL) Toggle output register of pin on event Position */
#define PORT_EVCTRL_PORTEI0_Pos 7 /**< (PORT_EVCTRL) PORT Event Input Enable 0 Position */
#define PORT_EVCTRL_PORTEI0_Msk (_U_(0x1) << PORT_EVCTRL_PORTEI0_Pos) /**< (PORT_EVCTRL) PORT Event Input Enable 0 Mask */
#define PORT_EVCTRL_PORTEI0 PORT_EVCTRL_PORTEI0_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PORT_EVCTRL_PORTEI0_Msk instead */
#define PORT_EVCTRL_PID1_Pos 8 /**< (PORT_EVCTRL) PORT Event Pin Identifier 1 Position */
#define PORT_EVCTRL_PID1_Msk (_U_(0x1F) << PORT_EVCTRL_PID1_Pos) /**< (PORT_EVCTRL) PORT Event Pin Identifier 1 Mask */
#define PORT_EVCTRL_PID1(value) (PORT_EVCTRL_PID1_Msk & ((value) << PORT_EVCTRL_PID1_Pos))
#define PORT_EVCTRL_EVACT1_Pos 13 /**< (PORT_EVCTRL) PORT Event Action 1 Position */
#define PORT_EVCTRL_EVACT1_Msk (_U_(0x3) << PORT_EVCTRL_EVACT1_Pos) /**< (PORT_EVCTRL) PORT Event Action 1 Mask */
#define PORT_EVCTRL_EVACT1(value) (PORT_EVCTRL_EVACT1_Msk & ((value) << PORT_EVCTRL_EVACT1_Pos))
#define PORT_EVCTRL_PORTEI1_Pos 15 /**< (PORT_EVCTRL) PORT Event Input Enable 1 Position */
#define PORT_EVCTRL_PORTEI1_Msk (_U_(0x1) << PORT_EVCTRL_PORTEI1_Pos) /**< (PORT_EVCTRL) PORT Event Input Enable 1 Mask */
#define PORT_EVCTRL_PORTEI1 PORT_EVCTRL_PORTEI1_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PORT_EVCTRL_PORTEI1_Msk instead */
#define PORT_EVCTRL_PID2_Pos 16 /**< (PORT_EVCTRL) PORT Event Pin Identifier 2 Position */
#define PORT_EVCTRL_PID2_Msk (_U_(0x1F) << PORT_EVCTRL_PID2_Pos) /**< (PORT_EVCTRL) PORT Event Pin Identifier 2 Mask */
#define PORT_EVCTRL_PID2(value) (PORT_EVCTRL_PID2_Msk & ((value) << PORT_EVCTRL_PID2_Pos))
#define PORT_EVCTRL_EVACT2_Pos 21 /**< (PORT_EVCTRL) PORT Event Action 2 Position */
#define PORT_EVCTRL_EVACT2_Msk (_U_(0x3) << PORT_EVCTRL_EVACT2_Pos) /**< (PORT_EVCTRL) PORT Event Action 2 Mask */
#define PORT_EVCTRL_EVACT2(value) (PORT_EVCTRL_EVACT2_Msk & ((value) << PORT_EVCTRL_EVACT2_Pos))
#define PORT_EVCTRL_PORTEI2_Pos 23 /**< (PORT_EVCTRL) PORT Event Input Enable 2 Position */
#define PORT_EVCTRL_PORTEI2_Msk (_U_(0x1) << PORT_EVCTRL_PORTEI2_Pos) /**< (PORT_EVCTRL) PORT Event Input Enable 2 Mask */
#define PORT_EVCTRL_PORTEI2 PORT_EVCTRL_PORTEI2_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PORT_EVCTRL_PORTEI2_Msk instead */
#define PORT_EVCTRL_PID3_Pos 24 /**< (PORT_EVCTRL) PORT Event Pin Identifier 3 Position */
#define PORT_EVCTRL_PID3_Msk (_U_(0x1F) << PORT_EVCTRL_PID3_Pos) /**< (PORT_EVCTRL) PORT Event Pin Identifier 3 Mask */
#define PORT_EVCTRL_PID3(value) (PORT_EVCTRL_PID3_Msk & ((value) << PORT_EVCTRL_PID3_Pos))
#define PORT_EVCTRL_EVACT3_Pos 29 /**< (PORT_EVCTRL) PORT Event Action 3 Position */
#define PORT_EVCTRL_EVACT3_Msk (_U_(0x3) << PORT_EVCTRL_EVACT3_Pos) /**< (PORT_EVCTRL) PORT Event Action 3 Mask */
#define PORT_EVCTRL_EVACT3(value) (PORT_EVCTRL_EVACT3_Msk & ((value) << PORT_EVCTRL_EVACT3_Pos))
#define PORT_EVCTRL_PORTEI3_Pos 31 /**< (PORT_EVCTRL) PORT Event Input Enable 3 Position */
#define PORT_EVCTRL_PORTEI3_Msk (_U_(0x1) << PORT_EVCTRL_PORTEI3_Pos) /**< (PORT_EVCTRL) PORT Event Input Enable 3 Mask */
#define PORT_EVCTRL_PORTEI3 PORT_EVCTRL_PORTEI3_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PORT_EVCTRL_PORTEI3_Msk instead */
#define PORT_EVCTRL_MASK _U_(0xFFFFFFFF) /**< \deprecated (PORT_EVCTRL) Register MASK (Use PORT_EVCTRL_Msk instead) */
#define PORT_EVCTRL_Msk _U_(0xFFFFFFFF) /**< (PORT_EVCTRL) Register Mask */
/* -------- PORT_PMUX : (PORT Offset: 0x30) (R/W 8) Peripheral Multiplexing -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t PMUXE:4; /**< bit: 0..3 Peripheral Multiplexing for Even-Numbered Pin */
uint8_t PMUXO:4; /**< bit: 4..7 Peripheral Multiplexing for Odd-Numbered Pin */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} PORT_PMUX_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define PORT_PMUX_OFFSET (0x30) /**< (PORT_PMUX) Peripheral Multiplexing Offset */
#define PORT_PMUX_RESETVALUE _U_(0x00) /**< (PORT_PMUX) Peripheral Multiplexing Reset Value */
#define PORT_PMUX_PMUXE_Pos 0 /**< (PORT_PMUX) Peripheral Multiplexing for Even-Numbered Pin Position */
#define PORT_PMUX_PMUXE_Msk (_U_(0xF) << PORT_PMUX_PMUXE_Pos) /**< (PORT_PMUX) Peripheral Multiplexing for Even-Numbered Pin Mask */
#define PORT_PMUX_PMUXE(value) (PORT_PMUX_PMUXE_Msk & ((value) << PORT_PMUX_PMUXE_Pos))
#define PORT_PMUX_PMUXO_Pos 4 /**< (PORT_PMUX) Peripheral Multiplexing for Odd-Numbered Pin Position */
#define PORT_PMUX_PMUXO_Msk (_U_(0xF) << PORT_PMUX_PMUXO_Pos) /**< (PORT_PMUX) Peripheral Multiplexing for Odd-Numbered Pin Mask */
#define PORT_PMUX_PMUXO(value) (PORT_PMUX_PMUXO_Msk & ((value) << PORT_PMUX_PMUXO_Pos))
#define PORT_PMUX_MASK _U_(0xFF) /**< \deprecated (PORT_PMUX) Register MASK (Use PORT_PMUX_Msk instead) */
#define PORT_PMUX_Msk _U_(0xFF) /**< (PORT_PMUX) Register Mask */
/* -------- PORT_PINCFG : (PORT Offset: 0x40) (R/W 8) Pin Configuration -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t PMUXEN:1; /**< bit: 0 Peripheral Multiplexer Enable */
uint8_t INEN:1; /**< bit: 1 Input Enable */
uint8_t PULLEN:1; /**< bit: 2 Pull Enable */
uint8_t :3; /**< bit: 3..5 Reserved */
uint8_t DRVSTR:1; /**< bit: 6 Output Driver Strength Selection */
uint8_t :1; /**< bit: 7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} PORT_PINCFG_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define PORT_PINCFG_OFFSET (0x40) /**< (PORT_PINCFG) Pin Configuration Offset */
#define PORT_PINCFG_RESETVALUE _U_(0x00) /**< (PORT_PINCFG) Pin Configuration Reset Value */
#define PORT_PINCFG_PMUXEN_Pos 0 /**< (PORT_PINCFG) Peripheral Multiplexer Enable Position */
#define PORT_PINCFG_PMUXEN_Msk (_U_(0x1) << PORT_PINCFG_PMUXEN_Pos) /**< (PORT_PINCFG) Peripheral Multiplexer Enable Mask */
#define PORT_PINCFG_PMUXEN PORT_PINCFG_PMUXEN_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PORT_PINCFG_PMUXEN_Msk instead */
#define PORT_PINCFG_INEN_Pos 1 /**< (PORT_PINCFG) Input Enable Position */
#define PORT_PINCFG_INEN_Msk (_U_(0x1) << PORT_PINCFG_INEN_Pos) /**< (PORT_PINCFG) Input Enable Mask */
#define PORT_PINCFG_INEN PORT_PINCFG_INEN_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PORT_PINCFG_INEN_Msk instead */
#define PORT_PINCFG_PULLEN_Pos 2 /**< (PORT_PINCFG) Pull Enable Position */
#define PORT_PINCFG_PULLEN_Msk (_U_(0x1) << PORT_PINCFG_PULLEN_Pos) /**< (PORT_PINCFG) Pull Enable Mask */
#define PORT_PINCFG_PULLEN PORT_PINCFG_PULLEN_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PORT_PINCFG_PULLEN_Msk instead */
#define PORT_PINCFG_DRVSTR_Pos 6 /**< (PORT_PINCFG) Output Driver Strength Selection Position */
#define PORT_PINCFG_DRVSTR_Msk (_U_(0x1) << PORT_PINCFG_DRVSTR_Pos) /**< (PORT_PINCFG) Output Driver Strength Selection Mask */
#define PORT_PINCFG_DRVSTR PORT_PINCFG_DRVSTR_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PORT_PINCFG_DRVSTR_Msk instead */
#define PORT_PINCFG_MASK _U_(0x47) /**< \deprecated (PORT_PINCFG) Register MASK (Use PORT_PINCFG_Msk instead) */
#define PORT_PINCFG_Msk _U_(0x47) /**< (PORT_PINCFG) Register Mask */
/* -------- PORT_INTENCLR : (PORT Offset: 0x60) (R/W 32) Interrupt Enable Clear -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t NSCHK:1; /**< bit: 0 Non-Secure Check Interrupt Enable */
uint32_t :31; /**< bit: 1..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} PORT_INTENCLR_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define PORT_INTENCLR_OFFSET (0x60) /**< (PORT_INTENCLR) Interrupt Enable Clear Offset */
#define PORT_INTENCLR_RESETVALUE _U_(0x00) /**< (PORT_INTENCLR) Interrupt Enable Clear Reset Value */
#define PORT_INTENCLR_NSCHK_Pos 0 /**< (PORT_INTENCLR) Non-Secure Check Interrupt Enable Position */
#define PORT_INTENCLR_NSCHK_Msk (_U_(0x1) << PORT_INTENCLR_NSCHK_Pos) /**< (PORT_INTENCLR) Non-Secure Check Interrupt Enable Mask */
#define PORT_INTENCLR_NSCHK PORT_INTENCLR_NSCHK_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PORT_INTENCLR_NSCHK_Msk instead */
#define PORT_INTENCLR_MASK _U_(0x01) /**< \deprecated (PORT_INTENCLR) Register MASK (Use PORT_INTENCLR_Msk instead) */
#define PORT_INTENCLR_Msk _U_(0x01) /**< (PORT_INTENCLR) Register Mask */
/* -------- PORT_INTENSET : (PORT Offset: 0x64) (R/W 32) Interrupt Enable Set -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t NSCHK:1; /**< bit: 0 Non-Secure Check Interrupt Enable */
uint32_t :31; /**< bit: 1..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} PORT_INTENSET_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define PORT_INTENSET_OFFSET (0x64) /**< (PORT_INTENSET) Interrupt Enable Set Offset */
#define PORT_INTENSET_RESETVALUE _U_(0x00) /**< (PORT_INTENSET) Interrupt Enable Set Reset Value */
#define PORT_INTENSET_NSCHK_Pos 0 /**< (PORT_INTENSET) Non-Secure Check Interrupt Enable Position */
#define PORT_INTENSET_NSCHK_Msk (_U_(0x1) << PORT_INTENSET_NSCHK_Pos) /**< (PORT_INTENSET) Non-Secure Check Interrupt Enable Mask */
#define PORT_INTENSET_NSCHK PORT_INTENSET_NSCHK_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PORT_INTENSET_NSCHK_Msk instead */
#define PORT_INTENSET_MASK _U_(0x01) /**< \deprecated (PORT_INTENSET) Register MASK (Use PORT_INTENSET_Msk instead) */
#define PORT_INTENSET_Msk _U_(0x01) /**< (PORT_INTENSET) Register Mask */
/* -------- PORT_INTFLAG : (PORT Offset: 0x68) (R/W 32) Interrupt Flag Status and Clear -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union { // __I to avoid read-modify-write on write-to-clear register
struct {
__I uint32_t NSCHK:1; /**< bit: 0 Non-Secure Check */
__I uint32_t :31; /**< bit: 1..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} PORT_INTFLAG_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define PORT_INTFLAG_OFFSET (0x68) /**< (PORT_INTFLAG) Interrupt Flag Status and Clear Offset */
#define PORT_INTFLAG_RESETVALUE _U_(0x00) /**< (PORT_INTFLAG) Interrupt Flag Status and Clear Reset Value */
#define PORT_INTFLAG_NSCHK_Pos 0 /**< (PORT_INTFLAG) Non-Secure Check Position */
#define PORT_INTFLAG_NSCHK_Msk (_U_(0x1) << PORT_INTFLAG_NSCHK_Pos) /**< (PORT_INTFLAG) Non-Secure Check Mask */
#define PORT_INTFLAG_NSCHK PORT_INTFLAG_NSCHK_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use PORT_INTFLAG_NSCHK_Msk instead */
#define PORT_INTFLAG_MASK _U_(0x01) /**< \deprecated (PORT_INTFLAG) Register MASK (Use PORT_INTFLAG_Msk instead) */
#define PORT_INTFLAG_Msk _U_(0x01) /**< (PORT_INTFLAG) Register Mask */
/* -------- PORT_NONSEC : (PORT Offset: 0x6c) (R/W 32) Security Attribution -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t NONSEC:32; /**< bit: 0..31 Port Security Attribution */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} PORT_NONSEC_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define PORT_NONSEC_OFFSET (0x6C) /**< (PORT_NONSEC) Security Attribution Offset */
#define PORT_NONSEC_RESETVALUE _U_(0x00) /**< (PORT_NONSEC) Security Attribution Reset Value */
#define PORT_NONSEC_NONSEC_Pos 0 /**< (PORT_NONSEC) Port Security Attribution Position */
#define PORT_NONSEC_NONSEC_Msk (_U_(0xFFFFFFFF) << PORT_NONSEC_NONSEC_Pos) /**< (PORT_NONSEC) Port Security Attribution Mask */
#define PORT_NONSEC_NONSEC(value) (PORT_NONSEC_NONSEC_Msk & ((value) << PORT_NONSEC_NONSEC_Pos))
#define PORT_NONSEC_MASK _U_(0xFFFFFFFF) /**< \deprecated (PORT_NONSEC) Register MASK (Use PORT_NONSEC_Msk instead) */
#define PORT_NONSEC_Msk _U_(0xFFFFFFFF) /**< (PORT_NONSEC) Register Mask */
/* -------- PORT_NSCHK : (PORT Offset: 0x70) (R/W 32) Security Attribution Check -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t NSCHK:32; /**< bit: 0..31 Port Security Attribution Check */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} PORT_NSCHK_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define PORT_NSCHK_OFFSET (0x70) /**< (PORT_NSCHK) Security Attribution Check Offset */
#define PORT_NSCHK_RESETVALUE _U_(0x00) /**< (PORT_NSCHK) Security Attribution Check Reset Value */
#define PORT_NSCHK_NSCHK_Pos 0 /**< (PORT_NSCHK) Port Security Attribution Check Position */
#define PORT_NSCHK_NSCHK_Msk (_U_(0xFFFFFFFF) << PORT_NSCHK_NSCHK_Pos) /**< (PORT_NSCHK) Port Security Attribution Check Mask */
#define PORT_NSCHK_NSCHK(value) (PORT_NSCHK_NSCHK_Msk & ((value) << PORT_NSCHK_NSCHK_Pos))
#define PORT_NSCHK_MASK _U_(0xFFFFFFFF) /**< \deprecated (PORT_NSCHK) Register MASK (Use PORT_NSCHK_Msk instead) */
#define PORT_NSCHK_Msk _U_(0xFFFFFFFF) /**< (PORT_NSCHK) Register Mask */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
/** \brief GROUP hardware registers */
typedef struct {
__IO PORT_DIR_Type DIR; /**< Offset: 0x00 (R/W 32) Data Direction */
__IO PORT_DIRCLR_Type DIRCLR; /**< Offset: 0x04 (R/W 32) Data Direction Clear */
__IO PORT_DIRSET_Type DIRSET; /**< Offset: 0x08 (R/W 32) Data Direction Set */
__IO PORT_DIRTGL_Type DIRTGL; /**< Offset: 0x0C (R/W 32) Data Direction Toggle */
__IO PORT_OUT_Type OUT; /**< Offset: 0x10 (R/W 32) Data Output Value */
__IO PORT_OUTCLR_Type OUTCLR; /**< Offset: 0x14 (R/W 32) Data Output Value Clear */
__IO PORT_OUTSET_Type OUTSET; /**< Offset: 0x18 (R/W 32) Data Output Value Set */
__IO PORT_OUTTGL_Type OUTTGL; /**< Offset: 0x1C (R/W 32) Data Output Value Toggle */
__I PORT_IN_Type IN; /**< Offset: 0x20 (R/ 32) Data Input Value */
__IO PORT_CTRL_Type CTRL; /**< Offset: 0x24 (R/W 32) Control */
__O PORT_WRCONFIG_Type WRCONFIG; /**< Offset: 0x28 ( /W 32) Write Configuration */
__IO PORT_EVCTRL_Type EVCTRL; /**< Offset: 0x2C (R/W 32) Event Input Control */
__IO PORT_PMUX_Type PMUX[16]; /**< Offset: 0x30 (R/W 8) Peripheral Multiplexing */
__IO PORT_PINCFG_Type PINCFG[32]; /**< Offset: 0x40 (R/W 8) Pin Configuration */
__IO PORT_INTENCLR_Type INTENCLR; /**< Offset: 0x60 (R/W 32) Interrupt Enable Clear */
__IO PORT_INTENSET_Type INTENSET; /**< Offset: 0x64 (R/W 32) Interrupt Enable Set */
__IO PORT_INTFLAG_Type INTFLAG; /**< Offset: 0x68 (R/W 32) Interrupt Flag Status and Clear */
__IO PORT_NONSEC_Type NONSEC; /**< Offset: 0x6C (R/W 32) Security Attribution */
__IO PORT_NSCHK_Type NSCHK; /**< Offset: 0x70 (R/W 32) Security Attribution Check */
__I uint8_t Reserved1[12];
} PortGroup;
/** \brief PORT hardware registers */
typedef struct { /* Port Module */
PortGroup Group[1]; /**< Offset: 0x00 */
} Port;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/** @} end of Port Module */
#endif /* _SAML10_PORT_COMPONENT_H_ */

View File

@ -0,0 +1,53 @@
/**
* \file
*
* \brief Component description for PTC
*
* Copyright (c) 2018 Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* 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
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
/* file generated from device description version 2018-08-31T13:51:50Z */
#ifndef _SAML10_PTC_COMPONENT_H_
#define _SAML10_PTC_COMPONENT_H_
#define _SAML10_PTC_COMPONENT_ /**< \deprecated Backward compatibility for ASF */
/** \addtogroup SAML_SAML10 Peripheral Touch Controller
* @{
*/
/* ========================================================================== */
/** SOFTWARE API DEFINITION FOR PTC */
/* ========================================================================== */
#define PTC_U2215 /**< (PTC) Module ID */
#define REV_PTC 0x500 /**< (PTC) Module revision */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
/** \brief No hardware registers defined for PTC */
typedef void Ptc;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/** @} end of Peripheral Touch Controller */
#endif /* _SAML10_PTC_COMPONENT_H_ */

View File

@ -0,0 +1,96 @@
/**
* \file
*
* \brief Component description for RSTC
*
* Copyright (c) 2018 Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* 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
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
/* file generated from device description version 2018-08-31T13:51:50Z */
#ifndef _SAML10_RSTC_COMPONENT_H_
#define _SAML10_RSTC_COMPONENT_H_
#define _SAML10_RSTC_COMPONENT_ /**< \deprecated Backward compatibility for ASF */
/** \addtogroup SAML_SAML10 Reset Controller
* @{
*/
/* ========================================================================== */
/** SOFTWARE API DEFINITION FOR RSTC */
/* ========================================================================== */
#define RSTC_U2239 /**< (RSTC) Module ID */
#define REV_RSTC 0x300 /**< (RSTC) Module revision */
/* -------- RSTC_RCAUSE : (RSTC Offset: 0x00) (R/ 8) Reset Cause -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t POR:1; /**< bit: 0 Power On Reset */
uint8_t BODCORE:1; /**< bit: 1 Brown Out CORE Detector Reset */
uint8_t BODVDD:1; /**< bit: 2 Brown Out VDD Detector Reset */
uint8_t :1; /**< bit: 3 Reserved */
uint8_t EXT:1; /**< bit: 4 External Reset */
uint8_t WDT:1; /**< bit: 5 Watchdog Reset */
uint8_t SYST:1; /**< bit: 6 System Reset Request */
uint8_t :1; /**< bit: 7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} RSTC_RCAUSE_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define RSTC_RCAUSE_OFFSET (0x00) /**< (RSTC_RCAUSE) Reset Cause Offset */
#define RSTC_RCAUSE_POR_Pos 0 /**< (RSTC_RCAUSE) Power On Reset Position */
#define RSTC_RCAUSE_POR_Msk (_U_(0x1) << RSTC_RCAUSE_POR_Pos) /**< (RSTC_RCAUSE) Power On Reset Mask */
#define RSTC_RCAUSE_POR RSTC_RCAUSE_POR_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use RSTC_RCAUSE_POR_Msk instead */
#define RSTC_RCAUSE_BODCORE_Pos 1 /**< (RSTC_RCAUSE) Brown Out CORE Detector Reset Position */
#define RSTC_RCAUSE_BODCORE_Msk (_U_(0x1) << RSTC_RCAUSE_BODCORE_Pos) /**< (RSTC_RCAUSE) Brown Out CORE Detector Reset Mask */
#define RSTC_RCAUSE_BODCORE RSTC_RCAUSE_BODCORE_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use RSTC_RCAUSE_BODCORE_Msk instead */
#define RSTC_RCAUSE_BODVDD_Pos 2 /**< (RSTC_RCAUSE) Brown Out VDD Detector Reset Position */
#define RSTC_RCAUSE_BODVDD_Msk (_U_(0x1) << RSTC_RCAUSE_BODVDD_Pos) /**< (RSTC_RCAUSE) Brown Out VDD Detector Reset Mask */
#define RSTC_RCAUSE_BODVDD RSTC_RCAUSE_BODVDD_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use RSTC_RCAUSE_BODVDD_Msk instead */
#define RSTC_RCAUSE_EXT_Pos 4 /**< (RSTC_RCAUSE) External Reset Position */
#define RSTC_RCAUSE_EXT_Msk (_U_(0x1) << RSTC_RCAUSE_EXT_Pos) /**< (RSTC_RCAUSE) External Reset Mask */
#define RSTC_RCAUSE_EXT RSTC_RCAUSE_EXT_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use RSTC_RCAUSE_EXT_Msk instead */
#define RSTC_RCAUSE_WDT_Pos 5 /**< (RSTC_RCAUSE) Watchdog Reset Position */
#define RSTC_RCAUSE_WDT_Msk (_U_(0x1) << RSTC_RCAUSE_WDT_Pos) /**< (RSTC_RCAUSE) Watchdog Reset Mask */
#define RSTC_RCAUSE_WDT RSTC_RCAUSE_WDT_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use RSTC_RCAUSE_WDT_Msk instead */
#define RSTC_RCAUSE_SYST_Pos 6 /**< (RSTC_RCAUSE) System Reset Request Position */
#define RSTC_RCAUSE_SYST_Msk (_U_(0x1) << RSTC_RCAUSE_SYST_Pos) /**< (RSTC_RCAUSE) System Reset Request Mask */
#define RSTC_RCAUSE_SYST RSTC_RCAUSE_SYST_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use RSTC_RCAUSE_SYST_Msk instead */
#define RSTC_RCAUSE_MASK _U_(0x77) /**< \deprecated (RSTC_RCAUSE) Register MASK (Use RSTC_RCAUSE_Msk instead) */
#define RSTC_RCAUSE_Msk _U_(0x77) /**< (RSTC_RCAUSE) Register Mask */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
/** \brief RSTC hardware registers */
typedef struct { /* Reset Controller */
__I RSTC_RCAUSE_Type RCAUSE; /**< Offset: 0x00 (R/ 8) Reset Cause */
} Rstc;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/** @} end of Reset Controller */
#endif /* _SAML10_RSTC_COMPONENT_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,653 @@
/**
* \file
*
* \brief Component description for SUPC
*
* Copyright (c) 2018 Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* 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
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
/* file generated from device description version 2018-08-31T13:51:50Z */
#ifndef _SAML10_SUPC_COMPONENT_H_
#define _SAML10_SUPC_COMPONENT_H_
#define _SAML10_SUPC_COMPONENT_ /**< \deprecated Backward compatibility for ASF */
/** \addtogroup SAML_SAML10 Supply Controller
* @{
*/
/* ========================================================================== */
/** SOFTWARE API DEFINITION FOR SUPC */
/* ========================================================================== */
#define SUPC_U2117 /**< (SUPC) Module ID */
#define REV_SUPC 0x400 /**< (SUPC) Module revision */
/* -------- SUPC_INTENCLR : (SUPC Offset: 0x00) (R/W 32) Interrupt Enable Clear -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t BOD33RDY:1; /**< bit: 0 BOD33 Ready */
uint32_t BOD33DET:1; /**< bit: 1 BOD33 Detection */
uint32_t B33SRDY:1; /**< bit: 2 BOD33 Synchronization Ready */
uint32_t BOD12RDY:1; /**< bit: 3 BOD12 Ready */
uint32_t BOD12DET:1; /**< bit: 4 BOD12 Detection */
uint32_t B12SRDY:1; /**< bit: 5 BOD12 Synchronization Ready */
uint32_t :2; /**< bit: 6..7 Reserved */
uint32_t VREGRDY:1; /**< bit: 8 Voltage Regulator Ready */
uint32_t :1; /**< bit: 9 Reserved */
uint32_t VCORERDY:1; /**< bit: 10 VDDCORE Ready */
uint32_t ULPVREFRDY:1; /**< bit: 11 ULPVREF Voltage Reference Ready */
uint32_t :20; /**< bit: 12..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} SUPC_INTENCLR_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define SUPC_INTENCLR_OFFSET (0x00) /**< (SUPC_INTENCLR) Interrupt Enable Clear Offset */
#define SUPC_INTENCLR_RESETVALUE _U_(0x00) /**< (SUPC_INTENCLR) Interrupt Enable Clear Reset Value */
#define SUPC_INTENCLR_BOD33RDY_Pos 0 /**< (SUPC_INTENCLR) BOD33 Ready Position */
#define SUPC_INTENCLR_BOD33RDY_Msk (_U_(0x1) << SUPC_INTENCLR_BOD33RDY_Pos) /**< (SUPC_INTENCLR) BOD33 Ready Mask */
#define SUPC_INTENCLR_BOD33RDY SUPC_INTENCLR_BOD33RDY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use SUPC_INTENCLR_BOD33RDY_Msk instead */
#define SUPC_INTENCLR_BOD33DET_Pos 1 /**< (SUPC_INTENCLR) BOD33 Detection Position */
#define SUPC_INTENCLR_BOD33DET_Msk (_U_(0x1) << SUPC_INTENCLR_BOD33DET_Pos) /**< (SUPC_INTENCLR) BOD33 Detection Mask */
#define SUPC_INTENCLR_BOD33DET SUPC_INTENCLR_BOD33DET_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use SUPC_INTENCLR_BOD33DET_Msk instead */
#define SUPC_INTENCLR_B33SRDY_Pos 2 /**< (SUPC_INTENCLR) BOD33 Synchronization Ready Position */
#define SUPC_INTENCLR_B33SRDY_Msk (_U_(0x1) << SUPC_INTENCLR_B33SRDY_Pos) /**< (SUPC_INTENCLR) BOD33 Synchronization Ready Mask */
#define SUPC_INTENCLR_B33SRDY SUPC_INTENCLR_B33SRDY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use SUPC_INTENCLR_B33SRDY_Msk instead */
#define SUPC_INTENCLR_BOD12RDY_Pos 3 /**< (SUPC_INTENCLR) BOD12 Ready Position */
#define SUPC_INTENCLR_BOD12RDY_Msk (_U_(0x1) << SUPC_INTENCLR_BOD12RDY_Pos) /**< (SUPC_INTENCLR) BOD12 Ready Mask */
#define SUPC_INTENCLR_BOD12RDY SUPC_INTENCLR_BOD12RDY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use SUPC_INTENCLR_BOD12RDY_Msk instead */
#define SUPC_INTENCLR_BOD12DET_Pos 4 /**< (SUPC_INTENCLR) BOD12 Detection Position */
#define SUPC_INTENCLR_BOD12DET_Msk (_U_(0x1) << SUPC_INTENCLR_BOD12DET_Pos) /**< (SUPC_INTENCLR) BOD12 Detection Mask */
#define SUPC_INTENCLR_BOD12DET SUPC_INTENCLR_BOD12DET_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use SUPC_INTENCLR_BOD12DET_Msk instead */
#define SUPC_INTENCLR_B12SRDY_Pos 5 /**< (SUPC_INTENCLR) BOD12 Synchronization Ready Position */
#define SUPC_INTENCLR_B12SRDY_Msk (_U_(0x1) << SUPC_INTENCLR_B12SRDY_Pos) /**< (SUPC_INTENCLR) BOD12 Synchronization Ready Mask */
#define SUPC_INTENCLR_B12SRDY SUPC_INTENCLR_B12SRDY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use SUPC_INTENCLR_B12SRDY_Msk instead */
#define SUPC_INTENCLR_VREGRDY_Pos 8 /**< (SUPC_INTENCLR) Voltage Regulator Ready Position */
#define SUPC_INTENCLR_VREGRDY_Msk (_U_(0x1) << SUPC_INTENCLR_VREGRDY_Pos) /**< (SUPC_INTENCLR) Voltage Regulator Ready Mask */
#define SUPC_INTENCLR_VREGRDY SUPC_INTENCLR_VREGRDY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use SUPC_INTENCLR_VREGRDY_Msk instead */
#define SUPC_INTENCLR_VCORERDY_Pos 10 /**< (SUPC_INTENCLR) VDDCORE Ready Position */
#define SUPC_INTENCLR_VCORERDY_Msk (_U_(0x1) << SUPC_INTENCLR_VCORERDY_Pos) /**< (SUPC_INTENCLR) VDDCORE Ready Mask */
#define SUPC_INTENCLR_VCORERDY SUPC_INTENCLR_VCORERDY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use SUPC_INTENCLR_VCORERDY_Msk instead */
#define SUPC_INTENCLR_ULPVREFRDY_Pos 11 /**< (SUPC_INTENCLR) ULPVREF Voltage Reference Ready Position */
#define SUPC_INTENCLR_ULPVREFRDY_Msk (_U_(0x1) << SUPC_INTENCLR_ULPVREFRDY_Pos) /**< (SUPC_INTENCLR) ULPVREF Voltage Reference Ready Mask */
#define SUPC_INTENCLR_ULPVREFRDY SUPC_INTENCLR_ULPVREFRDY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use SUPC_INTENCLR_ULPVREFRDY_Msk instead */
#define SUPC_INTENCLR_MASK _U_(0xD3F) /**< \deprecated (SUPC_INTENCLR) Register MASK (Use SUPC_INTENCLR_Msk instead) */
#define SUPC_INTENCLR_Msk _U_(0xD3F) /**< (SUPC_INTENCLR) Register Mask */
/* -------- SUPC_INTENSET : (SUPC Offset: 0x04) (R/W 32) Interrupt Enable Set -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t BOD33RDY:1; /**< bit: 0 BOD33 Ready */
uint32_t BOD33DET:1; /**< bit: 1 BOD33 Detection */
uint32_t B33SRDY:1; /**< bit: 2 BOD33 Synchronization Ready */
uint32_t BOD12RDY:1; /**< bit: 3 BOD12 Ready */
uint32_t BOD12DET:1; /**< bit: 4 BOD12 Detection */
uint32_t B12SRDY:1; /**< bit: 5 BOD12 Synchronization Ready */
uint32_t :2; /**< bit: 6..7 Reserved */
uint32_t VREGRDY:1; /**< bit: 8 Voltage Regulator Ready */
uint32_t :1; /**< bit: 9 Reserved */
uint32_t VCORERDY:1; /**< bit: 10 VDDCORE Ready */
uint32_t ULPVREFRDY:1; /**< bit: 11 ULPVREF Voltage Reference Ready */
uint32_t :20; /**< bit: 12..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} SUPC_INTENSET_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define SUPC_INTENSET_OFFSET (0x04) /**< (SUPC_INTENSET) Interrupt Enable Set Offset */
#define SUPC_INTENSET_RESETVALUE _U_(0x00) /**< (SUPC_INTENSET) Interrupt Enable Set Reset Value */
#define SUPC_INTENSET_BOD33RDY_Pos 0 /**< (SUPC_INTENSET) BOD33 Ready Position */
#define SUPC_INTENSET_BOD33RDY_Msk (_U_(0x1) << SUPC_INTENSET_BOD33RDY_Pos) /**< (SUPC_INTENSET) BOD33 Ready Mask */
#define SUPC_INTENSET_BOD33RDY SUPC_INTENSET_BOD33RDY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use SUPC_INTENSET_BOD33RDY_Msk instead */
#define SUPC_INTENSET_BOD33DET_Pos 1 /**< (SUPC_INTENSET) BOD33 Detection Position */
#define SUPC_INTENSET_BOD33DET_Msk (_U_(0x1) << SUPC_INTENSET_BOD33DET_Pos) /**< (SUPC_INTENSET) BOD33 Detection Mask */
#define SUPC_INTENSET_BOD33DET SUPC_INTENSET_BOD33DET_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use SUPC_INTENSET_BOD33DET_Msk instead */
#define SUPC_INTENSET_B33SRDY_Pos 2 /**< (SUPC_INTENSET) BOD33 Synchronization Ready Position */
#define SUPC_INTENSET_B33SRDY_Msk (_U_(0x1) << SUPC_INTENSET_B33SRDY_Pos) /**< (SUPC_INTENSET) BOD33 Synchronization Ready Mask */
#define SUPC_INTENSET_B33SRDY SUPC_INTENSET_B33SRDY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use SUPC_INTENSET_B33SRDY_Msk instead */
#define SUPC_INTENSET_BOD12RDY_Pos 3 /**< (SUPC_INTENSET) BOD12 Ready Position */
#define SUPC_INTENSET_BOD12RDY_Msk (_U_(0x1) << SUPC_INTENSET_BOD12RDY_Pos) /**< (SUPC_INTENSET) BOD12 Ready Mask */
#define SUPC_INTENSET_BOD12RDY SUPC_INTENSET_BOD12RDY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use SUPC_INTENSET_BOD12RDY_Msk instead */
#define SUPC_INTENSET_BOD12DET_Pos 4 /**< (SUPC_INTENSET) BOD12 Detection Position */
#define SUPC_INTENSET_BOD12DET_Msk (_U_(0x1) << SUPC_INTENSET_BOD12DET_Pos) /**< (SUPC_INTENSET) BOD12 Detection Mask */
#define SUPC_INTENSET_BOD12DET SUPC_INTENSET_BOD12DET_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use SUPC_INTENSET_BOD12DET_Msk instead */
#define SUPC_INTENSET_B12SRDY_Pos 5 /**< (SUPC_INTENSET) BOD12 Synchronization Ready Position */
#define SUPC_INTENSET_B12SRDY_Msk (_U_(0x1) << SUPC_INTENSET_B12SRDY_Pos) /**< (SUPC_INTENSET) BOD12 Synchronization Ready Mask */
#define SUPC_INTENSET_B12SRDY SUPC_INTENSET_B12SRDY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use SUPC_INTENSET_B12SRDY_Msk instead */
#define SUPC_INTENSET_VREGRDY_Pos 8 /**< (SUPC_INTENSET) Voltage Regulator Ready Position */
#define SUPC_INTENSET_VREGRDY_Msk (_U_(0x1) << SUPC_INTENSET_VREGRDY_Pos) /**< (SUPC_INTENSET) Voltage Regulator Ready Mask */
#define SUPC_INTENSET_VREGRDY SUPC_INTENSET_VREGRDY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use SUPC_INTENSET_VREGRDY_Msk instead */
#define SUPC_INTENSET_VCORERDY_Pos 10 /**< (SUPC_INTENSET) VDDCORE Ready Position */
#define SUPC_INTENSET_VCORERDY_Msk (_U_(0x1) << SUPC_INTENSET_VCORERDY_Pos) /**< (SUPC_INTENSET) VDDCORE Ready Mask */
#define SUPC_INTENSET_VCORERDY SUPC_INTENSET_VCORERDY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use SUPC_INTENSET_VCORERDY_Msk instead */
#define SUPC_INTENSET_ULPVREFRDY_Pos 11 /**< (SUPC_INTENSET) ULPVREF Voltage Reference Ready Position */
#define SUPC_INTENSET_ULPVREFRDY_Msk (_U_(0x1) << SUPC_INTENSET_ULPVREFRDY_Pos) /**< (SUPC_INTENSET) ULPVREF Voltage Reference Ready Mask */
#define SUPC_INTENSET_ULPVREFRDY SUPC_INTENSET_ULPVREFRDY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use SUPC_INTENSET_ULPVREFRDY_Msk instead */
#define SUPC_INTENSET_MASK _U_(0xD3F) /**< \deprecated (SUPC_INTENSET) Register MASK (Use SUPC_INTENSET_Msk instead) */
#define SUPC_INTENSET_Msk _U_(0xD3F) /**< (SUPC_INTENSET) Register Mask */
/* -------- SUPC_INTFLAG : (SUPC Offset: 0x08) (R/W 32) Interrupt Flag Status and Clear -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union { // __I to avoid read-modify-write on write-to-clear register
struct {
__I uint32_t BOD33RDY:1; /**< bit: 0 BOD33 Ready */
__I uint32_t BOD33DET:1; /**< bit: 1 BOD33 Detection */
__I uint32_t B33SRDY:1; /**< bit: 2 BOD33 Synchronization Ready */
__I uint32_t BOD12RDY:1; /**< bit: 3 BOD12 Ready */
__I uint32_t BOD12DET:1; /**< bit: 4 BOD12 Detection */
__I uint32_t B12SRDY:1; /**< bit: 5 BOD12 Synchronization Ready */
__I uint32_t :2; /**< bit: 6..7 Reserved */
__I uint32_t VREGRDY:1; /**< bit: 8 Voltage Regulator Ready */
__I uint32_t :1; /**< bit: 9 Reserved */
__I uint32_t VCORERDY:1; /**< bit: 10 VDDCORE Ready */
__I uint32_t ULPVREFRDY:1; /**< bit: 11 ULPVREF Voltage Reference Ready */
__I uint32_t :20; /**< bit: 12..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} SUPC_INTFLAG_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define SUPC_INTFLAG_OFFSET (0x08) /**< (SUPC_INTFLAG) Interrupt Flag Status and Clear Offset */
#define SUPC_INTFLAG_RESETVALUE _U_(0x00) /**< (SUPC_INTFLAG) Interrupt Flag Status and Clear Reset Value */
#define SUPC_INTFLAG_BOD33RDY_Pos 0 /**< (SUPC_INTFLAG) BOD33 Ready Position */
#define SUPC_INTFLAG_BOD33RDY_Msk (_U_(0x1) << SUPC_INTFLAG_BOD33RDY_Pos) /**< (SUPC_INTFLAG) BOD33 Ready Mask */
#define SUPC_INTFLAG_BOD33RDY SUPC_INTFLAG_BOD33RDY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use SUPC_INTFLAG_BOD33RDY_Msk instead */
#define SUPC_INTFLAG_BOD33DET_Pos 1 /**< (SUPC_INTFLAG) BOD33 Detection Position */
#define SUPC_INTFLAG_BOD33DET_Msk (_U_(0x1) << SUPC_INTFLAG_BOD33DET_Pos) /**< (SUPC_INTFLAG) BOD33 Detection Mask */
#define SUPC_INTFLAG_BOD33DET SUPC_INTFLAG_BOD33DET_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use SUPC_INTFLAG_BOD33DET_Msk instead */
#define SUPC_INTFLAG_B33SRDY_Pos 2 /**< (SUPC_INTFLAG) BOD33 Synchronization Ready Position */
#define SUPC_INTFLAG_B33SRDY_Msk (_U_(0x1) << SUPC_INTFLAG_B33SRDY_Pos) /**< (SUPC_INTFLAG) BOD33 Synchronization Ready Mask */
#define SUPC_INTFLAG_B33SRDY SUPC_INTFLAG_B33SRDY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use SUPC_INTFLAG_B33SRDY_Msk instead */
#define SUPC_INTFLAG_BOD12RDY_Pos 3 /**< (SUPC_INTFLAG) BOD12 Ready Position */
#define SUPC_INTFLAG_BOD12RDY_Msk (_U_(0x1) << SUPC_INTFLAG_BOD12RDY_Pos) /**< (SUPC_INTFLAG) BOD12 Ready Mask */
#define SUPC_INTFLAG_BOD12RDY SUPC_INTFLAG_BOD12RDY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use SUPC_INTFLAG_BOD12RDY_Msk instead */
#define SUPC_INTFLAG_BOD12DET_Pos 4 /**< (SUPC_INTFLAG) BOD12 Detection Position */
#define SUPC_INTFLAG_BOD12DET_Msk (_U_(0x1) << SUPC_INTFLAG_BOD12DET_Pos) /**< (SUPC_INTFLAG) BOD12 Detection Mask */
#define SUPC_INTFLAG_BOD12DET SUPC_INTFLAG_BOD12DET_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use SUPC_INTFLAG_BOD12DET_Msk instead */
#define SUPC_INTFLAG_B12SRDY_Pos 5 /**< (SUPC_INTFLAG) BOD12 Synchronization Ready Position */
#define SUPC_INTFLAG_B12SRDY_Msk (_U_(0x1) << SUPC_INTFLAG_B12SRDY_Pos) /**< (SUPC_INTFLAG) BOD12 Synchronization Ready Mask */
#define SUPC_INTFLAG_B12SRDY SUPC_INTFLAG_B12SRDY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use SUPC_INTFLAG_B12SRDY_Msk instead */
#define SUPC_INTFLAG_VREGRDY_Pos 8 /**< (SUPC_INTFLAG) Voltage Regulator Ready Position */
#define SUPC_INTFLAG_VREGRDY_Msk (_U_(0x1) << SUPC_INTFLAG_VREGRDY_Pos) /**< (SUPC_INTFLAG) Voltage Regulator Ready Mask */
#define SUPC_INTFLAG_VREGRDY SUPC_INTFLAG_VREGRDY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use SUPC_INTFLAG_VREGRDY_Msk instead */
#define SUPC_INTFLAG_VCORERDY_Pos 10 /**< (SUPC_INTFLAG) VDDCORE Ready Position */
#define SUPC_INTFLAG_VCORERDY_Msk (_U_(0x1) << SUPC_INTFLAG_VCORERDY_Pos) /**< (SUPC_INTFLAG) VDDCORE Ready Mask */
#define SUPC_INTFLAG_VCORERDY SUPC_INTFLAG_VCORERDY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use SUPC_INTFLAG_VCORERDY_Msk instead */
#define SUPC_INTFLAG_ULPVREFRDY_Pos 11 /**< (SUPC_INTFLAG) ULPVREF Voltage Reference Ready Position */
#define SUPC_INTFLAG_ULPVREFRDY_Msk (_U_(0x1) << SUPC_INTFLAG_ULPVREFRDY_Pos) /**< (SUPC_INTFLAG) ULPVREF Voltage Reference Ready Mask */
#define SUPC_INTFLAG_ULPVREFRDY SUPC_INTFLAG_ULPVREFRDY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use SUPC_INTFLAG_ULPVREFRDY_Msk instead */
#define SUPC_INTFLAG_MASK _U_(0xD3F) /**< \deprecated (SUPC_INTFLAG) Register MASK (Use SUPC_INTFLAG_Msk instead) */
#define SUPC_INTFLAG_Msk _U_(0xD3F) /**< (SUPC_INTFLAG) Register Mask */
/* -------- SUPC_STATUS : (SUPC Offset: 0x0c) (R/ 32) Power and Clocks Status -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t BOD33RDY:1; /**< bit: 0 BOD33 Ready */
uint32_t BOD33DET:1; /**< bit: 1 BOD33 Detection */
uint32_t B33SRDY:1; /**< bit: 2 BOD33 Synchronization Ready */
uint32_t BOD12RDY:1; /**< bit: 3 BOD12 Ready */
uint32_t BOD12DET:1; /**< bit: 4 BOD12 Detection */
uint32_t B12SRDY:1; /**< bit: 5 BOD12 Synchronization Ready */
uint32_t :2; /**< bit: 6..7 Reserved */
uint32_t VREGRDY:1; /**< bit: 8 Voltage Regulator Ready */
uint32_t :1; /**< bit: 9 Reserved */
uint32_t VCORERDY:1; /**< bit: 10 VDDCORE Ready */
uint32_t :1; /**< bit: 11 Reserved */
uint32_t ULPVREFRDY:1; /**< bit: 12 Low Power Voltage Reference Ready */
uint32_t ULPBIASRDY:1; /**< bit: 13 Low Power Voltage Bias Ready */
uint32_t :18; /**< bit: 14..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} SUPC_STATUS_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define SUPC_STATUS_OFFSET (0x0C) /**< (SUPC_STATUS) Power and Clocks Status Offset */
#define SUPC_STATUS_RESETVALUE _U_(0x00) /**< (SUPC_STATUS) Power and Clocks Status Reset Value */
#define SUPC_STATUS_BOD33RDY_Pos 0 /**< (SUPC_STATUS) BOD33 Ready Position */
#define SUPC_STATUS_BOD33RDY_Msk (_U_(0x1) << SUPC_STATUS_BOD33RDY_Pos) /**< (SUPC_STATUS) BOD33 Ready Mask */
#define SUPC_STATUS_BOD33RDY SUPC_STATUS_BOD33RDY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use SUPC_STATUS_BOD33RDY_Msk instead */
#define SUPC_STATUS_BOD33DET_Pos 1 /**< (SUPC_STATUS) BOD33 Detection Position */
#define SUPC_STATUS_BOD33DET_Msk (_U_(0x1) << SUPC_STATUS_BOD33DET_Pos) /**< (SUPC_STATUS) BOD33 Detection Mask */
#define SUPC_STATUS_BOD33DET SUPC_STATUS_BOD33DET_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use SUPC_STATUS_BOD33DET_Msk instead */
#define SUPC_STATUS_B33SRDY_Pos 2 /**< (SUPC_STATUS) BOD33 Synchronization Ready Position */
#define SUPC_STATUS_B33SRDY_Msk (_U_(0x1) << SUPC_STATUS_B33SRDY_Pos) /**< (SUPC_STATUS) BOD33 Synchronization Ready Mask */
#define SUPC_STATUS_B33SRDY SUPC_STATUS_B33SRDY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use SUPC_STATUS_B33SRDY_Msk instead */
#define SUPC_STATUS_BOD12RDY_Pos 3 /**< (SUPC_STATUS) BOD12 Ready Position */
#define SUPC_STATUS_BOD12RDY_Msk (_U_(0x1) << SUPC_STATUS_BOD12RDY_Pos) /**< (SUPC_STATUS) BOD12 Ready Mask */
#define SUPC_STATUS_BOD12RDY SUPC_STATUS_BOD12RDY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use SUPC_STATUS_BOD12RDY_Msk instead */
#define SUPC_STATUS_BOD12DET_Pos 4 /**< (SUPC_STATUS) BOD12 Detection Position */
#define SUPC_STATUS_BOD12DET_Msk (_U_(0x1) << SUPC_STATUS_BOD12DET_Pos) /**< (SUPC_STATUS) BOD12 Detection Mask */
#define SUPC_STATUS_BOD12DET SUPC_STATUS_BOD12DET_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use SUPC_STATUS_BOD12DET_Msk instead */
#define SUPC_STATUS_B12SRDY_Pos 5 /**< (SUPC_STATUS) BOD12 Synchronization Ready Position */
#define SUPC_STATUS_B12SRDY_Msk (_U_(0x1) << SUPC_STATUS_B12SRDY_Pos) /**< (SUPC_STATUS) BOD12 Synchronization Ready Mask */
#define SUPC_STATUS_B12SRDY SUPC_STATUS_B12SRDY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use SUPC_STATUS_B12SRDY_Msk instead */
#define SUPC_STATUS_VREGRDY_Pos 8 /**< (SUPC_STATUS) Voltage Regulator Ready Position */
#define SUPC_STATUS_VREGRDY_Msk (_U_(0x1) << SUPC_STATUS_VREGRDY_Pos) /**< (SUPC_STATUS) Voltage Regulator Ready Mask */
#define SUPC_STATUS_VREGRDY SUPC_STATUS_VREGRDY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use SUPC_STATUS_VREGRDY_Msk instead */
#define SUPC_STATUS_VCORERDY_Pos 10 /**< (SUPC_STATUS) VDDCORE Ready Position */
#define SUPC_STATUS_VCORERDY_Msk (_U_(0x1) << SUPC_STATUS_VCORERDY_Pos) /**< (SUPC_STATUS) VDDCORE Ready Mask */
#define SUPC_STATUS_VCORERDY SUPC_STATUS_VCORERDY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use SUPC_STATUS_VCORERDY_Msk instead */
#define SUPC_STATUS_ULPVREFRDY_Pos 12 /**< (SUPC_STATUS) Low Power Voltage Reference Ready Position */
#define SUPC_STATUS_ULPVREFRDY_Msk (_U_(0x1) << SUPC_STATUS_ULPVREFRDY_Pos) /**< (SUPC_STATUS) Low Power Voltage Reference Ready Mask */
#define SUPC_STATUS_ULPVREFRDY SUPC_STATUS_ULPVREFRDY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use SUPC_STATUS_ULPVREFRDY_Msk instead */
#define SUPC_STATUS_ULPBIASRDY_Pos 13 /**< (SUPC_STATUS) Low Power Voltage Bias Ready Position */
#define SUPC_STATUS_ULPBIASRDY_Msk (_U_(0x1) << SUPC_STATUS_ULPBIASRDY_Pos) /**< (SUPC_STATUS) Low Power Voltage Bias Ready Mask */
#define SUPC_STATUS_ULPBIASRDY SUPC_STATUS_ULPBIASRDY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use SUPC_STATUS_ULPBIASRDY_Msk instead */
#define SUPC_STATUS_MASK _U_(0x353F) /**< \deprecated (SUPC_STATUS) Register MASK (Use SUPC_STATUS_Msk instead) */
#define SUPC_STATUS_Msk _U_(0x353F) /**< (SUPC_STATUS) Register Mask */
/* -------- SUPC_BOD33 : (SUPC Offset: 0x10) (R/W 32) BOD33 Control -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t :1; /**< bit: 0 Reserved */
uint32_t ENABLE:1; /**< bit: 1 Enable */
uint32_t HYST:1; /**< bit: 2 Hysteresis Enable */
uint32_t ACTION:2; /**< bit: 3..4 Action when Threshold Crossed */
uint32_t STDBYCFG:1; /**< bit: 5 Configuration in Standby mode */
uint32_t RUNSTDBY:1; /**< bit: 6 Run during Standby */
uint32_t :1; /**< bit: 7 Reserved */
uint32_t ACTCFG:1; /**< bit: 8 Configuration in Active mode */
uint32_t :2; /**< bit: 9..10 Reserved */
uint32_t REFSEL:1; /**< bit: 11 BOD33 Voltage Reference Selection */
uint32_t PSEL:4; /**< bit: 12..15 Prescaler Select */
uint32_t LEVEL:6; /**< bit: 16..21 Threshold Level for VDD */
uint32_t :10; /**< bit: 22..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} SUPC_BOD33_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define SUPC_BOD33_OFFSET (0x10) /**< (SUPC_BOD33) BOD33 Control Offset */
#define SUPC_BOD33_RESETVALUE _U_(0x00) /**< (SUPC_BOD33) BOD33 Control Reset Value */
#define SUPC_BOD33_ENABLE_Pos 1 /**< (SUPC_BOD33) Enable Position */
#define SUPC_BOD33_ENABLE_Msk (_U_(0x1) << SUPC_BOD33_ENABLE_Pos) /**< (SUPC_BOD33) Enable Mask */
#define SUPC_BOD33_ENABLE SUPC_BOD33_ENABLE_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use SUPC_BOD33_ENABLE_Msk instead */
#define SUPC_BOD33_HYST_Pos 2 /**< (SUPC_BOD33) Hysteresis Enable Position */
#define SUPC_BOD33_HYST_Msk (_U_(0x1) << SUPC_BOD33_HYST_Pos) /**< (SUPC_BOD33) Hysteresis Enable Mask */
#define SUPC_BOD33_HYST SUPC_BOD33_HYST_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use SUPC_BOD33_HYST_Msk instead */
#define SUPC_BOD33_ACTION_Pos 3 /**< (SUPC_BOD33) Action when Threshold Crossed Position */
#define SUPC_BOD33_ACTION_Msk (_U_(0x3) << SUPC_BOD33_ACTION_Pos) /**< (SUPC_BOD33) Action when Threshold Crossed Mask */
#define SUPC_BOD33_ACTION(value) (SUPC_BOD33_ACTION_Msk & ((value) << SUPC_BOD33_ACTION_Pos))
#define SUPC_BOD33_ACTION_NONE_Val _U_(0x0) /**< (SUPC_BOD33) No action */
#define SUPC_BOD33_ACTION_RESET_Val _U_(0x1) /**< (SUPC_BOD33) The BOD33 generates a reset */
#define SUPC_BOD33_ACTION_INT_Val _U_(0x2) /**< (SUPC_BOD33) The BOD33 generates an interrupt */
#define SUPC_BOD33_ACTION_BKUP_Val _U_(0x3) /**< (SUPC_BOD33) The BOD33 puts the device in backup sleep mode if VMON=0 */
#define SUPC_BOD33_ACTION_NONE (SUPC_BOD33_ACTION_NONE_Val << SUPC_BOD33_ACTION_Pos) /**< (SUPC_BOD33) No action Position */
#define SUPC_BOD33_ACTION_RESET (SUPC_BOD33_ACTION_RESET_Val << SUPC_BOD33_ACTION_Pos) /**< (SUPC_BOD33) The BOD33 generates a reset Position */
#define SUPC_BOD33_ACTION_INT (SUPC_BOD33_ACTION_INT_Val << SUPC_BOD33_ACTION_Pos) /**< (SUPC_BOD33) The BOD33 generates an interrupt Position */
#define SUPC_BOD33_ACTION_BKUP (SUPC_BOD33_ACTION_BKUP_Val << SUPC_BOD33_ACTION_Pos) /**< (SUPC_BOD33) The BOD33 puts the device in backup sleep mode if VMON=0 Position */
#define SUPC_BOD33_STDBYCFG_Pos 5 /**< (SUPC_BOD33) Configuration in Standby mode Position */
#define SUPC_BOD33_STDBYCFG_Msk (_U_(0x1) << SUPC_BOD33_STDBYCFG_Pos) /**< (SUPC_BOD33) Configuration in Standby mode Mask */
#define SUPC_BOD33_STDBYCFG SUPC_BOD33_STDBYCFG_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use SUPC_BOD33_STDBYCFG_Msk instead */
#define SUPC_BOD33_RUNSTDBY_Pos 6 /**< (SUPC_BOD33) Run during Standby Position */
#define SUPC_BOD33_RUNSTDBY_Msk (_U_(0x1) << SUPC_BOD33_RUNSTDBY_Pos) /**< (SUPC_BOD33) Run during Standby Mask */
#define SUPC_BOD33_RUNSTDBY SUPC_BOD33_RUNSTDBY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use SUPC_BOD33_RUNSTDBY_Msk instead */
#define SUPC_BOD33_ACTCFG_Pos 8 /**< (SUPC_BOD33) Configuration in Active mode Position */
#define SUPC_BOD33_ACTCFG_Msk (_U_(0x1) << SUPC_BOD33_ACTCFG_Pos) /**< (SUPC_BOD33) Configuration in Active mode Mask */
#define SUPC_BOD33_ACTCFG SUPC_BOD33_ACTCFG_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use SUPC_BOD33_ACTCFG_Msk instead */
#define SUPC_BOD33_REFSEL_Pos 11 /**< (SUPC_BOD33) BOD33 Voltage Reference Selection Position */
#define SUPC_BOD33_REFSEL_Msk (_U_(0x1) << SUPC_BOD33_REFSEL_Pos) /**< (SUPC_BOD33) BOD33 Voltage Reference Selection Mask */
#define SUPC_BOD33_REFSEL SUPC_BOD33_REFSEL_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use SUPC_BOD33_REFSEL_Msk instead */
#define SUPC_BOD33_REFSEL_SEL_VREFDETREF_Val _U_(0x0) /**< (SUPC_BOD33) Selects VREFDETREF for the BOD33 */
#define SUPC_BOD33_REFSEL_SEL_ULPVREF_Val _U_(0x1) /**< (SUPC_BOD33) Selects ULPVREF for the BOD33 */
#define SUPC_BOD33_REFSEL_SEL_VREFDETREF (SUPC_BOD33_REFSEL_SEL_VREFDETREF_Val << SUPC_BOD33_REFSEL_Pos) /**< (SUPC_BOD33) Selects VREFDETREF for the BOD33 Position */
#define SUPC_BOD33_REFSEL_SEL_ULPVREF (SUPC_BOD33_REFSEL_SEL_ULPVREF_Val << SUPC_BOD33_REFSEL_Pos) /**< (SUPC_BOD33) Selects ULPVREF for the BOD33 Position */
#define SUPC_BOD33_PSEL_Pos 12 /**< (SUPC_BOD33) Prescaler Select Position */
#define SUPC_BOD33_PSEL_Msk (_U_(0xF) << SUPC_BOD33_PSEL_Pos) /**< (SUPC_BOD33) Prescaler Select Mask */
#define SUPC_BOD33_PSEL(value) (SUPC_BOD33_PSEL_Msk & ((value) << SUPC_BOD33_PSEL_Pos))
#define SUPC_BOD33_PSEL_DIV2_Val _U_(0x0) /**< (SUPC_BOD33) Divide clock by 2 */
#define SUPC_BOD33_PSEL_DIV4_Val _U_(0x1) /**< (SUPC_BOD33) Divide clock by 4 */
#define SUPC_BOD33_PSEL_DIV8_Val _U_(0x2) /**< (SUPC_BOD33) Divide clock by 8 */
#define SUPC_BOD33_PSEL_DIV16_Val _U_(0x3) /**< (SUPC_BOD33) Divide clock by 16 */
#define SUPC_BOD33_PSEL_DIV32_Val _U_(0x4) /**< (SUPC_BOD33) Divide clock by 32 */
#define SUPC_BOD33_PSEL_DIV64_Val _U_(0x5) /**< (SUPC_BOD33) Divide clock by 64 */
#define SUPC_BOD33_PSEL_DIV128_Val _U_(0x6) /**< (SUPC_BOD33) Divide clock by 128 */
#define SUPC_BOD33_PSEL_DIV256_Val _U_(0x7) /**< (SUPC_BOD33) Divide clock by 256 */
#define SUPC_BOD33_PSEL_DIV512_Val _U_(0x8) /**< (SUPC_BOD33) Divide clock by 512 */
#define SUPC_BOD33_PSEL_DIV1024_Val _U_(0x9) /**< (SUPC_BOD33) Divide clock by 1024 */
#define SUPC_BOD33_PSEL_DIV2048_Val _U_(0xA) /**< (SUPC_BOD33) Divide clock by 2048 */
#define SUPC_BOD33_PSEL_DIV4096_Val _U_(0xB) /**< (SUPC_BOD33) Divide clock by 4096 */
#define SUPC_BOD33_PSEL_DIV8192_Val _U_(0xC) /**< (SUPC_BOD33) Divide clock by 8192 */
#define SUPC_BOD33_PSEL_DIV16384_Val _U_(0xD) /**< (SUPC_BOD33) Divide clock by 16384 */
#define SUPC_BOD33_PSEL_DIV32768_Val _U_(0xE) /**< (SUPC_BOD33) Divide clock by 32768 */
#define SUPC_BOD33_PSEL_DIV65536_Val _U_(0xF) /**< (SUPC_BOD33) Divide clock by 65536 */
#define SUPC_BOD33_PSEL_DIV2 (SUPC_BOD33_PSEL_DIV2_Val << SUPC_BOD33_PSEL_Pos) /**< (SUPC_BOD33) Divide clock by 2 Position */
#define SUPC_BOD33_PSEL_DIV4 (SUPC_BOD33_PSEL_DIV4_Val << SUPC_BOD33_PSEL_Pos) /**< (SUPC_BOD33) Divide clock by 4 Position */
#define SUPC_BOD33_PSEL_DIV8 (SUPC_BOD33_PSEL_DIV8_Val << SUPC_BOD33_PSEL_Pos) /**< (SUPC_BOD33) Divide clock by 8 Position */
#define SUPC_BOD33_PSEL_DIV16 (SUPC_BOD33_PSEL_DIV16_Val << SUPC_BOD33_PSEL_Pos) /**< (SUPC_BOD33) Divide clock by 16 Position */
#define SUPC_BOD33_PSEL_DIV32 (SUPC_BOD33_PSEL_DIV32_Val << SUPC_BOD33_PSEL_Pos) /**< (SUPC_BOD33) Divide clock by 32 Position */
#define SUPC_BOD33_PSEL_DIV64 (SUPC_BOD33_PSEL_DIV64_Val << SUPC_BOD33_PSEL_Pos) /**< (SUPC_BOD33) Divide clock by 64 Position */
#define SUPC_BOD33_PSEL_DIV128 (SUPC_BOD33_PSEL_DIV128_Val << SUPC_BOD33_PSEL_Pos) /**< (SUPC_BOD33) Divide clock by 128 Position */
#define SUPC_BOD33_PSEL_DIV256 (SUPC_BOD33_PSEL_DIV256_Val << SUPC_BOD33_PSEL_Pos) /**< (SUPC_BOD33) Divide clock by 256 Position */
#define SUPC_BOD33_PSEL_DIV512 (SUPC_BOD33_PSEL_DIV512_Val << SUPC_BOD33_PSEL_Pos) /**< (SUPC_BOD33) Divide clock by 512 Position */
#define SUPC_BOD33_PSEL_DIV1024 (SUPC_BOD33_PSEL_DIV1024_Val << SUPC_BOD33_PSEL_Pos) /**< (SUPC_BOD33) Divide clock by 1024 Position */
#define SUPC_BOD33_PSEL_DIV2048 (SUPC_BOD33_PSEL_DIV2048_Val << SUPC_BOD33_PSEL_Pos) /**< (SUPC_BOD33) Divide clock by 2048 Position */
#define SUPC_BOD33_PSEL_DIV4096 (SUPC_BOD33_PSEL_DIV4096_Val << SUPC_BOD33_PSEL_Pos) /**< (SUPC_BOD33) Divide clock by 4096 Position */
#define SUPC_BOD33_PSEL_DIV8192 (SUPC_BOD33_PSEL_DIV8192_Val << SUPC_BOD33_PSEL_Pos) /**< (SUPC_BOD33) Divide clock by 8192 Position */
#define SUPC_BOD33_PSEL_DIV16384 (SUPC_BOD33_PSEL_DIV16384_Val << SUPC_BOD33_PSEL_Pos) /**< (SUPC_BOD33) Divide clock by 16384 Position */
#define SUPC_BOD33_PSEL_DIV32768 (SUPC_BOD33_PSEL_DIV32768_Val << SUPC_BOD33_PSEL_Pos) /**< (SUPC_BOD33) Divide clock by 32768 Position */
#define SUPC_BOD33_PSEL_DIV65536 (SUPC_BOD33_PSEL_DIV65536_Val << SUPC_BOD33_PSEL_Pos) /**< (SUPC_BOD33) Divide clock by 65536 Position */
#define SUPC_BOD33_LEVEL_Pos 16 /**< (SUPC_BOD33) Threshold Level for VDD Position */
#define SUPC_BOD33_LEVEL_Msk (_U_(0x3F) << SUPC_BOD33_LEVEL_Pos) /**< (SUPC_BOD33) Threshold Level for VDD Mask */
#define SUPC_BOD33_LEVEL(value) (SUPC_BOD33_LEVEL_Msk & ((value) << SUPC_BOD33_LEVEL_Pos))
#define SUPC_BOD33_MASK _U_(0x3FF97E) /**< \deprecated (SUPC_BOD33) Register MASK (Use SUPC_BOD33_Msk instead) */
#define SUPC_BOD33_Msk _U_(0x3FF97E) /**< (SUPC_BOD33) Register Mask */
/* -------- SUPC_BOD12 : (SUPC Offset: 0x14) (R/W 32) BOD12 Control -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t :1; /**< bit: 0 Reserved */
uint32_t ENABLE:1; /**< bit: 1 Enable */
uint32_t HYST:1; /**< bit: 2 Hysteresis Enable */
uint32_t ACTION:2; /**< bit: 3..4 Action when Threshold Crossed */
uint32_t STDBYCFG:1; /**< bit: 5 Configuration in Standby mode */
uint32_t RUNSTDBY:1; /**< bit: 6 Run during Standby */
uint32_t :1; /**< bit: 7 Reserved */
uint32_t ACTCFG:1; /**< bit: 8 Configuration in Active mode */
uint32_t :3; /**< bit: 9..11 Reserved */
uint32_t PSEL:4; /**< bit: 12..15 Prescaler Select */
uint32_t LEVEL:6; /**< bit: 16..21 Threshold Level */
uint32_t :10; /**< bit: 22..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} SUPC_BOD12_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define SUPC_BOD12_OFFSET (0x14) /**< (SUPC_BOD12) BOD12 Control Offset */
#define SUPC_BOD12_RESETVALUE _U_(0x00) /**< (SUPC_BOD12) BOD12 Control Reset Value */
#define SUPC_BOD12_ENABLE_Pos 1 /**< (SUPC_BOD12) Enable Position */
#define SUPC_BOD12_ENABLE_Msk (_U_(0x1) << SUPC_BOD12_ENABLE_Pos) /**< (SUPC_BOD12) Enable Mask */
#define SUPC_BOD12_ENABLE SUPC_BOD12_ENABLE_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use SUPC_BOD12_ENABLE_Msk instead */
#define SUPC_BOD12_HYST_Pos 2 /**< (SUPC_BOD12) Hysteresis Enable Position */
#define SUPC_BOD12_HYST_Msk (_U_(0x1) << SUPC_BOD12_HYST_Pos) /**< (SUPC_BOD12) Hysteresis Enable Mask */
#define SUPC_BOD12_HYST SUPC_BOD12_HYST_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use SUPC_BOD12_HYST_Msk instead */
#define SUPC_BOD12_ACTION_Pos 3 /**< (SUPC_BOD12) Action when Threshold Crossed Position */
#define SUPC_BOD12_ACTION_Msk (_U_(0x3) << SUPC_BOD12_ACTION_Pos) /**< (SUPC_BOD12) Action when Threshold Crossed Mask */
#define SUPC_BOD12_ACTION(value) (SUPC_BOD12_ACTION_Msk & ((value) << SUPC_BOD12_ACTION_Pos))
#define SUPC_BOD12_ACTION_NONE_Val _U_(0x0) /**< (SUPC_BOD12) No action */
#define SUPC_BOD12_ACTION_RESET_Val _U_(0x1) /**< (SUPC_BOD12) The BOD12 generates a reset */
#define SUPC_BOD12_ACTION_INT_Val _U_(0x2) /**< (SUPC_BOD12) The BOD12 generates an interrupt */
#define SUPC_BOD12_ACTION_NONE (SUPC_BOD12_ACTION_NONE_Val << SUPC_BOD12_ACTION_Pos) /**< (SUPC_BOD12) No action Position */
#define SUPC_BOD12_ACTION_RESET (SUPC_BOD12_ACTION_RESET_Val << SUPC_BOD12_ACTION_Pos) /**< (SUPC_BOD12) The BOD12 generates a reset Position */
#define SUPC_BOD12_ACTION_INT (SUPC_BOD12_ACTION_INT_Val << SUPC_BOD12_ACTION_Pos) /**< (SUPC_BOD12) The BOD12 generates an interrupt Position */
#define SUPC_BOD12_STDBYCFG_Pos 5 /**< (SUPC_BOD12) Configuration in Standby mode Position */
#define SUPC_BOD12_STDBYCFG_Msk (_U_(0x1) << SUPC_BOD12_STDBYCFG_Pos) /**< (SUPC_BOD12) Configuration in Standby mode Mask */
#define SUPC_BOD12_STDBYCFG SUPC_BOD12_STDBYCFG_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use SUPC_BOD12_STDBYCFG_Msk instead */
#define SUPC_BOD12_RUNSTDBY_Pos 6 /**< (SUPC_BOD12) Run during Standby Position */
#define SUPC_BOD12_RUNSTDBY_Msk (_U_(0x1) << SUPC_BOD12_RUNSTDBY_Pos) /**< (SUPC_BOD12) Run during Standby Mask */
#define SUPC_BOD12_RUNSTDBY SUPC_BOD12_RUNSTDBY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use SUPC_BOD12_RUNSTDBY_Msk instead */
#define SUPC_BOD12_ACTCFG_Pos 8 /**< (SUPC_BOD12) Configuration in Active mode Position */
#define SUPC_BOD12_ACTCFG_Msk (_U_(0x1) << SUPC_BOD12_ACTCFG_Pos) /**< (SUPC_BOD12) Configuration in Active mode Mask */
#define SUPC_BOD12_ACTCFG SUPC_BOD12_ACTCFG_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use SUPC_BOD12_ACTCFG_Msk instead */
#define SUPC_BOD12_PSEL_Pos 12 /**< (SUPC_BOD12) Prescaler Select Position */
#define SUPC_BOD12_PSEL_Msk (_U_(0xF) << SUPC_BOD12_PSEL_Pos) /**< (SUPC_BOD12) Prescaler Select Mask */
#define SUPC_BOD12_PSEL(value) (SUPC_BOD12_PSEL_Msk & ((value) << SUPC_BOD12_PSEL_Pos))
#define SUPC_BOD12_PSEL_DIV2_Val _U_(0x0) /**< (SUPC_BOD12) Divide clock by 2 */
#define SUPC_BOD12_PSEL_DIV4_Val _U_(0x1) /**< (SUPC_BOD12) Divide clock by 4 */
#define SUPC_BOD12_PSEL_DIV8_Val _U_(0x2) /**< (SUPC_BOD12) Divide clock by 8 */
#define SUPC_BOD12_PSEL_DIV16_Val _U_(0x3) /**< (SUPC_BOD12) Divide clock by 16 */
#define SUPC_BOD12_PSEL_DIV32_Val _U_(0x4) /**< (SUPC_BOD12) Divide clock by 32 */
#define SUPC_BOD12_PSEL_DIV64_Val _U_(0x5) /**< (SUPC_BOD12) Divide clock by 64 */
#define SUPC_BOD12_PSEL_DIV128_Val _U_(0x6) /**< (SUPC_BOD12) Divide clock by 128 */
#define SUPC_BOD12_PSEL_DIV256_Val _U_(0x7) /**< (SUPC_BOD12) Divide clock by 256 */
#define SUPC_BOD12_PSEL_DIV512_Val _U_(0x8) /**< (SUPC_BOD12) Divide clock by 512 */
#define SUPC_BOD12_PSEL_DIV1024_Val _U_(0x9) /**< (SUPC_BOD12) Divide clock by 1024 */
#define SUPC_BOD12_PSEL_DIV2048_Val _U_(0xA) /**< (SUPC_BOD12) Divide clock by 2048 */
#define SUPC_BOD12_PSEL_DIV4096_Val _U_(0xB) /**< (SUPC_BOD12) Divide clock by 4096 */
#define SUPC_BOD12_PSEL_DIV8192_Val _U_(0xC) /**< (SUPC_BOD12) Divide clock by 8192 */
#define SUPC_BOD12_PSEL_DIV16384_Val _U_(0xD) /**< (SUPC_BOD12) Divide clock by 16384 */
#define SUPC_BOD12_PSEL_DIV32768_Val _U_(0xE) /**< (SUPC_BOD12) Divide clock by 32768 */
#define SUPC_BOD12_PSEL_DIV65536_Val _U_(0xF) /**< (SUPC_BOD12) Divide clock by 65536 */
#define SUPC_BOD12_PSEL_DIV2 (SUPC_BOD12_PSEL_DIV2_Val << SUPC_BOD12_PSEL_Pos) /**< (SUPC_BOD12) Divide clock by 2 Position */
#define SUPC_BOD12_PSEL_DIV4 (SUPC_BOD12_PSEL_DIV4_Val << SUPC_BOD12_PSEL_Pos) /**< (SUPC_BOD12) Divide clock by 4 Position */
#define SUPC_BOD12_PSEL_DIV8 (SUPC_BOD12_PSEL_DIV8_Val << SUPC_BOD12_PSEL_Pos) /**< (SUPC_BOD12) Divide clock by 8 Position */
#define SUPC_BOD12_PSEL_DIV16 (SUPC_BOD12_PSEL_DIV16_Val << SUPC_BOD12_PSEL_Pos) /**< (SUPC_BOD12) Divide clock by 16 Position */
#define SUPC_BOD12_PSEL_DIV32 (SUPC_BOD12_PSEL_DIV32_Val << SUPC_BOD12_PSEL_Pos) /**< (SUPC_BOD12) Divide clock by 32 Position */
#define SUPC_BOD12_PSEL_DIV64 (SUPC_BOD12_PSEL_DIV64_Val << SUPC_BOD12_PSEL_Pos) /**< (SUPC_BOD12) Divide clock by 64 Position */
#define SUPC_BOD12_PSEL_DIV128 (SUPC_BOD12_PSEL_DIV128_Val << SUPC_BOD12_PSEL_Pos) /**< (SUPC_BOD12) Divide clock by 128 Position */
#define SUPC_BOD12_PSEL_DIV256 (SUPC_BOD12_PSEL_DIV256_Val << SUPC_BOD12_PSEL_Pos) /**< (SUPC_BOD12) Divide clock by 256 Position */
#define SUPC_BOD12_PSEL_DIV512 (SUPC_BOD12_PSEL_DIV512_Val << SUPC_BOD12_PSEL_Pos) /**< (SUPC_BOD12) Divide clock by 512 Position */
#define SUPC_BOD12_PSEL_DIV1024 (SUPC_BOD12_PSEL_DIV1024_Val << SUPC_BOD12_PSEL_Pos) /**< (SUPC_BOD12) Divide clock by 1024 Position */
#define SUPC_BOD12_PSEL_DIV2048 (SUPC_BOD12_PSEL_DIV2048_Val << SUPC_BOD12_PSEL_Pos) /**< (SUPC_BOD12) Divide clock by 2048 Position */
#define SUPC_BOD12_PSEL_DIV4096 (SUPC_BOD12_PSEL_DIV4096_Val << SUPC_BOD12_PSEL_Pos) /**< (SUPC_BOD12) Divide clock by 4096 Position */
#define SUPC_BOD12_PSEL_DIV8192 (SUPC_BOD12_PSEL_DIV8192_Val << SUPC_BOD12_PSEL_Pos) /**< (SUPC_BOD12) Divide clock by 8192 Position */
#define SUPC_BOD12_PSEL_DIV16384 (SUPC_BOD12_PSEL_DIV16384_Val << SUPC_BOD12_PSEL_Pos) /**< (SUPC_BOD12) Divide clock by 16384 Position */
#define SUPC_BOD12_PSEL_DIV32768 (SUPC_BOD12_PSEL_DIV32768_Val << SUPC_BOD12_PSEL_Pos) /**< (SUPC_BOD12) Divide clock by 32768 Position */
#define SUPC_BOD12_PSEL_DIV65536 (SUPC_BOD12_PSEL_DIV65536_Val << SUPC_BOD12_PSEL_Pos) /**< (SUPC_BOD12) Divide clock by 65536 Position */
#define SUPC_BOD12_LEVEL_Pos 16 /**< (SUPC_BOD12) Threshold Level Position */
#define SUPC_BOD12_LEVEL_Msk (_U_(0x3F) << SUPC_BOD12_LEVEL_Pos) /**< (SUPC_BOD12) Threshold Level Mask */
#define SUPC_BOD12_LEVEL(value) (SUPC_BOD12_LEVEL_Msk & ((value) << SUPC_BOD12_LEVEL_Pos))
#define SUPC_BOD12_MASK _U_(0x3FF17E) /**< \deprecated (SUPC_BOD12) Register MASK (Use SUPC_BOD12_Msk instead) */
#define SUPC_BOD12_Msk _U_(0x3FF17E) /**< (SUPC_BOD12) Register Mask */
/* -------- SUPC_VREG : (SUPC Offset: 0x18) (R/W 32) VREG Control -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t :1; /**< bit: 0 Reserved */
uint32_t ENABLE:1; /**< bit: 1 Enable */
uint32_t SEL:2; /**< bit: 2..3 Voltage Regulator Selection in active mode */
uint32_t :1; /**< bit: 4 Reserved */
uint32_t STDBYPL0:1; /**< bit: 5 Standby in PL0 */
uint32_t RUNSTDBY:1; /**< bit: 6 Run during Standby */
uint32_t :1; /**< bit: 7 Reserved */
uint32_t LPEFF:1; /**< bit: 8 Low Power efficiency */
uint32_t VREFSEL:1; /**< bit: 9 Voltage Regulator Voltage Reference Selection */
uint32_t :6; /**< bit: 10..15 Reserved */
uint32_t VSVSTEP:4; /**< bit: 16..19 Voltage Scaling Voltage Step */
uint32_t :4; /**< bit: 20..23 Reserved */
uint32_t VSPER:8; /**< bit: 24..31 Voltage Scaling Period */
} bit; /**< Structure used for bit access */
struct {
uint32_t :5; /**< bit: 0..4 Reserved */
uint32_t STDBYPL:1; /**< bit: 5 Standby in PLx */
uint32_t :26; /**< bit: 6..31 Reserved */
} vec; /**< Structure used for vec access */
uint32_t reg; /**< Type used for register access */
} SUPC_VREG_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define SUPC_VREG_OFFSET (0x18) /**< (SUPC_VREG) VREG Control Offset */
#define SUPC_VREG_RESETVALUE _U_(0x02) /**< (SUPC_VREG) VREG Control Reset Value */
#define SUPC_VREG_ENABLE_Pos 1 /**< (SUPC_VREG) Enable Position */
#define SUPC_VREG_ENABLE_Msk (_U_(0x1) << SUPC_VREG_ENABLE_Pos) /**< (SUPC_VREG) Enable Mask */
#define SUPC_VREG_ENABLE SUPC_VREG_ENABLE_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use SUPC_VREG_ENABLE_Msk instead */
#define SUPC_VREG_SEL_Pos 2 /**< (SUPC_VREG) Voltage Regulator Selection in active mode Position */
#define SUPC_VREG_SEL_Msk (_U_(0x3) << SUPC_VREG_SEL_Pos) /**< (SUPC_VREG) Voltage Regulator Selection in active mode Mask */
#define SUPC_VREG_SEL(value) (SUPC_VREG_SEL_Msk & ((value) << SUPC_VREG_SEL_Pos))
#define SUPC_VREG_SEL_LDO_Val _U_(0x0) /**< (SUPC_VREG) LDO selection */
#define SUPC_VREG_SEL_BUCK_Val _U_(0x1) /**< (SUPC_VREG) Buck selection */
#define SUPC_VREG_SEL_LDO (SUPC_VREG_SEL_LDO_Val << SUPC_VREG_SEL_Pos) /**< (SUPC_VREG) LDO selection Position */
#define SUPC_VREG_SEL_BUCK (SUPC_VREG_SEL_BUCK_Val << SUPC_VREG_SEL_Pos) /**< (SUPC_VREG) Buck selection Position */
#define SUPC_VREG_STDBYPL0_Pos 5 /**< (SUPC_VREG) Standby in PL0 Position */
#define SUPC_VREG_STDBYPL0_Msk (_U_(0x1) << SUPC_VREG_STDBYPL0_Pos) /**< (SUPC_VREG) Standby in PL0 Mask */
#define SUPC_VREG_STDBYPL0 SUPC_VREG_STDBYPL0_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use SUPC_VREG_STDBYPL0_Msk instead */
#define SUPC_VREG_RUNSTDBY_Pos 6 /**< (SUPC_VREG) Run during Standby Position */
#define SUPC_VREG_RUNSTDBY_Msk (_U_(0x1) << SUPC_VREG_RUNSTDBY_Pos) /**< (SUPC_VREG) Run during Standby Mask */
#define SUPC_VREG_RUNSTDBY SUPC_VREG_RUNSTDBY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use SUPC_VREG_RUNSTDBY_Msk instead */
#define SUPC_VREG_LPEFF_Pos 8 /**< (SUPC_VREG) Low Power efficiency Position */
#define SUPC_VREG_LPEFF_Msk (_U_(0x1) << SUPC_VREG_LPEFF_Pos) /**< (SUPC_VREG) Low Power efficiency Mask */
#define SUPC_VREG_LPEFF SUPC_VREG_LPEFF_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use SUPC_VREG_LPEFF_Msk instead */
#define SUPC_VREG_VREFSEL_Pos 9 /**< (SUPC_VREG) Voltage Regulator Voltage Reference Selection Position */
#define SUPC_VREG_VREFSEL_Msk (_U_(0x1) << SUPC_VREG_VREFSEL_Pos) /**< (SUPC_VREG) Voltage Regulator Voltage Reference Selection Mask */
#define SUPC_VREG_VREFSEL SUPC_VREG_VREFSEL_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use SUPC_VREG_VREFSEL_Msk instead */
#define SUPC_VREG_VSVSTEP_Pos 16 /**< (SUPC_VREG) Voltage Scaling Voltage Step Position */
#define SUPC_VREG_VSVSTEP_Msk (_U_(0xF) << SUPC_VREG_VSVSTEP_Pos) /**< (SUPC_VREG) Voltage Scaling Voltage Step Mask */
#define SUPC_VREG_VSVSTEP(value) (SUPC_VREG_VSVSTEP_Msk & ((value) << SUPC_VREG_VSVSTEP_Pos))
#define SUPC_VREG_VSPER_Pos 24 /**< (SUPC_VREG) Voltage Scaling Period Position */
#define SUPC_VREG_VSPER_Msk (_U_(0xFF) << SUPC_VREG_VSPER_Pos) /**< (SUPC_VREG) Voltage Scaling Period Mask */
#define SUPC_VREG_VSPER(value) (SUPC_VREG_VSPER_Msk & ((value) << SUPC_VREG_VSPER_Pos))
#define SUPC_VREG_MASK _U_(0xFF0F036E) /**< \deprecated (SUPC_VREG) Register MASK (Use SUPC_VREG_Msk instead) */
#define SUPC_VREG_Msk _U_(0xFF0F036E) /**< (SUPC_VREG) Register Mask */
#define SUPC_VREG_STDBYPL_Pos 5 /**< (SUPC_VREG Position) Standby in PLx */
#define SUPC_VREG_STDBYPL_Msk (_U_(0x1) << SUPC_VREG_STDBYPL_Pos) /**< (SUPC_VREG Mask) STDBYPL */
#define SUPC_VREG_STDBYPL(value) (SUPC_VREG_STDBYPL_Msk & ((value) << SUPC_VREG_STDBYPL_Pos))
/* -------- SUPC_VREF : (SUPC Offset: 0x1c) (R/W 32) VREF Control -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t :1; /**< bit: 0 Reserved */
uint32_t TSEN:1; /**< bit: 1 Temperature Sensor Output Enable */
uint32_t VREFOE:1; /**< bit: 2 Voltage Reference Output Enable */
uint32_t TSSEL:1; /**< bit: 3 Temperature Sensor Selection */
uint32_t :2; /**< bit: 4..5 Reserved */
uint32_t RUNSTDBY:1; /**< bit: 6 Run during Standby */
uint32_t ONDEMAND:1; /**< bit: 7 On Demand Control */
uint32_t :8; /**< bit: 8..15 Reserved */
uint32_t SEL:4; /**< bit: 16..19 Voltage Reference Selection */
uint32_t :12; /**< bit: 20..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} SUPC_VREF_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define SUPC_VREF_OFFSET (0x1C) /**< (SUPC_VREF) VREF Control Offset */
#define SUPC_VREF_RESETVALUE _U_(0x00) /**< (SUPC_VREF) VREF Control Reset Value */
#define SUPC_VREF_TSEN_Pos 1 /**< (SUPC_VREF) Temperature Sensor Output Enable Position */
#define SUPC_VREF_TSEN_Msk (_U_(0x1) << SUPC_VREF_TSEN_Pos) /**< (SUPC_VREF) Temperature Sensor Output Enable Mask */
#define SUPC_VREF_TSEN SUPC_VREF_TSEN_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use SUPC_VREF_TSEN_Msk instead */
#define SUPC_VREF_VREFOE_Pos 2 /**< (SUPC_VREF) Voltage Reference Output Enable Position */
#define SUPC_VREF_VREFOE_Msk (_U_(0x1) << SUPC_VREF_VREFOE_Pos) /**< (SUPC_VREF) Voltage Reference Output Enable Mask */
#define SUPC_VREF_VREFOE SUPC_VREF_VREFOE_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use SUPC_VREF_VREFOE_Msk instead */
#define SUPC_VREF_TSSEL_Pos 3 /**< (SUPC_VREF) Temperature Sensor Selection Position */
#define SUPC_VREF_TSSEL_Msk (_U_(0x1) << SUPC_VREF_TSSEL_Pos) /**< (SUPC_VREF) Temperature Sensor Selection Mask */
#define SUPC_VREF_TSSEL SUPC_VREF_TSSEL_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use SUPC_VREF_TSSEL_Msk instead */
#define SUPC_VREF_RUNSTDBY_Pos 6 /**< (SUPC_VREF) Run during Standby Position */
#define SUPC_VREF_RUNSTDBY_Msk (_U_(0x1) << SUPC_VREF_RUNSTDBY_Pos) /**< (SUPC_VREF) Run during Standby Mask */
#define SUPC_VREF_RUNSTDBY SUPC_VREF_RUNSTDBY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use SUPC_VREF_RUNSTDBY_Msk instead */
#define SUPC_VREF_ONDEMAND_Pos 7 /**< (SUPC_VREF) On Demand Control Position */
#define SUPC_VREF_ONDEMAND_Msk (_U_(0x1) << SUPC_VREF_ONDEMAND_Pos) /**< (SUPC_VREF) On Demand Control Mask */
#define SUPC_VREF_ONDEMAND SUPC_VREF_ONDEMAND_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use SUPC_VREF_ONDEMAND_Msk instead */
#define SUPC_VREF_SEL_Pos 16 /**< (SUPC_VREF) Voltage Reference Selection Position */
#define SUPC_VREF_SEL_Msk (_U_(0xF) << SUPC_VREF_SEL_Pos) /**< (SUPC_VREF) Voltage Reference Selection Mask */
#define SUPC_VREF_SEL(value) (SUPC_VREF_SEL_Msk & ((value) << SUPC_VREF_SEL_Pos))
#define SUPC_VREF_SEL_1V0_Val _U_(0x0) /**< (SUPC_VREF) 1.0V voltage reference typical value */
#define SUPC_VREF_SEL_1V1_Val _U_(0x1) /**< (SUPC_VREF) 1.1V voltage reference typical value */
#define SUPC_VREF_SEL_1V2_Val _U_(0x2) /**< (SUPC_VREF) 1.2V voltage reference typical value */
#define SUPC_VREF_SEL_1V25_Val _U_(0x3) /**< (SUPC_VREF) 1.25V voltage reference typical value */
#define SUPC_VREF_SEL_2V0_Val _U_(0x4) /**< (SUPC_VREF) 2.0V voltage reference typical value */
#define SUPC_VREF_SEL_2V2_Val _U_(0x5) /**< (SUPC_VREF) 2.2V voltage reference typical value */
#define SUPC_VREF_SEL_2V4_Val _U_(0x6) /**< (SUPC_VREF) 2.4V voltage reference typical value */
#define SUPC_VREF_SEL_2V5_Val _U_(0x7) /**< (SUPC_VREF) 2.5V voltage reference typical value */
#define SUPC_VREF_SEL_1V0 (SUPC_VREF_SEL_1V0_Val << SUPC_VREF_SEL_Pos) /**< (SUPC_VREF) 1.0V voltage reference typical value Position */
#define SUPC_VREF_SEL_1V1 (SUPC_VREF_SEL_1V1_Val << SUPC_VREF_SEL_Pos) /**< (SUPC_VREF) 1.1V voltage reference typical value Position */
#define SUPC_VREF_SEL_1V2 (SUPC_VREF_SEL_1V2_Val << SUPC_VREF_SEL_Pos) /**< (SUPC_VREF) 1.2V voltage reference typical value Position */
#define SUPC_VREF_SEL_1V25 (SUPC_VREF_SEL_1V25_Val << SUPC_VREF_SEL_Pos) /**< (SUPC_VREF) 1.25V voltage reference typical value Position */
#define SUPC_VREF_SEL_2V0 (SUPC_VREF_SEL_2V0_Val << SUPC_VREF_SEL_Pos) /**< (SUPC_VREF) 2.0V voltage reference typical value Position */
#define SUPC_VREF_SEL_2V2 (SUPC_VREF_SEL_2V2_Val << SUPC_VREF_SEL_Pos) /**< (SUPC_VREF) 2.2V voltage reference typical value Position */
#define SUPC_VREF_SEL_2V4 (SUPC_VREF_SEL_2V4_Val << SUPC_VREF_SEL_Pos) /**< (SUPC_VREF) 2.4V voltage reference typical value Position */
#define SUPC_VREF_SEL_2V5 (SUPC_VREF_SEL_2V5_Val << SUPC_VREF_SEL_Pos) /**< (SUPC_VREF) 2.5V voltage reference typical value Position */
#define SUPC_VREF_MASK _U_(0xF00CE) /**< \deprecated (SUPC_VREF) Register MASK (Use SUPC_VREF_Msk instead) */
#define SUPC_VREF_Msk _U_(0xF00CE) /**< (SUPC_VREF) Register Mask */
/* -------- SUPC_EVCTRL : (SUPC Offset: 0x2c) (R/W 32) Event Control -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t :1; /**< bit: 0 Reserved */
uint32_t BOD33DETEO:1; /**< bit: 1 BOD33 Detection Event Output Enable */
uint32_t :2; /**< bit: 2..3 Reserved */
uint32_t BOD12DETEO:1; /**< bit: 4 BOD12 Detection Event Output Enable */
uint32_t :27; /**< bit: 5..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} SUPC_EVCTRL_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define SUPC_EVCTRL_OFFSET (0x2C) /**< (SUPC_EVCTRL) Event Control Offset */
#define SUPC_EVCTRL_RESETVALUE _U_(0x00) /**< (SUPC_EVCTRL) Event Control Reset Value */
#define SUPC_EVCTRL_BOD33DETEO_Pos 1 /**< (SUPC_EVCTRL) BOD33 Detection Event Output Enable Position */
#define SUPC_EVCTRL_BOD33DETEO_Msk (_U_(0x1) << SUPC_EVCTRL_BOD33DETEO_Pos) /**< (SUPC_EVCTRL) BOD33 Detection Event Output Enable Mask */
#define SUPC_EVCTRL_BOD33DETEO SUPC_EVCTRL_BOD33DETEO_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use SUPC_EVCTRL_BOD33DETEO_Msk instead */
#define SUPC_EVCTRL_BOD12DETEO_Pos 4 /**< (SUPC_EVCTRL) BOD12 Detection Event Output Enable Position */
#define SUPC_EVCTRL_BOD12DETEO_Msk (_U_(0x1) << SUPC_EVCTRL_BOD12DETEO_Pos) /**< (SUPC_EVCTRL) BOD12 Detection Event Output Enable Mask */
#define SUPC_EVCTRL_BOD12DETEO SUPC_EVCTRL_BOD12DETEO_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use SUPC_EVCTRL_BOD12DETEO_Msk instead */
#define SUPC_EVCTRL_MASK _U_(0x12) /**< \deprecated (SUPC_EVCTRL) Register MASK (Use SUPC_EVCTRL_Msk instead) */
#define SUPC_EVCTRL_Msk _U_(0x12) /**< (SUPC_EVCTRL) Register Mask */
/* -------- SUPC_VREGSUSP : (SUPC Offset: 0x30) (R/W 32) VREG Suspend Control -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t VREGSEN:1; /**< bit: 0 Enable Voltage Regulator Suspend */
uint32_t :31; /**< bit: 1..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} SUPC_VREGSUSP_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define SUPC_VREGSUSP_OFFSET (0x30) /**< (SUPC_VREGSUSP) VREG Suspend Control Offset */
#define SUPC_VREGSUSP_RESETVALUE _U_(0x00) /**< (SUPC_VREGSUSP) VREG Suspend Control Reset Value */
#define SUPC_VREGSUSP_VREGSEN_Pos 0 /**< (SUPC_VREGSUSP) Enable Voltage Regulator Suspend Position */
#define SUPC_VREGSUSP_VREGSEN_Msk (_U_(0x1) << SUPC_VREGSUSP_VREGSEN_Pos) /**< (SUPC_VREGSUSP) Enable Voltage Regulator Suspend Mask */
#define SUPC_VREGSUSP_VREGSEN SUPC_VREGSUSP_VREGSEN_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use SUPC_VREGSUSP_VREGSEN_Msk instead */
#define SUPC_VREGSUSP_MASK _U_(0x01) /**< \deprecated (SUPC_VREGSUSP) Register MASK (Use SUPC_VREGSUSP_Msk instead) */
#define SUPC_VREGSUSP_Msk _U_(0x01) /**< (SUPC_VREGSUSP) Register Mask */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
/** \brief SUPC hardware registers */
typedef struct { /* Supply Controller */
__IO SUPC_INTENCLR_Type INTENCLR; /**< Offset: 0x00 (R/W 32) Interrupt Enable Clear */
__IO SUPC_INTENSET_Type INTENSET; /**< Offset: 0x04 (R/W 32) Interrupt Enable Set */
__IO SUPC_INTFLAG_Type INTFLAG; /**< Offset: 0x08 (R/W 32) Interrupt Flag Status and Clear */
__I SUPC_STATUS_Type STATUS; /**< Offset: 0x0C (R/ 32) Power and Clocks Status */
__IO SUPC_BOD33_Type BOD33; /**< Offset: 0x10 (R/W 32) BOD33 Control */
__IO SUPC_BOD12_Type BOD12; /**< Offset: 0x14 (R/W 32) BOD12 Control */
__IO SUPC_VREG_Type VREG; /**< Offset: 0x18 (R/W 32) VREG Control */
__IO SUPC_VREF_Type VREF; /**< Offset: 0x1C (R/W 32) VREF Control */
__I uint8_t Reserved1[12];
__IO SUPC_EVCTRL_Type EVCTRL; /**< Offset: 0x2C (R/W 32) Event Control */
__IO SUPC_VREGSUSP_Type VREGSUSP; /**< Offset: 0x30 (R/W 32) VREG Suspend Control */
} Supc;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/** @} end of Supply Controller */
#endif /* _SAML10_SUPC_COMPONENT_H_ */

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,316 @@
/**
* \file
*
* \brief Component description for TRAM
*
* Copyright (c) 2018 Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* 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
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
/* file generated from device description version 2018-08-31T13:51:50Z */
#ifndef _SAML10_TRAM_COMPONENT_H_
#define _SAML10_TRAM_COMPONENT_H_
#define _SAML10_TRAM_COMPONENT_ /**< \deprecated Backward compatibility for ASF */
/** \addtogroup SAML_SAML10 TrustRAM
* @{
*/
/* ========================================================================== */
/** SOFTWARE API DEFINITION FOR TRAM */
/* ========================================================================== */
#define TRAM_U2801 /**< (TRAM) Module ID */
#define REV_TRAM 0x100 /**< (TRAM) Module revision */
/* -------- TRAM_CTRLA : (TRAM Offset: 0x00) (R/W 8) Control -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t SWRST:1; /**< bit: 0 Software Reset */
uint8_t ENABLE:1; /**< bit: 1 Enable */
uint8_t :2; /**< bit: 2..3 Reserved */
uint8_t TAMPERS:1; /**< bit: 4 Tamper Erase */
uint8_t :1; /**< bit: 5 Reserved */
uint8_t DRP:1; /**< bit: 6 Data Remanence Prevention */
uint8_t SILACC:1; /**< bit: 7 Silent Access */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} TRAM_CTRLA_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define TRAM_CTRLA_OFFSET (0x00) /**< (TRAM_CTRLA) Control Offset */
#define TRAM_CTRLA_RESETVALUE _U_(0x00) /**< (TRAM_CTRLA) Control Reset Value */
#define TRAM_CTRLA_SWRST_Pos 0 /**< (TRAM_CTRLA) Software Reset Position */
#define TRAM_CTRLA_SWRST_Msk (_U_(0x1) << TRAM_CTRLA_SWRST_Pos) /**< (TRAM_CTRLA) Software Reset Mask */
#define TRAM_CTRLA_SWRST TRAM_CTRLA_SWRST_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use TRAM_CTRLA_SWRST_Msk instead */
#define TRAM_CTRLA_ENABLE_Pos 1 /**< (TRAM_CTRLA) Enable Position */
#define TRAM_CTRLA_ENABLE_Msk (_U_(0x1) << TRAM_CTRLA_ENABLE_Pos) /**< (TRAM_CTRLA) Enable Mask */
#define TRAM_CTRLA_ENABLE TRAM_CTRLA_ENABLE_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use TRAM_CTRLA_ENABLE_Msk instead */
#define TRAM_CTRLA_TAMPERS_Pos 4 /**< (TRAM_CTRLA) Tamper Erase Position */
#define TRAM_CTRLA_TAMPERS_Msk (_U_(0x1) << TRAM_CTRLA_TAMPERS_Pos) /**< (TRAM_CTRLA) Tamper Erase Mask */
#define TRAM_CTRLA_TAMPERS TRAM_CTRLA_TAMPERS_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use TRAM_CTRLA_TAMPERS_Msk instead */
#define TRAM_CTRLA_DRP_Pos 6 /**< (TRAM_CTRLA) Data Remanence Prevention Position */
#define TRAM_CTRLA_DRP_Msk (_U_(0x1) << TRAM_CTRLA_DRP_Pos) /**< (TRAM_CTRLA) Data Remanence Prevention Mask */
#define TRAM_CTRLA_DRP TRAM_CTRLA_DRP_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use TRAM_CTRLA_DRP_Msk instead */
#define TRAM_CTRLA_SILACC_Pos 7 /**< (TRAM_CTRLA) Silent Access Position */
#define TRAM_CTRLA_SILACC_Msk (_U_(0x1) << TRAM_CTRLA_SILACC_Pos) /**< (TRAM_CTRLA) Silent Access Mask */
#define TRAM_CTRLA_SILACC TRAM_CTRLA_SILACC_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use TRAM_CTRLA_SILACC_Msk instead */
#define TRAM_CTRLA_MASK _U_(0xD3) /**< \deprecated (TRAM_CTRLA) Register MASK (Use TRAM_CTRLA_Msk instead) */
#define TRAM_CTRLA_Msk _U_(0xD3) /**< (TRAM_CTRLA) Register Mask */
/* -------- TRAM_INTENCLR : (TRAM Offset: 0x04) (R/W 8) Interrupt Enable Clear -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t ERR:1; /**< bit: 0 TrustRAM Readout Error Interrupt Enable */
uint8_t DRP:1; /**< bit: 1 Data Remanence Prevention Ended Interrupt Enable */
uint8_t :6; /**< bit: 2..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} TRAM_INTENCLR_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define TRAM_INTENCLR_OFFSET (0x04) /**< (TRAM_INTENCLR) Interrupt Enable Clear Offset */
#define TRAM_INTENCLR_RESETVALUE _U_(0x00) /**< (TRAM_INTENCLR) Interrupt Enable Clear Reset Value */
#define TRAM_INTENCLR_ERR_Pos 0 /**< (TRAM_INTENCLR) TrustRAM Readout Error Interrupt Enable Position */
#define TRAM_INTENCLR_ERR_Msk (_U_(0x1) << TRAM_INTENCLR_ERR_Pos) /**< (TRAM_INTENCLR) TrustRAM Readout Error Interrupt Enable Mask */
#define TRAM_INTENCLR_ERR TRAM_INTENCLR_ERR_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use TRAM_INTENCLR_ERR_Msk instead */
#define TRAM_INTENCLR_DRP_Pos 1 /**< (TRAM_INTENCLR) Data Remanence Prevention Ended Interrupt Enable Position */
#define TRAM_INTENCLR_DRP_Msk (_U_(0x1) << TRAM_INTENCLR_DRP_Pos) /**< (TRAM_INTENCLR) Data Remanence Prevention Ended Interrupt Enable Mask */
#define TRAM_INTENCLR_DRP TRAM_INTENCLR_DRP_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use TRAM_INTENCLR_DRP_Msk instead */
#define TRAM_INTENCLR_MASK _U_(0x03) /**< \deprecated (TRAM_INTENCLR) Register MASK (Use TRAM_INTENCLR_Msk instead) */
#define TRAM_INTENCLR_Msk _U_(0x03) /**< (TRAM_INTENCLR) Register Mask */
/* -------- TRAM_INTENSET : (TRAM Offset: 0x05) (R/W 8) Interrupt Enable Set -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t ERR:1; /**< bit: 0 TrustRAM Readout Error Interrupt Enable */
uint8_t DRP:1; /**< bit: 1 Data Remanence Prevention Ended Interrupt Enable */
uint8_t :6; /**< bit: 2..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} TRAM_INTENSET_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define TRAM_INTENSET_OFFSET (0x05) /**< (TRAM_INTENSET) Interrupt Enable Set Offset */
#define TRAM_INTENSET_RESETVALUE _U_(0x00) /**< (TRAM_INTENSET) Interrupt Enable Set Reset Value */
#define TRAM_INTENSET_ERR_Pos 0 /**< (TRAM_INTENSET) TrustRAM Readout Error Interrupt Enable Position */
#define TRAM_INTENSET_ERR_Msk (_U_(0x1) << TRAM_INTENSET_ERR_Pos) /**< (TRAM_INTENSET) TrustRAM Readout Error Interrupt Enable Mask */
#define TRAM_INTENSET_ERR TRAM_INTENSET_ERR_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use TRAM_INTENSET_ERR_Msk instead */
#define TRAM_INTENSET_DRP_Pos 1 /**< (TRAM_INTENSET) Data Remanence Prevention Ended Interrupt Enable Position */
#define TRAM_INTENSET_DRP_Msk (_U_(0x1) << TRAM_INTENSET_DRP_Pos) /**< (TRAM_INTENSET) Data Remanence Prevention Ended Interrupt Enable Mask */
#define TRAM_INTENSET_DRP TRAM_INTENSET_DRP_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use TRAM_INTENSET_DRP_Msk instead */
#define TRAM_INTENSET_MASK _U_(0x03) /**< \deprecated (TRAM_INTENSET) Register MASK (Use TRAM_INTENSET_Msk instead) */
#define TRAM_INTENSET_Msk _U_(0x03) /**< (TRAM_INTENSET) Register Mask */
/* -------- TRAM_INTFLAG : (TRAM Offset: 0x06) (R/W 8) Interrupt Flag Status and Clear -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union { // __I to avoid read-modify-write on write-to-clear register
struct {
__I uint8_t ERR:1; /**< bit: 0 TrustRAM Readout Error */
__I uint8_t DRP:1; /**< bit: 1 Data Remanence Prevention Ended */
__I uint8_t :6; /**< bit: 2..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} TRAM_INTFLAG_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define TRAM_INTFLAG_OFFSET (0x06) /**< (TRAM_INTFLAG) Interrupt Flag Status and Clear Offset */
#define TRAM_INTFLAG_RESETVALUE _U_(0x00) /**< (TRAM_INTFLAG) Interrupt Flag Status and Clear Reset Value */
#define TRAM_INTFLAG_ERR_Pos 0 /**< (TRAM_INTFLAG) TrustRAM Readout Error Position */
#define TRAM_INTFLAG_ERR_Msk (_U_(0x1) << TRAM_INTFLAG_ERR_Pos) /**< (TRAM_INTFLAG) TrustRAM Readout Error Mask */
#define TRAM_INTFLAG_ERR TRAM_INTFLAG_ERR_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use TRAM_INTFLAG_ERR_Msk instead */
#define TRAM_INTFLAG_DRP_Pos 1 /**< (TRAM_INTFLAG) Data Remanence Prevention Ended Position */
#define TRAM_INTFLAG_DRP_Msk (_U_(0x1) << TRAM_INTFLAG_DRP_Pos) /**< (TRAM_INTFLAG) Data Remanence Prevention Ended Mask */
#define TRAM_INTFLAG_DRP TRAM_INTFLAG_DRP_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use TRAM_INTFLAG_DRP_Msk instead */
#define TRAM_INTFLAG_MASK _U_(0x03) /**< \deprecated (TRAM_INTFLAG) Register MASK (Use TRAM_INTFLAG_Msk instead) */
#define TRAM_INTFLAG_Msk _U_(0x03) /**< (TRAM_INTFLAG) Register Mask */
/* -------- TRAM_STATUS : (TRAM Offset: 0x07) (R/ 8) Status -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t RAMINV:1; /**< bit: 0 RAM Inversion Bit */
uint8_t DRP:1; /**< bit: 1 Data Remanence Prevention Ongoing */
uint8_t :6; /**< bit: 2..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} TRAM_STATUS_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define TRAM_STATUS_OFFSET (0x07) /**< (TRAM_STATUS) Status Offset */
#define TRAM_STATUS_RESETVALUE _U_(0x00) /**< (TRAM_STATUS) Status Reset Value */
#define TRAM_STATUS_RAMINV_Pos 0 /**< (TRAM_STATUS) RAM Inversion Bit Position */
#define TRAM_STATUS_RAMINV_Msk (_U_(0x1) << TRAM_STATUS_RAMINV_Pos) /**< (TRAM_STATUS) RAM Inversion Bit Mask */
#define TRAM_STATUS_RAMINV TRAM_STATUS_RAMINV_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use TRAM_STATUS_RAMINV_Msk instead */
#define TRAM_STATUS_DRP_Pos 1 /**< (TRAM_STATUS) Data Remanence Prevention Ongoing Position */
#define TRAM_STATUS_DRP_Msk (_U_(0x1) << TRAM_STATUS_DRP_Pos) /**< (TRAM_STATUS) Data Remanence Prevention Ongoing Mask */
#define TRAM_STATUS_DRP TRAM_STATUS_DRP_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use TRAM_STATUS_DRP_Msk instead */
#define TRAM_STATUS_MASK _U_(0x03) /**< \deprecated (TRAM_STATUS) Register MASK (Use TRAM_STATUS_Msk instead) */
#define TRAM_STATUS_Msk _U_(0x03) /**< (TRAM_STATUS) Register Mask */
/* -------- TRAM_SYNCBUSY : (TRAM Offset: 0x08) (R/ 32) Synchronization Busy Status -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t SWRST:1; /**< bit: 0 Software Reset Busy */
uint32_t ENABLE:1; /**< bit: 1 Enable Busy */
uint32_t :30; /**< bit: 2..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} TRAM_SYNCBUSY_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define TRAM_SYNCBUSY_OFFSET (0x08) /**< (TRAM_SYNCBUSY) Synchronization Busy Status Offset */
#define TRAM_SYNCBUSY_RESETVALUE _U_(0x00) /**< (TRAM_SYNCBUSY) Synchronization Busy Status Reset Value */
#define TRAM_SYNCBUSY_SWRST_Pos 0 /**< (TRAM_SYNCBUSY) Software Reset Busy Position */
#define TRAM_SYNCBUSY_SWRST_Msk (_U_(0x1) << TRAM_SYNCBUSY_SWRST_Pos) /**< (TRAM_SYNCBUSY) Software Reset Busy Mask */
#define TRAM_SYNCBUSY_SWRST TRAM_SYNCBUSY_SWRST_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use TRAM_SYNCBUSY_SWRST_Msk instead */
#define TRAM_SYNCBUSY_ENABLE_Pos 1 /**< (TRAM_SYNCBUSY) Enable Busy Position */
#define TRAM_SYNCBUSY_ENABLE_Msk (_U_(0x1) << TRAM_SYNCBUSY_ENABLE_Pos) /**< (TRAM_SYNCBUSY) Enable Busy Mask */
#define TRAM_SYNCBUSY_ENABLE TRAM_SYNCBUSY_ENABLE_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use TRAM_SYNCBUSY_ENABLE_Msk instead */
#define TRAM_SYNCBUSY_MASK _U_(0x03) /**< \deprecated (TRAM_SYNCBUSY) Register MASK (Use TRAM_SYNCBUSY_Msk instead) */
#define TRAM_SYNCBUSY_Msk _U_(0x03) /**< (TRAM_SYNCBUSY) Register Mask */
/* -------- TRAM_DSCC : (TRAM Offset: 0x0c) (/W 32) Data Scramble Control -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t DSCKEY:30; /**< bit: 0..29 Data Scramble Key */
uint32_t :1; /**< bit: 30 Reserved */
uint32_t DSCEN:1; /**< bit: 31 Data Scramble Enable */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} TRAM_DSCC_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define TRAM_DSCC_OFFSET (0x0C) /**< (TRAM_DSCC) Data Scramble Control Offset */
#define TRAM_DSCC_RESETVALUE _U_(0x00) /**< (TRAM_DSCC) Data Scramble Control Reset Value */
#define TRAM_DSCC_DSCKEY_Pos 0 /**< (TRAM_DSCC) Data Scramble Key Position */
#define TRAM_DSCC_DSCKEY_Msk (_U_(0x3FFFFFFF) << TRAM_DSCC_DSCKEY_Pos) /**< (TRAM_DSCC) Data Scramble Key Mask */
#define TRAM_DSCC_DSCKEY(value) (TRAM_DSCC_DSCKEY_Msk & ((value) << TRAM_DSCC_DSCKEY_Pos))
#define TRAM_DSCC_DSCEN_Pos 31 /**< (TRAM_DSCC) Data Scramble Enable Position */
#define TRAM_DSCC_DSCEN_Msk (_U_(0x1) << TRAM_DSCC_DSCEN_Pos) /**< (TRAM_DSCC) Data Scramble Enable Mask */
#define TRAM_DSCC_DSCEN TRAM_DSCC_DSCEN_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use TRAM_DSCC_DSCEN_Msk instead */
#define TRAM_DSCC_MASK _U_(0xBFFFFFFF) /**< \deprecated (TRAM_DSCC) Register MASK (Use TRAM_DSCC_Msk instead) */
#define TRAM_DSCC_Msk _U_(0xBFFFFFFF) /**< (TRAM_DSCC) Register Mask */
/* -------- TRAM_PERMW : (TRAM Offset: 0x10) (/W 8) Permutation Write -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t DATA:3; /**< bit: 0..2 Permutation Scrambler Data Input */
uint8_t :5; /**< bit: 3..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} TRAM_PERMW_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define TRAM_PERMW_OFFSET (0x10) /**< (TRAM_PERMW) Permutation Write Offset */
#define TRAM_PERMW_RESETVALUE _U_(0x00) /**< (TRAM_PERMW) Permutation Write Reset Value */
#define TRAM_PERMW_DATA_Pos 0 /**< (TRAM_PERMW) Permutation Scrambler Data Input Position */
#define TRAM_PERMW_DATA_Msk (_U_(0x7) << TRAM_PERMW_DATA_Pos) /**< (TRAM_PERMW) Permutation Scrambler Data Input Mask */
#define TRAM_PERMW_DATA(value) (TRAM_PERMW_DATA_Msk & ((value) << TRAM_PERMW_DATA_Pos))
#define TRAM_PERMW_MASK _U_(0x07) /**< \deprecated (TRAM_PERMW) Register MASK (Use TRAM_PERMW_Msk instead) */
#define TRAM_PERMW_Msk _U_(0x07) /**< (TRAM_PERMW) Register Mask */
/* -------- TRAM_PERMR : (TRAM Offset: 0x11) (R/ 8) Permutation Read -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t DATA:3; /**< bit: 0..2 Permutation Scrambler Data Output */
uint8_t :5; /**< bit: 3..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} TRAM_PERMR_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define TRAM_PERMR_OFFSET (0x11) /**< (TRAM_PERMR) Permutation Read Offset */
#define TRAM_PERMR_RESETVALUE _U_(0x00) /**< (TRAM_PERMR) Permutation Read Reset Value */
#define TRAM_PERMR_DATA_Pos 0 /**< (TRAM_PERMR) Permutation Scrambler Data Output Position */
#define TRAM_PERMR_DATA_Msk (_U_(0x7) << TRAM_PERMR_DATA_Pos) /**< (TRAM_PERMR) Permutation Scrambler Data Output Mask */
#define TRAM_PERMR_DATA(value) (TRAM_PERMR_DATA_Msk & ((value) << TRAM_PERMR_DATA_Pos))
#define TRAM_PERMR_MASK _U_(0x07) /**< \deprecated (TRAM_PERMR) Register MASK (Use TRAM_PERMR_Msk instead) */
#define TRAM_PERMR_Msk _U_(0x07) /**< (TRAM_PERMR) Register Mask */
/* -------- TRAM_RAM : (TRAM Offset: 0x100) (R/W 32) TrustRAM -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t DATA:32; /**< bit: 0..31 Trust RAM Data */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} TRAM_RAM_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define TRAM_RAM_OFFSET (0x100) /**< (TRAM_RAM) TrustRAM Offset */
#define TRAM_RAM_RESETVALUE _U_(0x00) /**< (TRAM_RAM) TrustRAM Reset Value */
#define TRAM_RAM_DATA_Pos 0 /**< (TRAM_RAM) Trust RAM Data Position */
#define TRAM_RAM_DATA_Msk (_U_(0xFFFFFFFF) << TRAM_RAM_DATA_Pos) /**< (TRAM_RAM) Trust RAM Data Mask */
#define TRAM_RAM_DATA(value) (TRAM_RAM_DATA_Msk & ((value) << TRAM_RAM_DATA_Pos))
#define TRAM_RAM_MASK _U_(0xFFFFFFFF) /**< \deprecated (TRAM_RAM) Register MASK (Use TRAM_RAM_Msk instead) */
#define TRAM_RAM_Msk _U_(0xFFFFFFFF) /**< (TRAM_RAM) Register Mask */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
/** \brief TRAM hardware registers */
typedef struct { /* TrustRAM */
__IO TRAM_CTRLA_Type CTRLA; /**< Offset: 0x00 (R/W 8) Control */
__I uint8_t Reserved1[3];
__IO TRAM_INTENCLR_Type INTENCLR; /**< Offset: 0x04 (R/W 8) Interrupt Enable Clear */
__IO TRAM_INTENSET_Type INTENSET; /**< Offset: 0x05 (R/W 8) Interrupt Enable Set */
__IO TRAM_INTFLAG_Type INTFLAG; /**< Offset: 0x06 (R/W 8) Interrupt Flag Status and Clear */
__I TRAM_STATUS_Type STATUS; /**< Offset: 0x07 (R/ 8) Status */
__I TRAM_SYNCBUSY_Type SYNCBUSY; /**< Offset: 0x08 (R/ 32) Synchronization Busy Status */
__O TRAM_DSCC_Type DSCC; /**< Offset: 0x0C ( /W 32) Data Scramble Control */
__O TRAM_PERMW_Type PERMW; /**< Offset: 0x10 ( /W 8) Permutation Write */
__I TRAM_PERMR_Type PERMR; /**< Offset: 0x11 (R/ 8) Permutation Read */
__I uint8_t Reserved2[238];
__IO TRAM_RAM_Type RAM[64]; /**< Offset: 0x100 (R/W 32) TrustRAM */
} Tram;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/** @} end of TrustRAM */
#endif /* _SAML10_TRAM_COMPONENT_H_ */

View File

@ -0,0 +1,194 @@
/**
* \file
*
* \brief Component description for TRNG
*
* Copyright (c) 2018 Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* 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
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
/* file generated from device description version 2018-08-31T13:51:50Z */
#ifndef _SAML10_TRNG_COMPONENT_H_
#define _SAML10_TRNG_COMPONENT_H_
#define _SAML10_TRNG_COMPONENT_ /**< \deprecated Backward compatibility for ASF */
/** \addtogroup SAML_SAML10 True Random Generator
* @{
*/
/* ========================================================================== */
/** SOFTWARE API DEFINITION FOR TRNG */
/* ========================================================================== */
#define TRNG_U2242 /**< (TRNG) Module ID */
#define REV_TRNG 0x120 /**< (TRNG) Module revision */
/* -------- TRNG_CTRLA : (TRNG Offset: 0x00) (R/W 8) Control A -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t :1; /**< bit: 0 Reserved */
uint8_t ENABLE:1; /**< bit: 1 Enable */
uint8_t :4; /**< bit: 2..5 Reserved */
uint8_t RUNSTDBY:1; /**< bit: 6 Run in Standby */
uint8_t :1; /**< bit: 7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} TRNG_CTRLA_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define TRNG_CTRLA_OFFSET (0x00) /**< (TRNG_CTRLA) Control A Offset */
#define TRNG_CTRLA_RESETVALUE _U_(0x00) /**< (TRNG_CTRLA) Control A Reset Value */
#define TRNG_CTRLA_ENABLE_Pos 1 /**< (TRNG_CTRLA) Enable Position */
#define TRNG_CTRLA_ENABLE_Msk (_U_(0x1) << TRNG_CTRLA_ENABLE_Pos) /**< (TRNG_CTRLA) Enable Mask */
#define TRNG_CTRLA_ENABLE TRNG_CTRLA_ENABLE_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use TRNG_CTRLA_ENABLE_Msk instead */
#define TRNG_CTRLA_RUNSTDBY_Pos 6 /**< (TRNG_CTRLA) Run in Standby Position */
#define TRNG_CTRLA_RUNSTDBY_Msk (_U_(0x1) << TRNG_CTRLA_RUNSTDBY_Pos) /**< (TRNG_CTRLA) Run in Standby Mask */
#define TRNG_CTRLA_RUNSTDBY TRNG_CTRLA_RUNSTDBY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use TRNG_CTRLA_RUNSTDBY_Msk instead */
#define TRNG_CTRLA_MASK _U_(0x42) /**< \deprecated (TRNG_CTRLA) Register MASK (Use TRNG_CTRLA_Msk instead) */
#define TRNG_CTRLA_Msk _U_(0x42) /**< (TRNG_CTRLA) Register Mask */
/* -------- TRNG_EVCTRL : (TRNG Offset: 0x04) (R/W 8) Event Control -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t DATARDYEO:1; /**< bit: 0 Data Ready Event Output */
uint8_t :7; /**< bit: 1..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} TRNG_EVCTRL_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define TRNG_EVCTRL_OFFSET (0x04) /**< (TRNG_EVCTRL) Event Control Offset */
#define TRNG_EVCTRL_RESETVALUE _U_(0x00) /**< (TRNG_EVCTRL) Event Control Reset Value */
#define TRNG_EVCTRL_DATARDYEO_Pos 0 /**< (TRNG_EVCTRL) Data Ready Event Output Position */
#define TRNG_EVCTRL_DATARDYEO_Msk (_U_(0x1) << TRNG_EVCTRL_DATARDYEO_Pos) /**< (TRNG_EVCTRL) Data Ready Event Output Mask */
#define TRNG_EVCTRL_DATARDYEO TRNG_EVCTRL_DATARDYEO_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use TRNG_EVCTRL_DATARDYEO_Msk instead */
#define TRNG_EVCTRL_MASK _U_(0x01) /**< \deprecated (TRNG_EVCTRL) Register MASK (Use TRNG_EVCTRL_Msk instead) */
#define TRNG_EVCTRL_Msk _U_(0x01) /**< (TRNG_EVCTRL) Register Mask */
/* -------- TRNG_INTENCLR : (TRNG Offset: 0x08) (R/W 8) Interrupt Enable Clear -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t DATARDY:1; /**< bit: 0 Data Ready Interrupt Enable */
uint8_t :7; /**< bit: 1..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} TRNG_INTENCLR_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define TRNG_INTENCLR_OFFSET (0x08) /**< (TRNG_INTENCLR) Interrupt Enable Clear Offset */
#define TRNG_INTENCLR_RESETVALUE _U_(0x00) /**< (TRNG_INTENCLR) Interrupt Enable Clear Reset Value */
#define TRNG_INTENCLR_DATARDY_Pos 0 /**< (TRNG_INTENCLR) Data Ready Interrupt Enable Position */
#define TRNG_INTENCLR_DATARDY_Msk (_U_(0x1) << TRNG_INTENCLR_DATARDY_Pos) /**< (TRNG_INTENCLR) Data Ready Interrupt Enable Mask */
#define TRNG_INTENCLR_DATARDY TRNG_INTENCLR_DATARDY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use TRNG_INTENCLR_DATARDY_Msk instead */
#define TRNG_INTENCLR_MASK _U_(0x01) /**< \deprecated (TRNG_INTENCLR) Register MASK (Use TRNG_INTENCLR_Msk instead) */
#define TRNG_INTENCLR_Msk _U_(0x01) /**< (TRNG_INTENCLR) Register Mask */
/* -------- TRNG_INTENSET : (TRNG Offset: 0x09) (R/W 8) Interrupt Enable Set -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t DATARDY:1; /**< bit: 0 Data Ready Interrupt Enable */
uint8_t :7; /**< bit: 1..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} TRNG_INTENSET_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define TRNG_INTENSET_OFFSET (0x09) /**< (TRNG_INTENSET) Interrupt Enable Set Offset */
#define TRNG_INTENSET_RESETVALUE _U_(0x00) /**< (TRNG_INTENSET) Interrupt Enable Set Reset Value */
#define TRNG_INTENSET_DATARDY_Pos 0 /**< (TRNG_INTENSET) Data Ready Interrupt Enable Position */
#define TRNG_INTENSET_DATARDY_Msk (_U_(0x1) << TRNG_INTENSET_DATARDY_Pos) /**< (TRNG_INTENSET) Data Ready Interrupt Enable Mask */
#define TRNG_INTENSET_DATARDY TRNG_INTENSET_DATARDY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use TRNG_INTENSET_DATARDY_Msk instead */
#define TRNG_INTENSET_MASK _U_(0x01) /**< \deprecated (TRNG_INTENSET) Register MASK (Use TRNG_INTENSET_Msk instead) */
#define TRNG_INTENSET_Msk _U_(0x01) /**< (TRNG_INTENSET) Register Mask */
/* -------- TRNG_INTFLAG : (TRNG Offset: 0x0a) (R/W 8) Interrupt Flag Status and Clear -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union { // __I to avoid read-modify-write on write-to-clear register
struct {
__I uint8_t DATARDY:1; /**< bit: 0 Data Ready Interrupt Flag */
__I uint8_t :7; /**< bit: 1..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} TRNG_INTFLAG_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define TRNG_INTFLAG_OFFSET (0x0A) /**< (TRNG_INTFLAG) Interrupt Flag Status and Clear Offset */
#define TRNG_INTFLAG_RESETVALUE _U_(0x00) /**< (TRNG_INTFLAG) Interrupt Flag Status and Clear Reset Value */
#define TRNG_INTFLAG_DATARDY_Pos 0 /**< (TRNG_INTFLAG) Data Ready Interrupt Flag Position */
#define TRNG_INTFLAG_DATARDY_Msk (_U_(0x1) << TRNG_INTFLAG_DATARDY_Pos) /**< (TRNG_INTFLAG) Data Ready Interrupt Flag Mask */
#define TRNG_INTFLAG_DATARDY TRNG_INTFLAG_DATARDY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use TRNG_INTFLAG_DATARDY_Msk instead */
#define TRNG_INTFLAG_MASK _U_(0x01) /**< \deprecated (TRNG_INTFLAG) Register MASK (Use TRNG_INTFLAG_Msk instead) */
#define TRNG_INTFLAG_Msk _U_(0x01) /**< (TRNG_INTFLAG) Register Mask */
/* -------- TRNG_DATA : (TRNG Offset: 0x20) (R/ 32) Output Data -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t DATA:32; /**< bit: 0..31 Output Data */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} TRNG_DATA_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define TRNG_DATA_OFFSET (0x20) /**< (TRNG_DATA) Output Data Offset */
#define TRNG_DATA_RESETVALUE _U_(0x00) /**< (TRNG_DATA) Output Data Reset Value */
#define TRNG_DATA_DATA_Pos 0 /**< (TRNG_DATA) Output Data Position */
#define TRNG_DATA_DATA_Msk (_U_(0xFFFFFFFF) << TRNG_DATA_DATA_Pos) /**< (TRNG_DATA) Output Data Mask */
#define TRNG_DATA_DATA(value) (TRNG_DATA_DATA_Msk & ((value) << TRNG_DATA_DATA_Pos))
#define TRNG_DATA_MASK _U_(0xFFFFFFFF) /**< \deprecated (TRNG_DATA) Register MASK (Use TRNG_DATA_Msk instead) */
#define TRNG_DATA_Msk _U_(0xFFFFFFFF) /**< (TRNG_DATA) Register Mask */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
/** \brief TRNG hardware registers */
typedef struct { /* True Random Generator */
__IO TRNG_CTRLA_Type CTRLA; /**< Offset: 0x00 (R/W 8) Control A */
__I uint8_t Reserved1[3];
__IO TRNG_EVCTRL_Type EVCTRL; /**< Offset: 0x04 (R/W 8) Event Control */
__I uint8_t Reserved2[3];
__IO TRNG_INTENCLR_Type INTENCLR; /**< Offset: 0x08 (R/W 8) Interrupt Enable Clear */
__IO TRNG_INTENSET_Type INTENSET; /**< Offset: 0x09 (R/W 8) Interrupt Enable Set */
__IO TRNG_INTFLAG_Type INTFLAG; /**< Offset: 0x0A (R/W 8) Interrupt Flag Status and Clear */
__I uint8_t Reserved3[21];
__I TRNG_DATA_Type DATA; /**< Offset: 0x20 (R/ 32) Output Data */
} Trng;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/** @} end of True Random Generator */
#endif /* _SAML10_TRNG_COMPONENT_H_ */

View File

@ -0,0 +1,338 @@
/**
* \file
*
* \brief Component description for WDT
*
* Copyright (c) 2018 Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* 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
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
/* file generated from device description version 2018-08-31T13:51:50Z */
#ifndef _SAML10_WDT_COMPONENT_H_
#define _SAML10_WDT_COMPONENT_H_
#define _SAML10_WDT_COMPONENT_ /**< \deprecated Backward compatibility for ASF */
/** \addtogroup SAML_SAML10 Watchdog Timer
* @{
*/
/* ========================================================================== */
/** SOFTWARE API DEFINITION FOR WDT */
/* ========================================================================== */
#define WDT_U2251 /**< (WDT) Module ID */
#define REV_WDT 0x200 /**< (WDT) Module revision */
/* -------- WDT_CTRLA : (WDT Offset: 0x00) (R/W 8) Control -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t :1; /**< bit: 0 Reserved */
uint8_t ENABLE:1; /**< bit: 1 Enable */
uint8_t WEN:1; /**< bit: 2 Watchdog Timer Window Mode Enable */
uint8_t :3; /**< bit: 3..5 Reserved */
uint8_t RUNSTDBY:1; /**< bit: 6 Run During Standby */
uint8_t ALWAYSON:1; /**< bit: 7 Always-On */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} WDT_CTRLA_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define WDT_CTRLA_OFFSET (0x00) /**< (WDT_CTRLA) Control Offset */
#define WDT_CTRLA_RESETVALUE _U_(0x00) /**< (WDT_CTRLA) Control Reset Value */
#define WDT_CTRLA_ENABLE_Pos 1 /**< (WDT_CTRLA) Enable Position */
#define WDT_CTRLA_ENABLE_Msk (_U_(0x1) << WDT_CTRLA_ENABLE_Pos) /**< (WDT_CTRLA) Enable Mask */
#define WDT_CTRLA_ENABLE WDT_CTRLA_ENABLE_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use WDT_CTRLA_ENABLE_Msk instead */
#define WDT_CTRLA_WEN_Pos 2 /**< (WDT_CTRLA) Watchdog Timer Window Mode Enable Position */
#define WDT_CTRLA_WEN_Msk (_U_(0x1) << WDT_CTRLA_WEN_Pos) /**< (WDT_CTRLA) Watchdog Timer Window Mode Enable Mask */
#define WDT_CTRLA_WEN WDT_CTRLA_WEN_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use WDT_CTRLA_WEN_Msk instead */
#define WDT_CTRLA_RUNSTDBY_Pos 6 /**< (WDT_CTRLA) Run During Standby Position */
#define WDT_CTRLA_RUNSTDBY_Msk (_U_(0x1) << WDT_CTRLA_RUNSTDBY_Pos) /**< (WDT_CTRLA) Run During Standby Mask */
#define WDT_CTRLA_RUNSTDBY WDT_CTRLA_RUNSTDBY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use WDT_CTRLA_RUNSTDBY_Msk instead */
#define WDT_CTRLA_ALWAYSON_Pos 7 /**< (WDT_CTRLA) Always-On Position */
#define WDT_CTRLA_ALWAYSON_Msk (_U_(0x1) << WDT_CTRLA_ALWAYSON_Pos) /**< (WDT_CTRLA) Always-On Mask */
#define WDT_CTRLA_ALWAYSON WDT_CTRLA_ALWAYSON_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use WDT_CTRLA_ALWAYSON_Msk instead */
#define WDT_CTRLA_MASK _U_(0xC6) /**< \deprecated (WDT_CTRLA) Register MASK (Use WDT_CTRLA_Msk instead) */
#define WDT_CTRLA_Msk _U_(0xC6) /**< (WDT_CTRLA) Register Mask */
/* -------- WDT_CONFIG : (WDT Offset: 0x01) (R/W 8) Configuration -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t PER:4; /**< bit: 0..3 Time-Out Period */
uint8_t WINDOW:4; /**< bit: 4..7 Window Mode Time-Out Period */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} WDT_CONFIG_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define WDT_CONFIG_OFFSET (0x01) /**< (WDT_CONFIG) Configuration Offset */
#define WDT_CONFIG_RESETVALUE _U_(0xBB) /**< (WDT_CONFIG) Configuration Reset Value */
#define WDT_CONFIG_PER_Pos 0 /**< (WDT_CONFIG) Time-Out Period Position */
#define WDT_CONFIG_PER_Msk (_U_(0xF) << WDT_CONFIG_PER_Pos) /**< (WDT_CONFIG) Time-Out Period Mask */
#define WDT_CONFIG_PER(value) (WDT_CONFIG_PER_Msk & ((value) << WDT_CONFIG_PER_Pos))
#define WDT_CONFIG_PER_CYC8_Val _U_(0x0) /**< (WDT_CONFIG) 8 clock cycles */
#define WDT_CONFIG_PER_CYC16_Val _U_(0x1) /**< (WDT_CONFIG) 16 clock cycles */
#define WDT_CONFIG_PER_CYC32_Val _U_(0x2) /**< (WDT_CONFIG) 32 clock cycles */
#define WDT_CONFIG_PER_CYC64_Val _U_(0x3) /**< (WDT_CONFIG) 64 clock cycles */
#define WDT_CONFIG_PER_CYC128_Val _U_(0x4) /**< (WDT_CONFIG) 128 clock cycles */
#define WDT_CONFIG_PER_CYC256_Val _U_(0x5) /**< (WDT_CONFIG) 256 clock cycles */
#define WDT_CONFIG_PER_CYC512_Val _U_(0x6) /**< (WDT_CONFIG) 512 clock cycles */
#define WDT_CONFIG_PER_CYC1024_Val _U_(0x7) /**< (WDT_CONFIG) 1024 clock cycles */
#define WDT_CONFIG_PER_CYC2048_Val _U_(0x8) /**< (WDT_CONFIG) 2048 clock cycles */
#define WDT_CONFIG_PER_CYC4096_Val _U_(0x9) /**< (WDT_CONFIG) 4096 clock cycles */
#define WDT_CONFIG_PER_CYC8192_Val _U_(0xA) /**< (WDT_CONFIG) 8192 clock cycles */
#define WDT_CONFIG_PER_CYC16384_Val _U_(0xB) /**< (WDT_CONFIG) 16384 clock cycles */
#define WDT_CONFIG_PER_CYC8 (WDT_CONFIG_PER_CYC8_Val << WDT_CONFIG_PER_Pos) /**< (WDT_CONFIG) 8 clock cycles Position */
#define WDT_CONFIG_PER_CYC16 (WDT_CONFIG_PER_CYC16_Val << WDT_CONFIG_PER_Pos) /**< (WDT_CONFIG) 16 clock cycles Position */
#define WDT_CONFIG_PER_CYC32 (WDT_CONFIG_PER_CYC32_Val << WDT_CONFIG_PER_Pos) /**< (WDT_CONFIG) 32 clock cycles Position */
#define WDT_CONFIG_PER_CYC64 (WDT_CONFIG_PER_CYC64_Val << WDT_CONFIG_PER_Pos) /**< (WDT_CONFIG) 64 clock cycles Position */
#define WDT_CONFIG_PER_CYC128 (WDT_CONFIG_PER_CYC128_Val << WDT_CONFIG_PER_Pos) /**< (WDT_CONFIG) 128 clock cycles Position */
#define WDT_CONFIG_PER_CYC256 (WDT_CONFIG_PER_CYC256_Val << WDT_CONFIG_PER_Pos) /**< (WDT_CONFIG) 256 clock cycles Position */
#define WDT_CONFIG_PER_CYC512 (WDT_CONFIG_PER_CYC512_Val << WDT_CONFIG_PER_Pos) /**< (WDT_CONFIG) 512 clock cycles Position */
#define WDT_CONFIG_PER_CYC1024 (WDT_CONFIG_PER_CYC1024_Val << WDT_CONFIG_PER_Pos) /**< (WDT_CONFIG) 1024 clock cycles Position */
#define WDT_CONFIG_PER_CYC2048 (WDT_CONFIG_PER_CYC2048_Val << WDT_CONFIG_PER_Pos) /**< (WDT_CONFIG) 2048 clock cycles Position */
#define WDT_CONFIG_PER_CYC4096 (WDT_CONFIG_PER_CYC4096_Val << WDT_CONFIG_PER_Pos) /**< (WDT_CONFIG) 4096 clock cycles Position */
#define WDT_CONFIG_PER_CYC8192 (WDT_CONFIG_PER_CYC8192_Val << WDT_CONFIG_PER_Pos) /**< (WDT_CONFIG) 8192 clock cycles Position */
#define WDT_CONFIG_PER_CYC16384 (WDT_CONFIG_PER_CYC16384_Val << WDT_CONFIG_PER_Pos) /**< (WDT_CONFIG) 16384 clock cycles Position */
#define WDT_CONFIG_WINDOW_Pos 4 /**< (WDT_CONFIG) Window Mode Time-Out Period Position */
#define WDT_CONFIG_WINDOW_Msk (_U_(0xF) << WDT_CONFIG_WINDOW_Pos) /**< (WDT_CONFIG) Window Mode Time-Out Period Mask */
#define WDT_CONFIG_WINDOW(value) (WDT_CONFIG_WINDOW_Msk & ((value) << WDT_CONFIG_WINDOW_Pos))
#define WDT_CONFIG_WINDOW_CYC8_Val _U_(0x0) /**< (WDT_CONFIG) 8 clock cycles */
#define WDT_CONFIG_WINDOW_CYC16_Val _U_(0x1) /**< (WDT_CONFIG) 16 clock cycles */
#define WDT_CONFIG_WINDOW_CYC32_Val _U_(0x2) /**< (WDT_CONFIG) 32 clock cycles */
#define WDT_CONFIG_WINDOW_CYC64_Val _U_(0x3) /**< (WDT_CONFIG) 64 clock cycles */
#define WDT_CONFIG_WINDOW_CYC128_Val _U_(0x4) /**< (WDT_CONFIG) 128 clock cycles */
#define WDT_CONFIG_WINDOW_CYC256_Val _U_(0x5) /**< (WDT_CONFIG) 256 clock cycles */
#define WDT_CONFIG_WINDOW_CYC512_Val _U_(0x6) /**< (WDT_CONFIG) 512 clock cycles */
#define WDT_CONFIG_WINDOW_CYC1024_Val _U_(0x7) /**< (WDT_CONFIG) 1024 clock cycles */
#define WDT_CONFIG_WINDOW_CYC2048_Val _U_(0x8) /**< (WDT_CONFIG) 2048 clock cycles */
#define WDT_CONFIG_WINDOW_CYC4096_Val _U_(0x9) /**< (WDT_CONFIG) 4096 clock cycles */
#define WDT_CONFIG_WINDOW_CYC8192_Val _U_(0xA) /**< (WDT_CONFIG) 8192 clock cycles */
#define WDT_CONFIG_WINDOW_CYC16384_Val _U_(0xB) /**< (WDT_CONFIG) 16384 clock cycles */
#define WDT_CONFIG_WINDOW_CYC8 (WDT_CONFIG_WINDOW_CYC8_Val << WDT_CONFIG_WINDOW_Pos) /**< (WDT_CONFIG) 8 clock cycles Position */
#define WDT_CONFIG_WINDOW_CYC16 (WDT_CONFIG_WINDOW_CYC16_Val << WDT_CONFIG_WINDOW_Pos) /**< (WDT_CONFIG) 16 clock cycles Position */
#define WDT_CONFIG_WINDOW_CYC32 (WDT_CONFIG_WINDOW_CYC32_Val << WDT_CONFIG_WINDOW_Pos) /**< (WDT_CONFIG) 32 clock cycles Position */
#define WDT_CONFIG_WINDOW_CYC64 (WDT_CONFIG_WINDOW_CYC64_Val << WDT_CONFIG_WINDOW_Pos) /**< (WDT_CONFIG) 64 clock cycles Position */
#define WDT_CONFIG_WINDOW_CYC128 (WDT_CONFIG_WINDOW_CYC128_Val << WDT_CONFIG_WINDOW_Pos) /**< (WDT_CONFIG) 128 clock cycles Position */
#define WDT_CONFIG_WINDOW_CYC256 (WDT_CONFIG_WINDOW_CYC256_Val << WDT_CONFIG_WINDOW_Pos) /**< (WDT_CONFIG) 256 clock cycles Position */
#define WDT_CONFIG_WINDOW_CYC512 (WDT_CONFIG_WINDOW_CYC512_Val << WDT_CONFIG_WINDOW_Pos) /**< (WDT_CONFIG) 512 clock cycles Position */
#define WDT_CONFIG_WINDOW_CYC1024 (WDT_CONFIG_WINDOW_CYC1024_Val << WDT_CONFIG_WINDOW_Pos) /**< (WDT_CONFIG) 1024 clock cycles Position */
#define WDT_CONFIG_WINDOW_CYC2048 (WDT_CONFIG_WINDOW_CYC2048_Val << WDT_CONFIG_WINDOW_Pos) /**< (WDT_CONFIG) 2048 clock cycles Position */
#define WDT_CONFIG_WINDOW_CYC4096 (WDT_CONFIG_WINDOW_CYC4096_Val << WDT_CONFIG_WINDOW_Pos) /**< (WDT_CONFIG) 4096 clock cycles Position */
#define WDT_CONFIG_WINDOW_CYC8192 (WDT_CONFIG_WINDOW_CYC8192_Val << WDT_CONFIG_WINDOW_Pos) /**< (WDT_CONFIG) 8192 clock cycles Position */
#define WDT_CONFIG_WINDOW_CYC16384 (WDT_CONFIG_WINDOW_CYC16384_Val << WDT_CONFIG_WINDOW_Pos) /**< (WDT_CONFIG) 16384 clock cycles Position */
#define WDT_CONFIG_MASK _U_(0xFF) /**< \deprecated (WDT_CONFIG) Register MASK (Use WDT_CONFIG_Msk instead) */
#define WDT_CONFIG_Msk _U_(0xFF) /**< (WDT_CONFIG) Register Mask */
/* -------- WDT_EWCTRL : (WDT Offset: 0x02) (R/W 8) Early Warning Interrupt Control -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t EWOFFSET:4; /**< bit: 0..3 Early Warning Interrupt Time Offset */
uint8_t :4; /**< bit: 4..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} WDT_EWCTRL_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define WDT_EWCTRL_OFFSET (0x02) /**< (WDT_EWCTRL) Early Warning Interrupt Control Offset */
#define WDT_EWCTRL_RESETVALUE _U_(0x0B) /**< (WDT_EWCTRL) Early Warning Interrupt Control Reset Value */
#define WDT_EWCTRL_EWOFFSET_Pos 0 /**< (WDT_EWCTRL) Early Warning Interrupt Time Offset Position */
#define WDT_EWCTRL_EWOFFSET_Msk (_U_(0xF) << WDT_EWCTRL_EWOFFSET_Pos) /**< (WDT_EWCTRL) Early Warning Interrupt Time Offset Mask */
#define WDT_EWCTRL_EWOFFSET(value) (WDT_EWCTRL_EWOFFSET_Msk & ((value) << WDT_EWCTRL_EWOFFSET_Pos))
#define WDT_EWCTRL_EWOFFSET_CYC8_Val _U_(0x0) /**< (WDT_EWCTRL) 8 clock cycles */
#define WDT_EWCTRL_EWOFFSET_CYC16_Val _U_(0x1) /**< (WDT_EWCTRL) 16 clock cycles */
#define WDT_EWCTRL_EWOFFSET_CYC32_Val _U_(0x2) /**< (WDT_EWCTRL) 32 clock cycles */
#define WDT_EWCTRL_EWOFFSET_CYC64_Val _U_(0x3) /**< (WDT_EWCTRL) 64 clock cycles */
#define WDT_EWCTRL_EWOFFSET_CYC128_Val _U_(0x4) /**< (WDT_EWCTRL) 128 clock cycles */
#define WDT_EWCTRL_EWOFFSET_CYC256_Val _U_(0x5) /**< (WDT_EWCTRL) 256 clock cycles */
#define WDT_EWCTRL_EWOFFSET_CYC512_Val _U_(0x6) /**< (WDT_EWCTRL) 512 clock cycles */
#define WDT_EWCTRL_EWOFFSET_CYC1024_Val _U_(0x7) /**< (WDT_EWCTRL) 1024 clock cycles */
#define WDT_EWCTRL_EWOFFSET_CYC2048_Val _U_(0x8) /**< (WDT_EWCTRL) 2048 clock cycles */
#define WDT_EWCTRL_EWOFFSET_CYC4096_Val _U_(0x9) /**< (WDT_EWCTRL) 4096 clock cycles */
#define WDT_EWCTRL_EWOFFSET_CYC8192_Val _U_(0xA) /**< (WDT_EWCTRL) 8192 clock cycles */
#define WDT_EWCTRL_EWOFFSET_CYC16384_Val _U_(0xB) /**< (WDT_EWCTRL) 16384 clock cycles */
#define WDT_EWCTRL_EWOFFSET_CYC8 (WDT_EWCTRL_EWOFFSET_CYC8_Val << WDT_EWCTRL_EWOFFSET_Pos) /**< (WDT_EWCTRL) 8 clock cycles Position */
#define WDT_EWCTRL_EWOFFSET_CYC16 (WDT_EWCTRL_EWOFFSET_CYC16_Val << WDT_EWCTRL_EWOFFSET_Pos) /**< (WDT_EWCTRL) 16 clock cycles Position */
#define WDT_EWCTRL_EWOFFSET_CYC32 (WDT_EWCTRL_EWOFFSET_CYC32_Val << WDT_EWCTRL_EWOFFSET_Pos) /**< (WDT_EWCTRL) 32 clock cycles Position */
#define WDT_EWCTRL_EWOFFSET_CYC64 (WDT_EWCTRL_EWOFFSET_CYC64_Val << WDT_EWCTRL_EWOFFSET_Pos) /**< (WDT_EWCTRL) 64 clock cycles Position */
#define WDT_EWCTRL_EWOFFSET_CYC128 (WDT_EWCTRL_EWOFFSET_CYC128_Val << WDT_EWCTRL_EWOFFSET_Pos) /**< (WDT_EWCTRL) 128 clock cycles Position */
#define WDT_EWCTRL_EWOFFSET_CYC256 (WDT_EWCTRL_EWOFFSET_CYC256_Val << WDT_EWCTRL_EWOFFSET_Pos) /**< (WDT_EWCTRL) 256 clock cycles Position */
#define WDT_EWCTRL_EWOFFSET_CYC512 (WDT_EWCTRL_EWOFFSET_CYC512_Val << WDT_EWCTRL_EWOFFSET_Pos) /**< (WDT_EWCTRL) 512 clock cycles Position */
#define WDT_EWCTRL_EWOFFSET_CYC1024 (WDT_EWCTRL_EWOFFSET_CYC1024_Val << WDT_EWCTRL_EWOFFSET_Pos) /**< (WDT_EWCTRL) 1024 clock cycles Position */
#define WDT_EWCTRL_EWOFFSET_CYC2048 (WDT_EWCTRL_EWOFFSET_CYC2048_Val << WDT_EWCTRL_EWOFFSET_Pos) /**< (WDT_EWCTRL) 2048 clock cycles Position */
#define WDT_EWCTRL_EWOFFSET_CYC4096 (WDT_EWCTRL_EWOFFSET_CYC4096_Val << WDT_EWCTRL_EWOFFSET_Pos) /**< (WDT_EWCTRL) 4096 clock cycles Position */
#define WDT_EWCTRL_EWOFFSET_CYC8192 (WDT_EWCTRL_EWOFFSET_CYC8192_Val << WDT_EWCTRL_EWOFFSET_Pos) /**< (WDT_EWCTRL) 8192 clock cycles Position */
#define WDT_EWCTRL_EWOFFSET_CYC16384 (WDT_EWCTRL_EWOFFSET_CYC16384_Val << WDT_EWCTRL_EWOFFSET_Pos) /**< (WDT_EWCTRL) 16384 clock cycles Position */
#define WDT_EWCTRL_MASK _U_(0x0F) /**< \deprecated (WDT_EWCTRL) Register MASK (Use WDT_EWCTRL_Msk instead) */
#define WDT_EWCTRL_Msk _U_(0x0F) /**< (WDT_EWCTRL) Register Mask */
/* -------- WDT_INTENCLR : (WDT Offset: 0x04) (R/W 8) Interrupt Enable Clear -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t EW:1; /**< bit: 0 Early Warning Interrupt Enable */
uint8_t :7; /**< bit: 1..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} WDT_INTENCLR_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define WDT_INTENCLR_OFFSET (0x04) /**< (WDT_INTENCLR) Interrupt Enable Clear Offset */
#define WDT_INTENCLR_RESETVALUE _U_(0x00) /**< (WDT_INTENCLR) Interrupt Enable Clear Reset Value */
#define WDT_INTENCLR_EW_Pos 0 /**< (WDT_INTENCLR) Early Warning Interrupt Enable Position */
#define WDT_INTENCLR_EW_Msk (_U_(0x1) << WDT_INTENCLR_EW_Pos) /**< (WDT_INTENCLR) Early Warning Interrupt Enable Mask */
#define WDT_INTENCLR_EW WDT_INTENCLR_EW_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use WDT_INTENCLR_EW_Msk instead */
#define WDT_INTENCLR_MASK _U_(0x01) /**< \deprecated (WDT_INTENCLR) Register MASK (Use WDT_INTENCLR_Msk instead) */
#define WDT_INTENCLR_Msk _U_(0x01) /**< (WDT_INTENCLR) Register Mask */
/* -------- WDT_INTENSET : (WDT Offset: 0x05) (R/W 8) Interrupt Enable Set -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t EW:1; /**< bit: 0 Early Warning Interrupt Enable */
uint8_t :7; /**< bit: 1..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} WDT_INTENSET_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define WDT_INTENSET_OFFSET (0x05) /**< (WDT_INTENSET) Interrupt Enable Set Offset */
#define WDT_INTENSET_RESETVALUE _U_(0x00) /**< (WDT_INTENSET) Interrupt Enable Set Reset Value */
#define WDT_INTENSET_EW_Pos 0 /**< (WDT_INTENSET) Early Warning Interrupt Enable Position */
#define WDT_INTENSET_EW_Msk (_U_(0x1) << WDT_INTENSET_EW_Pos) /**< (WDT_INTENSET) Early Warning Interrupt Enable Mask */
#define WDT_INTENSET_EW WDT_INTENSET_EW_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use WDT_INTENSET_EW_Msk instead */
#define WDT_INTENSET_MASK _U_(0x01) /**< \deprecated (WDT_INTENSET) Register MASK (Use WDT_INTENSET_Msk instead) */
#define WDT_INTENSET_Msk _U_(0x01) /**< (WDT_INTENSET) Register Mask */
/* -------- WDT_INTFLAG : (WDT Offset: 0x06) (R/W 8) Interrupt Flag Status and Clear -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union { // __I to avoid read-modify-write on write-to-clear register
struct {
__I uint8_t EW:1; /**< bit: 0 Early Warning */
__I uint8_t :7; /**< bit: 1..7 Reserved */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} WDT_INTFLAG_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define WDT_INTFLAG_OFFSET (0x06) /**< (WDT_INTFLAG) Interrupt Flag Status and Clear Offset */
#define WDT_INTFLAG_RESETVALUE _U_(0x00) /**< (WDT_INTFLAG) Interrupt Flag Status and Clear Reset Value */
#define WDT_INTFLAG_EW_Pos 0 /**< (WDT_INTFLAG) Early Warning Position */
#define WDT_INTFLAG_EW_Msk (_U_(0x1) << WDT_INTFLAG_EW_Pos) /**< (WDT_INTFLAG) Early Warning Mask */
#define WDT_INTFLAG_EW WDT_INTFLAG_EW_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use WDT_INTFLAG_EW_Msk instead */
#define WDT_INTFLAG_MASK _U_(0x01) /**< \deprecated (WDT_INTFLAG) Register MASK (Use WDT_INTFLAG_Msk instead) */
#define WDT_INTFLAG_Msk _U_(0x01) /**< (WDT_INTFLAG) Register Mask */
/* -------- WDT_SYNCBUSY : (WDT Offset: 0x08) (R/ 32) Synchronization Busy -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint32_t :1; /**< bit: 0 Reserved */
uint32_t ENABLE:1; /**< bit: 1 Enable Synchronization Busy */
uint32_t WEN:1; /**< bit: 2 Window Enable Synchronization Busy */
uint32_t RUNSTDBY:1; /**< bit: 3 Run During Standby Synchronization Busy */
uint32_t ALWAYSON:1; /**< bit: 4 Always-On Synchronization Busy */
uint32_t CLEAR:1; /**< bit: 5 Clear Synchronization Busy */
uint32_t :26; /**< bit: 6..31 Reserved */
} bit; /**< Structure used for bit access */
uint32_t reg; /**< Type used for register access */
} WDT_SYNCBUSY_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define WDT_SYNCBUSY_OFFSET (0x08) /**< (WDT_SYNCBUSY) Synchronization Busy Offset */
#define WDT_SYNCBUSY_RESETVALUE _U_(0x00) /**< (WDT_SYNCBUSY) Synchronization Busy Reset Value */
#define WDT_SYNCBUSY_ENABLE_Pos 1 /**< (WDT_SYNCBUSY) Enable Synchronization Busy Position */
#define WDT_SYNCBUSY_ENABLE_Msk (_U_(0x1) << WDT_SYNCBUSY_ENABLE_Pos) /**< (WDT_SYNCBUSY) Enable Synchronization Busy Mask */
#define WDT_SYNCBUSY_ENABLE WDT_SYNCBUSY_ENABLE_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use WDT_SYNCBUSY_ENABLE_Msk instead */
#define WDT_SYNCBUSY_WEN_Pos 2 /**< (WDT_SYNCBUSY) Window Enable Synchronization Busy Position */
#define WDT_SYNCBUSY_WEN_Msk (_U_(0x1) << WDT_SYNCBUSY_WEN_Pos) /**< (WDT_SYNCBUSY) Window Enable Synchronization Busy Mask */
#define WDT_SYNCBUSY_WEN WDT_SYNCBUSY_WEN_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use WDT_SYNCBUSY_WEN_Msk instead */
#define WDT_SYNCBUSY_RUNSTDBY_Pos 3 /**< (WDT_SYNCBUSY) Run During Standby Synchronization Busy Position */
#define WDT_SYNCBUSY_RUNSTDBY_Msk (_U_(0x1) << WDT_SYNCBUSY_RUNSTDBY_Pos) /**< (WDT_SYNCBUSY) Run During Standby Synchronization Busy Mask */
#define WDT_SYNCBUSY_RUNSTDBY WDT_SYNCBUSY_RUNSTDBY_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use WDT_SYNCBUSY_RUNSTDBY_Msk instead */
#define WDT_SYNCBUSY_ALWAYSON_Pos 4 /**< (WDT_SYNCBUSY) Always-On Synchronization Busy Position */
#define WDT_SYNCBUSY_ALWAYSON_Msk (_U_(0x1) << WDT_SYNCBUSY_ALWAYSON_Pos) /**< (WDT_SYNCBUSY) Always-On Synchronization Busy Mask */
#define WDT_SYNCBUSY_ALWAYSON WDT_SYNCBUSY_ALWAYSON_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use WDT_SYNCBUSY_ALWAYSON_Msk instead */
#define WDT_SYNCBUSY_CLEAR_Pos 5 /**< (WDT_SYNCBUSY) Clear Synchronization Busy Position */
#define WDT_SYNCBUSY_CLEAR_Msk (_U_(0x1) << WDT_SYNCBUSY_CLEAR_Pos) /**< (WDT_SYNCBUSY) Clear Synchronization Busy Mask */
#define WDT_SYNCBUSY_CLEAR WDT_SYNCBUSY_CLEAR_Msk /**< \deprecated Old style mask definition for 1 bit bitfield. Use WDT_SYNCBUSY_CLEAR_Msk instead */
#define WDT_SYNCBUSY_MASK _U_(0x3E) /**< \deprecated (WDT_SYNCBUSY) Register MASK (Use WDT_SYNCBUSY_Msk instead) */
#define WDT_SYNCBUSY_Msk _U_(0x3E) /**< (WDT_SYNCBUSY) Register Mask */
/* -------- WDT_CLEAR : (WDT Offset: 0x0c) (/W 8) Clear -------- */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef union {
struct {
uint8_t CLEAR:8; /**< bit: 0..7 Watchdog Clear */
} bit; /**< Structure used for bit access */
uint8_t reg; /**< Type used for register access */
} WDT_CLEAR_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#define WDT_CLEAR_OFFSET (0x0C) /**< (WDT_CLEAR) Clear Offset */
#define WDT_CLEAR_RESETVALUE _U_(0x00) /**< (WDT_CLEAR) Clear Reset Value */
#define WDT_CLEAR_CLEAR_Pos 0 /**< (WDT_CLEAR) Watchdog Clear Position */
#define WDT_CLEAR_CLEAR_Msk (_U_(0xFF) << WDT_CLEAR_CLEAR_Pos) /**< (WDT_CLEAR) Watchdog Clear Mask */
#define WDT_CLEAR_CLEAR(value) (WDT_CLEAR_CLEAR_Msk & ((value) << WDT_CLEAR_CLEAR_Pos))
#define WDT_CLEAR_CLEAR_KEY_Val _U_(0xA5) /**< (WDT_CLEAR) Clear Key */
#define WDT_CLEAR_CLEAR_KEY (WDT_CLEAR_CLEAR_KEY_Val << WDT_CLEAR_CLEAR_Pos) /**< (WDT_CLEAR) Clear Key Position */
#define WDT_CLEAR_MASK _U_(0xFF) /**< \deprecated (WDT_CLEAR) Register MASK (Use WDT_CLEAR_Msk instead) */
#define WDT_CLEAR_Msk _U_(0xFF) /**< (WDT_CLEAR) Register Mask */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
/** \brief WDT hardware registers */
typedef struct { /* Watchdog Timer */
__IO WDT_CTRLA_Type CTRLA; /**< Offset: 0x00 (R/W 8) Control */
__IO WDT_CONFIG_Type CONFIG; /**< Offset: 0x01 (R/W 8) Configuration */
__IO WDT_EWCTRL_Type EWCTRL; /**< Offset: 0x02 (R/W 8) Early Warning Interrupt Control */
__I uint8_t Reserved1[1];
__IO WDT_INTENCLR_Type INTENCLR; /**< Offset: 0x04 (R/W 8) Interrupt Enable Clear */
__IO WDT_INTENSET_Type INTENSET; /**< Offset: 0x05 (R/W 8) Interrupt Enable Set */
__IO WDT_INTFLAG_Type INTFLAG; /**< Offset: 0x06 (R/W 8) Interrupt Flag Status and Clear */
__I uint8_t Reserved2[1];
__I WDT_SYNCBUSY_Type SYNCBUSY; /**< Offset: 0x08 (R/ 32) Synchronization Busy */
__O WDT_CLEAR_Type CLEAR; /**< Offset: 0x0C ( /W 8) Clear */
} Wdt;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/** @} end of Watchdog Timer */
#endif /* _SAML10_WDT_COMPONENT_H_ */

View File

@ -0,0 +1,83 @@
/**
* \file
*
* \brief Instance description for AC
*
* Copyright (c) 2018 Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* 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
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
/* file generated from device description version 2018-08-31T13:51:50Z */
#ifndef _SAML10_AC_INSTANCE_H_
#define _SAML10_AC_INSTANCE_H_
/* ========== Register definition for AC peripheral ========== */
#if (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
#define REG_AC_CTRLA (0x40003400) /**< (AC) Control A */
#define REG_AC_CTRLB (0x40003401) /**< (AC) Control B */
#define REG_AC_EVCTRL (0x40003402) /**< (AC) Event Control */
#define REG_AC_INTENCLR (0x40003404) /**< (AC) Interrupt Enable Clear */
#define REG_AC_INTENSET (0x40003405) /**< (AC) Interrupt Enable Set */
#define REG_AC_INTFLAG (0x40003406) /**< (AC) Interrupt Flag Status and Clear */
#define REG_AC_STATUSA (0x40003407) /**< (AC) Status A */
#define REG_AC_STATUSB (0x40003408) /**< (AC) Status B */
#define REG_AC_DBGCTRL (0x40003409) /**< (AC) Debug Control */
#define REG_AC_WINCTRL (0x4000340A) /**< (AC) Window Control */
#define REG_AC_SCALER (0x4000340C) /**< (AC) Scaler n */
#define REG_AC_SCALER0 (0x4000340C) /**< (AC) Scaler 0 */
#define REG_AC_SCALER1 (0x4000340D) /**< (AC) Scaler 1 */
#define REG_AC_COMPCTRL (0x40003410) /**< (AC) Comparator Control n */
#define REG_AC_COMPCTRL0 (0x40003410) /**< (AC) Comparator Control 0 */
#define REG_AC_COMPCTRL1 (0x40003414) /**< (AC) Comparator Control 1 */
#define REG_AC_SYNCBUSY (0x40003420) /**< (AC) Synchronization Busy */
#else
#define REG_AC_CTRLA (*(__IO uint8_t*)0x40003400U) /**< (AC) Control A */
#define REG_AC_CTRLB (*(__O uint8_t*)0x40003401U) /**< (AC) Control B */
#define REG_AC_EVCTRL (*(__IO uint16_t*)0x40003402U) /**< (AC) Event Control */
#define REG_AC_INTENCLR (*(__IO uint8_t*)0x40003404U) /**< (AC) Interrupt Enable Clear */
#define REG_AC_INTENSET (*(__IO uint8_t*)0x40003405U) /**< (AC) Interrupt Enable Set */
#define REG_AC_INTFLAG (*(__IO uint8_t*)0x40003406U) /**< (AC) Interrupt Flag Status and Clear */
#define REG_AC_STATUSA (*(__I uint8_t*)0x40003407U) /**< (AC) Status A */
#define REG_AC_STATUSB (*(__I uint8_t*)0x40003408U) /**< (AC) Status B */
#define REG_AC_DBGCTRL (*(__IO uint8_t*)0x40003409U) /**< (AC) Debug Control */
#define REG_AC_WINCTRL (*(__IO uint8_t*)0x4000340AU) /**< (AC) Window Control */
#define REG_AC_SCALER (*(__IO uint8_t*)0x4000340CU) /**< (AC) Scaler n */
#define REG_AC_SCALER0 (*(__IO uint8_t*)0x4000340CU) /**< (AC) Scaler 0 */
#define REG_AC_SCALER1 (*(__IO uint8_t*)0x4000340DU) /**< (AC) Scaler 1 */
#define REG_AC_COMPCTRL (*(__IO uint32_t*)0x40003410U) /**< (AC) Comparator Control n */
#define REG_AC_COMPCTRL0 (*(__IO uint32_t*)0x40003410U) /**< (AC) Comparator Control 0 */
#define REG_AC_COMPCTRL1 (*(__IO uint32_t*)0x40003414U) /**< (AC) Comparator Control 1 */
#define REG_AC_SYNCBUSY (*(__I uint32_t*)0x40003420U) /**< (AC) Synchronization Busy */
#endif /* (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/* ========== Instance Parameter definitions for AC peripheral ========== */
#define AC_GCLK_ID 17 /* Index of Generic Clock */
#define AC_NUM_CMP 2 /* Number of comparators */
#define AC_PAIRS 1 /* Number of pairs of comparators */
#define AC_INSTANCE_ID 13
#endif /* _SAML10_AC_INSTANCE_ */

View File

@ -0,0 +1,95 @@
/**
* \file
*
* \brief Instance description for ADC
*
* Copyright (c) 2018 Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* 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
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
/* file generated from device description version 2018-08-31T13:51:50Z */
#ifndef _SAML10_ADC_INSTANCE_H_
#define _SAML10_ADC_INSTANCE_H_
/* ========== Register definition for ADC peripheral ========== */
#if (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
#define REG_ADC_CTRLA (0x42001C00) /**< (ADC) Control A */
#define REG_ADC_CTRLB (0x42001C01) /**< (ADC) Control B */
#define REG_ADC_REFCTRL (0x42001C02) /**< (ADC) Reference Control */
#define REG_ADC_EVCTRL (0x42001C03) /**< (ADC) Event Control */
#define REG_ADC_INTENCLR (0x42001C04) /**< (ADC) Interrupt Enable Clear */
#define REG_ADC_INTENSET (0x42001C05) /**< (ADC) Interrupt Enable Set */
#define REG_ADC_INTFLAG (0x42001C06) /**< (ADC) Interrupt Flag Status and Clear */
#define REG_ADC_SEQSTATUS (0x42001C07) /**< (ADC) Sequence Status */
#define REG_ADC_INPUTCTRL (0x42001C08) /**< (ADC) Input Control */
#define REG_ADC_CTRLC (0x42001C0A) /**< (ADC) Control C */
#define REG_ADC_AVGCTRL (0x42001C0C) /**< (ADC) Average Control */
#define REG_ADC_SAMPCTRL (0x42001C0D) /**< (ADC) Sample Time Control */
#define REG_ADC_WINLT (0x42001C0E) /**< (ADC) Window Monitor Lower Threshold */
#define REG_ADC_WINUT (0x42001C10) /**< (ADC) Window Monitor Upper Threshold */
#define REG_ADC_GAINCORR (0x42001C12) /**< (ADC) Gain Correction */
#define REG_ADC_OFFSETCORR (0x42001C14) /**< (ADC) Offset Correction */
#define REG_ADC_SWTRIG (0x42001C18) /**< (ADC) Software Trigger */
#define REG_ADC_DBGCTRL (0x42001C1C) /**< (ADC) Debug Control */
#define REG_ADC_SYNCBUSY (0x42001C20) /**< (ADC) Synchronization Busy */
#define REG_ADC_RESULT (0x42001C24) /**< (ADC) Result */
#define REG_ADC_SEQCTRL (0x42001C28) /**< (ADC) Sequence Control */
#define REG_ADC_CALIB (0x42001C2C) /**< (ADC) Calibration */
#else
#define REG_ADC_CTRLA (*(__IO uint8_t*)0x42001C00U) /**< (ADC) Control A */
#define REG_ADC_CTRLB (*(__IO uint8_t*)0x42001C01U) /**< (ADC) Control B */
#define REG_ADC_REFCTRL (*(__IO uint8_t*)0x42001C02U) /**< (ADC) Reference Control */
#define REG_ADC_EVCTRL (*(__IO uint8_t*)0x42001C03U) /**< (ADC) Event Control */
#define REG_ADC_INTENCLR (*(__IO uint8_t*)0x42001C04U) /**< (ADC) Interrupt Enable Clear */
#define REG_ADC_INTENSET (*(__IO uint8_t*)0x42001C05U) /**< (ADC) Interrupt Enable Set */
#define REG_ADC_INTFLAG (*(__IO uint8_t*)0x42001C06U) /**< (ADC) Interrupt Flag Status and Clear */
#define REG_ADC_SEQSTATUS (*(__I uint8_t*)0x42001C07U) /**< (ADC) Sequence Status */
#define REG_ADC_INPUTCTRL (*(__IO uint16_t*)0x42001C08U) /**< (ADC) Input Control */
#define REG_ADC_CTRLC (*(__IO uint16_t*)0x42001C0AU) /**< (ADC) Control C */
#define REG_ADC_AVGCTRL (*(__IO uint8_t*)0x42001C0CU) /**< (ADC) Average Control */
#define REG_ADC_SAMPCTRL (*(__IO uint8_t*)0x42001C0DU) /**< (ADC) Sample Time Control */
#define REG_ADC_WINLT (*(__IO uint16_t*)0x42001C0EU) /**< (ADC) Window Monitor Lower Threshold */
#define REG_ADC_WINUT (*(__IO uint16_t*)0x42001C10U) /**< (ADC) Window Monitor Upper Threshold */
#define REG_ADC_GAINCORR (*(__IO uint16_t*)0x42001C12U) /**< (ADC) Gain Correction */
#define REG_ADC_OFFSETCORR (*(__IO uint16_t*)0x42001C14U) /**< (ADC) Offset Correction */
#define REG_ADC_SWTRIG (*(__IO uint8_t*)0x42001C18U) /**< (ADC) Software Trigger */
#define REG_ADC_DBGCTRL (*(__IO uint8_t*)0x42001C1CU) /**< (ADC) Debug Control */
#define REG_ADC_SYNCBUSY (*(__I uint16_t*)0x42001C20U) /**< (ADC) Synchronization Busy */
#define REG_ADC_RESULT (*(__I uint16_t*)0x42001C24U) /**< (ADC) Result */
#define REG_ADC_SEQCTRL (*(__IO uint32_t*)0x42001C28U) /**< (ADC) Sequence Control */
#define REG_ADC_CALIB (*(__IO uint16_t*)0x42001C2CU) /**< (ADC) Calibration */
#endif /* (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/* ========== Instance Parameter definitions for ADC peripheral ========== */
#define ADC_DMAC_ID_RESRDY 19 /* index of DMA RESRDY trigger */
#define ADC_EXTCHANNEL_MSB 9 /* Number of external channels */
#define ADC_GCLK_ID 16 /* index of Generic Clock */
#define ADC_INT_CH30 1 /* Select OPAMP or CTAT on Channel 30 */
#define ADC_MASTER_SLAVE_MODE 0 /* ADC Master/Slave Mode */
#define ADC_INSTANCE_ID 71
#endif /* _SAML10_ADC_INSTANCE_ */

View File

@ -0,0 +1,61 @@
/**
* \file
*
* \brief Instance description for CCL
*
* Copyright (c) 2018 Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* 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
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
/* file generated from device description version 2018-08-31T13:51:50Z */
#ifndef _SAML10_CCL_INSTANCE_H_
#define _SAML10_CCL_INSTANCE_H_
/* ========== Register definition for CCL peripheral ========== */
#if (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
#define REG_CCL_CTRL (0x42002C00) /**< (CCL) Control */
#define REG_CCL_SEQCTRL (0x42002C04) /**< (CCL) SEQ Control x */
#define REG_CCL_SEQCTRL0 (0x42002C04) /**< (CCL) SEQ Control x 0 */
#define REG_CCL_LUTCTRL (0x42002C08) /**< (CCL) LUT Control x */
#define REG_CCL_LUTCTRL0 (0x42002C08) /**< (CCL) LUT Control x 0 */
#define REG_CCL_LUTCTRL1 (0x42002C0C) /**< (CCL) LUT Control x 1 */
#else
#define REG_CCL_CTRL (*(__IO uint8_t*)0x42002C00U) /**< (CCL) Control */
#define REG_CCL_SEQCTRL (*(__IO uint8_t*)0x42002C04U) /**< (CCL) SEQ Control x */
#define REG_CCL_SEQCTRL0 (*(__IO uint8_t*)0x42002C04U) /**< (CCL) SEQ Control x 0 */
#define REG_CCL_LUTCTRL (*(__IO uint32_t*)0x42002C08U) /**< (CCL) LUT Control x */
#define REG_CCL_LUTCTRL0 (*(__IO uint32_t*)0x42002C08U) /**< (CCL) LUT Control x 0 */
#define REG_CCL_LUTCTRL1 (*(__IO uint32_t*)0x42002C0CU) /**< (CCL) LUT Control x 1 */
#endif /* (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/* ========== Instance Parameter definitions for CCL peripheral ========== */
#define CCL_GCLK_ID 20 /* GCLK index for CCL */
#define CCL_LUT_NUM 2 /* Number of LUT in a CCL */
#define CCL_SEQ_NUM 1 /* Number of SEQ in a CCL */
#define CCL_INSTANCE_ID 75
#endif /* _SAML10_CCL_INSTANCE_ */

View File

@ -0,0 +1,70 @@
/**
* \file
*
* \brief Instance description for DAC
*
* Copyright (c) 2018 Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* 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
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
/* file generated from device description version 2018-08-31T13:51:50Z */
#ifndef _SAML10_DAC_INSTANCE_H_
#define _SAML10_DAC_INSTANCE_H_
/* ========== Register definition for DAC peripheral ========== */
#if (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
#define REG_DAC_CTRLA (0x42002000) /**< (DAC) Control A */
#define REG_DAC_CTRLB (0x42002001) /**< (DAC) Control B */
#define REG_DAC_EVCTRL (0x42002002) /**< (DAC) Event Control */
#define REG_DAC_INTENCLR (0x42002004) /**< (DAC) Interrupt Enable Clear */
#define REG_DAC_INTENSET (0x42002005) /**< (DAC) Interrupt Enable Set */
#define REG_DAC_INTFLAG (0x42002006) /**< (DAC) Interrupt Flag Status and Clear */
#define REG_DAC_STATUS (0x42002007) /**< (DAC) Status */
#define REG_DAC_DATA (0x42002008) /**< (DAC) Data */
#define REG_DAC_DATABUF (0x4200200C) /**< (DAC) Data Buffer */
#define REG_DAC_SYNCBUSY (0x42002010) /**< (DAC) Synchronization Busy */
#define REG_DAC_DBGCTRL (0x42002014) /**< (DAC) Debug Control */
#else
#define REG_DAC_CTRLA (*(__IO uint8_t*)0x42002000U) /**< (DAC) Control A */
#define REG_DAC_CTRLB (*(__IO uint8_t*)0x42002001U) /**< (DAC) Control B */
#define REG_DAC_EVCTRL (*(__IO uint8_t*)0x42002002U) /**< (DAC) Event Control */
#define REG_DAC_INTENCLR (*(__IO uint8_t*)0x42002004U) /**< (DAC) Interrupt Enable Clear */
#define REG_DAC_INTENSET (*(__IO uint8_t*)0x42002005U) /**< (DAC) Interrupt Enable Set */
#define REG_DAC_INTFLAG (*(__IO uint8_t*)0x42002006U) /**< (DAC) Interrupt Flag Status and Clear */
#define REG_DAC_STATUS (*(__I uint8_t*)0x42002007U) /**< (DAC) Status */
#define REG_DAC_DATA (*(__O uint16_t*)0x42002008U) /**< (DAC) Data */
#define REG_DAC_DATABUF (*(__O uint16_t*)0x4200200CU) /**< (DAC) Data Buffer */
#define REG_DAC_SYNCBUSY (*(__I uint32_t*)0x42002010U) /**< (DAC) Synchronization Busy */
#define REG_DAC_DBGCTRL (*(__IO uint8_t*)0x42002014U) /**< (DAC) Debug Control */
#endif /* (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/* ========== Instance Parameter definitions for DAC peripheral ========== */
#define DAC_DMAC_ID_EMPTY 20 /* Index of DMA EMPTY trigger */
#define DAC_GCLK_ID 18
#define DAC_INSTANCE_ID 72
#endif /* _SAML10_DAC_INSTANCE_ */

View File

@ -0,0 +1,103 @@
/**
* \file
*
* \brief Instance description for DMAC
*
* Copyright (c) 2018 Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* 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
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
/* file generated from device description version 2018-08-31T13:51:50Z */
#ifndef _SAML10_DMAC_INSTANCE_H_
#define _SAML10_DMAC_INSTANCE_H_
/* ========== Register definition for DMAC peripheral ========== */
#if (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
#define REG_DMAC_CTRL (0x41006000) /**< (DMAC) Control */
#define REG_DMAC_CRCCTRL (0x41006002) /**< (DMAC) CRC Control */
#define REG_DMAC_CRCDATAIN (0x41006004) /**< (DMAC) CRC Data Input */
#define REG_DMAC_CRCCHKSUM (0x41006008) /**< (DMAC) CRC Checksum */
#define REG_DMAC_CRCSTATUS (0x4100600C) /**< (DMAC) CRC Status */
#define REG_DMAC_DBGCTRL (0x4100600D) /**< (DMAC) Debug Control */
#define REG_DMAC_QOSCTRL (0x4100600E) /**< (DMAC) QOS Control */
#define REG_DMAC_SWTRIGCTRL (0x41006010) /**< (DMAC) Software Trigger Control */
#define REG_DMAC_PRICTRL0 (0x41006014) /**< (DMAC) Priority Control 0 */
#define REG_DMAC_INTPEND (0x41006020) /**< (DMAC) Interrupt Pending */
#define REG_DMAC_INTSTATUS (0x41006024) /**< (DMAC) Interrupt Status */
#define REG_DMAC_BUSYCH (0x41006028) /**< (DMAC) Busy Channels */
#define REG_DMAC_PENDCH (0x4100602C) /**< (DMAC) Pending Channels */
#define REG_DMAC_ACTIVE (0x41006030) /**< (DMAC) Active Channel and Levels */
#define REG_DMAC_BASEADDR (0x41006034) /**< (DMAC) Descriptor Memory Section Base Address */
#define REG_DMAC_WRBADDR (0x41006038) /**< (DMAC) Write-Back Memory Section Base Address */
#define REG_DMAC_CHID (0x4100603F) /**< (DMAC) Channel ID */
#define REG_DMAC_CHCTRLA (0x41006040) /**< (DMAC) Channel Control A */
#define REG_DMAC_CHCTRLB (0x41006044) /**< (DMAC) Channel Control B */
#define REG_DMAC_CHINTENCLR (0x4100604C) /**< (DMAC) Channel Interrupt Enable Clear */
#define REG_DMAC_CHINTENSET (0x4100604D) /**< (DMAC) Channel Interrupt Enable Set */
#define REG_DMAC_CHINTFLAG (0x4100604E) /**< (DMAC) Channel Interrupt Flag Status and Clear */
#define REG_DMAC_CHSTATUS (0x4100604F) /**< (DMAC) Channel Status */
#else
#define REG_DMAC_CTRL (*(__IO uint16_t*)0x41006000U) /**< (DMAC) Control */
#define REG_DMAC_CRCCTRL (*(__IO uint16_t*)0x41006002U) /**< (DMAC) CRC Control */
#define REG_DMAC_CRCDATAIN (*(__IO uint32_t*)0x41006004U) /**< (DMAC) CRC Data Input */
#define REG_DMAC_CRCCHKSUM (*(__IO uint32_t*)0x41006008U) /**< (DMAC) CRC Checksum */
#define REG_DMAC_CRCSTATUS (*(__IO uint8_t*)0x4100600CU) /**< (DMAC) CRC Status */
#define REG_DMAC_DBGCTRL (*(__IO uint8_t*)0x4100600DU) /**< (DMAC) Debug Control */
#define REG_DMAC_QOSCTRL (*(__IO uint8_t*)0x4100600EU) /**< (DMAC) QOS Control */
#define REG_DMAC_SWTRIGCTRL (*(__IO uint32_t*)0x41006010U) /**< (DMAC) Software Trigger Control */
#define REG_DMAC_PRICTRL0 (*(__IO uint32_t*)0x41006014U) /**< (DMAC) Priority Control 0 */
#define REG_DMAC_INTPEND (*(__IO uint16_t*)0x41006020U) /**< (DMAC) Interrupt Pending */
#define REG_DMAC_INTSTATUS (*(__I uint32_t*)0x41006024U) /**< (DMAC) Interrupt Status */
#define REG_DMAC_BUSYCH (*(__I uint32_t*)0x41006028U) /**< (DMAC) Busy Channels */
#define REG_DMAC_PENDCH (*(__I uint32_t*)0x4100602CU) /**< (DMAC) Pending Channels */
#define REG_DMAC_ACTIVE (*(__I uint32_t*)0x41006030U) /**< (DMAC) Active Channel and Levels */
#define REG_DMAC_BASEADDR (*(__IO uint32_t*)0x41006034U) /**< (DMAC) Descriptor Memory Section Base Address */
#define REG_DMAC_WRBADDR (*(__IO uint32_t*)0x41006038U) /**< (DMAC) Write-Back Memory Section Base Address */
#define REG_DMAC_CHID (*(__IO uint8_t*)0x4100603FU) /**< (DMAC) Channel ID */
#define REG_DMAC_CHCTRLA (*(__IO uint8_t*)0x41006040U) /**< (DMAC) Channel Control A */
#define REG_DMAC_CHCTRLB (*(__IO uint32_t*)0x41006044U) /**< (DMAC) Channel Control B */
#define REG_DMAC_CHINTENCLR (*(__IO uint8_t*)0x4100604CU) /**< (DMAC) Channel Interrupt Enable Clear */
#define REG_DMAC_CHINTENSET (*(__IO uint8_t*)0x4100604DU) /**< (DMAC) Channel Interrupt Enable Set */
#define REG_DMAC_CHINTFLAG (*(__IO uint8_t*)0x4100604EU) /**< (DMAC) Channel Interrupt Flag Status and Clear */
#define REG_DMAC_CHSTATUS (*(__I uint8_t*)0x4100604FU) /**< (DMAC) Channel Status */
#endif /* (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/* ========== Instance Parameter definitions for DMAC peripheral ========== */
#define DMAC_CH_BITS 3 /* Number of bits to select channel */
#define DMAC_CH_NUM 8 /* Number of channels */
#define DMAC_EVIN_NUM 4 /* Number of input events */
#define DMAC_EVOUT_NUM 4 /* Number of output events */
#define DMAC_LVL_BITS 2 /* Number of bit to select level priority */
#define DMAC_LVL_NUM 4 /* Enable priority level number */
#define DMAC_QOSCTRL_D_RESETVALUE 2 /* QOS dmac ahb interface reset value */
#define DMAC_QOSCTRL_F_RESETVALUE 2 /* QOS dmac fetch interface reset value */
#define DMAC_QOSCTRL_WRB_RESETVALUE 2 /* QOS dmac write back interface reset value */
#define DMAC_TRIG_BITS 5 /* Number of bits to select trigger source */
#define DMAC_TRIG_NUM 24 /* Number of peripheral triggers */
#define DMAC_INSTANCE_ID 35
#endif /* _SAML10_DMAC_INSTANCE_ */

View File

@ -0,0 +1,116 @@
/**
* \file
*
* \brief Instance description for DSU
*
* Copyright (c) 2018 Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* 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
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
/* file generated from device description version 2018-08-31T13:51:50Z */
#ifndef _SAML10_DSU_INSTANCE_H_
#define _SAML10_DSU_INSTANCE_H_
/* ========== Register definition for DSU peripheral ========== */
#if (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
#define REG_DSU_CTRL (0x41002000) /**< (DSU) Control */
#define REG_DSU_STATUSA (0x41002001) /**< (DSU) Status A */
#define REG_DSU_STATUSB (0x41002002) /**< (DSU) Status B */
#define REG_DSU_STATUSC (0x41002003) /**< (DSU) Status C */
#define REG_DSU_ADDR (0x41002004) /**< (DSU) Address */
#define REG_DSU_LENGTH (0x41002008) /**< (DSU) Length */
#define REG_DSU_DATA (0x4100200C) /**< (DSU) Data */
#define REG_DSU_DCC (0x41002010) /**< (DSU) Debug Communication Channel n */
#define REG_DSU_DCC0 (0x41002010) /**< (DSU) Debug Communication Channel 0 */
#define REG_DSU_DCC1 (0x41002014) /**< (DSU) Debug Communication Channel 1 */
#define REG_DSU_DID (0x41002018) /**< (DSU) Device Identification */
#define REG_DSU_CFG (0x4100201C) /**< (DSU) Configuration */
#define REG_DSU_BCC (0x41002020) /**< (DSU) Boot ROM Communication Channel n */
#define REG_DSU_BCC0 (0x41002020) /**< (DSU) Boot ROM Communication Channel 0 */
#define REG_DSU_BCC1 (0x41002024) /**< (DSU) Boot ROM Communication Channel 1 */
#define REG_DSU_DCFG (0x410020F0) /**< (DSU) Device Configuration */
#define REG_DSU_DCFG0 (0x410020F0) /**< (DSU) Device Configuration 0 */
#define REG_DSU_DCFG1 (0x410020F4) /**< (DSU) Device Configuration 1 */
#define REG_DSU_ENTRY0 (0x41003000) /**< (DSU) CoreSight ROM Table Entry 0 */
#define REG_DSU_ENTRY1 (0x41003004) /**< (DSU) CoreSight ROM Table Entry 1 */
#define REG_DSU_END (0x41003008) /**< (DSU) CoreSight ROM Table End */
#define REG_DSU_MEMTYPE (0x41003FCC) /**< (DSU) CoreSight ROM Table Memory Type */
#define REG_DSU_PID4 (0x41003FD0) /**< (DSU) Peripheral Identification 4 */
#define REG_DSU_PID5 (0x41003FD4) /**< (DSU) Peripheral Identification 5 */
#define REG_DSU_PID6 (0x41003FD8) /**< (DSU) Peripheral Identification 6 */
#define REG_DSU_PID7 (0x41003FDC) /**< (DSU) Peripheral Identification 7 */
#define REG_DSU_PID0 (0x41003FE0) /**< (DSU) Peripheral Identification 0 */
#define REG_DSU_PID1 (0x41003FE4) /**< (DSU) Peripheral Identification 1 */
#define REG_DSU_PID2 (0x41003FE8) /**< (DSU) Peripheral Identification 2 */
#define REG_DSU_PID3 (0x41003FEC) /**< (DSU) Peripheral Identification 3 */
#define REG_DSU_CID0 (0x41003FF0) /**< (DSU) Component Identification 0 */
#define REG_DSU_CID1 (0x41003FF4) /**< (DSU) Component Identification 1 */
#define REG_DSU_CID2 (0x41003FF8) /**< (DSU) Component Identification 2 */
#define REG_DSU_CID3 (0x41003FFC) /**< (DSU) Component Identification 3 */
#else
#define REG_DSU_CTRL (*(__O uint8_t*)0x41002000U) /**< (DSU) Control */
#define REG_DSU_STATUSA (*(__IO uint8_t*)0x41002001U) /**< (DSU) Status A */
#define REG_DSU_STATUSB (*(__I uint8_t*)0x41002002U) /**< (DSU) Status B */
#define REG_DSU_STATUSC (*(__I uint8_t*)0x41002003U) /**< (DSU) Status C */
#define REG_DSU_ADDR (*(__IO uint32_t*)0x41002004U) /**< (DSU) Address */
#define REG_DSU_LENGTH (*(__IO uint32_t*)0x41002008U) /**< (DSU) Length */
#define REG_DSU_DATA (*(__IO uint32_t*)0x4100200CU) /**< (DSU) Data */
#define REG_DSU_DCC (*(__IO uint32_t*)0x41002010U) /**< (DSU) Debug Communication Channel n */
#define REG_DSU_DCC0 (*(__IO uint32_t*)0x41002010U) /**< (DSU) Debug Communication Channel 0 */
#define REG_DSU_DCC1 (*(__IO uint32_t*)0x41002014U) /**< (DSU) Debug Communication Channel 1 */
#define REG_DSU_DID (*(__I uint32_t*)0x41002018U) /**< (DSU) Device Identification */
#define REG_DSU_CFG (*(__IO uint32_t*)0x4100201CU) /**< (DSU) Configuration */
#define REG_DSU_BCC (*(__IO uint32_t*)0x41002020U) /**< (DSU) Boot ROM Communication Channel n */
#define REG_DSU_BCC0 (*(__IO uint32_t*)0x41002020U) /**< (DSU) Boot ROM Communication Channel 0 */
#define REG_DSU_BCC1 (*(__IO uint32_t*)0x41002024U) /**< (DSU) Boot ROM Communication Channel 1 */
#define REG_DSU_DCFG (*(__IO uint32_t*)0x410020F0U) /**< (DSU) Device Configuration */
#define REG_DSU_DCFG0 (*(__IO uint32_t*)0x410020F0U) /**< (DSU) Device Configuration 0 */
#define REG_DSU_DCFG1 (*(__IO uint32_t*)0x410020F4U) /**< (DSU) Device Configuration 1 */
#define REG_DSU_ENTRY0 (*(__I uint32_t*)0x41003000U) /**< (DSU) CoreSight ROM Table Entry 0 */
#define REG_DSU_ENTRY1 (*(__I uint32_t*)0x41003004U) /**< (DSU) CoreSight ROM Table Entry 1 */
#define REG_DSU_END (*(__I uint32_t*)0x41003008U) /**< (DSU) CoreSight ROM Table End */
#define REG_DSU_MEMTYPE (*(__I uint32_t*)0x41003FCCU) /**< (DSU) CoreSight ROM Table Memory Type */
#define REG_DSU_PID4 (*(__I uint32_t*)0x41003FD0U) /**< (DSU) Peripheral Identification 4 */
#define REG_DSU_PID5 (*(__I uint32_t*)0x41003FD4U) /**< (DSU) Peripheral Identification 5 */
#define REG_DSU_PID6 (*(__I uint32_t*)0x41003FD8U) /**< (DSU) Peripheral Identification 6 */
#define REG_DSU_PID7 (*(__I uint32_t*)0x41003FDCU) /**< (DSU) Peripheral Identification 7 */
#define REG_DSU_PID0 (*(__I uint32_t*)0x41003FE0U) /**< (DSU) Peripheral Identification 0 */
#define REG_DSU_PID1 (*(__I uint32_t*)0x41003FE4U) /**< (DSU) Peripheral Identification 1 */
#define REG_DSU_PID2 (*(__I uint32_t*)0x41003FE8U) /**< (DSU) Peripheral Identification 2 */
#define REG_DSU_PID3 (*(__I uint32_t*)0x41003FECU) /**< (DSU) Peripheral Identification 3 */
#define REG_DSU_CID0 (*(__I uint32_t*)0x41003FF0U) /**< (DSU) Component Identification 0 */
#define REG_DSU_CID1 (*(__I uint32_t*)0x41003FF4U) /**< (DSU) Component Identification 1 */
#define REG_DSU_CID2 (*(__I uint32_t*)0x41003FF8U) /**< (DSU) Component Identification 2 */
#define REG_DSU_CID3 (*(__I uint32_t*)0x41003FFCU) /**< (DSU) Component Identification 3 */
#endif /* (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/* ========== Instance Parameter definitions for DSU peripheral ========== */
#define DSU_DMAC_ID_DCC0 2 /* DMAC ID for DCC0 register */
#define DSU_DMAC_ID_DCC1 3 /* DMAC ID for DCC1 register */
#define DSU_INSTANCE_ID 33
#endif /* _SAML10_DSU_INSTANCE_ */

View File

@ -0,0 +1,84 @@
/**
* \file
*
* \brief Instance description for EIC
*
* Copyright (c) 2018 Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* 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
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
/* file generated from device description version 2018-08-31T13:51:50Z */
#ifndef _SAML10_EIC_INSTANCE_H_
#define _SAML10_EIC_INSTANCE_H_
/* ========== Register definition for EIC peripheral ========== */
#if (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
#define REG_EIC_CTRLA (0x40002800) /**< (EIC) Control A */
#define REG_EIC_NMICTRL (0x40002801) /**< (EIC) Non-Maskable Interrupt Control */
#define REG_EIC_NMIFLAG (0x40002802) /**< (EIC) Non-Maskable Interrupt Flag Status and Clear */
#define REG_EIC_SYNCBUSY (0x40002804) /**< (EIC) Synchronization Busy */
#define REG_EIC_EVCTRL (0x40002808) /**< (EIC) Event Control */
#define REG_EIC_INTENCLR (0x4000280C) /**< (EIC) Interrupt Enable Clear */
#define REG_EIC_INTENSET (0x40002810) /**< (EIC) Interrupt Enable Set */
#define REG_EIC_INTFLAG (0x40002814) /**< (EIC) Interrupt Flag Status and Clear */
#define REG_EIC_ASYNCH (0x40002818) /**< (EIC) External Interrupt Asynchronous Mode */
#define REG_EIC_CONFIG (0x4000281C) /**< (EIC) External Interrupt Sense Configuration */
#define REG_EIC_CONFIG0 (0x4000281C) /**< (EIC) External Interrupt Sense Configuration 0 */
#define REG_EIC_DEBOUNCEN (0x40002830) /**< (EIC) Debouncer Enable */
#define REG_EIC_DPRESCALER (0x40002834) /**< (EIC) Debouncer Prescaler */
#define REG_EIC_PINSTATE (0x40002838) /**< (EIC) Pin State */
#define REG_EIC_NSCHK (0x4000283C) /**< (EIC) Non-secure Interrupt Check Enable */
#define REG_EIC_NONSEC (0x40002840) /**< (EIC) Non-secure Interrupt */
#else
#define REG_EIC_CTRLA (*(__IO uint8_t*)0x40002800U) /**< (EIC) Control A */
#define REG_EIC_NMICTRL (*(__IO uint8_t*)0x40002801U) /**< (EIC) Non-Maskable Interrupt Control */
#define REG_EIC_NMIFLAG (*(__IO uint16_t*)0x40002802U) /**< (EIC) Non-Maskable Interrupt Flag Status and Clear */
#define REG_EIC_SYNCBUSY (*(__I uint32_t*)0x40002804U) /**< (EIC) Synchronization Busy */
#define REG_EIC_EVCTRL (*(__IO uint32_t*)0x40002808U) /**< (EIC) Event Control */
#define REG_EIC_INTENCLR (*(__IO uint32_t*)0x4000280CU) /**< (EIC) Interrupt Enable Clear */
#define REG_EIC_INTENSET (*(__IO uint32_t*)0x40002810U) /**< (EIC) Interrupt Enable Set */
#define REG_EIC_INTFLAG (*(__IO uint32_t*)0x40002814U) /**< (EIC) Interrupt Flag Status and Clear */
#define REG_EIC_ASYNCH (*(__IO uint32_t*)0x40002818U) /**< (EIC) External Interrupt Asynchronous Mode */
#define REG_EIC_CONFIG (*(__IO uint32_t*)0x4000281CU) /**< (EIC) External Interrupt Sense Configuration */
#define REG_EIC_CONFIG0 (*(__IO uint32_t*)0x4000281CU) /**< (EIC) External Interrupt Sense Configuration 0 */
#define REG_EIC_DEBOUNCEN (*(__IO uint32_t*)0x40002830U) /**< (EIC) Debouncer Enable */
#define REG_EIC_DPRESCALER (*(__IO uint32_t*)0x40002834U) /**< (EIC) Debouncer Prescaler */
#define REG_EIC_PINSTATE (*(__I uint32_t*)0x40002838U) /**< (EIC) Pin State */
#define REG_EIC_NSCHK (*(__IO uint32_t*)0x4000283CU) /**< (EIC) Non-secure Interrupt Check Enable */
#define REG_EIC_NONSEC (*(__IO uint32_t*)0x40002840U) /**< (EIC) Non-secure Interrupt */
#endif /* (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/* ========== Instance Parameter definitions for EIC peripheral ========== */
#define EIC_EXTINT_NUM 8 /* Number of external interrupts */
#define EIC_GCLK_ID 3 /* Generic Clock index */
#define EIC_NUMBER_OF_CONFIG_REGS 1 /* Number of CONFIG registers */
#define EIC_NUMBER_OF_DPRESCALER_REGS 1 /* Number of DPRESCALER registers */
#define EIC_NUMBER_OF_INTERRUPTS 8 /* Number of external interrupts (obsolete) */
#define EIC_SECURE_IMPLEMENTED 1 /* Security Configuration implemented? */
#define EIC_INSTANCE_ID 10
#endif /* _SAML10_EIC_INSTANCE_ */

View File

@ -0,0 +1,221 @@
/**
* \file
*
* \brief Instance description for EVSYS
*
* Copyright (c) 2018 Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* 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
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
/* file generated from device description version 2018-08-31T13:51:50Z */
#ifndef _SAML10_EVSYS_INSTANCE_H_
#define _SAML10_EVSYS_INSTANCE_H_
/* ========== Register definition for EVSYS peripheral ========== */
#if (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
#define REG_EVSYS_CHANNEL0 (0x42000020) /**< (EVSYS) Channel 0 Control */
#define REG_EVSYS_CHINTENCLR0 (0x42000024) /**< (EVSYS) Channel 0 Interrupt Enable Clear */
#define REG_EVSYS_CHINTENSET0 (0x42000025) /**< (EVSYS) Channel 0 Interrupt Enable Set */
#define REG_EVSYS_CHINTFLAG0 (0x42000026) /**< (EVSYS) Channel 0 Interrupt Flag Status and Clear */
#define REG_EVSYS_CHSTATUS0 (0x42000027) /**< (EVSYS) Channel 0 Status */
#define REG_EVSYS_CHANNEL1 (0x42000028) /**< (EVSYS) Channel 1 Control */
#define REG_EVSYS_CHINTENCLR1 (0x4200002C) /**< (EVSYS) Channel 1 Interrupt Enable Clear */
#define REG_EVSYS_CHINTENSET1 (0x4200002D) /**< (EVSYS) Channel 1 Interrupt Enable Set */
#define REG_EVSYS_CHINTFLAG1 (0x4200002E) /**< (EVSYS) Channel 1 Interrupt Flag Status and Clear */
#define REG_EVSYS_CHSTATUS1 (0x4200002F) /**< (EVSYS) Channel 1 Status */
#define REG_EVSYS_CHANNEL2 (0x42000030) /**< (EVSYS) Channel 2 Control */
#define REG_EVSYS_CHINTENCLR2 (0x42000034) /**< (EVSYS) Channel 2 Interrupt Enable Clear */
#define REG_EVSYS_CHINTENSET2 (0x42000035) /**< (EVSYS) Channel 2 Interrupt Enable Set */
#define REG_EVSYS_CHINTFLAG2 (0x42000036) /**< (EVSYS) Channel 2 Interrupt Flag Status and Clear */
#define REG_EVSYS_CHSTATUS2 (0x42000037) /**< (EVSYS) Channel 2 Status */
#define REG_EVSYS_CHANNEL3 (0x42000038) /**< (EVSYS) Channel 3 Control */
#define REG_EVSYS_CHINTENCLR3 (0x4200003C) /**< (EVSYS) Channel 3 Interrupt Enable Clear */
#define REG_EVSYS_CHINTENSET3 (0x4200003D) /**< (EVSYS) Channel 3 Interrupt Enable Set */
#define REG_EVSYS_CHINTFLAG3 (0x4200003E) /**< (EVSYS) Channel 3 Interrupt Flag Status and Clear */
#define REG_EVSYS_CHSTATUS3 (0x4200003F) /**< (EVSYS) Channel 3 Status */
#define REG_EVSYS_CHANNEL4 (0x42000040) /**< (EVSYS) Channel 4 Control */
#define REG_EVSYS_CHINTENCLR4 (0x42000044) /**< (EVSYS) Channel 4 Interrupt Enable Clear */
#define REG_EVSYS_CHINTENSET4 (0x42000045) /**< (EVSYS) Channel 4 Interrupt Enable Set */
#define REG_EVSYS_CHINTFLAG4 (0x42000046) /**< (EVSYS) Channel 4 Interrupt Flag Status and Clear */
#define REG_EVSYS_CHSTATUS4 (0x42000047) /**< (EVSYS) Channel 4 Status */
#define REG_EVSYS_CHANNEL5 (0x42000048) /**< (EVSYS) Channel 5 Control */
#define REG_EVSYS_CHINTENCLR5 (0x4200004C) /**< (EVSYS) Channel 5 Interrupt Enable Clear */
#define REG_EVSYS_CHINTENSET5 (0x4200004D) /**< (EVSYS) Channel 5 Interrupt Enable Set */
#define REG_EVSYS_CHINTFLAG5 (0x4200004E) /**< (EVSYS) Channel 5 Interrupt Flag Status and Clear */
#define REG_EVSYS_CHSTATUS5 (0x4200004F) /**< (EVSYS) Channel 5 Status */
#define REG_EVSYS_CHANNEL6 (0x42000050) /**< (EVSYS) Channel 6 Control */
#define REG_EVSYS_CHINTENCLR6 (0x42000054) /**< (EVSYS) Channel 6 Interrupt Enable Clear */
#define REG_EVSYS_CHINTENSET6 (0x42000055) /**< (EVSYS) Channel 6 Interrupt Enable Set */
#define REG_EVSYS_CHINTFLAG6 (0x42000056) /**< (EVSYS) Channel 6 Interrupt Flag Status and Clear */
#define REG_EVSYS_CHSTATUS6 (0x42000057) /**< (EVSYS) Channel 6 Status */
#define REG_EVSYS_CHANNEL7 (0x42000058) /**< (EVSYS) Channel 7 Control */
#define REG_EVSYS_CHINTENCLR7 (0x4200005C) /**< (EVSYS) Channel 7 Interrupt Enable Clear */
#define REG_EVSYS_CHINTENSET7 (0x4200005D) /**< (EVSYS) Channel 7 Interrupt Enable Set */
#define REG_EVSYS_CHINTFLAG7 (0x4200005E) /**< (EVSYS) Channel 7 Interrupt Flag Status and Clear */
#define REG_EVSYS_CHSTATUS7 (0x4200005F) /**< (EVSYS) Channel 7 Status */
#define REG_EVSYS_CTRLA (0x42000000) /**< (EVSYS) Control */
#define REG_EVSYS_SWEVT (0x42000004) /**< (EVSYS) Software Event */
#define REG_EVSYS_PRICTRL (0x42000008) /**< (EVSYS) Priority Control */
#define REG_EVSYS_INTPEND (0x42000010) /**< (EVSYS) Channel Pending Interrupt */
#define REG_EVSYS_INTSTATUS (0x42000014) /**< (EVSYS) Interrupt Status */
#define REG_EVSYS_BUSYCH (0x42000018) /**< (EVSYS) Busy Channels */
#define REG_EVSYS_READYUSR (0x4200001C) /**< (EVSYS) Ready Users */
#define REG_EVSYS_USER (0x42000120) /**< (EVSYS) User Multiplexer n */
#define REG_EVSYS_USER0 (0x42000120) /**< (EVSYS) User Multiplexer 0 */
#define REG_EVSYS_USER1 (0x42000121) /**< (EVSYS) User Multiplexer 1 */
#define REG_EVSYS_USER2 (0x42000122) /**< (EVSYS) User Multiplexer 2 */
#define REG_EVSYS_USER3 (0x42000123) /**< (EVSYS) User Multiplexer 3 */
#define REG_EVSYS_USER4 (0x42000124) /**< (EVSYS) User Multiplexer 4 */
#define REG_EVSYS_USER5 (0x42000125) /**< (EVSYS) User Multiplexer 5 */
#define REG_EVSYS_USER6 (0x42000126) /**< (EVSYS) User Multiplexer 6 */
#define REG_EVSYS_USER7 (0x42000127) /**< (EVSYS) User Multiplexer 7 */
#define REG_EVSYS_USER8 (0x42000128) /**< (EVSYS) User Multiplexer 8 */
#define REG_EVSYS_USER9 (0x42000129) /**< (EVSYS) User Multiplexer 9 */
#define REG_EVSYS_USER10 (0x4200012A) /**< (EVSYS) User Multiplexer 10 */
#define REG_EVSYS_USER11 (0x4200012B) /**< (EVSYS) User Multiplexer 11 */
#define REG_EVSYS_USER12 (0x4200012C) /**< (EVSYS) User Multiplexer 12 */
#define REG_EVSYS_USER13 (0x4200012D) /**< (EVSYS) User Multiplexer 13 */
#define REG_EVSYS_USER14 (0x4200012E) /**< (EVSYS) User Multiplexer 14 */
#define REG_EVSYS_USER15 (0x4200012F) /**< (EVSYS) User Multiplexer 15 */
#define REG_EVSYS_USER16 (0x42000130) /**< (EVSYS) User Multiplexer 16 */
#define REG_EVSYS_USER17 (0x42000131) /**< (EVSYS) User Multiplexer 17 */
#define REG_EVSYS_USER18 (0x42000132) /**< (EVSYS) User Multiplexer 18 */
#define REG_EVSYS_USER19 (0x42000133) /**< (EVSYS) User Multiplexer 19 */
#define REG_EVSYS_USER20 (0x42000134) /**< (EVSYS) User Multiplexer 20 */
#define REG_EVSYS_USER21 (0x42000135) /**< (EVSYS) User Multiplexer 21 */
#define REG_EVSYS_USER22 (0x42000136) /**< (EVSYS) User Multiplexer 22 */
#define REG_EVSYS_INTENCLR (0x420001D4) /**< (EVSYS) Interrupt Enable Clear */
#define REG_EVSYS_INTENSET (0x420001D5) /**< (EVSYS) Interrupt Enable Set */
#define REG_EVSYS_INTFLAG (0x420001D6) /**< (EVSYS) Interrupt Flag Status and Clear */
#define REG_EVSYS_NONSECCHAN (0x420001D8) /**< (EVSYS) Channels Security Attribution */
#define REG_EVSYS_NSCHKCHAN (0x420001DC) /**< (EVSYS) Non-Secure Channels Check */
#define REG_EVSYS_NONSECUSER (0x420001E0) /**< (EVSYS) Users Security Attribution */
#define REG_EVSYS_NONSECUSER0 (0x420001E0) /**< (EVSYS) Users Security Attribution 0 */
#define REG_EVSYS_NSCHKUSER (0x420001F0) /**< (EVSYS) Non-Secure Users Check */
#define REG_EVSYS_NSCHKUSER0 (0x420001F0) /**< (EVSYS) Non-Secure Users Check 0 */
#else
#define REG_EVSYS_CHANNEL0 (*(__IO uint32_t*)0x42000020U) /**< (EVSYS) Channel 0 Control */
#define REG_EVSYS_CHINTENCLR0 (*(__IO uint8_t*)0x42000024U) /**< (EVSYS) Channel 0 Interrupt Enable Clear */
#define REG_EVSYS_CHINTENSET0 (*(__IO uint8_t*)0x42000025U) /**< (EVSYS) Channel 0 Interrupt Enable Set */
#define REG_EVSYS_CHINTFLAG0 (*(__IO uint8_t*)0x42000026U) /**< (EVSYS) Channel 0 Interrupt Flag Status and Clear */
#define REG_EVSYS_CHSTATUS0 (*(__I uint8_t*)0x42000027U) /**< (EVSYS) Channel 0 Status */
#define REG_EVSYS_CHANNEL1 (*(__IO uint32_t*)0x42000028U) /**< (EVSYS) Channel 1 Control */
#define REG_EVSYS_CHINTENCLR1 (*(__IO uint8_t*)0x4200002CU) /**< (EVSYS) Channel 1 Interrupt Enable Clear */
#define REG_EVSYS_CHINTENSET1 (*(__IO uint8_t*)0x4200002DU) /**< (EVSYS) Channel 1 Interrupt Enable Set */
#define REG_EVSYS_CHINTFLAG1 (*(__IO uint8_t*)0x4200002EU) /**< (EVSYS) Channel 1 Interrupt Flag Status and Clear */
#define REG_EVSYS_CHSTATUS1 (*(__I uint8_t*)0x4200002FU) /**< (EVSYS) Channel 1 Status */
#define REG_EVSYS_CHANNEL2 (*(__IO uint32_t*)0x42000030U) /**< (EVSYS) Channel 2 Control */
#define REG_EVSYS_CHINTENCLR2 (*(__IO uint8_t*)0x42000034U) /**< (EVSYS) Channel 2 Interrupt Enable Clear */
#define REG_EVSYS_CHINTENSET2 (*(__IO uint8_t*)0x42000035U) /**< (EVSYS) Channel 2 Interrupt Enable Set */
#define REG_EVSYS_CHINTFLAG2 (*(__IO uint8_t*)0x42000036U) /**< (EVSYS) Channel 2 Interrupt Flag Status and Clear */
#define REG_EVSYS_CHSTATUS2 (*(__I uint8_t*)0x42000037U) /**< (EVSYS) Channel 2 Status */
#define REG_EVSYS_CHANNEL3 (*(__IO uint32_t*)0x42000038U) /**< (EVSYS) Channel 3 Control */
#define REG_EVSYS_CHINTENCLR3 (*(__IO uint8_t*)0x4200003CU) /**< (EVSYS) Channel 3 Interrupt Enable Clear */
#define REG_EVSYS_CHINTENSET3 (*(__IO uint8_t*)0x4200003DU) /**< (EVSYS) Channel 3 Interrupt Enable Set */
#define REG_EVSYS_CHINTFLAG3 (*(__IO uint8_t*)0x4200003EU) /**< (EVSYS) Channel 3 Interrupt Flag Status and Clear */
#define REG_EVSYS_CHSTATUS3 (*(__I uint8_t*)0x4200003FU) /**< (EVSYS) Channel 3 Status */
#define REG_EVSYS_CHANNEL4 (*(__IO uint32_t*)0x42000040U) /**< (EVSYS) Channel 4 Control */
#define REG_EVSYS_CHINTENCLR4 (*(__IO uint8_t*)0x42000044U) /**< (EVSYS) Channel 4 Interrupt Enable Clear */
#define REG_EVSYS_CHINTENSET4 (*(__IO uint8_t*)0x42000045U) /**< (EVSYS) Channel 4 Interrupt Enable Set */
#define REG_EVSYS_CHINTFLAG4 (*(__IO uint8_t*)0x42000046U) /**< (EVSYS) Channel 4 Interrupt Flag Status and Clear */
#define REG_EVSYS_CHSTATUS4 (*(__I uint8_t*)0x42000047U) /**< (EVSYS) Channel 4 Status */
#define REG_EVSYS_CHANNEL5 (*(__IO uint32_t*)0x42000048U) /**< (EVSYS) Channel 5 Control */
#define REG_EVSYS_CHINTENCLR5 (*(__IO uint8_t*)0x4200004CU) /**< (EVSYS) Channel 5 Interrupt Enable Clear */
#define REG_EVSYS_CHINTENSET5 (*(__IO uint8_t*)0x4200004DU) /**< (EVSYS) Channel 5 Interrupt Enable Set */
#define REG_EVSYS_CHINTFLAG5 (*(__IO uint8_t*)0x4200004EU) /**< (EVSYS) Channel 5 Interrupt Flag Status and Clear */
#define REG_EVSYS_CHSTATUS5 (*(__I uint8_t*)0x4200004FU) /**< (EVSYS) Channel 5 Status */
#define REG_EVSYS_CHANNEL6 (*(__IO uint32_t*)0x42000050U) /**< (EVSYS) Channel 6 Control */
#define REG_EVSYS_CHINTENCLR6 (*(__IO uint8_t*)0x42000054U) /**< (EVSYS) Channel 6 Interrupt Enable Clear */
#define REG_EVSYS_CHINTENSET6 (*(__IO uint8_t*)0x42000055U) /**< (EVSYS) Channel 6 Interrupt Enable Set */
#define REG_EVSYS_CHINTFLAG6 (*(__IO uint8_t*)0x42000056U) /**< (EVSYS) Channel 6 Interrupt Flag Status and Clear */
#define REG_EVSYS_CHSTATUS6 (*(__I uint8_t*)0x42000057U) /**< (EVSYS) Channel 6 Status */
#define REG_EVSYS_CHANNEL7 (*(__IO uint32_t*)0x42000058U) /**< (EVSYS) Channel 7 Control */
#define REG_EVSYS_CHINTENCLR7 (*(__IO uint8_t*)0x4200005CU) /**< (EVSYS) Channel 7 Interrupt Enable Clear */
#define REG_EVSYS_CHINTENSET7 (*(__IO uint8_t*)0x4200005DU) /**< (EVSYS) Channel 7 Interrupt Enable Set */
#define REG_EVSYS_CHINTFLAG7 (*(__IO uint8_t*)0x4200005EU) /**< (EVSYS) Channel 7 Interrupt Flag Status and Clear */
#define REG_EVSYS_CHSTATUS7 (*(__I uint8_t*)0x4200005FU) /**< (EVSYS) Channel 7 Status */
#define REG_EVSYS_CTRLA (*(__O uint8_t*)0x42000000U) /**< (EVSYS) Control */
#define REG_EVSYS_SWEVT (*(__O uint32_t*)0x42000004U) /**< (EVSYS) Software Event */
#define REG_EVSYS_PRICTRL (*(__IO uint8_t*)0x42000008U) /**< (EVSYS) Priority Control */
#define REG_EVSYS_INTPEND (*(__IO uint16_t*)0x42000010U) /**< (EVSYS) Channel Pending Interrupt */
#define REG_EVSYS_INTSTATUS (*(__I uint32_t*)0x42000014U) /**< (EVSYS) Interrupt Status */
#define REG_EVSYS_BUSYCH (*(__I uint32_t*)0x42000018U) /**< (EVSYS) Busy Channels */
#define REG_EVSYS_READYUSR (*(__I uint32_t*)0x4200001CU) /**< (EVSYS) Ready Users */
#define REG_EVSYS_USER (*(__IO uint8_t*)0x42000120U) /**< (EVSYS) User Multiplexer n */
#define REG_EVSYS_USER0 (*(__IO uint8_t*)0x42000120U) /**< (EVSYS) User Multiplexer 0 */
#define REG_EVSYS_USER1 (*(__IO uint8_t*)0x42000121U) /**< (EVSYS) User Multiplexer 1 */
#define REG_EVSYS_USER2 (*(__IO uint8_t*)0x42000122U) /**< (EVSYS) User Multiplexer 2 */
#define REG_EVSYS_USER3 (*(__IO uint8_t*)0x42000123U) /**< (EVSYS) User Multiplexer 3 */
#define REG_EVSYS_USER4 (*(__IO uint8_t*)0x42000124U) /**< (EVSYS) User Multiplexer 4 */
#define REG_EVSYS_USER5 (*(__IO uint8_t*)0x42000125U) /**< (EVSYS) User Multiplexer 5 */
#define REG_EVSYS_USER6 (*(__IO uint8_t*)0x42000126U) /**< (EVSYS) User Multiplexer 6 */
#define REG_EVSYS_USER7 (*(__IO uint8_t*)0x42000127U) /**< (EVSYS) User Multiplexer 7 */
#define REG_EVSYS_USER8 (*(__IO uint8_t*)0x42000128U) /**< (EVSYS) User Multiplexer 8 */
#define REG_EVSYS_USER9 (*(__IO uint8_t*)0x42000129U) /**< (EVSYS) User Multiplexer 9 */
#define REG_EVSYS_USER10 (*(__IO uint8_t*)0x4200012AU) /**< (EVSYS) User Multiplexer 10 */
#define REG_EVSYS_USER11 (*(__IO uint8_t*)0x4200012BU) /**< (EVSYS) User Multiplexer 11 */
#define REG_EVSYS_USER12 (*(__IO uint8_t*)0x4200012CU) /**< (EVSYS) User Multiplexer 12 */
#define REG_EVSYS_USER13 (*(__IO uint8_t*)0x4200012DU) /**< (EVSYS) User Multiplexer 13 */
#define REG_EVSYS_USER14 (*(__IO uint8_t*)0x4200012EU) /**< (EVSYS) User Multiplexer 14 */
#define REG_EVSYS_USER15 (*(__IO uint8_t*)0x4200012FU) /**< (EVSYS) User Multiplexer 15 */
#define REG_EVSYS_USER16 (*(__IO uint8_t*)0x42000130U) /**< (EVSYS) User Multiplexer 16 */
#define REG_EVSYS_USER17 (*(__IO uint8_t*)0x42000131U) /**< (EVSYS) User Multiplexer 17 */
#define REG_EVSYS_USER18 (*(__IO uint8_t*)0x42000132U) /**< (EVSYS) User Multiplexer 18 */
#define REG_EVSYS_USER19 (*(__IO uint8_t*)0x42000133U) /**< (EVSYS) User Multiplexer 19 */
#define REG_EVSYS_USER20 (*(__IO uint8_t*)0x42000134U) /**< (EVSYS) User Multiplexer 20 */
#define REG_EVSYS_USER21 (*(__IO uint8_t*)0x42000135U) /**< (EVSYS) User Multiplexer 21 */
#define REG_EVSYS_USER22 (*(__IO uint8_t*)0x42000136U) /**< (EVSYS) User Multiplexer 22 */
#define REG_EVSYS_INTENCLR (*(__IO uint8_t*)0x420001D4U) /**< (EVSYS) Interrupt Enable Clear */
#define REG_EVSYS_INTENSET (*(__IO uint8_t*)0x420001D5U) /**< (EVSYS) Interrupt Enable Set */
#define REG_EVSYS_INTFLAG (*(__IO uint8_t*)0x420001D6U) /**< (EVSYS) Interrupt Flag Status and Clear */
#define REG_EVSYS_NONSECCHAN (*(__IO uint32_t*)0x420001D8U) /**< (EVSYS) Channels Security Attribution */
#define REG_EVSYS_NSCHKCHAN (*(__IO uint32_t*)0x420001DCU) /**< (EVSYS) Non-Secure Channels Check */
#define REG_EVSYS_NONSECUSER (*(__IO uint32_t*)0x420001E0U) /**< (EVSYS) Users Security Attribution */
#define REG_EVSYS_NONSECUSER0 (*(__IO uint32_t*)0x420001E0U) /**< (EVSYS) Users Security Attribution 0 */
#define REG_EVSYS_NSCHKUSER (*(__IO uint32_t*)0x420001F0U) /**< (EVSYS) Non-Secure Users Check */
#define REG_EVSYS_NSCHKUSER0 (*(__IO uint32_t*)0x420001F0U) /**< (EVSYS) Non-Secure Users Check 0 */
#endif /* (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/* ========== Instance Parameter definitions for EVSYS peripheral ========== */
#define EVSYS_ASYNCHRONOUS_CHANNELS 0x000000F0 /* Mask of Only Asynchronous Channels */
#define EVSYS_CHANNELS 8 /* Number of Channels */
#define EVSYS_CHANNELS_BITS 3 /* Number of bits to select Channel */
#define EVSYS_GCLK_ID_0 6 /* Index of Generic Clock 0 */
#define EVSYS_GCLK_ID_1 7 /* Index of Generic Clock 1 */
#define EVSYS_GCLK_ID_2 8 /* Index of Generic Clock 2 */
#define EVSYS_GCLK_ID_3 9 /* Index of Generic Clock 3 */
#define EVSYS_GENERATORS 49 /* Total Number of Event Generators */
#define EVSYS_GENERATORS_BITS 6 /* Number of bits to select Event Generator */
#define EVSYS_SECURE_IMPLEMENTED 1 /* Secure Channels/Users supported? */
#define EVSYS_SYNCH_NUM 4 /* Number of Synchronous Channels */
#define EVSYS_SYNCH_NUM_BITS 2 /* Number of bits to select Synchronous Channels */
#define EVSYS_USERS 23 /* Total Number of Event Users */
#define EVSYS_USERS_BITS 5 /* Number of bits to select Event User */
#define EVSYS_USERS_GROUPS 1 /* Number of 32-user groups */
#define EVSYS_INSTANCE_ID 64
#endif /* _SAML10_EVSYS_INSTANCE_ */

View File

@ -0,0 +1,66 @@
/**
* \file
*
* \brief Instance description for FREQM
*
* Copyright (c) 2018 Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* 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
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
/* file generated from device description version 2018-08-31T13:51:50Z */
#ifndef _SAML10_FREQM_INSTANCE_H_
#define _SAML10_FREQM_INSTANCE_H_
/* ========== Register definition for FREQM peripheral ========== */
#if (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
#define REG_FREQM_CTRLA (0x40002C00) /**< (FREQM) Control A Register */
#define REG_FREQM_CTRLB (0x40002C01) /**< (FREQM) Control B Register */
#define REG_FREQM_CFGA (0x40002C02) /**< (FREQM) Config A register */
#define REG_FREQM_INTENCLR (0x40002C08) /**< (FREQM) Interrupt Enable Clear Register */
#define REG_FREQM_INTENSET (0x40002C09) /**< (FREQM) Interrupt Enable Set Register */
#define REG_FREQM_INTFLAG (0x40002C0A) /**< (FREQM) Interrupt Flag Register */
#define REG_FREQM_STATUS (0x40002C0B) /**< (FREQM) Status Register */
#define REG_FREQM_SYNCBUSY (0x40002C0C) /**< (FREQM) Synchronization Busy Register */
#define REG_FREQM_VALUE (0x40002C10) /**< (FREQM) Count Value Register */
#else
#define REG_FREQM_CTRLA (*(__IO uint8_t*)0x40002C00U) /**< (FREQM) Control A Register */
#define REG_FREQM_CTRLB (*(__O uint8_t*)0x40002C01U) /**< (FREQM) Control B Register */
#define REG_FREQM_CFGA (*(__IO uint16_t*)0x40002C02U) /**< (FREQM) Config A register */
#define REG_FREQM_INTENCLR (*(__IO uint8_t*)0x40002C08U) /**< (FREQM) Interrupt Enable Clear Register */
#define REG_FREQM_INTENSET (*(__IO uint8_t*)0x40002C09U) /**< (FREQM) Interrupt Enable Set Register */
#define REG_FREQM_INTFLAG (*(__IO uint8_t*)0x40002C0AU) /**< (FREQM) Interrupt Flag Register */
#define REG_FREQM_STATUS (*(__IO uint8_t*)0x40002C0BU) /**< (FREQM) Status Register */
#define REG_FREQM_SYNCBUSY (*(__I uint32_t*)0x40002C0CU) /**< (FREQM) Synchronization Busy Register */
#define REG_FREQM_VALUE (*(__I uint32_t*)0x40002C10U) /**< (FREQM) Count Value Register */
#endif /* (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/* ========== Instance Parameter definitions for FREQM peripheral ========== */
#define FREQM_GCLK_ID_MSR 4 /* Index of measure generic clock */
#define FREQM_GCLK_ID_REF 5 /* Index of reference generic clock */
#define FREQM_INSTANCE_ID 11
#endif /* _SAML10_FREQM_INSTANCE_ */

View File

@ -0,0 +1,114 @@
/**
* \file
*
* \brief Instance description for GCLK
*
* Copyright (c) 2018 Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* 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
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
/* file generated from device description version 2018-08-31T13:51:50Z */
#ifndef _SAML10_GCLK_INSTANCE_H_
#define _SAML10_GCLK_INSTANCE_H_
/* ========== Register definition for GCLK peripheral ========== */
#if (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
#define REG_GCLK_CTRLA (0x40001C00) /**< (GCLK) Control */
#define REG_GCLK_SYNCBUSY (0x40001C04) /**< (GCLK) Synchronization Busy */
#define REG_GCLK_GENCTRL (0x40001C20) /**< (GCLK) Generic Clock Generator Control */
#define REG_GCLK_GENCTRL0 (0x40001C20) /**< (GCLK) Generic Clock Generator Control 0 */
#define REG_GCLK_GENCTRL1 (0x40001C24) /**< (GCLK) Generic Clock Generator Control 1 */
#define REG_GCLK_GENCTRL2 (0x40001C28) /**< (GCLK) Generic Clock Generator Control 2 */
#define REG_GCLK_GENCTRL3 (0x40001C2C) /**< (GCLK) Generic Clock Generator Control 3 */
#define REG_GCLK_GENCTRL4 (0x40001C30) /**< (GCLK) Generic Clock Generator Control 4 */
#define REG_GCLK_PCHCTRL (0x40001C80) /**< (GCLK) Peripheral Clock Control */
#define REG_GCLK_PCHCTRL0 (0x40001C80) /**< (GCLK) Peripheral Clock Control 0 */
#define REG_GCLK_PCHCTRL1 (0x40001C84) /**< (GCLK) Peripheral Clock Control 1 */
#define REG_GCLK_PCHCTRL2 (0x40001C88) /**< (GCLK) Peripheral Clock Control 2 */
#define REG_GCLK_PCHCTRL3 (0x40001C8C) /**< (GCLK) Peripheral Clock Control 3 */
#define REG_GCLK_PCHCTRL4 (0x40001C90) /**< (GCLK) Peripheral Clock Control 4 */
#define REG_GCLK_PCHCTRL5 (0x40001C94) /**< (GCLK) Peripheral Clock Control 5 */
#define REG_GCLK_PCHCTRL6 (0x40001C98) /**< (GCLK) Peripheral Clock Control 6 */
#define REG_GCLK_PCHCTRL7 (0x40001C9C) /**< (GCLK) Peripheral Clock Control 7 */
#define REG_GCLK_PCHCTRL8 (0x40001CA0) /**< (GCLK) Peripheral Clock Control 8 */
#define REG_GCLK_PCHCTRL9 (0x40001CA4) /**< (GCLK) Peripheral Clock Control 9 */
#define REG_GCLK_PCHCTRL10 (0x40001CA8) /**< (GCLK) Peripheral Clock Control 10 */
#define REG_GCLK_PCHCTRL11 (0x40001CAC) /**< (GCLK) Peripheral Clock Control 11 */
#define REG_GCLK_PCHCTRL12 (0x40001CB0) /**< (GCLK) Peripheral Clock Control 12 */
#define REG_GCLK_PCHCTRL13 (0x40001CB4) /**< (GCLK) Peripheral Clock Control 13 */
#define REG_GCLK_PCHCTRL14 (0x40001CB8) /**< (GCLK) Peripheral Clock Control 14 */
#define REG_GCLK_PCHCTRL15 (0x40001CBC) /**< (GCLK) Peripheral Clock Control 15 */
#define REG_GCLK_PCHCTRL16 (0x40001CC0) /**< (GCLK) Peripheral Clock Control 16 */
#define REG_GCLK_PCHCTRL17 (0x40001CC4) /**< (GCLK) Peripheral Clock Control 17 */
#define REG_GCLK_PCHCTRL18 (0x40001CC8) /**< (GCLK) Peripheral Clock Control 18 */
#define REG_GCLK_PCHCTRL19 (0x40001CCC) /**< (GCLK) Peripheral Clock Control 19 */
#define REG_GCLK_PCHCTRL20 (0x40001CD0) /**< (GCLK) Peripheral Clock Control 20 */
#else
#define REG_GCLK_CTRLA (*(__IO uint8_t*)0x40001C00U) /**< (GCLK) Control */
#define REG_GCLK_SYNCBUSY (*(__I uint32_t*)0x40001C04U) /**< (GCLK) Synchronization Busy */
#define REG_GCLK_GENCTRL (*(__IO uint32_t*)0x40001C20U) /**< (GCLK) Generic Clock Generator Control */
#define REG_GCLK_GENCTRL0 (*(__IO uint32_t*)0x40001C20U) /**< (GCLK) Generic Clock Generator Control 0 */
#define REG_GCLK_GENCTRL1 (*(__IO uint32_t*)0x40001C24U) /**< (GCLK) Generic Clock Generator Control 1 */
#define REG_GCLK_GENCTRL2 (*(__IO uint32_t*)0x40001C28U) /**< (GCLK) Generic Clock Generator Control 2 */
#define REG_GCLK_GENCTRL3 (*(__IO uint32_t*)0x40001C2CU) /**< (GCLK) Generic Clock Generator Control 3 */
#define REG_GCLK_GENCTRL4 (*(__IO uint32_t*)0x40001C30U) /**< (GCLK) Generic Clock Generator Control 4 */
#define REG_GCLK_PCHCTRL (*(__IO uint32_t*)0x40001C80U) /**< (GCLK) Peripheral Clock Control */
#define REG_GCLK_PCHCTRL0 (*(__IO uint32_t*)0x40001C80U) /**< (GCLK) Peripheral Clock Control 0 */
#define REG_GCLK_PCHCTRL1 (*(__IO uint32_t*)0x40001C84U) /**< (GCLK) Peripheral Clock Control 1 */
#define REG_GCLK_PCHCTRL2 (*(__IO uint32_t*)0x40001C88U) /**< (GCLK) Peripheral Clock Control 2 */
#define REG_GCLK_PCHCTRL3 (*(__IO uint32_t*)0x40001C8CU) /**< (GCLK) Peripheral Clock Control 3 */
#define REG_GCLK_PCHCTRL4 (*(__IO uint32_t*)0x40001C90U) /**< (GCLK) Peripheral Clock Control 4 */
#define REG_GCLK_PCHCTRL5 (*(__IO uint32_t*)0x40001C94U) /**< (GCLK) Peripheral Clock Control 5 */
#define REG_GCLK_PCHCTRL6 (*(__IO uint32_t*)0x40001C98U) /**< (GCLK) Peripheral Clock Control 6 */
#define REG_GCLK_PCHCTRL7 (*(__IO uint32_t*)0x40001C9CU) /**< (GCLK) Peripheral Clock Control 7 */
#define REG_GCLK_PCHCTRL8 (*(__IO uint32_t*)0x40001CA0U) /**< (GCLK) Peripheral Clock Control 8 */
#define REG_GCLK_PCHCTRL9 (*(__IO uint32_t*)0x40001CA4U) /**< (GCLK) Peripheral Clock Control 9 */
#define REG_GCLK_PCHCTRL10 (*(__IO uint32_t*)0x40001CA8U) /**< (GCLK) Peripheral Clock Control 10 */
#define REG_GCLK_PCHCTRL11 (*(__IO uint32_t*)0x40001CACU) /**< (GCLK) Peripheral Clock Control 11 */
#define REG_GCLK_PCHCTRL12 (*(__IO uint32_t*)0x40001CB0U) /**< (GCLK) Peripheral Clock Control 12 */
#define REG_GCLK_PCHCTRL13 (*(__IO uint32_t*)0x40001CB4U) /**< (GCLK) Peripheral Clock Control 13 */
#define REG_GCLK_PCHCTRL14 (*(__IO uint32_t*)0x40001CB8U) /**< (GCLK) Peripheral Clock Control 14 */
#define REG_GCLK_PCHCTRL15 (*(__IO uint32_t*)0x40001CBCU) /**< (GCLK) Peripheral Clock Control 15 */
#define REG_GCLK_PCHCTRL16 (*(__IO uint32_t*)0x40001CC0U) /**< (GCLK) Peripheral Clock Control 16 */
#define REG_GCLK_PCHCTRL17 (*(__IO uint32_t*)0x40001CC4U) /**< (GCLK) Peripheral Clock Control 17 */
#define REG_GCLK_PCHCTRL18 (*(__IO uint32_t*)0x40001CC8U) /**< (GCLK) Peripheral Clock Control 18 */
#define REG_GCLK_PCHCTRL19 (*(__IO uint32_t*)0x40001CCCU) /**< (GCLK) Peripheral Clock Control 19 */
#define REG_GCLK_PCHCTRL20 (*(__IO uint32_t*)0x40001CD0U) /**< (GCLK) Peripheral Clock Control 20 */
#endif /* (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/* ========== Instance Parameter definitions for GCLK peripheral ========== */
#define GCLK_GENDIV_BITS 16
#define GCLK_GEN_BITS 3
#define GCLK_GEN_NUM 5 /* Number of Generic Clock Generators */
#define GCLK_GEN_NUM_MSB 4 /* Number of Generic Clock Generators - 1 */
#define GCLK_GEN_SOURCE_NUM_MSB 7 /* Number of Generic Clock Sources - 1 */
#define GCLK_NUM 21 /* Number of Generic Clock Users */
#define GCLK_SOURCE_BITS 3
#define GCLK_SOURCE_NUM 8 /* Number of Generic Clock Sources */
#define GCLK_INSTANCE_ID 7
#endif /* _SAML10_GCLK_INSTANCE_ */

View File

@ -0,0 +1,53 @@
/**
* \file
*
* \brief Instance description for IDAU
*
* Copyright (c) 2018 Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* 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
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
/* file generated from device description version 2018-08-31T13:51:50Z */
#ifndef _SAML10_IDAU_INSTANCE_H_
#define _SAML10_IDAU_INSTANCE_H_
/* ========== Register definition for IDAU peripheral ========== */
#if (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
#else
#endif /* (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/* ========== Instance Parameter definitions for IDAU peripheral ========== */
#define IDAU_GRANULARITY_BOOTPROT 0x100 /* BOOTPROT region granularity */
#define IDAU_REGION_BOOTROM 0x09 /* Boot ROM region number */
#define IDAU_REGION_IOBUS 0x00 /* IOBUS region number (invalid) */
#define IDAU_REGION_OTHER 0x00 /* Others region number (invalid) */
#define IDAU_REGION_PERIPHERALS 0x00 /* Peripherals region number (invalid) */
#define IDAU_INSTANCE_ID 32
#endif /* _SAML10_IDAU_INSTANCE_ */

View File

@ -0,0 +1,66 @@
/**
* \file
*
* \brief Instance description for MCLK
*
* Copyright (c) 2018 Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* 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
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
/* file generated from device description version 2018-08-31T13:51:50Z */
#ifndef _SAML10_MCLK_INSTANCE_H_
#define _SAML10_MCLK_INSTANCE_H_
/* ========== Register definition for MCLK peripheral ========== */
#if (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
#define REG_MCLK_CTRLA (0x40000800) /**< (MCLK) Control */
#define REG_MCLK_INTENCLR (0x40000801) /**< (MCLK) Interrupt Enable Clear */
#define REG_MCLK_INTENSET (0x40000802) /**< (MCLK) Interrupt Enable Set */
#define REG_MCLK_INTFLAG (0x40000803) /**< (MCLK) Interrupt Flag Status and Clear */
#define REG_MCLK_CPUDIV (0x40000804) /**< (MCLK) CPU Clock Division */
#define REG_MCLK_AHBMASK (0x40000810) /**< (MCLK) AHB Mask */
#define REG_MCLK_APBAMASK (0x40000814) /**< (MCLK) APBA Mask */
#define REG_MCLK_APBBMASK (0x40000818) /**< (MCLK) APBB Mask */
#define REG_MCLK_APBCMASK (0x4000081C) /**< (MCLK) APBC Mask */
#else
#define REG_MCLK_CTRLA (*(__IO uint8_t*)0x40000800U) /**< (MCLK) Control */
#define REG_MCLK_INTENCLR (*(__IO uint8_t*)0x40000801U) /**< (MCLK) Interrupt Enable Clear */
#define REG_MCLK_INTENSET (*(__IO uint8_t*)0x40000802U) /**< (MCLK) Interrupt Enable Set */
#define REG_MCLK_INTFLAG (*(__IO uint8_t*)0x40000803U) /**< (MCLK) Interrupt Flag Status and Clear */
#define REG_MCLK_CPUDIV (*(__IO uint8_t*)0x40000804U) /**< (MCLK) CPU Clock Division */
#define REG_MCLK_AHBMASK (*(__IO uint32_t*)0x40000810U) /**< (MCLK) AHB Mask */
#define REG_MCLK_APBAMASK (*(__IO uint32_t*)0x40000814U) /**< (MCLK) APBA Mask */
#define REG_MCLK_APBBMASK (*(__IO uint32_t*)0x40000818U) /**< (MCLK) APBB Mask */
#define REG_MCLK_APBCMASK (*(__IO uint32_t*)0x4000081CU) /**< (MCLK) APBC Mask */
#endif /* (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/* ========== Instance Parameter definitions for MCLK peripheral ========== */
#define MCLK_MCLK_CLK_APB_NUM 3
#define MCLK_SYSTEM_CLOCK 4000000 /* System Clock Frequency at Reset */
#define MCLK_INSTANCE_ID 2
#endif /* _SAML10_MCLK_INSTANCE_ */

View File

@ -0,0 +1,100 @@
/**
* \file
*
* \brief Instance description for NVMCTRL
*
* Copyright (c) 2018 Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* 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
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
/* file generated from device description version 2018-08-31T13:51:50Z */
#ifndef _SAML10_NVMCTRL_INSTANCE_H_
#define _SAML10_NVMCTRL_INSTANCE_H_
/* ========== Register definition for NVMCTRL peripheral ========== */
#if (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
#define REG_NVMCTRL_CTRLA (0x41004000) /**< (NVMCTRL) Control A */
#define REG_NVMCTRL_CTRLB (0x41004004) /**< (NVMCTRL) Control B */
#define REG_NVMCTRL_CTRLC (0x41004008) /**< (NVMCTRL) Control C */
#define REG_NVMCTRL_EVCTRL (0x4100400A) /**< (NVMCTRL) Event Control */
#define REG_NVMCTRL_INTENCLR (0x4100400C) /**< (NVMCTRL) Interrupt Enable Clear */
#define REG_NVMCTRL_INTENSET (0x41004010) /**< (NVMCTRL) Interrupt Enable Set */
#define REG_NVMCTRL_INTFLAG (0x41004014) /**< (NVMCTRL) Interrupt Flag Status and Clear */
#define REG_NVMCTRL_STATUS (0x41004018) /**< (NVMCTRL) Status */
#define REG_NVMCTRL_ADDR (0x4100401C) /**< (NVMCTRL) Address */
#define REG_NVMCTRL_SULCK (0x41004020) /**< (NVMCTRL) Secure Unlock Register */
#define REG_NVMCTRL_NSULCK (0x41004022) /**< (NVMCTRL) Non-Secure Unlock Register */
#define REG_NVMCTRL_PARAM (0x41004024) /**< (NVMCTRL) NVM Parameter */
#define REG_NVMCTRL_DSCC (0x41004030) /**< (NVMCTRL) Data Scramble Configuration */
#define REG_NVMCTRL_SECCTRL (0x41004034) /**< (NVMCTRL) Security Control */
#define REG_NVMCTRL_SCFGB (0x41004038) /**< (NVMCTRL) Secure Boot Configuration */
#define REG_NVMCTRL_SCFGAD (0x4100403C) /**< (NVMCTRL) Secure Application and Data Configuration */
#define REG_NVMCTRL_NONSEC (0x41004040) /**< (NVMCTRL) Non-secure Write Enable */
#define REG_NVMCTRL_NSCHK (0x41004044) /**< (NVMCTRL) Non-secure Write Reference Value */
#else
#define REG_NVMCTRL_CTRLA (*(__O uint16_t*)0x41004000U) /**< (NVMCTRL) Control A */
#define REG_NVMCTRL_CTRLB (*(__IO uint32_t*)0x41004004U) /**< (NVMCTRL) Control B */
#define REG_NVMCTRL_CTRLC (*(__IO uint8_t*)0x41004008U) /**< (NVMCTRL) Control C */
#define REG_NVMCTRL_EVCTRL (*(__IO uint8_t*)0x4100400AU) /**< (NVMCTRL) Event Control */
#define REG_NVMCTRL_INTENCLR (*(__IO uint8_t*)0x4100400CU) /**< (NVMCTRL) Interrupt Enable Clear */
#define REG_NVMCTRL_INTENSET (*(__IO uint8_t*)0x41004010U) /**< (NVMCTRL) Interrupt Enable Set */
#define REG_NVMCTRL_INTFLAG (*(__IO uint8_t*)0x41004014U) /**< (NVMCTRL) Interrupt Flag Status and Clear */
#define REG_NVMCTRL_STATUS (*(__I uint16_t*)0x41004018U) /**< (NVMCTRL) Status */
#define REG_NVMCTRL_ADDR (*(__IO uint32_t*)0x4100401CU) /**< (NVMCTRL) Address */
#define REG_NVMCTRL_SULCK (*(__IO uint16_t*)0x41004020U) /**< (NVMCTRL) Secure Unlock Register */
#define REG_NVMCTRL_NSULCK (*(__IO uint16_t*)0x41004022U) /**< (NVMCTRL) Non-Secure Unlock Register */
#define REG_NVMCTRL_PARAM (*(__IO uint32_t*)0x41004024U) /**< (NVMCTRL) NVM Parameter */
#define REG_NVMCTRL_DSCC (*(__O uint32_t*)0x41004030U) /**< (NVMCTRL) Data Scramble Configuration */
#define REG_NVMCTRL_SECCTRL (*(__IO uint32_t*)0x41004034U) /**< (NVMCTRL) Security Control */
#define REG_NVMCTRL_SCFGB (*(__IO uint32_t*)0x41004038U) /**< (NVMCTRL) Secure Boot Configuration */
#define REG_NVMCTRL_SCFGAD (*(__IO uint32_t*)0x4100403CU) /**< (NVMCTRL) Secure Application and Data Configuration */
#define REG_NVMCTRL_NONSEC (*(__IO uint32_t*)0x41004040U) /**< (NVMCTRL) Non-secure Write Enable */
#define REG_NVMCTRL_NSCHK (*(__IO uint32_t*)0x41004044U) /**< (NVMCTRL) Non-secure Write Reference Value */
#endif /* (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/* ========== Instance Parameter definitions for NVMCTRL peripheral ========== */
#define NVMCTRL_DATAFLASH_PAGES 32
#define NVMCTRL_PMSB 3
#define NVMCTRL_PSZ_BITS 6
#define NVMCTRL_ROW_PAGES 4
#define NVMCTRL_SECURE_IMPLEMENTED 1 /* Security Configuration implemented? */
#define NVMCTRL_FLASH_SIZE 65536
#define NVMCTRL_PAGE_SIZE 64
#define NVMCTRL_PAGES 1024
#define NVMCTRL_PAGES_PR_REGION 64
#define NVMCTRL_PSM_0_FRMFW_FWS_1_MAX_FREQ 12000000
#define NVMCTRL_PSM_0_FRMLP_FWS_0_MAX_FREQ 18000000
#define NVMCTRL_PSM_0_FRMLP_FWS_1_MAX_FREQ 36000000
#define NVMCTRL_PSM_0_FRMHS_FWS_0_MAX_FREQ 25000000
#define NVMCTRL_PSM_0_FRMHS_FWS_1_MAX_FREQ 50000000
#define NVMCTRL_PSM_1_FRMFW_FWS_1_MAX_FREQ 12000000
#define NVMCTRL_PSM_1_FRMLP_FWS_0_MAX_FREQ 8000000
#define NVMCTRL_PSM_1_FRMLP_FWS_1_MAX_FREQ 12000000
#define NVMCTRL_INSTANCE_ID 34
#define NVMCTRL_ROW_SIZE 256
#endif /* _SAML10_NVMCTRL_INSTANCE_ */

View File

@ -0,0 +1,60 @@
/**
* \file
*
* \brief Instance description for OPAMP
*
* Copyright (c) 2018 Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* 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
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
/* file generated from device description version 2018-08-31T13:51:50Z */
#ifndef _SAML10_OPAMP_INSTANCE_H_
#define _SAML10_OPAMP_INSTANCE_H_
/* ========== Register definition for OPAMP peripheral ========== */
#if (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
#define REG_OPAMP_CTRLA (0x42003000) /**< (OPAMP) Control A */
#define REG_OPAMP_STATUS (0x42003002) /**< (OPAMP) Status */
#define REG_OPAMP_OPAMPCTRL (0x42003004) /**< (OPAMP) OPAMP n Control */
#define REG_OPAMP_OPAMPCTRL0 (0x42003004) /**< (OPAMP) OPAMP 0 Control */
#define REG_OPAMP_OPAMPCTRL1 (0x42003008) /**< (OPAMP) OPAMP 1 Control */
#define REG_OPAMP_OPAMPCTRL2 (0x4200300C) /**< (OPAMP) OPAMP 2 Control */
#define REG_OPAMP_RESCTRL (0x42003010) /**< (OPAMP) Resister Control */
#else
#define REG_OPAMP_CTRLA (*(__IO uint8_t*)0x42003000U) /**< (OPAMP) Control A */
#define REG_OPAMP_STATUS (*(__I uint8_t*)0x42003002U) /**< (OPAMP) Status */
#define REG_OPAMP_OPAMPCTRL (*(__IO uint32_t*)0x42003004U) /**< (OPAMP) OPAMP n Control */
#define REG_OPAMP_OPAMPCTRL0 (*(__IO uint32_t*)0x42003004U) /**< (OPAMP) OPAMP 0 Control */
#define REG_OPAMP_OPAMPCTRL1 (*(__IO uint32_t*)0x42003008U) /**< (OPAMP) OPAMP 1 Control */
#define REG_OPAMP_OPAMPCTRL2 (*(__IO uint32_t*)0x4200300CU) /**< (OPAMP) OPAMP 2 Control */
#define REG_OPAMP_RESCTRL (*(__IO uint8_t*)0x42003010U) /**< (OPAMP) Resister Control */
#endif /* (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/* ========== Instance Parameter definitions for OPAMP peripheral ========== */
#define OPAMP_INSTANCE_ID 76
#endif /* _SAML10_OPAMP_INSTANCE_ */

View File

@ -0,0 +1,65 @@
/**
* \file
*
* \brief Instance description for OSC32KCTRL
*
* Copyright (c) 2018 Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* 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
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
/* file generated from device description version 2018-08-31T13:51:50Z */
#ifndef _SAML10_OSC32KCTRL_INSTANCE_H_
#define _SAML10_OSC32KCTRL_INSTANCE_H_
/* ========== Register definition for OSC32KCTRL peripheral ========== */
#if (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
#define REG_OSC32KCTRL_INTENCLR (0x40001400) /**< (OSC32KCTRL) Interrupt Enable Clear */
#define REG_OSC32KCTRL_INTENSET (0x40001404) /**< (OSC32KCTRL) Interrupt Enable Set */
#define REG_OSC32KCTRL_INTFLAG (0x40001408) /**< (OSC32KCTRL) Interrupt Flag Status and Clear */
#define REG_OSC32KCTRL_STATUS (0x4000140C) /**< (OSC32KCTRL) Power and Clocks Status */
#define REG_OSC32KCTRL_RTCCTRL (0x40001410) /**< (OSC32KCTRL) RTC Clock Selection */
#define REG_OSC32KCTRL_XOSC32K (0x40001414) /**< (OSC32KCTRL) 32kHz External Crystal Oscillator (XOSC32K) Control */
#define REG_OSC32KCTRL_CFDCTRL (0x40001416) /**< (OSC32KCTRL) Clock Failure Detector Control */
#define REG_OSC32KCTRL_EVCTRL (0x40001417) /**< (OSC32KCTRL) Event Control */
#define REG_OSC32KCTRL_OSCULP32K (0x4000141C) /**< (OSC32KCTRL) 32kHz Ultra Low Power Internal Oscillator (OSCULP32K) Control */
#else
#define REG_OSC32KCTRL_INTENCLR (*(__IO uint32_t*)0x40001400U) /**< (OSC32KCTRL) Interrupt Enable Clear */
#define REG_OSC32KCTRL_INTENSET (*(__IO uint32_t*)0x40001404U) /**< (OSC32KCTRL) Interrupt Enable Set */
#define REG_OSC32KCTRL_INTFLAG (*(__IO uint32_t*)0x40001408U) /**< (OSC32KCTRL) Interrupt Flag Status and Clear */
#define REG_OSC32KCTRL_STATUS (*(__I uint32_t*)0x4000140CU) /**< (OSC32KCTRL) Power and Clocks Status */
#define REG_OSC32KCTRL_RTCCTRL (*(__IO uint8_t*)0x40001410U) /**< (OSC32KCTRL) RTC Clock Selection */
#define REG_OSC32KCTRL_XOSC32K (*(__IO uint16_t*)0x40001414U) /**< (OSC32KCTRL) 32kHz External Crystal Oscillator (XOSC32K) Control */
#define REG_OSC32KCTRL_CFDCTRL (*(__IO uint8_t*)0x40001416U) /**< (OSC32KCTRL) Clock Failure Detector Control */
#define REG_OSC32KCTRL_EVCTRL (*(__IO uint8_t*)0x40001417U) /**< (OSC32KCTRL) Event Control */
#define REG_OSC32KCTRL_OSCULP32K (*(__IO uint32_t*)0x4000141CU) /**< (OSC32KCTRL) 32kHz Ultra Low Power Internal Oscillator (OSCULP32K) Control */
#endif /* (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/* ========== Instance Parameter definitions for OSC32KCTRL peripheral ========== */
#define OSC32KCTRL_OSC32K_COARSE_CALIB_MSB 0
#define OSC32KCTRL_INSTANCE_ID 5
#endif /* _SAML10_OSC32KCTRL_INSTANCE_ */

View File

@ -0,0 +1,94 @@
/**
* \file
*
* \brief Instance description for OSCCTRL
*
* Copyright (c) 2018 Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* 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
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
/* file generated from device description version 2018-08-31T13:51:50Z */
#ifndef _SAML10_OSCCTRL_INSTANCE_H_
#define _SAML10_OSCCTRL_INSTANCE_H_
/* ========== Register definition for OSCCTRL peripheral ========== */
#if (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
#define REG_OSCCTRL_EVCTRL (0x40001000) /**< (OSCCTRL) Event Control */
#define REG_OSCCTRL_INTENCLR (0x40001004) /**< (OSCCTRL) Interrupt Enable Clear */
#define REG_OSCCTRL_INTENSET (0x40001008) /**< (OSCCTRL) Interrupt Enable Set */
#define REG_OSCCTRL_INTFLAG (0x4000100C) /**< (OSCCTRL) Interrupt Flag Status and Clear */
#define REG_OSCCTRL_STATUS (0x40001010) /**< (OSCCTRL) Status */
#define REG_OSCCTRL_XOSCCTRL (0x40001014) /**< (OSCCTRL) External Multipurpose Crystal Oscillator (XOSC) Control */
#define REG_OSCCTRL_CFDPRESC (0x40001016) /**< (OSCCTRL) Clock Failure Detector Prescaler */
#define REG_OSCCTRL_OSC16MCTRL (0x40001018) /**< (OSCCTRL) 16MHz Internal Oscillator (OSC16M) Control */
#define REG_OSCCTRL_DFLLULPCTRL (0x4000101C) /**< (OSCCTRL) DFLLULP Control */
#define REG_OSCCTRL_DFLLULPDITHER (0x4000101E) /**< (OSCCTRL) DFLLULP Dither Control */
#define REG_OSCCTRL_DFLLULPRREQ (0x4000101F) /**< (OSCCTRL) DFLLULP Read Request */
#define REG_OSCCTRL_DFLLULPDLY (0x40001020) /**< (OSCCTRL) DFLLULP Delay Value */
#define REG_OSCCTRL_DFLLULPRATIO (0x40001024) /**< (OSCCTRL) DFLLULP Target Ratio */
#define REG_OSCCTRL_DFLLULPSYNCBUSY (0x40001028) /**< (OSCCTRL) DFLLULP Synchronization Busy */
#define REG_OSCCTRL_DPLLCTRLA (0x4000102C) /**< (OSCCTRL) DPLL Control A */
#define REG_OSCCTRL_DPLLRATIO (0x40001030) /**< (OSCCTRL) DPLL Ratio Control */
#define REG_OSCCTRL_DPLLCTRLB (0x40001034) /**< (OSCCTRL) DPLL Control B */
#define REG_OSCCTRL_DPLLPRESC (0x40001038) /**< (OSCCTRL) DPLL Prescaler */
#define REG_OSCCTRL_DPLLSYNCBUSY (0x4000103C) /**< (OSCCTRL) DPLL Synchronization Busy */
#define REG_OSCCTRL_DPLLSTATUS (0x40001040) /**< (OSCCTRL) DPLL Status */
#else
#define REG_OSCCTRL_EVCTRL (*(__IO uint8_t*)0x40001000U) /**< (OSCCTRL) Event Control */
#define REG_OSCCTRL_INTENCLR (*(__IO uint32_t*)0x40001004U) /**< (OSCCTRL) Interrupt Enable Clear */
#define REG_OSCCTRL_INTENSET (*(__IO uint32_t*)0x40001008U) /**< (OSCCTRL) Interrupt Enable Set */
#define REG_OSCCTRL_INTFLAG (*(__IO uint32_t*)0x4000100CU) /**< (OSCCTRL) Interrupt Flag Status and Clear */
#define REG_OSCCTRL_STATUS (*(__I uint32_t*)0x40001010U) /**< (OSCCTRL) Status */
#define REG_OSCCTRL_XOSCCTRL (*(__IO uint16_t*)0x40001014U) /**< (OSCCTRL) External Multipurpose Crystal Oscillator (XOSC) Control */
#define REG_OSCCTRL_CFDPRESC (*(__IO uint8_t*)0x40001016U) /**< (OSCCTRL) Clock Failure Detector Prescaler */
#define REG_OSCCTRL_OSC16MCTRL (*(__IO uint8_t*)0x40001018U) /**< (OSCCTRL) 16MHz Internal Oscillator (OSC16M) Control */
#define REG_OSCCTRL_DFLLULPCTRL (*(__IO uint16_t*)0x4000101CU) /**< (OSCCTRL) DFLLULP Control */
#define REG_OSCCTRL_DFLLULPDITHER (*(__IO uint8_t*)0x4000101EU) /**< (OSCCTRL) DFLLULP Dither Control */
#define REG_OSCCTRL_DFLLULPRREQ (*(__IO uint8_t*)0x4000101FU) /**< (OSCCTRL) DFLLULP Read Request */
#define REG_OSCCTRL_DFLLULPDLY (*(__IO uint32_t*)0x40001020U) /**< (OSCCTRL) DFLLULP Delay Value */
#define REG_OSCCTRL_DFLLULPRATIO (*(__IO uint32_t*)0x40001024U) /**< (OSCCTRL) DFLLULP Target Ratio */
#define REG_OSCCTRL_DFLLULPSYNCBUSY (*(__I uint32_t*)0x40001028U) /**< (OSCCTRL) DFLLULP Synchronization Busy */
#define REG_OSCCTRL_DPLLCTRLA (*(__IO uint8_t*)0x4000102CU) /**< (OSCCTRL) DPLL Control A */
#define REG_OSCCTRL_DPLLRATIO (*(__IO uint32_t*)0x40001030U) /**< (OSCCTRL) DPLL Ratio Control */
#define REG_OSCCTRL_DPLLCTRLB (*(__IO uint32_t*)0x40001034U) /**< (OSCCTRL) DPLL Control B */
#define REG_OSCCTRL_DPLLPRESC (*(__IO uint8_t*)0x40001038U) /**< (OSCCTRL) DPLL Prescaler */
#define REG_OSCCTRL_DPLLSYNCBUSY (*(__I uint8_t*)0x4000103CU) /**< (OSCCTRL) DPLL Synchronization Busy */
#define REG_OSCCTRL_DPLLSTATUS (*(__I uint8_t*)0x40001040U) /**< (OSCCTRL) DPLL Status */
#endif /* (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/* ========== Instance Parameter definitions for OSCCTRL peripheral ========== */
#define OSCCTRL_GCLK_ID_DFLLULP 2 /* Index of Generic Clock for DFLLULP */
#define OSCCTRL_GCLK_ID_DPLL 0 /* Index of Generic Clock for DPLL */
#define OSCCTRL_GCLK_ID_DPLL32K 1 /* Index of Generic Clock for DPLL 32K */
#define OSCCTRL_CFD_VERSION 0x112
#define OSCCTRL_DFLLULP_VERSION 0x100
#define OSCCTRL_FDPLL_VERSION 0x213
#define OSCCTRL_OSC16M_VERSION 0x102
#define OSCCTRL_XOSC_VERSION 0x210
#define OSCCTRL_INSTANCE_ID 4
#endif /* _SAML10_OSCCTRL_INSTANCE_ */

View File

@ -0,0 +1,82 @@
/**
* \file
*
* \brief Instance description for PAC
*
* Copyright (c) 2018 Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* 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
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
/* file generated from device description version 2018-08-31T13:51:50Z */
#ifndef _SAML10_PAC_INSTANCE_H_
#define _SAML10_PAC_INSTANCE_H_
/* ========== Register definition for PAC peripheral ========== */
#if (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
#define REG_PAC_WRCTRL (0x40000000) /**< (PAC) Write control */
#define REG_PAC_EVCTRL (0x40000004) /**< (PAC) Event control */
#define REG_PAC_INTENCLR (0x40000008) /**< (PAC) Interrupt enable clear */
#define REG_PAC_INTENSET (0x40000009) /**< (PAC) Interrupt enable set */
#define REG_PAC_INTFLAGAHB (0x40000010) /**< (PAC) Bridge interrupt flag status */
#define REG_PAC_INTFLAGA (0x40000014) /**< (PAC) Peripheral interrupt flag status - Bridge A */
#define REG_PAC_INTFLAGB (0x40000018) /**< (PAC) Peripheral interrupt flag status - Bridge B */
#define REG_PAC_INTFLAGC (0x4000001C) /**< (PAC) Peripheral interrupt flag status - Bridge C */
#define REG_PAC_STATUSA (0x40000034) /**< (PAC) Peripheral write protection status - Bridge A */
#define REG_PAC_STATUSB (0x40000038) /**< (PAC) Peripheral write protection status - Bridge B */
#define REG_PAC_STATUSC (0x4000003C) /**< (PAC) Peripheral write protection status - Bridge C */
#define REG_PAC_NONSECA (0x40000054) /**< (PAC) Peripheral non-secure status - Bridge A */
#define REG_PAC_NONSECB (0x40000058) /**< (PAC) Peripheral non-secure status - Bridge B */
#define REG_PAC_NONSECC (0x4000005C) /**< (PAC) Peripheral non-secure status - Bridge C */
#define REG_PAC_SECLOCKA (0x40000074) /**< (PAC) Peripheral secure status locked - Bridge A */
#define REG_PAC_SECLOCKB (0x40000078) /**< (PAC) Peripheral secure status locked - Bridge B */
#define REG_PAC_SECLOCKC (0x4000007C) /**< (PAC) Peripheral secure status locked - Bridge C */
#else
#define REG_PAC_WRCTRL (*(__IO uint32_t*)0x40000000U) /**< (PAC) Write control */
#define REG_PAC_EVCTRL (*(__IO uint8_t*)0x40000004U) /**< (PAC) Event control */
#define REG_PAC_INTENCLR (*(__IO uint8_t*)0x40000008U) /**< (PAC) Interrupt enable clear */
#define REG_PAC_INTENSET (*(__IO uint8_t*)0x40000009U) /**< (PAC) Interrupt enable set */
#define REG_PAC_INTFLAGAHB (*(__IO uint32_t*)0x40000010U) /**< (PAC) Bridge interrupt flag status */
#define REG_PAC_INTFLAGA (*(__IO uint32_t*)0x40000014U) /**< (PAC) Peripheral interrupt flag status - Bridge A */
#define REG_PAC_INTFLAGB (*(__IO uint32_t*)0x40000018U) /**< (PAC) Peripheral interrupt flag status - Bridge B */
#define REG_PAC_INTFLAGC (*(__IO uint32_t*)0x4000001CU) /**< (PAC) Peripheral interrupt flag status - Bridge C */
#define REG_PAC_STATUSA (*(__I uint32_t*)0x40000034U) /**< (PAC) Peripheral write protection status - Bridge A */
#define REG_PAC_STATUSB (*(__I uint32_t*)0x40000038U) /**< (PAC) Peripheral write protection status - Bridge B */
#define REG_PAC_STATUSC (*(__I uint32_t*)0x4000003CU) /**< (PAC) Peripheral write protection status - Bridge C */
#define REG_PAC_NONSECA (*(__I uint32_t*)0x40000054U) /**< (PAC) Peripheral non-secure status - Bridge A */
#define REG_PAC_NONSECB (*(__I uint32_t*)0x40000058U) /**< (PAC) Peripheral non-secure status - Bridge B */
#define REG_PAC_NONSECC (*(__I uint32_t*)0x4000005CU) /**< (PAC) Peripheral non-secure status - Bridge C */
#define REG_PAC_SECLOCKA (*(__I uint32_t*)0x40000074U) /**< (PAC) Peripheral secure status locked - Bridge A */
#define REG_PAC_SECLOCKB (*(__I uint32_t*)0x40000078U) /**< (PAC) Peripheral secure status locked - Bridge B */
#define REG_PAC_SECLOCKC (*(__I uint32_t*)0x4000007CU) /**< (PAC) Peripheral secure status locked - Bridge C */
#endif /* (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/* ========== Instance Parameter definitions for PAC peripheral ========== */
#define PAC_HPB_NUM 3 /* Number of bridges AHB/APB */
#define PAC_SECURE_IMPLEMENTED 1 /* Security Configuration implemented? */
#define PAC_INSTANCE_ID 0
#endif /* _SAML10_PAC_INSTANCE_ */

View File

@ -0,0 +1,62 @@
/**
* \file
*
* \brief Instance description for PM
*
* Copyright (c) 2018 Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* 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
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
/* file generated from device description version 2018-08-31T13:51:50Z */
#ifndef _SAML10_PM_INSTANCE_H_
#define _SAML10_PM_INSTANCE_H_
/* ========== Register definition for PM peripheral ========== */
#if (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
#define REG_PM_SLEEPCFG (0x40000401) /**< (PM) Sleep Configuration */
#define REG_PM_PLCFG (0x40000402) /**< (PM) Performance Level Configuration */
#define REG_PM_PWCFG (0x40000403) /**< (PM) Power Configuration */
#define REG_PM_INTENCLR (0x40000404) /**< (PM) Interrupt Enable Clear */
#define REG_PM_INTENSET (0x40000405) /**< (PM) Interrupt Enable Set */
#define REG_PM_INTFLAG (0x40000406) /**< (PM) Interrupt Flag Status and Clear */
#define REG_PM_STDBYCFG (0x40000408) /**< (PM) Standby Configuration */
#else
#define REG_PM_SLEEPCFG (*(__IO uint8_t*)0x40000401U) /**< (PM) Sleep Configuration */
#define REG_PM_PLCFG (*(__IO uint8_t*)0x40000402U) /**< (PM) Performance Level Configuration */
#define REG_PM_PWCFG (*(__IO uint8_t*)0x40000403U) /**< (PM) Power Configuration */
#define REG_PM_INTENCLR (*(__IO uint8_t*)0x40000404U) /**< (PM) Interrupt Enable Clear */
#define REG_PM_INTENSET (*(__IO uint8_t*)0x40000405U) /**< (PM) Interrupt Enable Set */
#define REG_PM_INTFLAG (*(__IO uint8_t*)0x40000406U) /**< (PM) Interrupt Flag Status and Clear */
#define REG_PM_STDBYCFG (*(__IO uint16_t*)0x40000408U) /**< (PM) Standby Configuration */
#endif /* (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/* ========== Instance Parameter definitions for PM peripheral ========== */
#define PM_BIAS_RAM_HS 1 /* one if RAM HS can be back biased */
#define PM_PD_NUM 1 /* Number of switchable Power Domain */
#define PM_INSTANCE_ID 1
#endif /* _SAML10_PM_INSTANCE_ */

View File

@ -0,0 +1,93 @@
/**
* \file
*
* \brief Instance description for PORT
*
* Copyright (c) 2018 Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* 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
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
/* file generated from device description version 2018-08-31T13:51:50Z */
#ifndef _SAML10_PORT_INSTANCE_H_
#define _SAML10_PORT_INSTANCE_H_
/* ========== Register definition for PORT peripheral ========== */
#if (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
#define REG_PORT_DIR0 (0x40003000) /**< (PORT) Data Direction 0 */
#define REG_PORT_DIRCLR0 (0x40003004) /**< (PORT) Data Direction Clear 0 */
#define REG_PORT_DIRSET0 (0x40003008) /**< (PORT) Data Direction Set 0 */
#define REG_PORT_DIRTGL0 (0x4000300C) /**< (PORT) Data Direction Toggle 0 */
#define REG_PORT_OUT0 (0x40003010) /**< (PORT) Data Output Value 0 */
#define REG_PORT_OUTCLR0 (0x40003014) /**< (PORT) Data Output Value Clear 0 */
#define REG_PORT_OUTSET0 (0x40003018) /**< (PORT) Data Output Value Set 0 */
#define REG_PORT_OUTTGL0 (0x4000301C) /**< (PORT) Data Output Value Toggle 0 */
#define REG_PORT_IN0 (0x40003020) /**< (PORT) Data Input Value 0 */
#define REG_PORT_CTRL0 (0x40003024) /**< (PORT) Control 0 */
#define REG_PORT_WRCONFIG0 (0x40003028) /**< (PORT) Write Configuration 0 */
#define REG_PORT_EVCTRL0 (0x4000302C) /**< (PORT) Event Input Control 0 */
#define REG_PORT_PMUX0 (0x40003030) /**< (PORT) Peripheral Multiplexing 0 */
#define REG_PORT_PINCFG0 (0x40003040) /**< (PORT) Pin Configuration 0 */
#define REG_PORT_INTENCLR0 (0x40003060) /**< (PORT) Interrupt Enable Clear 0 */
#define REG_PORT_INTENSET0 (0x40003064) /**< (PORT) Interrupt Enable Set 0 */
#define REG_PORT_INTFLAG0 (0x40003068) /**< (PORT) Interrupt Flag Status and Clear 0 */
#define REG_PORT_NONSEC0 (0x4000306C) /**< (PORT) Security Attribution 0 */
#define REG_PORT_NSCHK0 (0x40003070) /**< (PORT) Security Attribution Check 0 */
#else
#define REG_PORT_DIR0 (*(__IO uint32_t*)0x40003000U) /**< (PORT) Data Direction 0 */
#define REG_PORT_DIRCLR0 (*(__IO uint32_t*)0x40003004U) /**< (PORT) Data Direction Clear 0 */
#define REG_PORT_DIRSET0 (*(__IO uint32_t*)0x40003008U) /**< (PORT) Data Direction Set 0 */
#define REG_PORT_DIRTGL0 (*(__IO uint32_t*)0x4000300CU) /**< (PORT) Data Direction Toggle 0 */
#define REG_PORT_OUT0 (*(__IO uint32_t*)0x40003010U) /**< (PORT) Data Output Value 0 */
#define REG_PORT_OUTCLR0 (*(__IO uint32_t*)0x40003014U) /**< (PORT) Data Output Value Clear 0 */
#define REG_PORT_OUTSET0 (*(__IO uint32_t*)0x40003018U) /**< (PORT) Data Output Value Set 0 */
#define REG_PORT_OUTTGL0 (*(__IO uint32_t*)0x4000301CU) /**< (PORT) Data Output Value Toggle 0 */
#define REG_PORT_IN0 (*(__I uint32_t*)0x40003020U) /**< (PORT) Data Input Value 0 */
#define REG_PORT_CTRL0 (*(__IO uint32_t*)0x40003024U) /**< (PORT) Control 0 */
#define REG_PORT_WRCONFIG0 (*(__O uint32_t*)0x40003028U) /**< (PORT) Write Configuration 0 */
#define REG_PORT_EVCTRL0 (*(__IO uint32_t*)0x4000302CU) /**< (PORT) Event Input Control 0 */
#define REG_PORT_PMUX0 (*(__IO uint8_t*)0x40003030U) /**< (PORT) Peripheral Multiplexing 0 */
#define REG_PORT_PINCFG0 (*(__IO uint8_t*)0x40003040U) /**< (PORT) Pin Configuration 0 */
#define REG_PORT_INTENCLR0 (*(__IO uint32_t*)0x40003060U) /**< (PORT) Interrupt Enable Clear 0 */
#define REG_PORT_INTENSET0 (*(__IO uint32_t*)0x40003064U) /**< (PORT) Interrupt Enable Set 0 */
#define REG_PORT_INTFLAG0 (*(__IO uint32_t*)0x40003068U) /**< (PORT) Interrupt Flag Status and Clear 0 */
#define REG_PORT_NONSEC0 (*(__IO uint32_t*)0x4000306CU) /**< (PORT) Security Attribution 0 */
#define REG_PORT_NSCHK0 (*(__IO uint32_t*)0x40003070U) /**< (PORT) Security Attribution Check 0 */
#endif /* (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/* ========== Instance Parameter definitions for PORT peripheral ========== */
#define PORT_BITS 32
#define PORT_DRVSTR 1 /* DRVSTR supported */
#define PORT_EV_NUM 4
#define PORT_GROUPS 1
#define PORT_MSB 31
#define PORT_ODRAIN 0 /* ODRAIN supported */
#define PORT_PPP_IMPLEMENTED 0 /* IOBUS2 implemented? */
#define PORT_SECURE_IMPLEMENTED 1 /* Secure I/Os supported? */
#define PORT_SLEWLIM 0 /* SLEWLIM supported */
#define PORT_INSTANCE_ID 12
#endif /* _SAML10_PORT_INSTANCE_ */

View File

@ -0,0 +1,54 @@
/**
* \file
*
* \brief Instance description for PTC
*
* Copyright (c) 2018 Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* 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
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
/* file generated from device description version 2018-08-31T13:51:50Z */
#ifndef _SAML10_PTC_INSTANCE_H_
#define _SAML10_PTC_INSTANCE_H_
/* ========== Register definition for PTC peripheral ========== */
#if (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
#else
#endif /* (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/* ========== Instance Parameter definitions for PTC peripheral ========== */
#define PTC_DMAC_ID_EOC 21 /* Index of DMA EOC trigger */
#define PTC_DMAC_ID_SEQ 22 /* Index of DMA SEQ trigger */
#define PTC_DMAC_ID_WCOMP 23 /* Index of DMA WCOMP trigger */
#define PTC_GCLK_ID 19 /* Index of Generic Clock */
#define PTC_LINES_MSB 19
#define PTC_LINES_NUM 20 /* Number of PTC lines */
#define PTC_INSTANCE_ID 73
#endif /* _SAML10_PTC_INSTANCE_ */

View File

@ -0,0 +1,50 @@
/**
* \file
*
* \brief Instance description for RSTC
*
* Copyright (c) 2018 Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* 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
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
/* file generated from device description version 2018-08-31T13:51:50Z */
#ifndef _SAML10_RSTC_INSTANCE_H_
#define _SAML10_RSTC_INSTANCE_H_
/* ========== Register definition for RSTC peripheral ========== */
#if (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
#define REG_RSTC_RCAUSE (0x40000C00) /**< (RSTC) Reset Cause */
#else
#define REG_RSTC_RCAUSE (*(__I uint8_t*)0x40000C00U) /**< (RSTC) Reset Cause */
#endif /* (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/* ========== Instance Parameter definitions for RSTC peripheral ========== */
#define RSTC_BACKUP_IMPLEMENTED 0
#define RSTC_NUMBER_OF_EXTWAKE 0 /* number of external wakeup line */
#define RSTC_INSTANCE_ID 3
#endif /* _SAML10_RSTC_INSTANCE_ */

View File

@ -0,0 +1,140 @@
/**
* \file
*
* \brief Instance description for RTC
*
* Copyright (c) 2018 Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* 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
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
/* file generated from device description version 2018-08-31T13:51:50Z */
#ifndef _SAML10_RTC_INSTANCE_H_
#define _SAML10_RTC_INSTANCE_H_
/* ========== Register definition for RTC peripheral ========== */
#if (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
#define REG_RTC_DBGCTRL (0x4000240E) /**< (RTC) Debug Control */
#define REG_RTC_FREQCORR (0x40002414) /**< (RTC) Frequency Correction */
#define REG_RTC_GP (0x40002440) /**< (RTC) General Purpose */
#define REG_RTC_GP0 (0x40002440) /**< (RTC) General Purpose 0 */
#define REG_RTC_GP1 (0x40002444) /**< (RTC) General Purpose 1 */
#define REG_RTC_TAMPCTRL (0x40002460) /**< (RTC) Tamper Control */
#define REG_RTC_TAMPID (0x40002468) /**< (RTC) Tamper ID */
#define REG_RTC_TAMPCTRLB (0x4000246C) /**< (RTC) Tamper Control B */
#define REG_RTC_MODE0_CTRLA (0x40002400) /**< (RTC) MODE0 Control A */
#define REG_RTC_MODE0_CTRLB (0x40002402) /**< (RTC) MODE0 Control B */
#define REG_RTC_MODE0_EVCTRL (0x40002404) /**< (RTC) MODE0 Event Control */
#define REG_RTC_MODE0_INTENCLR (0x40002408) /**< (RTC) MODE0 Interrupt Enable Clear */
#define REG_RTC_MODE0_INTENSET (0x4000240A) /**< (RTC) MODE0 Interrupt Enable Set */
#define REG_RTC_MODE0_INTFLAG (0x4000240C) /**< (RTC) MODE0 Interrupt Flag Status and Clear */
#define REG_RTC_MODE0_SYNCBUSY (0x40002410) /**< (RTC) MODE0 Synchronization Busy Status */
#define REG_RTC_MODE0_COUNT (0x40002418) /**< (RTC) MODE0 Counter Value */
#define REG_RTC_MODE0_COMP (0x40002420) /**< (RTC) MODE0 Compare n Value */
#define REG_RTC_MODE0_COMP0 (0x40002420) /**< (RTC) MODE0 Compare 0 Value */
#define REG_RTC_MODE0_TIMESTAMP (0x40002464) /**< (RTC) MODE0 Timestamp */
#define REG_RTC_MODE1_CTRLA (0x40002400) /**< (RTC) MODE1 Control A */
#define REG_RTC_MODE1_CTRLB (0x40002402) /**< (RTC) MODE1 Control B */
#define REG_RTC_MODE1_EVCTRL (0x40002404) /**< (RTC) MODE1 Event Control */
#define REG_RTC_MODE1_INTENCLR (0x40002408) /**< (RTC) MODE1 Interrupt Enable Clear */
#define REG_RTC_MODE1_INTENSET (0x4000240A) /**< (RTC) MODE1 Interrupt Enable Set */
#define REG_RTC_MODE1_INTFLAG (0x4000240C) /**< (RTC) MODE1 Interrupt Flag Status and Clear */
#define REG_RTC_MODE1_SYNCBUSY (0x40002410) /**< (RTC) MODE1 Synchronization Busy Status */
#define REG_RTC_MODE1_COUNT (0x40002418) /**< (RTC) MODE1 Counter Value */
#define REG_RTC_MODE1_PER (0x4000241C) /**< (RTC) MODE1 Counter Period */
#define REG_RTC_MODE1_COMP (0x40002420) /**< (RTC) MODE1 Compare n Value */
#define REG_RTC_MODE1_COMP0 (0x40002420) /**< (RTC) MODE1 Compare 0 Value */
#define REG_RTC_MODE1_COMP1 (0x40002422) /**< (RTC) MODE1 Compare 1 Value */
#define REG_RTC_MODE1_TIMESTAMP (0x40002464) /**< (RTC) MODE1 Timestamp */
#define REG_RTC_MODE2_ALARM0 (0x40002420) /**< (RTC) MODE2_ALARM Alarm 0 Value */
#define REG_RTC_MODE2_MASK0 (0x40002424) /**< (RTC) MODE2_ALARM Alarm 0 Mask */
#define REG_RTC_MODE2_CTRLA (0x40002400) /**< (RTC) MODE2 Control A */
#define REG_RTC_MODE2_CTRLB (0x40002402) /**< (RTC) MODE2 Control B */
#define REG_RTC_MODE2_EVCTRL (0x40002404) /**< (RTC) MODE2 Event Control */
#define REG_RTC_MODE2_INTENCLR (0x40002408) /**< (RTC) MODE2 Interrupt Enable Clear */
#define REG_RTC_MODE2_INTENSET (0x4000240A) /**< (RTC) MODE2 Interrupt Enable Set */
#define REG_RTC_MODE2_INTFLAG (0x4000240C) /**< (RTC) MODE2 Interrupt Flag Status and Clear */
#define REG_RTC_MODE2_SYNCBUSY (0x40002410) /**< (RTC) MODE2 Synchronization Busy Status */
#define REG_RTC_MODE2_CLOCK (0x40002418) /**< (RTC) MODE2 Clock Value */
#define REG_RTC_MODE2_TIMESTAMP (0x40002464) /**< (RTC) MODE2 Timestamp */
#else
#define REG_RTC_DBGCTRL (*(__IO uint8_t*)0x4000240EU) /**< (RTC) Debug Control */
#define REG_RTC_FREQCORR (*(__IO uint8_t*)0x40002414U) /**< (RTC) Frequency Correction */
#define REG_RTC_GP (*(__IO uint32_t*)0x40002440U) /**< (RTC) General Purpose */
#define REG_RTC_GP0 (*(__IO uint32_t*)0x40002440U) /**< (RTC) General Purpose 0 */
#define REG_RTC_GP1 (*(__IO uint32_t*)0x40002444U) /**< (RTC) General Purpose 1 */
#define REG_RTC_TAMPCTRL (*(__IO uint32_t*)0x40002460U) /**< (RTC) Tamper Control */
#define REG_RTC_TAMPID (*(__IO uint32_t*)0x40002468U) /**< (RTC) Tamper ID */
#define REG_RTC_TAMPCTRLB (*(__IO uint32_t*)0x4000246CU) /**< (RTC) Tamper Control B */
#define REG_RTC_MODE0_CTRLA (*(__IO uint16_t*)0x40002400U) /**< (RTC) MODE0 Control A */
#define REG_RTC_MODE0_CTRLB (*(__IO uint16_t*)0x40002402U) /**< (RTC) MODE0 Control B */
#define REG_RTC_MODE0_EVCTRL (*(__IO uint32_t*)0x40002404U) /**< (RTC) MODE0 Event Control */
#define REG_RTC_MODE0_INTENCLR (*(__IO uint16_t*)0x40002408U) /**< (RTC) MODE0 Interrupt Enable Clear */
#define REG_RTC_MODE0_INTENSET (*(__IO uint16_t*)0x4000240AU) /**< (RTC) MODE0 Interrupt Enable Set */
#define REG_RTC_MODE0_INTFLAG (*(__IO uint16_t*)0x4000240CU) /**< (RTC) MODE0 Interrupt Flag Status and Clear */
#define REG_RTC_MODE0_SYNCBUSY (*(__I uint32_t*)0x40002410U) /**< (RTC) MODE0 Synchronization Busy Status */
#define REG_RTC_MODE0_COUNT (*(__IO uint32_t*)0x40002418U) /**< (RTC) MODE0 Counter Value */
#define REG_RTC_MODE0_COMP (*(__IO uint32_t*)0x40002420U) /**< (RTC) MODE0 Compare n Value */
#define REG_RTC_MODE0_COMP0 (*(__IO uint32_t*)0x40002420U) /**< (RTC) MODE0 Compare 0 Value */
#define REG_RTC_MODE0_TIMESTAMP (*(__I uint32_t*)0x40002464U) /**< (RTC) MODE0 Timestamp */
#define REG_RTC_MODE1_CTRLA (*(__IO uint16_t*)0x40002400U) /**< (RTC) MODE1 Control A */
#define REG_RTC_MODE1_CTRLB (*(__IO uint16_t*)0x40002402U) /**< (RTC) MODE1 Control B */
#define REG_RTC_MODE1_EVCTRL (*(__IO uint32_t*)0x40002404U) /**< (RTC) MODE1 Event Control */
#define REG_RTC_MODE1_INTENCLR (*(__IO uint16_t*)0x40002408U) /**< (RTC) MODE1 Interrupt Enable Clear */
#define REG_RTC_MODE1_INTENSET (*(__IO uint16_t*)0x4000240AU) /**< (RTC) MODE1 Interrupt Enable Set */
#define REG_RTC_MODE1_INTFLAG (*(__IO uint16_t*)0x4000240CU) /**< (RTC) MODE1 Interrupt Flag Status and Clear */
#define REG_RTC_MODE1_SYNCBUSY (*(__I uint32_t*)0x40002410U) /**< (RTC) MODE1 Synchronization Busy Status */
#define REG_RTC_MODE1_COUNT (*(__IO uint16_t*)0x40002418U) /**< (RTC) MODE1 Counter Value */
#define REG_RTC_MODE1_PER (*(__IO uint16_t*)0x4000241CU) /**< (RTC) MODE1 Counter Period */
#define REG_RTC_MODE1_COMP (*(__IO uint16_t*)0x40002420U) /**< (RTC) MODE1 Compare n Value */
#define REG_RTC_MODE1_COMP0 (*(__IO uint16_t*)0x40002420U) /**< (RTC) MODE1 Compare 0 Value */
#define REG_RTC_MODE1_COMP1 (*(__IO uint16_t*)0x40002422U) /**< (RTC) MODE1 Compare 1 Value */
#define REG_RTC_MODE1_TIMESTAMP (*(__I uint32_t*)0x40002464U) /**< (RTC) MODE1 Timestamp */
#define REG_RTC_MODE2_ALARM0 (*(__IO uint32_t*)0x40002420U) /**< (RTC) MODE2_ALARM Alarm 0 Value */
#define REG_RTC_MODE2_MASK0 (*(__IO uint8_t*)0x40002424U) /**< (RTC) MODE2_ALARM Alarm 0 Mask */
#define REG_RTC_MODE2_CTRLA (*(__IO uint16_t*)0x40002400U) /**< (RTC) MODE2 Control A */
#define REG_RTC_MODE2_CTRLB (*(__IO uint16_t*)0x40002402U) /**< (RTC) MODE2 Control B */
#define REG_RTC_MODE2_EVCTRL (*(__IO uint32_t*)0x40002404U) /**< (RTC) MODE2 Event Control */
#define REG_RTC_MODE2_INTENCLR (*(__IO uint16_t*)0x40002408U) /**< (RTC) MODE2 Interrupt Enable Clear */
#define REG_RTC_MODE2_INTENSET (*(__IO uint16_t*)0x4000240AU) /**< (RTC) MODE2 Interrupt Enable Set */
#define REG_RTC_MODE2_INTFLAG (*(__IO uint16_t*)0x4000240CU) /**< (RTC) MODE2 Interrupt Flag Status and Clear */
#define REG_RTC_MODE2_SYNCBUSY (*(__I uint32_t*)0x40002410U) /**< (RTC) MODE2 Synchronization Busy Status */
#define REG_RTC_MODE2_CLOCK (*(__IO uint32_t*)0x40002418U) /**< (RTC) MODE2 Clock Value */
#define REG_RTC_MODE2_TIMESTAMP (*(__I uint32_t*)0x40002464U) /**< (RTC) MODE2 Timestamp */
#endif /* (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/* ========== Instance Parameter definitions for RTC peripheral ========== */
#define RTC_DMAC_ID_TIMESTAMP 1 /* DMA RTC timestamp trigger */
#define RTC_GPR_NUM 2 /* Number of General-Purpose Registers */
#define RTC_NUM_OF_ALARMS 1 /* Number of Alarms */
#define RTC_NUM_OF_BKREGS 0 /* Number of Backup Registers */
#define RTC_NUM_OF_COMP16 2 /* Number of 16-bit Comparators */
#define RTC_NUM_OF_COMP32 1 /* Number of 32-bit Comparators */
#define RTC_NUM_OF_TAMPERS 4 /* Number of Tamper Inputs */
#define RTC_PER_NUM 8 /* Number of Periodic Intervals */
#define RTC_INSTANCE_ID 9
#endif /* _SAML10_RTC_INSTANCE_ */

View File

@ -0,0 +1,150 @@
/**
* \file
*
* \brief Instance description for SERCOM0
*
* Copyright (c) 2018 Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* 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
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
/* file generated from device description version 2018-08-31T13:51:50Z */
#ifndef _SAML10_SERCOM0_INSTANCE_H_
#define _SAML10_SERCOM0_INSTANCE_H_
/* ========== Register definition for SERCOM0 peripheral ========== */
#if (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
#define REG_SERCOM0_I2CM_CTRLA (0x42000400) /**< (SERCOM0) I2CM Control A */
#define REG_SERCOM0_I2CM_CTRLB (0x42000404) /**< (SERCOM0) I2CM Control B */
#define REG_SERCOM0_I2CM_BAUD (0x4200040C) /**< (SERCOM0) I2CM Baud Rate */
#define REG_SERCOM0_I2CM_INTENCLR (0x42000414) /**< (SERCOM0) I2CM Interrupt Enable Clear */
#define REG_SERCOM0_I2CM_INTENSET (0x42000416) /**< (SERCOM0) I2CM Interrupt Enable Set */
#define REG_SERCOM0_I2CM_INTFLAG (0x42000418) /**< (SERCOM0) I2CM Interrupt Flag Status and Clear */
#define REG_SERCOM0_I2CM_STATUS (0x4200041A) /**< (SERCOM0) I2CM Status */
#define REG_SERCOM0_I2CM_SYNCBUSY (0x4200041C) /**< (SERCOM0) I2CM Synchronization Busy */
#define REG_SERCOM0_I2CM_ADDR (0x42000424) /**< (SERCOM0) I2CM Address */
#define REG_SERCOM0_I2CM_DATA (0x42000428) /**< (SERCOM0) I2CM Data */
#define REG_SERCOM0_I2CM_DBGCTRL (0x42000430) /**< (SERCOM0) I2CM Debug Control */
#define REG_SERCOM0_I2CS_CTRLA (0x42000400) /**< (SERCOM0) I2CS Control A */
#define REG_SERCOM0_I2CS_CTRLB (0x42000404) /**< (SERCOM0) I2CS Control B */
#define REG_SERCOM0_I2CS_INTENCLR (0x42000414) /**< (SERCOM0) I2CS Interrupt Enable Clear */
#define REG_SERCOM0_I2CS_INTENSET (0x42000416) /**< (SERCOM0) I2CS Interrupt Enable Set */
#define REG_SERCOM0_I2CS_INTFLAG (0x42000418) /**< (SERCOM0) I2CS Interrupt Flag Status and Clear */
#define REG_SERCOM0_I2CS_STATUS (0x4200041A) /**< (SERCOM0) I2CS Status */
#define REG_SERCOM0_I2CS_SYNCBUSY (0x4200041C) /**< (SERCOM0) I2CS Synchronization Busy */
#define REG_SERCOM0_I2CS_ADDR (0x42000424) /**< (SERCOM0) I2CS Address */
#define REG_SERCOM0_I2CS_DATA (0x42000428) /**< (SERCOM0) I2CS Data */
#define REG_SERCOM0_SPI_CTRLA (0x42000400) /**< (SERCOM0) SPI Control A */
#define REG_SERCOM0_SPI_CTRLB (0x42000404) /**< (SERCOM0) SPI Control B */
#define REG_SERCOM0_SPI_BAUD (0x4200040C) /**< (SERCOM0) SPI Baud Rate */
#define REG_SERCOM0_SPI_INTENCLR (0x42000414) /**< (SERCOM0) SPI Interrupt Enable Clear */
#define REG_SERCOM0_SPI_INTENSET (0x42000416) /**< (SERCOM0) SPI Interrupt Enable Set */
#define REG_SERCOM0_SPI_INTFLAG (0x42000418) /**< (SERCOM0) SPI Interrupt Flag Status and Clear */
#define REG_SERCOM0_SPI_STATUS (0x4200041A) /**< (SERCOM0) SPI Status */
#define REG_SERCOM0_SPI_SYNCBUSY (0x4200041C) /**< (SERCOM0) SPI Synchronization Busy */
#define REG_SERCOM0_SPI_ADDR (0x42000424) /**< (SERCOM0) SPI Address */
#define REG_SERCOM0_SPI_DATA (0x42000428) /**< (SERCOM0) SPI Data */
#define REG_SERCOM0_SPI_DBGCTRL (0x42000430) /**< (SERCOM0) SPI Debug Control */
#define REG_SERCOM0_USART_CTRLA (0x42000400) /**< (SERCOM0) USART Control A */
#define REG_SERCOM0_USART_CTRLB (0x42000404) /**< (SERCOM0) USART Control B */
#define REG_SERCOM0_USART_CTRLC (0x42000408) /**< (SERCOM0) USART Control C */
#define REG_SERCOM0_USART_BAUD (0x4200040C) /**< (SERCOM0) USART Baud Rate */
#define REG_SERCOM0_USART_RXPL (0x4200040E) /**< (SERCOM0) USART Receive Pulse Length */
#define REG_SERCOM0_USART_INTENCLR (0x42000414) /**< (SERCOM0) USART Interrupt Enable Clear */
#define REG_SERCOM0_USART_INTENSET (0x42000416) /**< (SERCOM0) USART Interrupt Enable Set */
#define REG_SERCOM0_USART_INTFLAG (0x42000418) /**< (SERCOM0) USART Interrupt Flag Status and Clear */
#define REG_SERCOM0_USART_STATUS (0x4200041A) /**< (SERCOM0) USART Status */
#define REG_SERCOM0_USART_SYNCBUSY (0x4200041C) /**< (SERCOM0) USART Synchronization Busy */
#define REG_SERCOM0_USART_RXERRCNT (0x42000420) /**< (SERCOM0) USART Receive Error Count */
#define REG_SERCOM0_USART_DATA (0x42000428) /**< (SERCOM0) USART Data */
#define REG_SERCOM0_USART_DBGCTRL (0x42000430) /**< (SERCOM0) USART Debug Control */
#else
#define REG_SERCOM0_I2CM_CTRLA (*(__IO uint32_t*)0x42000400U) /**< (SERCOM0) I2CM Control A */
#define REG_SERCOM0_I2CM_CTRLB (*(__IO uint32_t*)0x42000404U) /**< (SERCOM0) I2CM Control B */
#define REG_SERCOM0_I2CM_BAUD (*(__IO uint32_t*)0x4200040CU) /**< (SERCOM0) I2CM Baud Rate */
#define REG_SERCOM0_I2CM_INTENCLR (*(__IO uint8_t*)0x42000414U) /**< (SERCOM0) I2CM Interrupt Enable Clear */
#define REG_SERCOM0_I2CM_INTENSET (*(__IO uint8_t*)0x42000416U) /**< (SERCOM0) I2CM Interrupt Enable Set */
#define REG_SERCOM0_I2CM_INTFLAG (*(__IO uint8_t*)0x42000418U) /**< (SERCOM0) I2CM Interrupt Flag Status and Clear */
#define REG_SERCOM0_I2CM_STATUS (*(__IO uint16_t*)0x4200041AU) /**< (SERCOM0) I2CM Status */
#define REG_SERCOM0_I2CM_SYNCBUSY (*(__I uint32_t*)0x4200041CU) /**< (SERCOM0) I2CM Synchronization Busy */
#define REG_SERCOM0_I2CM_ADDR (*(__IO uint32_t*)0x42000424U) /**< (SERCOM0) I2CM Address */
#define REG_SERCOM0_I2CM_DATA (*(__IO uint8_t*)0x42000428U) /**< (SERCOM0) I2CM Data */
#define REG_SERCOM0_I2CM_DBGCTRL (*(__IO uint8_t*)0x42000430U) /**< (SERCOM0) I2CM Debug Control */
#define REG_SERCOM0_I2CS_CTRLA (*(__IO uint32_t*)0x42000400U) /**< (SERCOM0) I2CS Control A */
#define REG_SERCOM0_I2CS_CTRLB (*(__IO uint32_t*)0x42000404U) /**< (SERCOM0) I2CS Control B */
#define REG_SERCOM0_I2CS_INTENCLR (*(__IO uint8_t*)0x42000414U) /**< (SERCOM0) I2CS Interrupt Enable Clear */
#define REG_SERCOM0_I2CS_INTENSET (*(__IO uint8_t*)0x42000416U) /**< (SERCOM0) I2CS Interrupt Enable Set */
#define REG_SERCOM0_I2CS_INTFLAG (*(__IO uint8_t*)0x42000418U) /**< (SERCOM0) I2CS Interrupt Flag Status and Clear */
#define REG_SERCOM0_I2CS_STATUS (*(__IO uint16_t*)0x4200041AU) /**< (SERCOM0) I2CS Status */
#define REG_SERCOM0_I2CS_SYNCBUSY (*(__I uint32_t*)0x4200041CU) /**< (SERCOM0) I2CS Synchronization Busy */
#define REG_SERCOM0_I2CS_ADDR (*(__IO uint32_t*)0x42000424U) /**< (SERCOM0) I2CS Address */
#define REG_SERCOM0_I2CS_DATA (*(__IO uint8_t*)0x42000428U) /**< (SERCOM0) I2CS Data */
#define REG_SERCOM0_SPI_CTRLA (*(__IO uint32_t*)0x42000400U) /**< (SERCOM0) SPI Control A */
#define REG_SERCOM0_SPI_CTRLB (*(__IO uint32_t*)0x42000404U) /**< (SERCOM0) SPI Control B */
#define REG_SERCOM0_SPI_BAUD (*(__IO uint8_t*)0x4200040CU) /**< (SERCOM0) SPI Baud Rate */
#define REG_SERCOM0_SPI_INTENCLR (*(__IO uint8_t*)0x42000414U) /**< (SERCOM0) SPI Interrupt Enable Clear */
#define REG_SERCOM0_SPI_INTENSET (*(__IO uint8_t*)0x42000416U) /**< (SERCOM0) SPI Interrupt Enable Set */
#define REG_SERCOM0_SPI_INTFLAG (*(__IO uint8_t*)0x42000418U) /**< (SERCOM0) SPI Interrupt Flag Status and Clear */
#define REG_SERCOM0_SPI_STATUS (*(__IO uint16_t*)0x4200041AU) /**< (SERCOM0) SPI Status */
#define REG_SERCOM0_SPI_SYNCBUSY (*(__I uint32_t*)0x4200041CU) /**< (SERCOM0) SPI Synchronization Busy */
#define REG_SERCOM0_SPI_ADDR (*(__IO uint32_t*)0x42000424U) /**< (SERCOM0) SPI Address */
#define REG_SERCOM0_SPI_DATA (*(__IO uint32_t*)0x42000428U) /**< (SERCOM0) SPI Data */
#define REG_SERCOM0_SPI_DBGCTRL (*(__IO uint8_t*)0x42000430U) /**< (SERCOM0) SPI Debug Control */
#define REG_SERCOM0_USART_CTRLA (*(__IO uint32_t*)0x42000400U) /**< (SERCOM0) USART Control A */
#define REG_SERCOM0_USART_CTRLB (*(__IO uint32_t*)0x42000404U) /**< (SERCOM0) USART Control B */
#define REG_SERCOM0_USART_CTRLC (*(__IO uint32_t*)0x42000408U) /**< (SERCOM0) USART Control C */
#define REG_SERCOM0_USART_BAUD (*(__IO uint16_t*)0x4200040CU) /**< (SERCOM0) USART Baud Rate */
#define REG_SERCOM0_USART_RXPL (*(__IO uint8_t*)0x4200040EU) /**< (SERCOM0) USART Receive Pulse Length */
#define REG_SERCOM0_USART_INTENCLR (*(__IO uint8_t*)0x42000414U) /**< (SERCOM0) USART Interrupt Enable Clear */
#define REG_SERCOM0_USART_INTENSET (*(__IO uint8_t*)0x42000416U) /**< (SERCOM0) USART Interrupt Enable Set */
#define REG_SERCOM0_USART_INTFLAG (*(__IO uint8_t*)0x42000418U) /**< (SERCOM0) USART Interrupt Flag Status and Clear */
#define REG_SERCOM0_USART_STATUS (*(__IO uint16_t*)0x4200041AU) /**< (SERCOM0) USART Status */
#define REG_SERCOM0_USART_SYNCBUSY (*(__I uint32_t*)0x4200041CU) /**< (SERCOM0) USART Synchronization Busy */
#define REG_SERCOM0_USART_RXERRCNT (*(__I uint8_t*)0x42000420U) /**< (SERCOM0) USART Receive Error Count */
#define REG_SERCOM0_USART_DATA (*(__IO uint16_t*)0x42000428U) /**< (SERCOM0) USART Data */
#define REG_SERCOM0_USART_DBGCTRL (*(__IO uint8_t*)0x42000430U) /**< (SERCOM0) USART Debug Control */
#endif /* (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/* ========== Instance Parameter definitions for SERCOM0 peripheral ========== */
#define SERCOM0_DMAC_ID_RX 4 /* Index of DMA RX trigger */
#define SERCOM0_DMAC_ID_TX 5 /* Index of DMA TX trigger */
#define SERCOM0_FIFO_DEPTH_POWER 1 /* Rx Fifo depth = 2^FIFO_DEPTH_POWER */
#define SERCOM0_GCLK_ID_CORE 11
#define SERCOM0_GCLK_ID_SLOW 10
#define SERCOM0_INT_MSB 6
#define SERCOM0_PMSB 3
#define SERCOM0_SPI 1 /* SPI mode implemented? */
#define SERCOM0_TWIM 1 /* TWI Master mode implemented? */
#define SERCOM0_TWIS 1 /* TWI Slave mode implemented? */
#define SERCOM0_TWI_HSMODE 1 /* TWI HighSpeed mode implemented? */
#define SERCOM0_USART 1 /* USART mode implemented? */
#define SERCOM0_USART_AUTOBAUD 0 /* USART AUTOBAUD mode implemented? */
#define SERCOM0_USART_ISO7816 0 /* USART ISO7816 mode implemented? */
#define SERCOM0_USART_LIN_MASTER 0 /* USART LIN Master mode implemented? */
#define SERCOM0_USART_RS485 0 /* USART RS485 mode implemented? */
#define SERCOM0_INSTANCE_ID 65
#endif /* _SAML10_SERCOM0_INSTANCE_ */

View File

@ -0,0 +1,150 @@
/**
* \file
*
* \brief Instance description for SERCOM1
*
* Copyright (c) 2018 Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* 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
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
/* file generated from device description version 2018-08-31T13:51:50Z */
#ifndef _SAML10_SERCOM1_INSTANCE_H_
#define _SAML10_SERCOM1_INSTANCE_H_
/* ========== Register definition for SERCOM1 peripheral ========== */
#if (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
#define REG_SERCOM1_I2CM_CTRLA (0x42000800) /**< (SERCOM1) I2CM Control A */
#define REG_SERCOM1_I2CM_CTRLB (0x42000804) /**< (SERCOM1) I2CM Control B */
#define REG_SERCOM1_I2CM_BAUD (0x4200080C) /**< (SERCOM1) I2CM Baud Rate */
#define REG_SERCOM1_I2CM_INTENCLR (0x42000814) /**< (SERCOM1) I2CM Interrupt Enable Clear */
#define REG_SERCOM1_I2CM_INTENSET (0x42000816) /**< (SERCOM1) I2CM Interrupt Enable Set */
#define REG_SERCOM1_I2CM_INTFLAG (0x42000818) /**< (SERCOM1) I2CM Interrupt Flag Status and Clear */
#define REG_SERCOM1_I2CM_STATUS (0x4200081A) /**< (SERCOM1) I2CM Status */
#define REG_SERCOM1_I2CM_SYNCBUSY (0x4200081C) /**< (SERCOM1) I2CM Synchronization Busy */
#define REG_SERCOM1_I2CM_ADDR (0x42000824) /**< (SERCOM1) I2CM Address */
#define REG_SERCOM1_I2CM_DATA (0x42000828) /**< (SERCOM1) I2CM Data */
#define REG_SERCOM1_I2CM_DBGCTRL (0x42000830) /**< (SERCOM1) I2CM Debug Control */
#define REG_SERCOM1_I2CS_CTRLA (0x42000800) /**< (SERCOM1) I2CS Control A */
#define REG_SERCOM1_I2CS_CTRLB (0x42000804) /**< (SERCOM1) I2CS Control B */
#define REG_SERCOM1_I2CS_INTENCLR (0x42000814) /**< (SERCOM1) I2CS Interrupt Enable Clear */
#define REG_SERCOM1_I2CS_INTENSET (0x42000816) /**< (SERCOM1) I2CS Interrupt Enable Set */
#define REG_SERCOM1_I2CS_INTFLAG (0x42000818) /**< (SERCOM1) I2CS Interrupt Flag Status and Clear */
#define REG_SERCOM1_I2CS_STATUS (0x4200081A) /**< (SERCOM1) I2CS Status */
#define REG_SERCOM1_I2CS_SYNCBUSY (0x4200081C) /**< (SERCOM1) I2CS Synchronization Busy */
#define REG_SERCOM1_I2CS_ADDR (0x42000824) /**< (SERCOM1) I2CS Address */
#define REG_SERCOM1_I2CS_DATA (0x42000828) /**< (SERCOM1) I2CS Data */
#define REG_SERCOM1_SPI_CTRLA (0x42000800) /**< (SERCOM1) SPI Control A */
#define REG_SERCOM1_SPI_CTRLB (0x42000804) /**< (SERCOM1) SPI Control B */
#define REG_SERCOM1_SPI_BAUD (0x4200080C) /**< (SERCOM1) SPI Baud Rate */
#define REG_SERCOM1_SPI_INTENCLR (0x42000814) /**< (SERCOM1) SPI Interrupt Enable Clear */
#define REG_SERCOM1_SPI_INTENSET (0x42000816) /**< (SERCOM1) SPI Interrupt Enable Set */
#define REG_SERCOM1_SPI_INTFLAG (0x42000818) /**< (SERCOM1) SPI Interrupt Flag Status and Clear */
#define REG_SERCOM1_SPI_STATUS (0x4200081A) /**< (SERCOM1) SPI Status */
#define REG_SERCOM1_SPI_SYNCBUSY (0x4200081C) /**< (SERCOM1) SPI Synchronization Busy */
#define REG_SERCOM1_SPI_ADDR (0x42000824) /**< (SERCOM1) SPI Address */
#define REG_SERCOM1_SPI_DATA (0x42000828) /**< (SERCOM1) SPI Data */
#define REG_SERCOM1_SPI_DBGCTRL (0x42000830) /**< (SERCOM1) SPI Debug Control */
#define REG_SERCOM1_USART_CTRLA (0x42000800) /**< (SERCOM1) USART Control A */
#define REG_SERCOM1_USART_CTRLB (0x42000804) /**< (SERCOM1) USART Control B */
#define REG_SERCOM1_USART_CTRLC (0x42000808) /**< (SERCOM1) USART Control C */
#define REG_SERCOM1_USART_BAUD (0x4200080C) /**< (SERCOM1) USART Baud Rate */
#define REG_SERCOM1_USART_RXPL (0x4200080E) /**< (SERCOM1) USART Receive Pulse Length */
#define REG_SERCOM1_USART_INTENCLR (0x42000814) /**< (SERCOM1) USART Interrupt Enable Clear */
#define REG_SERCOM1_USART_INTENSET (0x42000816) /**< (SERCOM1) USART Interrupt Enable Set */
#define REG_SERCOM1_USART_INTFLAG (0x42000818) /**< (SERCOM1) USART Interrupt Flag Status and Clear */
#define REG_SERCOM1_USART_STATUS (0x4200081A) /**< (SERCOM1) USART Status */
#define REG_SERCOM1_USART_SYNCBUSY (0x4200081C) /**< (SERCOM1) USART Synchronization Busy */
#define REG_SERCOM1_USART_RXERRCNT (0x42000820) /**< (SERCOM1) USART Receive Error Count */
#define REG_SERCOM1_USART_DATA (0x42000828) /**< (SERCOM1) USART Data */
#define REG_SERCOM1_USART_DBGCTRL (0x42000830) /**< (SERCOM1) USART Debug Control */
#else
#define REG_SERCOM1_I2CM_CTRLA (*(__IO uint32_t*)0x42000800U) /**< (SERCOM1) I2CM Control A */
#define REG_SERCOM1_I2CM_CTRLB (*(__IO uint32_t*)0x42000804U) /**< (SERCOM1) I2CM Control B */
#define REG_SERCOM1_I2CM_BAUD (*(__IO uint32_t*)0x4200080CU) /**< (SERCOM1) I2CM Baud Rate */
#define REG_SERCOM1_I2CM_INTENCLR (*(__IO uint8_t*)0x42000814U) /**< (SERCOM1) I2CM Interrupt Enable Clear */
#define REG_SERCOM1_I2CM_INTENSET (*(__IO uint8_t*)0x42000816U) /**< (SERCOM1) I2CM Interrupt Enable Set */
#define REG_SERCOM1_I2CM_INTFLAG (*(__IO uint8_t*)0x42000818U) /**< (SERCOM1) I2CM Interrupt Flag Status and Clear */
#define REG_SERCOM1_I2CM_STATUS (*(__IO uint16_t*)0x4200081AU) /**< (SERCOM1) I2CM Status */
#define REG_SERCOM1_I2CM_SYNCBUSY (*(__I uint32_t*)0x4200081CU) /**< (SERCOM1) I2CM Synchronization Busy */
#define REG_SERCOM1_I2CM_ADDR (*(__IO uint32_t*)0x42000824U) /**< (SERCOM1) I2CM Address */
#define REG_SERCOM1_I2CM_DATA (*(__IO uint8_t*)0x42000828U) /**< (SERCOM1) I2CM Data */
#define REG_SERCOM1_I2CM_DBGCTRL (*(__IO uint8_t*)0x42000830U) /**< (SERCOM1) I2CM Debug Control */
#define REG_SERCOM1_I2CS_CTRLA (*(__IO uint32_t*)0x42000800U) /**< (SERCOM1) I2CS Control A */
#define REG_SERCOM1_I2CS_CTRLB (*(__IO uint32_t*)0x42000804U) /**< (SERCOM1) I2CS Control B */
#define REG_SERCOM1_I2CS_INTENCLR (*(__IO uint8_t*)0x42000814U) /**< (SERCOM1) I2CS Interrupt Enable Clear */
#define REG_SERCOM1_I2CS_INTENSET (*(__IO uint8_t*)0x42000816U) /**< (SERCOM1) I2CS Interrupt Enable Set */
#define REG_SERCOM1_I2CS_INTFLAG (*(__IO uint8_t*)0x42000818U) /**< (SERCOM1) I2CS Interrupt Flag Status and Clear */
#define REG_SERCOM1_I2CS_STATUS (*(__IO uint16_t*)0x4200081AU) /**< (SERCOM1) I2CS Status */
#define REG_SERCOM1_I2CS_SYNCBUSY (*(__I uint32_t*)0x4200081CU) /**< (SERCOM1) I2CS Synchronization Busy */
#define REG_SERCOM1_I2CS_ADDR (*(__IO uint32_t*)0x42000824U) /**< (SERCOM1) I2CS Address */
#define REG_SERCOM1_I2CS_DATA (*(__IO uint8_t*)0x42000828U) /**< (SERCOM1) I2CS Data */
#define REG_SERCOM1_SPI_CTRLA (*(__IO uint32_t*)0x42000800U) /**< (SERCOM1) SPI Control A */
#define REG_SERCOM1_SPI_CTRLB (*(__IO uint32_t*)0x42000804U) /**< (SERCOM1) SPI Control B */
#define REG_SERCOM1_SPI_BAUD (*(__IO uint8_t*)0x4200080CU) /**< (SERCOM1) SPI Baud Rate */
#define REG_SERCOM1_SPI_INTENCLR (*(__IO uint8_t*)0x42000814U) /**< (SERCOM1) SPI Interrupt Enable Clear */
#define REG_SERCOM1_SPI_INTENSET (*(__IO uint8_t*)0x42000816U) /**< (SERCOM1) SPI Interrupt Enable Set */
#define REG_SERCOM1_SPI_INTFLAG (*(__IO uint8_t*)0x42000818U) /**< (SERCOM1) SPI Interrupt Flag Status and Clear */
#define REG_SERCOM1_SPI_STATUS (*(__IO uint16_t*)0x4200081AU) /**< (SERCOM1) SPI Status */
#define REG_SERCOM1_SPI_SYNCBUSY (*(__I uint32_t*)0x4200081CU) /**< (SERCOM1) SPI Synchronization Busy */
#define REG_SERCOM1_SPI_ADDR (*(__IO uint32_t*)0x42000824U) /**< (SERCOM1) SPI Address */
#define REG_SERCOM1_SPI_DATA (*(__IO uint32_t*)0x42000828U) /**< (SERCOM1) SPI Data */
#define REG_SERCOM1_SPI_DBGCTRL (*(__IO uint8_t*)0x42000830U) /**< (SERCOM1) SPI Debug Control */
#define REG_SERCOM1_USART_CTRLA (*(__IO uint32_t*)0x42000800U) /**< (SERCOM1) USART Control A */
#define REG_SERCOM1_USART_CTRLB (*(__IO uint32_t*)0x42000804U) /**< (SERCOM1) USART Control B */
#define REG_SERCOM1_USART_CTRLC (*(__IO uint32_t*)0x42000808U) /**< (SERCOM1) USART Control C */
#define REG_SERCOM1_USART_BAUD (*(__IO uint16_t*)0x4200080CU) /**< (SERCOM1) USART Baud Rate */
#define REG_SERCOM1_USART_RXPL (*(__IO uint8_t*)0x4200080EU) /**< (SERCOM1) USART Receive Pulse Length */
#define REG_SERCOM1_USART_INTENCLR (*(__IO uint8_t*)0x42000814U) /**< (SERCOM1) USART Interrupt Enable Clear */
#define REG_SERCOM1_USART_INTENSET (*(__IO uint8_t*)0x42000816U) /**< (SERCOM1) USART Interrupt Enable Set */
#define REG_SERCOM1_USART_INTFLAG (*(__IO uint8_t*)0x42000818U) /**< (SERCOM1) USART Interrupt Flag Status and Clear */
#define REG_SERCOM1_USART_STATUS (*(__IO uint16_t*)0x4200081AU) /**< (SERCOM1) USART Status */
#define REG_SERCOM1_USART_SYNCBUSY (*(__I uint32_t*)0x4200081CU) /**< (SERCOM1) USART Synchronization Busy */
#define REG_SERCOM1_USART_RXERRCNT (*(__I uint8_t*)0x42000820U) /**< (SERCOM1) USART Receive Error Count */
#define REG_SERCOM1_USART_DATA (*(__IO uint16_t*)0x42000828U) /**< (SERCOM1) USART Data */
#define REG_SERCOM1_USART_DBGCTRL (*(__IO uint8_t*)0x42000830U) /**< (SERCOM1) USART Debug Control */
#endif /* (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/* ========== Instance Parameter definitions for SERCOM1 peripheral ========== */
#define SERCOM1_DMAC_ID_RX 6 /* Index of DMA RX trigger */
#define SERCOM1_DMAC_ID_TX 7 /* Index of DMA TX trigger */
#define SERCOM1_FIFO_DEPTH_POWER 2 /* Rx Fifo depth = 2^FIFO_DEPTH_POWER */
#define SERCOM1_GCLK_ID_CORE 12
#define SERCOM1_GCLK_ID_SLOW 10
#define SERCOM1_INT_MSB 6
#define SERCOM1_PMSB 3
#define SERCOM1_SPI 1 /* SPI mode implemented? */
#define SERCOM1_TWIM 1 /* TWI Master mode implemented? */
#define SERCOM1_TWIS 1 /* TWI Slave mode implemented? */
#define SERCOM1_TWI_HSMODE 0 /* TWI HighSpeed mode implemented? */
#define SERCOM1_USART 1 /* USART mode implemented? */
#define SERCOM1_USART_AUTOBAUD 0 /* USART AUTOBAUD mode implemented? */
#define SERCOM1_USART_ISO7816 0 /* USART ISO7816 mode implemented? */
#define SERCOM1_USART_LIN_MASTER 0 /* USART LIN Master mode implemented? */
#define SERCOM1_USART_RS485 0 /* USART RS485 mode implemented? */
#define SERCOM1_INSTANCE_ID 66
#endif /* _SAML10_SERCOM1_INSTANCE_ */

View File

@ -0,0 +1,150 @@
/**
* \file
*
* \brief Instance description for SERCOM2
*
* Copyright (c) 2018 Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* 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
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
/* file generated from device description version 2018-08-31T13:51:50Z */
#ifndef _SAML10_SERCOM2_INSTANCE_H_
#define _SAML10_SERCOM2_INSTANCE_H_
/* ========== Register definition for SERCOM2 peripheral ========== */
#if (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
#define REG_SERCOM2_I2CM_CTRLA (0x42000C00) /**< (SERCOM2) I2CM Control A */
#define REG_SERCOM2_I2CM_CTRLB (0x42000C04) /**< (SERCOM2) I2CM Control B */
#define REG_SERCOM2_I2CM_BAUD (0x42000C0C) /**< (SERCOM2) I2CM Baud Rate */
#define REG_SERCOM2_I2CM_INTENCLR (0x42000C14) /**< (SERCOM2) I2CM Interrupt Enable Clear */
#define REG_SERCOM2_I2CM_INTENSET (0x42000C16) /**< (SERCOM2) I2CM Interrupt Enable Set */
#define REG_SERCOM2_I2CM_INTFLAG (0x42000C18) /**< (SERCOM2) I2CM Interrupt Flag Status and Clear */
#define REG_SERCOM2_I2CM_STATUS (0x42000C1A) /**< (SERCOM2) I2CM Status */
#define REG_SERCOM2_I2CM_SYNCBUSY (0x42000C1C) /**< (SERCOM2) I2CM Synchronization Busy */
#define REG_SERCOM2_I2CM_ADDR (0x42000C24) /**< (SERCOM2) I2CM Address */
#define REG_SERCOM2_I2CM_DATA (0x42000C28) /**< (SERCOM2) I2CM Data */
#define REG_SERCOM2_I2CM_DBGCTRL (0x42000C30) /**< (SERCOM2) I2CM Debug Control */
#define REG_SERCOM2_I2CS_CTRLA (0x42000C00) /**< (SERCOM2) I2CS Control A */
#define REG_SERCOM2_I2CS_CTRLB (0x42000C04) /**< (SERCOM2) I2CS Control B */
#define REG_SERCOM2_I2CS_INTENCLR (0x42000C14) /**< (SERCOM2) I2CS Interrupt Enable Clear */
#define REG_SERCOM2_I2CS_INTENSET (0x42000C16) /**< (SERCOM2) I2CS Interrupt Enable Set */
#define REG_SERCOM2_I2CS_INTFLAG (0x42000C18) /**< (SERCOM2) I2CS Interrupt Flag Status and Clear */
#define REG_SERCOM2_I2CS_STATUS (0x42000C1A) /**< (SERCOM2) I2CS Status */
#define REG_SERCOM2_I2CS_SYNCBUSY (0x42000C1C) /**< (SERCOM2) I2CS Synchronization Busy */
#define REG_SERCOM2_I2CS_ADDR (0x42000C24) /**< (SERCOM2) I2CS Address */
#define REG_SERCOM2_I2CS_DATA (0x42000C28) /**< (SERCOM2) I2CS Data */
#define REG_SERCOM2_SPI_CTRLA (0x42000C00) /**< (SERCOM2) SPI Control A */
#define REG_SERCOM2_SPI_CTRLB (0x42000C04) /**< (SERCOM2) SPI Control B */
#define REG_SERCOM2_SPI_BAUD (0x42000C0C) /**< (SERCOM2) SPI Baud Rate */
#define REG_SERCOM2_SPI_INTENCLR (0x42000C14) /**< (SERCOM2) SPI Interrupt Enable Clear */
#define REG_SERCOM2_SPI_INTENSET (0x42000C16) /**< (SERCOM2) SPI Interrupt Enable Set */
#define REG_SERCOM2_SPI_INTFLAG (0x42000C18) /**< (SERCOM2) SPI Interrupt Flag Status and Clear */
#define REG_SERCOM2_SPI_STATUS (0x42000C1A) /**< (SERCOM2) SPI Status */
#define REG_SERCOM2_SPI_SYNCBUSY (0x42000C1C) /**< (SERCOM2) SPI Synchronization Busy */
#define REG_SERCOM2_SPI_ADDR (0x42000C24) /**< (SERCOM2) SPI Address */
#define REG_SERCOM2_SPI_DATA (0x42000C28) /**< (SERCOM2) SPI Data */
#define REG_SERCOM2_SPI_DBGCTRL (0x42000C30) /**< (SERCOM2) SPI Debug Control */
#define REG_SERCOM2_USART_CTRLA (0x42000C00) /**< (SERCOM2) USART Control A */
#define REG_SERCOM2_USART_CTRLB (0x42000C04) /**< (SERCOM2) USART Control B */
#define REG_SERCOM2_USART_CTRLC (0x42000C08) /**< (SERCOM2) USART Control C */
#define REG_SERCOM2_USART_BAUD (0x42000C0C) /**< (SERCOM2) USART Baud Rate */
#define REG_SERCOM2_USART_RXPL (0x42000C0E) /**< (SERCOM2) USART Receive Pulse Length */
#define REG_SERCOM2_USART_INTENCLR (0x42000C14) /**< (SERCOM2) USART Interrupt Enable Clear */
#define REG_SERCOM2_USART_INTENSET (0x42000C16) /**< (SERCOM2) USART Interrupt Enable Set */
#define REG_SERCOM2_USART_INTFLAG (0x42000C18) /**< (SERCOM2) USART Interrupt Flag Status and Clear */
#define REG_SERCOM2_USART_STATUS (0x42000C1A) /**< (SERCOM2) USART Status */
#define REG_SERCOM2_USART_SYNCBUSY (0x42000C1C) /**< (SERCOM2) USART Synchronization Busy */
#define REG_SERCOM2_USART_RXERRCNT (0x42000C20) /**< (SERCOM2) USART Receive Error Count */
#define REG_SERCOM2_USART_DATA (0x42000C28) /**< (SERCOM2) USART Data */
#define REG_SERCOM2_USART_DBGCTRL (0x42000C30) /**< (SERCOM2) USART Debug Control */
#else
#define REG_SERCOM2_I2CM_CTRLA (*(__IO uint32_t*)0x42000C00U) /**< (SERCOM2) I2CM Control A */
#define REG_SERCOM2_I2CM_CTRLB (*(__IO uint32_t*)0x42000C04U) /**< (SERCOM2) I2CM Control B */
#define REG_SERCOM2_I2CM_BAUD (*(__IO uint32_t*)0x42000C0CU) /**< (SERCOM2) I2CM Baud Rate */
#define REG_SERCOM2_I2CM_INTENCLR (*(__IO uint8_t*)0x42000C14U) /**< (SERCOM2) I2CM Interrupt Enable Clear */
#define REG_SERCOM2_I2CM_INTENSET (*(__IO uint8_t*)0x42000C16U) /**< (SERCOM2) I2CM Interrupt Enable Set */
#define REG_SERCOM2_I2CM_INTFLAG (*(__IO uint8_t*)0x42000C18U) /**< (SERCOM2) I2CM Interrupt Flag Status and Clear */
#define REG_SERCOM2_I2CM_STATUS (*(__IO uint16_t*)0x42000C1AU) /**< (SERCOM2) I2CM Status */
#define REG_SERCOM2_I2CM_SYNCBUSY (*(__I uint32_t*)0x42000C1CU) /**< (SERCOM2) I2CM Synchronization Busy */
#define REG_SERCOM2_I2CM_ADDR (*(__IO uint32_t*)0x42000C24U) /**< (SERCOM2) I2CM Address */
#define REG_SERCOM2_I2CM_DATA (*(__IO uint8_t*)0x42000C28U) /**< (SERCOM2) I2CM Data */
#define REG_SERCOM2_I2CM_DBGCTRL (*(__IO uint8_t*)0x42000C30U) /**< (SERCOM2) I2CM Debug Control */
#define REG_SERCOM2_I2CS_CTRLA (*(__IO uint32_t*)0x42000C00U) /**< (SERCOM2) I2CS Control A */
#define REG_SERCOM2_I2CS_CTRLB (*(__IO uint32_t*)0x42000C04U) /**< (SERCOM2) I2CS Control B */
#define REG_SERCOM2_I2CS_INTENCLR (*(__IO uint8_t*)0x42000C14U) /**< (SERCOM2) I2CS Interrupt Enable Clear */
#define REG_SERCOM2_I2CS_INTENSET (*(__IO uint8_t*)0x42000C16U) /**< (SERCOM2) I2CS Interrupt Enable Set */
#define REG_SERCOM2_I2CS_INTFLAG (*(__IO uint8_t*)0x42000C18U) /**< (SERCOM2) I2CS Interrupt Flag Status and Clear */
#define REG_SERCOM2_I2CS_STATUS (*(__IO uint16_t*)0x42000C1AU) /**< (SERCOM2) I2CS Status */
#define REG_SERCOM2_I2CS_SYNCBUSY (*(__I uint32_t*)0x42000C1CU) /**< (SERCOM2) I2CS Synchronization Busy */
#define REG_SERCOM2_I2CS_ADDR (*(__IO uint32_t*)0x42000C24U) /**< (SERCOM2) I2CS Address */
#define REG_SERCOM2_I2CS_DATA (*(__IO uint8_t*)0x42000C28U) /**< (SERCOM2) I2CS Data */
#define REG_SERCOM2_SPI_CTRLA (*(__IO uint32_t*)0x42000C00U) /**< (SERCOM2) SPI Control A */
#define REG_SERCOM2_SPI_CTRLB (*(__IO uint32_t*)0x42000C04U) /**< (SERCOM2) SPI Control B */
#define REG_SERCOM2_SPI_BAUD (*(__IO uint8_t*)0x42000C0CU) /**< (SERCOM2) SPI Baud Rate */
#define REG_SERCOM2_SPI_INTENCLR (*(__IO uint8_t*)0x42000C14U) /**< (SERCOM2) SPI Interrupt Enable Clear */
#define REG_SERCOM2_SPI_INTENSET (*(__IO uint8_t*)0x42000C16U) /**< (SERCOM2) SPI Interrupt Enable Set */
#define REG_SERCOM2_SPI_INTFLAG (*(__IO uint8_t*)0x42000C18U) /**< (SERCOM2) SPI Interrupt Flag Status and Clear */
#define REG_SERCOM2_SPI_STATUS (*(__IO uint16_t*)0x42000C1AU) /**< (SERCOM2) SPI Status */
#define REG_SERCOM2_SPI_SYNCBUSY (*(__I uint32_t*)0x42000C1CU) /**< (SERCOM2) SPI Synchronization Busy */
#define REG_SERCOM2_SPI_ADDR (*(__IO uint32_t*)0x42000C24U) /**< (SERCOM2) SPI Address */
#define REG_SERCOM2_SPI_DATA (*(__IO uint32_t*)0x42000C28U) /**< (SERCOM2) SPI Data */
#define REG_SERCOM2_SPI_DBGCTRL (*(__IO uint8_t*)0x42000C30U) /**< (SERCOM2) SPI Debug Control */
#define REG_SERCOM2_USART_CTRLA (*(__IO uint32_t*)0x42000C00U) /**< (SERCOM2) USART Control A */
#define REG_SERCOM2_USART_CTRLB (*(__IO uint32_t*)0x42000C04U) /**< (SERCOM2) USART Control B */
#define REG_SERCOM2_USART_CTRLC (*(__IO uint32_t*)0x42000C08U) /**< (SERCOM2) USART Control C */
#define REG_SERCOM2_USART_BAUD (*(__IO uint16_t*)0x42000C0CU) /**< (SERCOM2) USART Baud Rate */
#define REG_SERCOM2_USART_RXPL (*(__IO uint8_t*)0x42000C0EU) /**< (SERCOM2) USART Receive Pulse Length */
#define REG_SERCOM2_USART_INTENCLR (*(__IO uint8_t*)0x42000C14U) /**< (SERCOM2) USART Interrupt Enable Clear */
#define REG_SERCOM2_USART_INTENSET (*(__IO uint8_t*)0x42000C16U) /**< (SERCOM2) USART Interrupt Enable Set */
#define REG_SERCOM2_USART_INTFLAG (*(__IO uint8_t*)0x42000C18U) /**< (SERCOM2) USART Interrupt Flag Status and Clear */
#define REG_SERCOM2_USART_STATUS (*(__IO uint16_t*)0x42000C1AU) /**< (SERCOM2) USART Status */
#define REG_SERCOM2_USART_SYNCBUSY (*(__I uint32_t*)0x42000C1CU) /**< (SERCOM2) USART Synchronization Busy */
#define REG_SERCOM2_USART_RXERRCNT (*(__I uint8_t*)0x42000C20U) /**< (SERCOM2) USART Receive Error Count */
#define REG_SERCOM2_USART_DATA (*(__IO uint16_t*)0x42000C28U) /**< (SERCOM2) USART Data */
#define REG_SERCOM2_USART_DBGCTRL (*(__IO uint8_t*)0x42000C30U) /**< (SERCOM2) USART Debug Control */
#endif /* (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/* ========== Instance Parameter definitions for SERCOM2 peripheral ========== */
#define SERCOM2_DMAC_ID_RX 8 /* Index of DMA RX trigger */
#define SERCOM2_DMAC_ID_TX 9 /* Index of DMA TX trigger */
#define SERCOM2_FIFO_DEPTH_POWER 1 /* Rx Fifo depth = 2^FIFO_DEPTH_POWER */
#define SERCOM2_GCLK_ID_CORE 13
#define SERCOM2_GCLK_ID_SLOW 10
#define SERCOM2_INT_MSB 6
#define SERCOM2_PMSB 3
#define SERCOM2_SPI 1 /* SPI mode implemented? */
#define SERCOM2_TWIM 0 /* TWI Master mode implemented? */
#define SERCOM2_TWIS 0 /* TWI Slave mode implemented? */
#define SERCOM2_TWI_HSMODE 0 /* TWI HighSpeed mode implemented? */
#define SERCOM2_USART 1 /* USART mode implemented? */
#define SERCOM2_USART_AUTOBAUD 1 /* USART AUTOBAUD mode implemented? */
#define SERCOM2_USART_ISO7816 1 /* USART ISO7816 mode implemented? */
#define SERCOM2_USART_LIN_MASTER 0 /* USART LIN Master mode implemented? */
#define SERCOM2_USART_RS485 1 /* USART RS485 mode implemented? */
#define SERCOM2_INSTANCE_ID 67
#endif /* _SAML10_SERCOM2_INSTANCE_ */

View File

@ -0,0 +1,68 @@
/**
* \file
*
* \brief Instance description for SUPC
*
* Copyright (c) 2018 Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* 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
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
/* file generated from device description version 2018-08-31T13:51:50Z */
#ifndef _SAML10_SUPC_INSTANCE_H_
#define _SAML10_SUPC_INSTANCE_H_
/* ========== Register definition for SUPC peripheral ========== */
#if (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
#define REG_SUPC_INTENCLR (0x40001800) /**< (SUPC) Interrupt Enable Clear */
#define REG_SUPC_INTENSET (0x40001804) /**< (SUPC) Interrupt Enable Set */
#define REG_SUPC_INTFLAG (0x40001808) /**< (SUPC) Interrupt Flag Status and Clear */
#define REG_SUPC_STATUS (0x4000180C) /**< (SUPC) Power and Clocks Status */
#define REG_SUPC_BOD33 (0x40001810) /**< (SUPC) BOD33 Control */
#define REG_SUPC_BOD12 (0x40001814) /**< (SUPC) BOD12 Control */
#define REG_SUPC_VREG (0x40001818) /**< (SUPC) VREG Control */
#define REG_SUPC_VREF (0x4000181C) /**< (SUPC) VREF Control */
#define REG_SUPC_EVCTRL (0x4000182C) /**< (SUPC) Event Control */
#define REG_SUPC_VREGSUSP (0x40001830) /**< (SUPC) VREG Suspend Control */
#else
#define REG_SUPC_INTENCLR (*(__IO uint32_t*)0x40001800U) /**< (SUPC) Interrupt Enable Clear */
#define REG_SUPC_INTENSET (*(__IO uint32_t*)0x40001804U) /**< (SUPC) Interrupt Enable Set */
#define REG_SUPC_INTFLAG (*(__IO uint32_t*)0x40001808U) /**< (SUPC) Interrupt Flag Status and Clear */
#define REG_SUPC_STATUS (*(__I uint32_t*)0x4000180CU) /**< (SUPC) Power and Clocks Status */
#define REG_SUPC_BOD33 (*(__IO uint32_t*)0x40001810U) /**< (SUPC) BOD33 Control */
#define REG_SUPC_BOD12 (*(__IO uint32_t*)0x40001814U) /**< (SUPC) BOD12 Control */
#define REG_SUPC_VREG (*(__IO uint32_t*)0x40001818U) /**< (SUPC) VREG Control */
#define REG_SUPC_VREF (*(__IO uint32_t*)0x4000181CU) /**< (SUPC) VREF Control */
#define REG_SUPC_EVCTRL (*(__IO uint32_t*)0x4000182CU) /**< (SUPC) Event Control */
#define REG_SUPC_VREGSUSP (*(__IO uint32_t*)0x40001830U) /**< (SUPC) VREG Suspend Control */
#endif /* (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/* ========== Instance Parameter definitions for SUPC peripheral ========== */
#define SUPC_BOD12_CALIB_MSB 5
#define SUPC_BOD33_CALIB_MSB 5
#define SUPC_INSTANCE_ID 6
#endif /* _SAML10_SUPC_INSTANCE_ */

View File

@ -0,0 +1,130 @@
/**
* \file
*
* \brief Instance description for TC0
*
* Copyright (c) 2018 Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* 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
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
/* file generated from device description version 2018-08-31T13:51:50Z */
#ifndef _SAML10_TC0_INSTANCE_H_
#define _SAML10_TC0_INSTANCE_H_
/* ========== Register definition for TC0 peripheral ========== */
#if (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
#define REG_TC0_CTRLA (0x42001000) /**< (TC0) Control A */
#define REG_TC0_CTRLBCLR (0x42001004) /**< (TC0) Control B Clear */
#define REG_TC0_CTRLBSET (0x42001005) /**< (TC0) Control B Set */
#define REG_TC0_EVCTRL (0x42001006) /**< (TC0) Event Control */
#define REG_TC0_INTENCLR (0x42001008) /**< (TC0) Interrupt Enable Clear */
#define REG_TC0_INTENSET (0x42001009) /**< (TC0) Interrupt Enable Set */
#define REG_TC0_INTFLAG (0x4200100A) /**< (TC0) Interrupt Flag Status and Clear */
#define REG_TC0_STATUS (0x4200100B) /**< (TC0) Status */
#define REG_TC0_WAVE (0x4200100C) /**< (TC0) Waveform Generation Control */
#define REG_TC0_DRVCTRL (0x4200100D) /**< (TC0) Control C */
#define REG_TC0_DBGCTRL (0x4200100F) /**< (TC0) Debug Control */
#define REG_TC0_SYNCBUSY (0x42001010) /**< (TC0) Synchronization Status */
#define REG_TC0_COUNT8_COUNT (0x42001014) /**< (TC0) COUNT8 Count */
#define REG_TC0_COUNT8_PER (0x4200101B) /**< (TC0) COUNT8 Period */
#define REG_TC0_COUNT8_CC (0x4200101C) /**< (TC0) COUNT8 Compare and Capture */
#define REG_TC0_COUNT8_CC0 (0x4200101C) /**< (TC0) COUNT8 Compare and Capture 0 */
#define REG_TC0_COUNT8_CC1 (0x4200101D) /**< (TC0) COUNT8 Compare and Capture 1 */
#define REG_TC0_COUNT8_PERBUF (0x4200102F) /**< (TC0) COUNT8 Period Buffer */
#define REG_TC0_COUNT8_CCBUF (0x42001030) /**< (TC0) COUNT8 Compare and Capture Buffer */
#define REG_TC0_COUNT8_CCBUF0 (0x42001030) /**< (TC0) COUNT8 Compare and Capture Buffer 0 */
#define REG_TC0_COUNT8_CCBUF1 (0x42001031) /**< (TC0) COUNT8 Compare and Capture Buffer 1 */
#define REG_TC0_COUNT16_COUNT (0x42001014) /**< (TC0) COUNT16 Count */
#define REG_TC0_COUNT16_PER (0x4200101A) /**< (TC0) COUNT16 Period */
#define REG_TC0_COUNT16_CC (0x4200101C) /**< (TC0) COUNT16 Compare and Capture */
#define REG_TC0_COUNT16_CC0 (0x4200101C) /**< (TC0) COUNT16 Compare and Capture 0 */
#define REG_TC0_COUNT16_CC1 (0x4200101E) /**< (TC0) COUNT16 Compare and Capture 1 */
#define REG_TC0_COUNT16_PERBUF (0x4200102E) /**< (TC0) COUNT16 Period Buffer */
#define REG_TC0_COUNT16_CCBUF (0x42001030) /**< (TC0) COUNT16 Compare and Capture Buffer */
#define REG_TC0_COUNT16_CCBUF0 (0x42001030) /**< (TC0) COUNT16 Compare and Capture Buffer 0 */
#define REG_TC0_COUNT16_CCBUF1 (0x42001032) /**< (TC0) COUNT16 Compare and Capture Buffer 1 */
#define REG_TC0_COUNT32_COUNT (0x42001014) /**< (TC0) COUNT32 Count */
#define REG_TC0_COUNT32_PER (0x42001018) /**< (TC0) COUNT32 Period */
#define REG_TC0_COUNT32_CC (0x4200101C) /**< (TC0) COUNT32 Compare and Capture */
#define REG_TC0_COUNT32_CC0 (0x4200101C) /**< (TC0) COUNT32 Compare and Capture 0 */
#define REG_TC0_COUNT32_CC1 (0x42001020) /**< (TC0) COUNT32 Compare and Capture 1 */
#define REG_TC0_COUNT32_PERBUF (0x4200102C) /**< (TC0) COUNT32 Period Buffer */
#define REG_TC0_COUNT32_CCBUF (0x42001030) /**< (TC0) COUNT32 Compare and Capture Buffer */
#define REG_TC0_COUNT32_CCBUF0 (0x42001030) /**< (TC0) COUNT32 Compare and Capture Buffer 0 */
#define REG_TC0_COUNT32_CCBUF1 (0x42001034) /**< (TC0) COUNT32 Compare and Capture Buffer 1 */
#else
#define REG_TC0_CTRLA (*(__IO uint32_t*)0x42001000U) /**< (TC0) Control A */
#define REG_TC0_CTRLBCLR (*(__IO uint8_t*)0x42001004U) /**< (TC0) Control B Clear */
#define REG_TC0_CTRLBSET (*(__IO uint8_t*)0x42001005U) /**< (TC0) Control B Set */
#define REG_TC0_EVCTRL (*(__IO uint16_t*)0x42001006U) /**< (TC0) Event Control */
#define REG_TC0_INTENCLR (*(__IO uint8_t*)0x42001008U) /**< (TC0) Interrupt Enable Clear */
#define REG_TC0_INTENSET (*(__IO uint8_t*)0x42001009U) /**< (TC0) Interrupt Enable Set */
#define REG_TC0_INTFLAG (*(__IO uint8_t*)0x4200100AU) /**< (TC0) Interrupt Flag Status and Clear */
#define REG_TC0_STATUS (*(__IO uint8_t*)0x4200100BU) /**< (TC0) Status */
#define REG_TC0_WAVE (*(__IO uint8_t*)0x4200100CU) /**< (TC0) Waveform Generation Control */
#define REG_TC0_DRVCTRL (*(__IO uint8_t*)0x4200100DU) /**< (TC0) Control C */
#define REG_TC0_DBGCTRL (*(__IO uint8_t*)0x4200100FU) /**< (TC0) Debug Control */
#define REG_TC0_SYNCBUSY (*(__I uint32_t*)0x42001010U) /**< (TC0) Synchronization Status */
#define REG_TC0_COUNT8_COUNT (*(__IO uint8_t*)0x42001014U) /**< (TC0) COUNT8 Count */
#define REG_TC0_COUNT8_PER (*(__IO uint8_t*)0x4200101BU) /**< (TC0) COUNT8 Period */
#define REG_TC0_COUNT8_CC (*(__IO uint8_t*)0x4200101CU) /**< (TC0) COUNT8 Compare and Capture */
#define REG_TC0_COUNT8_CC0 (*(__IO uint8_t*)0x4200101CU) /**< (TC0) COUNT8 Compare and Capture 0 */
#define REG_TC0_COUNT8_CC1 (*(__IO uint8_t*)0x4200101DU) /**< (TC0) COUNT8 Compare and Capture 1 */
#define REG_TC0_COUNT8_PERBUF (*(__IO uint8_t*)0x4200102FU) /**< (TC0) COUNT8 Period Buffer */
#define REG_TC0_COUNT8_CCBUF (*(__IO uint8_t*)0x42001030U) /**< (TC0) COUNT8 Compare and Capture Buffer */
#define REG_TC0_COUNT8_CCBUF0 (*(__IO uint8_t*)0x42001030U) /**< (TC0) COUNT8 Compare and Capture Buffer 0 */
#define REG_TC0_COUNT8_CCBUF1 (*(__IO uint8_t*)0x42001031U) /**< (TC0) COUNT8 Compare and Capture Buffer 1 */
#define REG_TC0_COUNT16_COUNT (*(__IO uint16_t*)0x42001014U) /**< (TC0) COUNT16 Count */
#define REG_TC0_COUNT16_PER (*(__IO uint16_t*)0x4200101AU) /**< (TC0) COUNT16 Period */
#define REG_TC0_COUNT16_CC (*(__IO uint16_t*)0x4200101CU) /**< (TC0) COUNT16 Compare and Capture */
#define REG_TC0_COUNT16_CC0 (*(__IO uint16_t*)0x4200101CU) /**< (TC0) COUNT16 Compare and Capture 0 */
#define REG_TC0_COUNT16_CC1 (*(__IO uint16_t*)0x4200101EU) /**< (TC0) COUNT16 Compare and Capture 1 */
#define REG_TC0_COUNT16_PERBUF (*(__IO uint16_t*)0x4200102EU) /**< (TC0) COUNT16 Period Buffer */
#define REG_TC0_COUNT16_CCBUF (*(__IO uint16_t*)0x42001030U) /**< (TC0) COUNT16 Compare and Capture Buffer */
#define REG_TC0_COUNT16_CCBUF0 (*(__IO uint16_t*)0x42001030U) /**< (TC0) COUNT16 Compare and Capture Buffer 0 */
#define REG_TC0_COUNT16_CCBUF1 (*(__IO uint16_t*)0x42001032U) /**< (TC0) COUNT16 Compare and Capture Buffer 1 */
#define REG_TC0_COUNT32_COUNT (*(__IO uint32_t*)0x42001014U) /**< (TC0) COUNT32 Count */
#define REG_TC0_COUNT32_PER (*(__IO uint32_t*)0x42001018U) /**< (TC0) COUNT32 Period */
#define REG_TC0_COUNT32_CC (*(__IO uint32_t*)0x4200101CU) /**< (TC0) COUNT32 Compare and Capture */
#define REG_TC0_COUNT32_CC0 (*(__IO uint32_t*)0x4200101CU) /**< (TC0) COUNT32 Compare and Capture 0 */
#define REG_TC0_COUNT32_CC1 (*(__IO uint32_t*)0x42001020U) /**< (TC0) COUNT32 Compare and Capture 1 */
#define REG_TC0_COUNT32_PERBUF (*(__IO uint32_t*)0x4200102CU) /**< (TC0) COUNT32 Period Buffer */
#define REG_TC0_COUNT32_CCBUF (*(__IO uint32_t*)0x42001030U) /**< (TC0) COUNT32 Compare and Capture Buffer */
#define REG_TC0_COUNT32_CCBUF0 (*(__IO uint32_t*)0x42001030U) /**< (TC0) COUNT32 Compare and Capture Buffer 0 */
#define REG_TC0_COUNT32_CCBUF1 (*(__IO uint32_t*)0x42001034U) /**< (TC0) COUNT32 Compare and Capture Buffer 1 */
#endif /* (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/* ========== Instance Parameter definitions for TC0 peripheral ========== */
#define TC0_CC_NUM 2
#define TC0_DMAC_ID_OVF 10 /* Indexes of DMA Overflow trigger */
#define TC0_EXT 1 /* Coding of implemented extended features (keep 0 value) */
#define TC0_GCLK_ID 14 /* Index of Generic Clock */
#define TC0_MASTER_SLAVE_MODE 1 /* TC type 0 : NA, 1 : Master, 2 : Slave */
#define TC0_OW_NUM 2 /* Number of Output Waveforms */
#define TC0_INSTANCE_ID 68
#endif /* _SAML10_TC0_INSTANCE_ */

View File

@ -0,0 +1,130 @@
/**
* \file
*
* \brief Instance description for TC1
*
* Copyright (c) 2018 Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* 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
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
/* file generated from device description version 2018-08-31T13:51:50Z */
#ifndef _SAML10_TC1_INSTANCE_H_
#define _SAML10_TC1_INSTANCE_H_
/* ========== Register definition for TC1 peripheral ========== */
#if (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
#define REG_TC1_CTRLA (0x42001400) /**< (TC1) Control A */
#define REG_TC1_CTRLBCLR (0x42001404) /**< (TC1) Control B Clear */
#define REG_TC1_CTRLBSET (0x42001405) /**< (TC1) Control B Set */
#define REG_TC1_EVCTRL (0x42001406) /**< (TC1) Event Control */
#define REG_TC1_INTENCLR (0x42001408) /**< (TC1) Interrupt Enable Clear */
#define REG_TC1_INTENSET (0x42001409) /**< (TC1) Interrupt Enable Set */
#define REG_TC1_INTFLAG (0x4200140A) /**< (TC1) Interrupt Flag Status and Clear */
#define REG_TC1_STATUS (0x4200140B) /**< (TC1) Status */
#define REG_TC1_WAVE (0x4200140C) /**< (TC1) Waveform Generation Control */
#define REG_TC1_DRVCTRL (0x4200140D) /**< (TC1) Control C */
#define REG_TC1_DBGCTRL (0x4200140F) /**< (TC1) Debug Control */
#define REG_TC1_SYNCBUSY (0x42001410) /**< (TC1) Synchronization Status */
#define REG_TC1_COUNT8_COUNT (0x42001414) /**< (TC1) COUNT8 Count */
#define REG_TC1_COUNT8_PER (0x4200141B) /**< (TC1) COUNT8 Period */
#define REG_TC1_COUNT8_CC (0x4200141C) /**< (TC1) COUNT8 Compare and Capture */
#define REG_TC1_COUNT8_CC0 (0x4200141C) /**< (TC1) COUNT8 Compare and Capture 0 */
#define REG_TC1_COUNT8_CC1 (0x4200141D) /**< (TC1) COUNT8 Compare and Capture 1 */
#define REG_TC1_COUNT8_PERBUF (0x4200142F) /**< (TC1) COUNT8 Period Buffer */
#define REG_TC1_COUNT8_CCBUF (0x42001430) /**< (TC1) COUNT8 Compare and Capture Buffer */
#define REG_TC1_COUNT8_CCBUF0 (0x42001430) /**< (TC1) COUNT8 Compare and Capture Buffer 0 */
#define REG_TC1_COUNT8_CCBUF1 (0x42001431) /**< (TC1) COUNT8 Compare and Capture Buffer 1 */
#define REG_TC1_COUNT16_COUNT (0x42001414) /**< (TC1) COUNT16 Count */
#define REG_TC1_COUNT16_PER (0x4200141A) /**< (TC1) COUNT16 Period */
#define REG_TC1_COUNT16_CC (0x4200141C) /**< (TC1) COUNT16 Compare and Capture */
#define REG_TC1_COUNT16_CC0 (0x4200141C) /**< (TC1) COUNT16 Compare and Capture 0 */
#define REG_TC1_COUNT16_CC1 (0x4200141E) /**< (TC1) COUNT16 Compare and Capture 1 */
#define REG_TC1_COUNT16_PERBUF (0x4200142E) /**< (TC1) COUNT16 Period Buffer */
#define REG_TC1_COUNT16_CCBUF (0x42001430) /**< (TC1) COUNT16 Compare and Capture Buffer */
#define REG_TC1_COUNT16_CCBUF0 (0x42001430) /**< (TC1) COUNT16 Compare and Capture Buffer 0 */
#define REG_TC1_COUNT16_CCBUF1 (0x42001432) /**< (TC1) COUNT16 Compare and Capture Buffer 1 */
#define REG_TC1_COUNT32_COUNT (0x42001414) /**< (TC1) COUNT32 Count */
#define REG_TC1_COUNT32_PER (0x42001418) /**< (TC1) COUNT32 Period */
#define REG_TC1_COUNT32_CC (0x4200141C) /**< (TC1) COUNT32 Compare and Capture */
#define REG_TC1_COUNT32_CC0 (0x4200141C) /**< (TC1) COUNT32 Compare and Capture 0 */
#define REG_TC1_COUNT32_CC1 (0x42001420) /**< (TC1) COUNT32 Compare and Capture 1 */
#define REG_TC1_COUNT32_PERBUF (0x4200142C) /**< (TC1) COUNT32 Period Buffer */
#define REG_TC1_COUNT32_CCBUF (0x42001430) /**< (TC1) COUNT32 Compare and Capture Buffer */
#define REG_TC1_COUNT32_CCBUF0 (0x42001430) /**< (TC1) COUNT32 Compare and Capture Buffer 0 */
#define REG_TC1_COUNT32_CCBUF1 (0x42001434) /**< (TC1) COUNT32 Compare and Capture Buffer 1 */
#else
#define REG_TC1_CTRLA (*(__IO uint32_t*)0x42001400U) /**< (TC1) Control A */
#define REG_TC1_CTRLBCLR (*(__IO uint8_t*)0x42001404U) /**< (TC1) Control B Clear */
#define REG_TC1_CTRLBSET (*(__IO uint8_t*)0x42001405U) /**< (TC1) Control B Set */
#define REG_TC1_EVCTRL (*(__IO uint16_t*)0x42001406U) /**< (TC1) Event Control */
#define REG_TC1_INTENCLR (*(__IO uint8_t*)0x42001408U) /**< (TC1) Interrupt Enable Clear */
#define REG_TC1_INTENSET (*(__IO uint8_t*)0x42001409U) /**< (TC1) Interrupt Enable Set */
#define REG_TC1_INTFLAG (*(__IO uint8_t*)0x4200140AU) /**< (TC1) Interrupt Flag Status and Clear */
#define REG_TC1_STATUS (*(__IO uint8_t*)0x4200140BU) /**< (TC1) Status */
#define REG_TC1_WAVE (*(__IO uint8_t*)0x4200140CU) /**< (TC1) Waveform Generation Control */
#define REG_TC1_DRVCTRL (*(__IO uint8_t*)0x4200140DU) /**< (TC1) Control C */
#define REG_TC1_DBGCTRL (*(__IO uint8_t*)0x4200140FU) /**< (TC1) Debug Control */
#define REG_TC1_SYNCBUSY (*(__I uint32_t*)0x42001410U) /**< (TC1) Synchronization Status */
#define REG_TC1_COUNT8_COUNT (*(__IO uint8_t*)0x42001414U) /**< (TC1) COUNT8 Count */
#define REG_TC1_COUNT8_PER (*(__IO uint8_t*)0x4200141BU) /**< (TC1) COUNT8 Period */
#define REG_TC1_COUNT8_CC (*(__IO uint8_t*)0x4200141CU) /**< (TC1) COUNT8 Compare and Capture */
#define REG_TC1_COUNT8_CC0 (*(__IO uint8_t*)0x4200141CU) /**< (TC1) COUNT8 Compare and Capture 0 */
#define REG_TC1_COUNT8_CC1 (*(__IO uint8_t*)0x4200141DU) /**< (TC1) COUNT8 Compare and Capture 1 */
#define REG_TC1_COUNT8_PERBUF (*(__IO uint8_t*)0x4200142FU) /**< (TC1) COUNT8 Period Buffer */
#define REG_TC1_COUNT8_CCBUF (*(__IO uint8_t*)0x42001430U) /**< (TC1) COUNT8 Compare and Capture Buffer */
#define REG_TC1_COUNT8_CCBUF0 (*(__IO uint8_t*)0x42001430U) /**< (TC1) COUNT8 Compare and Capture Buffer 0 */
#define REG_TC1_COUNT8_CCBUF1 (*(__IO uint8_t*)0x42001431U) /**< (TC1) COUNT8 Compare and Capture Buffer 1 */
#define REG_TC1_COUNT16_COUNT (*(__IO uint16_t*)0x42001414U) /**< (TC1) COUNT16 Count */
#define REG_TC1_COUNT16_PER (*(__IO uint16_t*)0x4200141AU) /**< (TC1) COUNT16 Period */
#define REG_TC1_COUNT16_CC (*(__IO uint16_t*)0x4200141CU) /**< (TC1) COUNT16 Compare and Capture */
#define REG_TC1_COUNT16_CC0 (*(__IO uint16_t*)0x4200141CU) /**< (TC1) COUNT16 Compare and Capture 0 */
#define REG_TC1_COUNT16_CC1 (*(__IO uint16_t*)0x4200141EU) /**< (TC1) COUNT16 Compare and Capture 1 */
#define REG_TC1_COUNT16_PERBUF (*(__IO uint16_t*)0x4200142EU) /**< (TC1) COUNT16 Period Buffer */
#define REG_TC1_COUNT16_CCBUF (*(__IO uint16_t*)0x42001430U) /**< (TC1) COUNT16 Compare and Capture Buffer */
#define REG_TC1_COUNT16_CCBUF0 (*(__IO uint16_t*)0x42001430U) /**< (TC1) COUNT16 Compare and Capture Buffer 0 */
#define REG_TC1_COUNT16_CCBUF1 (*(__IO uint16_t*)0x42001432U) /**< (TC1) COUNT16 Compare and Capture Buffer 1 */
#define REG_TC1_COUNT32_COUNT (*(__IO uint32_t*)0x42001414U) /**< (TC1) COUNT32 Count */
#define REG_TC1_COUNT32_PER (*(__IO uint32_t*)0x42001418U) /**< (TC1) COUNT32 Period */
#define REG_TC1_COUNT32_CC (*(__IO uint32_t*)0x4200141CU) /**< (TC1) COUNT32 Compare and Capture */
#define REG_TC1_COUNT32_CC0 (*(__IO uint32_t*)0x4200141CU) /**< (TC1) COUNT32 Compare and Capture 0 */
#define REG_TC1_COUNT32_CC1 (*(__IO uint32_t*)0x42001420U) /**< (TC1) COUNT32 Compare and Capture 1 */
#define REG_TC1_COUNT32_PERBUF (*(__IO uint32_t*)0x4200142CU) /**< (TC1) COUNT32 Period Buffer */
#define REG_TC1_COUNT32_CCBUF (*(__IO uint32_t*)0x42001430U) /**< (TC1) COUNT32 Compare and Capture Buffer */
#define REG_TC1_COUNT32_CCBUF0 (*(__IO uint32_t*)0x42001430U) /**< (TC1) COUNT32 Compare and Capture Buffer 0 */
#define REG_TC1_COUNT32_CCBUF1 (*(__IO uint32_t*)0x42001434U) /**< (TC1) COUNT32 Compare and Capture Buffer 1 */
#endif /* (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/* ========== Instance Parameter definitions for TC1 peripheral ========== */
#define TC1_CC_NUM 2
#define TC1_DMAC_ID_OVF 13 /* Indexes of DMA Overflow trigger */
#define TC1_EXT 1 /* Coding of implemented extended features (keep 0 value) */
#define TC1_GCLK_ID 14 /* Index of Generic Clock */
#define TC1_MASTER_SLAVE_MODE 2 /* TC type 0 : NA, 1 : Master, 2 : Slave */
#define TC1_OW_NUM 2 /* Number of Output Waveforms */
#define TC1_INSTANCE_ID 69
#endif /* _SAML10_TC1_INSTANCE_ */

View File

@ -0,0 +1,130 @@
/**
* \file
*
* \brief Instance description for TC2
*
* Copyright (c) 2018 Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* 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
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
/* file generated from device description version 2018-08-31T13:51:50Z */
#ifndef _SAML10_TC2_INSTANCE_H_
#define _SAML10_TC2_INSTANCE_H_
/* ========== Register definition for TC2 peripheral ========== */
#if (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
#define REG_TC2_CTRLA (0x42001800) /**< (TC2) Control A */
#define REG_TC2_CTRLBCLR (0x42001804) /**< (TC2) Control B Clear */
#define REG_TC2_CTRLBSET (0x42001805) /**< (TC2) Control B Set */
#define REG_TC2_EVCTRL (0x42001806) /**< (TC2) Event Control */
#define REG_TC2_INTENCLR (0x42001808) /**< (TC2) Interrupt Enable Clear */
#define REG_TC2_INTENSET (0x42001809) /**< (TC2) Interrupt Enable Set */
#define REG_TC2_INTFLAG (0x4200180A) /**< (TC2) Interrupt Flag Status and Clear */
#define REG_TC2_STATUS (0x4200180B) /**< (TC2) Status */
#define REG_TC2_WAVE (0x4200180C) /**< (TC2) Waveform Generation Control */
#define REG_TC2_DRVCTRL (0x4200180D) /**< (TC2) Control C */
#define REG_TC2_DBGCTRL (0x4200180F) /**< (TC2) Debug Control */
#define REG_TC2_SYNCBUSY (0x42001810) /**< (TC2) Synchronization Status */
#define REG_TC2_COUNT8_COUNT (0x42001814) /**< (TC2) COUNT8 Count */
#define REG_TC2_COUNT8_PER (0x4200181B) /**< (TC2) COUNT8 Period */
#define REG_TC2_COUNT8_CC (0x4200181C) /**< (TC2) COUNT8 Compare and Capture */
#define REG_TC2_COUNT8_CC0 (0x4200181C) /**< (TC2) COUNT8 Compare and Capture 0 */
#define REG_TC2_COUNT8_CC1 (0x4200181D) /**< (TC2) COUNT8 Compare and Capture 1 */
#define REG_TC2_COUNT8_PERBUF (0x4200182F) /**< (TC2) COUNT8 Period Buffer */
#define REG_TC2_COUNT8_CCBUF (0x42001830) /**< (TC2) COUNT8 Compare and Capture Buffer */
#define REG_TC2_COUNT8_CCBUF0 (0x42001830) /**< (TC2) COUNT8 Compare and Capture Buffer 0 */
#define REG_TC2_COUNT8_CCBUF1 (0x42001831) /**< (TC2) COUNT8 Compare and Capture Buffer 1 */
#define REG_TC2_COUNT16_COUNT (0x42001814) /**< (TC2) COUNT16 Count */
#define REG_TC2_COUNT16_PER (0x4200181A) /**< (TC2) COUNT16 Period */
#define REG_TC2_COUNT16_CC (0x4200181C) /**< (TC2) COUNT16 Compare and Capture */
#define REG_TC2_COUNT16_CC0 (0x4200181C) /**< (TC2) COUNT16 Compare and Capture 0 */
#define REG_TC2_COUNT16_CC1 (0x4200181E) /**< (TC2) COUNT16 Compare and Capture 1 */
#define REG_TC2_COUNT16_PERBUF (0x4200182E) /**< (TC2) COUNT16 Period Buffer */
#define REG_TC2_COUNT16_CCBUF (0x42001830) /**< (TC2) COUNT16 Compare and Capture Buffer */
#define REG_TC2_COUNT16_CCBUF0 (0x42001830) /**< (TC2) COUNT16 Compare and Capture Buffer 0 */
#define REG_TC2_COUNT16_CCBUF1 (0x42001832) /**< (TC2) COUNT16 Compare and Capture Buffer 1 */
#define REG_TC2_COUNT32_COUNT (0x42001814) /**< (TC2) COUNT32 Count */
#define REG_TC2_COUNT32_PER (0x42001818) /**< (TC2) COUNT32 Period */
#define REG_TC2_COUNT32_CC (0x4200181C) /**< (TC2) COUNT32 Compare and Capture */
#define REG_TC2_COUNT32_CC0 (0x4200181C) /**< (TC2) COUNT32 Compare and Capture 0 */
#define REG_TC2_COUNT32_CC1 (0x42001820) /**< (TC2) COUNT32 Compare and Capture 1 */
#define REG_TC2_COUNT32_PERBUF (0x4200182C) /**< (TC2) COUNT32 Period Buffer */
#define REG_TC2_COUNT32_CCBUF (0x42001830) /**< (TC2) COUNT32 Compare and Capture Buffer */
#define REG_TC2_COUNT32_CCBUF0 (0x42001830) /**< (TC2) COUNT32 Compare and Capture Buffer 0 */
#define REG_TC2_COUNT32_CCBUF1 (0x42001834) /**< (TC2) COUNT32 Compare and Capture Buffer 1 */
#else
#define REG_TC2_CTRLA (*(__IO uint32_t*)0x42001800U) /**< (TC2) Control A */
#define REG_TC2_CTRLBCLR (*(__IO uint8_t*)0x42001804U) /**< (TC2) Control B Clear */
#define REG_TC2_CTRLBSET (*(__IO uint8_t*)0x42001805U) /**< (TC2) Control B Set */
#define REG_TC2_EVCTRL (*(__IO uint16_t*)0x42001806U) /**< (TC2) Event Control */
#define REG_TC2_INTENCLR (*(__IO uint8_t*)0x42001808U) /**< (TC2) Interrupt Enable Clear */
#define REG_TC2_INTENSET (*(__IO uint8_t*)0x42001809U) /**< (TC2) Interrupt Enable Set */
#define REG_TC2_INTFLAG (*(__IO uint8_t*)0x4200180AU) /**< (TC2) Interrupt Flag Status and Clear */
#define REG_TC2_STATUS (*(__IO uint8_t*)0x4200180BU) /**< (TC2) Status */
#define REG_TC2_WAVE (*(__IO uint8_t*)0x4200180CU) /**< (TC2) Waveform Generation Control */
#define REG_TC2_DRVCTRL (*(__IO uint8_t*)0x4200180DU) /**< (TC2) Control C */
#define REG_TC2_DBGCTRL (*(__IO uint8_t*)0x4200180FU) /**< (TC2) Debug Control */
#define REG_TC2_SYNCBUSY (*(__I uint32_t*)0x42001810U) /**< (TC2) Synchronization Status */
#define REG_TC2_COUNT8_COUNT (*(__IO uint8_t*)0x42001814U) /**< (TC2) COUNT8 Count */
#define REG_TC2_COUNT8_PER (*(__IO uint8_t*)0x4200181BU) /**< (TC2) COUNT8 Period */
#define REG_TC2_COUNT8_CC (*(__IO uint8_t*)0x4200181CU) /**< (TC2) COUNT8 Compare and Capture */
#define REG_TC2_COUNT8_CC0 (*(__IO uint8_t*)0x4200181CU) /**< (TC2) COUNT8 Compare and Capture 0 */
#define REG_TC2_COUNT8_CC1 (*(__IO uint8_t*)0x4200181DU) /**< (TC2) COUNT8 Compare and Capture 1 */
#define REG_TC2_COUNT8_PERBUF (*(__IO uint8_t*)0x4200182FU) /**< (TC2) COUNT8 Period Buffer */
#define REG_TC2_COUNT8_CCBUF (*(__IO uint8_t*)0x42001830U) /**< (TC2) COUNT8 Compare and Capture Buffer */
#define REG_TC2_COUNT8_CCBUF0 (*(__IO uint8_t*)0x42001830U) /**< (TC2) COUNT8 Compare and Capture Buffer 0 */
#define REG_TC2_COUNT8_CCBUF1 (*(__IO uint8_t*)0x42001831U) /**< (TC2) COUNT8 Compare and Capture Buffer 1 */
#define REG_TC2_COUNT16_COUNT (*(__IO uint16_t*)0x42001814U) /**< (TC2) COUNT16 Count */
#define REG_TC2_COUNT16_PER (*(__IO uint16_t*)0x4200181AU) /**< (TC2) COUNT16 Period */
#define REG_TC2_COUNT16_CC (*(__IO uint16_t*)0x4200181CU) /**< (TC2) COUNT16 Compare and Capture */
#define REG_TC2_COUNT16_CC0 (*(__IO uint16_t*)0x4200181CU) /**< (TC2) COUNT16 Compare and Capture 0 */
#define REG_TC2_COUNT16_CC1 (*(__IO uint16_t*)0x4200181EU) /**< (TC2) COUNT16 Compare and Capture 1 */
#define REG_TC2_COUNT16_PERBUF (*(__IO uint16_t*)0x4200182EU) /**< (TC2) COUNT16 Period Buffer */
#define REG_TC2_COUNT16_CCBUF (*(__IO uint16_t*)0x42001830U) /**< (TC2) COUNT16 Compare and Capture Buffer */
#define REG_TC2_COUNT16_CCBUF0 (*(__IO uint16_t*)0x42001830U) /**< (TC2) COUNT16 Compare and Capture Buffer 0 */
#define REG_TC2_COUNT16_CCBUF1 (*(__IO uint16_t*)0x42001832U) /**< (TC2) COUNT16 Compare and Capture Buffer 1 */
#define REG_TC2_COUNT32_COUNT (*(__IO uint32_t*)0x42001814U) /**< (TC2) COUNT32 Count */
#define REG_TC2_COUNT32_PER (*(__IO uint32_t*)0x42001818U) /**< (TC2) COUNT32 Period */
#define REG_TC2_COUNT32_CC (*(__IO uint32_t*)0x4200181CU) /**< (TC2) COUNT32 Compare and Capture */
#define REG_TC2_COUNT32_CC0 (*(__IO uint32_t*)0x4200181CU) /**< (TC2) COUNT32 Compare and Capture 0 */
#define REG_TC2_COUNT32_CC1 (*(__IO uint32_t*)0x42001820U) /**< (TC2) COUNT32 Compare and Capture 1 */
#define REG_TC2_COUNT32_PERBUF (*(__IO uint32_t*)0x4200182CU) /**< (TC2) COUNT32 Period Buffer */
#define REG_TC2_COUNT32_CCBUF (*(__IO uint32_t*)0x42001830U) /**< (TC2) COUNT32 Compare and Capture Buffer */
#define REG_TC2_COUNT32_CCBUF0 (*(__IO uint32_t*)0x42001830U) /**< (TC2) COUNT32 Compare and Capture Buffer 0 */
#define REG_TC2_COUNT32_CCBUF1 (*(__IO uint32_t*)0x42001834U) /**< (TC2) COUNT32 Compare and Capture Buffer 1 */
#endif /* (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/* ========== Instance Parameter definitions for TC2 peripheral ========== */
#define TC2_CC_NUM 2
#define TC2_DMAC_ID_OVF 16 /* Indexes of DMA Overflow trigger */
#define TC2_EXT 1 /* Coding of implemented extended features (keep 0 value) */
#define TC2_GCLK_ID 15 /* Index of Generic Clock */
#define TC2_MASTER_SLAVE_MODE 0 /* TC type 0 : NA, 1 : Master, 2 : Slave */
#define TC2_OW_NUM 2 /* Number of Output Waveforms */
#define TC2_INSTANCE_ID 70
#endif /* _SAML10_TC2_INSTANCE_ */

View File

@ -0,0 +1,194 @@
/**
* \file
*
* \brief Instance description for TRAM
*
* Copyright (c) 2018 Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* 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
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
/* file generated from device description version 2018-08-31T13:51:50Z */
#ifndef _SAML10_TRAM_INSTANCE_H_
#define _SAML10_TRAM_INSTANCE_H_
/* ========== Register definition for TRAM peripheral ========== */
#if (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
#define REG_TRAM_CTRLA (0x42003400) /**< (TRAM) Control */
#define REG_TRAM_INTENCLR (0x42003404) /**< (TRAM) Interrupt Enable Clear */
#define REG_TRAM_INTENSET (0x42003405) /**< (TRAM) Interrupt Enable Set */
#define REG_TRAM_INTFLAG (0x42003406) /**< (TRAM) Interrupt Flag Status and Clear */
#define REG_TRAM_STATUS (0x42003407) /**< (TRAM) Status */
#define REG_TRAM_SYNCBUSY (0x42003408) /**< (TRAM) Synchronization Busy Status */
#define REG_TRAM_DSCC (0x4200340C) /**< (TRAM) Data Scramble Control */
#define REG_TRAM_PERMW (0x42003410) /**< (TRAM) Permutation Write */
#define REG_TRAM_PERMR (0x42003411) /**< (TRAM) Permutation Read */
#define REG_TRAM_RAM (0x42003500) /**< (TRAM) TrustRAM */
#define REG_TRAM_RAM0 (0x42003500) /**< (TRAM) TrustRAM 0 */
#define REG_TRAM_RAM1 (0x42003504) /**< (TRAM) TrustRAM 1 */
#define REG_TRAM_RAM2 (0x42003508) /**< (TRAM) TrustRAM 2 */
#define REG_TRAM_RAM3 (0x4200350C) /**< (TRAM) TrustRAM 3 */
#define REG_TRAM_RAM4 (0x42003510) /**< (TRAM) TrustRAM 4 */
#define REG_TRAM_RAM5 (0x42003514) /**< (TRAM) TrustRAM 5 */
#define REG_TRAM_RAM6 (0x42003518) /**< (TRAM) TrustRAM 6 */
#define REG_TRAM_RAM7 (0x4200351C) /**< (TRAM) TrustRAM 7 */
#define REG_TRAM_RAM8 (0x42003520) /**< (TRAM) TrustRAM 8 */
#define REG_TRAM_RAM9 (0x42003524) /**< (TRAM) TrustRAM 9 */
#define REG_TRAM_RAM10 (0x42003528) /**< (TRAM) TrustRAM 10 */
#define REG_TRAM_RAM11 (0x4200352C) /**< (TRAM) TrustRAM 11 */
#define REG_TRAM_RAM12 (0x42003530) /**< (TRAM) TrustRAM 12 */
#define REG_TRAM_RAM13 (0x42003534) /**< (TRAM) TrustRAM 13 */
#define REG_TRAM_RAM14 (0x42003538) /**< (TRAM) TrustRAM 14 */
#define REG_TRAM_RAM15 (0x4200353C) /**< (TRAM) TrustRAM 15 */
#define REG_TRAM_RAM16 (0x42003540) /**< (TRAM) TrustRAM 16 */
#define REG_TRAM_RAM17 (0x42003544) /**< (TRAM) TrustRAM 17 */
#define REG_TRAM_RAM18 (0x42003548) /**< (TRAM) TrustRAM 18 */
#define REG_TRAM_RAM19 (0x4200354C) /**< (TRAM) TrustRAM 19 */
#define REG_TRAM_RAM20 (0x42003550) /**< (TRAM) TrustRAM 20 */
#define REG_TRAM_RAM21 (0x42003554) /**< (TRAM) TrustRAM 21 */
#define REG_TRAM_RAM22 (0x42003558) /**< (TRAM) TrustRAM 22 */
#define REG_TRAM_RAM23 (0x4200355C) /**< (TRAM) TrustRAM 23 */
#define REG_TRAM_RAM24 (0x42003560) /**< (TRAM) TrustRAM 24 */
#define REG_TRAM_RAM25 (0x42003564) /**< (TRAM) TrustRAM 25 */
#define REG_TRAM_RAM26 (0x42003568) /**< (TRAM) TrustRAM 26 */
#define REG_TRAM_RAM27 (0x4200356C) /**< (TRAM) TrustRAM 27 */
#define REG_TRAM_RAM28 (0x42003570) /**< (TRAM) TrustRAM 28 */
#define REG_TRAM_RAM29 (0x42003574) /**< (TRAM) TrustRAM 29 */
#define REG_TRAM_RAM30 (0x42003578) /**< (TRAM) TrustRAM 30 */
#define REG_TRAM_RAM31 (0x4200357C) /**< (TRAM) TrustRAM 31 */
#define REG_TRAM_RAM32 (0x42003580) /**< (TRAM) TrustRAM 32 */
#define REG_TRAM_RAM33 (0x42003584) /**< (TRAM) TrustRAM 33 */
#define REG_TRAM_RAM34 (0x42003588) /**< (TRAM) TrustRAM 34 */
#define REG_TRAM_RAM35 (0x4200358C) /**< (TRAM) TrustRAM 35 */
#define REG_TRAM_RAM36 (0x42003590) /**< (TRAM) TrustRAM 36 */
#define REG_TRAM_RAM37 (0x42003594) /**< (TRAM) TrustRAM 37 */
#define REG_TRAM_RAM38 (0x42003598) /**< (TRAM) TrustRAM 38 */
#define REG_TRAM_RAM39 (0x4200359C) /**< (TRAM) TrustRAM 39 */
#define REG_TRAM_RAM40 (0x420035A0) /**< (TRAM) TrustRAM 40 */
#define REG_TRAM_RAM41 (0x420035A4) /**< (TRAM) TrustRAM 41 */
#define REG_TRAM_RAM42 (0x420035A8) /**< (TRAM) TrustRAM 42 */
#define REG_TRAM_RAM43 (0x420035AC) /**< (TRAM) TrustRAM 43 */
#define REG_TRAM_RAM44 (0x420035B0) /**< (TRAM) TrustRAM 44 */
#define REG_TRAM_RAM45 (0x420035B4) /**< (TRAM) TrustRAM 45 */
#define REG_TRAM_RAM46 (0x420035B8) /**< (TRAM) TrustRAM 46 */
#define REG_TRAM_RAM47 (0x420035BC) /**< (TRAM) TrustRAM 47 */
#define REG_TRAM_RAM48 (0x420035C0) /**< (TRAM) TrustRAM 48 */
#define REG_TRAM_RAM49 (0x420035C4) /**< (TRAM) TrustRAM 49 */
#define REG_TRAM_RAM50 (0x420035C8) /**< (TRAM) TrustRAM 50 */
#define REG_TRAM_RAM51 (0x420035CC) /**< (TRAM) TrustRAM 51 */
#define REG_TRAM_RAM52 (0x420035D0) /**< (TRAM) TrustRAM 52 */
#define REG_TRAM_RAM53 (0x420035D4) /**< (TRAM) TrustRAM 53 */
#define REG_TRAM_RAM54 (0x420035D8) /**< (TRAM) TrustRAM 54 */
#define REG_TRAM_RAM55 (0x420035DC) /**< (TRAM) TrustRAM 55 */
#define REG_TRAM_RAM56 (0x420035E0) /**< (TRAM) TrustRAM 56 */
#define REG_TRAM_RAM57 (0x420035E4) /**< (TRAM) TrustRAM 57 */
#define REG_TRAM_RAM58 (0x420035E8) /**< (TRAM) TrustRAM 58 */
#define REG_TRAM_RAM59 (0x420035EC) /**< (TRAM) TrustRAM 59 */
#define REG_TRAM_RAM60 (0x420035F0) /**< (TRAM) TrustRAM 60 */
#define REG_TRAM_RAM61 (0x420035F4) /**< (TRAM) TrustRAM 61 */
#define REG_TRAM_RAM62 (0x420035F8) /**< (TRAM) TrustRAM 62 */
#define REG_TRAM_RAM63 (0x420035FC) /**< (TRAM) TrustRAM 63 */
#else
#define REG_TRAM_CTRLA (*(__IO uint8_t*)0x42003400U) /**< (TRAM) Control */
#define REG_TRAM_INTENCLR (*(__IO uint8_t*)0x42003404U) /**< (TRAM) Interrupt Enable Clear */
#define REG_TRAM_INTENSET (*(__IO uint8_t*)0x42003405U) /**< (TRAM) Interrupt Enable Set */
#define REG_TRAM_INTFLAG (*(__IO uint8_t*)0x42003406U) /**< (TRAM) Interrupt Flag Status and Clear */
#define REG_TRAM_STATUS (*(__I uint8_t*)0x42003407U) /**< (TRAM) Status */
#define REG_TRAM_SYNCBUSY (*(__I uint32_t*)0x42003408U) /**< (TRAM) Synchronization Busy Status */
#define REG_TRAM_DSCC (*(__O uint32_t*)0x4200340CU) /**< (TRAM) Data Scramble Control */
#define REG_TRAM_PERMW (*(__O uint8_t*)0x42003410U) /**< (TRAM) Permutation Write */
#define REG_TRAM_PERMR (*(__I uint8_t*)0x42003411U) /**< (TRAM) Permutation Read */
#define REG_TRAM_RAM (*(__IO uint32_t*)0x42003500U) /**< (TRAM) TrustRAM */
#define REG_TRAM_RAM0 (*(__IO uint32_t*)0x42003500U) /**< (TRAM) TrustRAM 0 */
#define REG_TRAM_RAM1 (*(__IO uint32_t*)0x42003504U) /**< (TRAM) TrustRAM 1 */
#define REG_TRAM_RAM2 (*(__IO uint32_t*)0x42003508U) /**< (TRAM) TrustRAM 2 */
#define REG_TRAM_RAM3 (*(__IO uint32_t*)0x4200350CU) /**< (TRAM) TrustRAM 3 */
#define REG_TRAM_RAM4 (*(__IO uint32_t*)0x42003510U) /**< (TRAM) TrustRAM 4 */
#define REG_TRAM_RAM5 (*(__IO uint32_t*)0x42003514U) /**< (TRAM) TrustRAM 5 */
#define REG_TRAM_RAM6 (*(__IO uint32_t*)0x42003518U) /**< (TRAM) TrustRAM 6 */
#define REG_TRAM_RAM7 (*(__IO uint32_t*)0x4200351CU) /**< (TRAM) TrustRAM 7 */
#define REG_TRAM_RAM8 (*(__IO uint32_t*)0x42003520U) /**< (TRAM) TrustRAM 8 */
#define REG_TRAM_RAM9 (*(__IO uint32_t*)0x42003524U) /**< (TRAM) TrustRAM 9 */
#define REG_TRAM_RAM10 (*(__IO uint32_t*)0x42003528U) /**< (TRAM) TrustRAM 10 */
#define REG_TRAM_RAM11 (*(__IO uint32_t*)0x4200352CU) /**< (TRAM) TrustRAM 11 */
#define REG_TRAM_RAM12 (*(__IO uint32_t*)0x42003530U) /**< (TRAM) TrustRAM 12 */
#define REG_TRAM_RAM13 (*(__IO uint32_t*)0x42003534U) /**< (TRAM) TrustRAM 13 */
#define REG_TRAM_RAM14 (*(__IO uint32_t*)0x42003538U) /**< (TRAM) TrustRAM 14 */
#define REG_TRAM_RAM15 (*(__IO uint32_t*)0x4200353CU) /**< (TRAM) TrustRAM 15 */
#define REG_TRAM_RAM16 (*(__IO uint32_t*)0x42003540U) /**< (TRAM) TrustRAM 16 */
#define REG_TRAM_RAM17 (*(__IO uint32_t*)0x42003544U) /**< (TRAM) TrustRAM 17 */
#define REG_TRAM_RAM18 (*(__IO uint32_t*)0x42003548U) /**< (TRAM) TrustRAM 18 */
#define REG_TRAM_RAM19 (*(__IO uint32_t*)0x4200354CU) /**< (TRAM) TrustRAM 19 */
#define REG_TRAM_RAM20 (*(__IO uint32_t*)0x42003550U) /**< (TRAM) TrustRAM 20 */
#define REG_TRAM_RAM21 (*(__IO uint32_t*)0x42003554U) /**< (TRAM) TrustRAM 21 */
#define REG_TRAM_RAM22 (*(__IO uint32_t*)0x42003558U) /**< (TRAM) TrustRAM 22 */
#define REG_TRAM_RAM23 (*(__IO uint32_t*)0x4200355CU) /**< (TRAM) TrustRAM 23 */
#define REG_TRAM_RAM24 (*(__IO uint32_t*)0x42003560U) /**< (TRAM) TrustRAM 24 */
#define REG_TRAM_RAM25 (*(__IO uint32_t*)0x42003564U) /**< (TRAM) TrustRAM 25 */
#define REG_TRAM_RAM26 (*(__IO uint32_t*)0x42003568U) /**< (TRAM) TrustRAM 26 */
#define REG_TRAM_RAM27 (*(__IO uint32_t*)0x4200356CU) /**< (TRAM) TrustRAM 27 */
#define REG_TRAM_RAM28 (*(__IO uint32_t*)0x42003570U) /**< (TRAM) TrustRAM 28 */
#define REG_TRAM_RAM29 (*(__IO uint32_t*)0x42003574U) /**< (TRAM) TrustRAM 29 */
#define REG_TRAM_RAM30 (*(__IO uint32_t*)0x42003578U) /**< (TRAM) TrustRAM 30 */
#define REG_TRAM_RAM31 (*(__IO uint32_t*)0x4200357CU) /**< (TRAM) TrustRAM 31 */
#define REG_TRAM_RAM32 (*(__IO uint32_t*)0x42003580U) /**< (TRAM) TrustRAM 32 */
#define REG_TRAM_RAM33 (*(__IO uint32_t*)0x42003584U) /**< (TRAM) TrustRAM 33 */
#define REG_TRAM_RAM34 (*(__IO uint32_t*)0x42003588U) /**< (TRAM) TrustRAM 34 */
#define REG_TRAM_RAM35 (*(__IO uint32_t*)0x4200358CU) /**< (TRAM) TrustRAM 35 */
#define REG_TRAM_RAM36 (*(__IO uint32_t*)0x42003590U) /**< (TRAM) TrustRAM 36 */
#define REG_TRAM_RAM37 (*(__IO uint32_t*)0x42003594U) /**< (TRAM) TrustRAM 37 */
#define REG_TRAM_RAM38 (*(__IO uint32_t*)0x42003598U) /**< (TRAM) TrustRAM 38 */
#define REG_TRAM_RAM39 (*(__IO uint32_t*)0x4200359CU) /**< (TRAM) TrustRAM 39 */
#define REG_TRAM_RAM40 (*(__IO uint32_t*)0x420035A0U) /**< (TRAM) TrustRAM 40 */
#define REG_TRAM_RAM41 (*(__IO uint32_t*)0x420035A4U) /**< (TRAM) TrustRAM 41 */
#define REG_TRAM_RAM42 (*(__IO uint32_t*)0x420035A8U) /**< (TRAM) TrustRAM 42 */
#define REG_TRAM_RAM43 (*(__IO uint32_t*)0x420035ACU) /**< (TRAM) TrustRAM 43 */
#define REG_TRAM_RAM44 (*(__IO uint32_t*)0x420035B0U) /**< (TRAM) TrustRAM 44 */
#define REG_TRAM_RAM45 (*(__IO uint32_t*)0x420035B4U) /**< (TRAM) TrustRAM 45 */
#define REG_TRAM_RAM46 (*(__IO uint32_t*)0x420035B8U) /**< (TRAM) TrustRAM 46 */
#define REG_TRAM_RAM47 (*(__IO uint32_t*)0x420035BCU) /**< (TRAM) TrustRAM 47 */
#define REG_TRAM_RAM48 (*(__IO uint32_t*)0x420035C0U) /**< (TRAM) TrustRAM 48 */
#define REG_TRAM_RAM49 (*(__IO uint32_t*)0x420035C4U) /**< (TRAM) TrustRAM 49 */
#define REG_TRAM_RAM50 (*(__IO uint32_t*)0x420035C8U) /**< (TRAM) TrustRAM 50 */
#define REG_TRAM_RAM51 (*(__IO uint32_t*)0x420035CCU) /**< (TRAM) TrustRAM 51 */
#define REG_TRAM_RAM52 (*(__IO uint32_t*)0x420035D0U) /**< (TRAM) TrustRAM 52 */
#define REG_TRAM_RAM53 (*(__IO uint32_t*)0x420035D4U) /**< (TRAM) TrustRAM 53 */
#define REG_TRAM_RAM54 (*(__IO uint32_t*)0x420035D8U) /**< (TRAM) TrustRAM 54 */
#define REG_TRAM_RAM55 (*(__IO uint32_t*)0x420035DCU) /**< (TRAM) TrustRAM 55 */
#define REG_TRAM_RAM56 (*(__IO uint32_t*)0x420035E0U) /**< (TRAM) TrustRAM 56 */
#define REG_TRAM_RAM57 (*(__IO uint32_t*)0x420035E4U) /**< (TRAM) TrustRAM 57 */
#define REG_TRAM_RAM58 (*(__IO uint32_t*)0x420035E8U) /**< (TRAM) TrustRAM 58 */
#define REG_TRAM_RAM59 (*(__IO uint32_t*)0x420035ECU) /**< (TRAM) TrustRAM 59 */
#define REG_TRAM_RAM60 (*(__IO uint32_t*)0x420035F0U) /**< (TRAM) TrustRAM 60 */
#define REG_TRAM_RAM61 (*(__IO uint32_t*)0x420035F4U) /**< (TRAM) TrustRAM 61 */
#define REG_TRAM_RAM62 (*(__IO uint32_t*)0x420035F8U) /**< (TRAM) TrustRAM 62 */
#define REG_TRAM_RAM63 (*(__IO uint32_t*)0x420035FCU) /**< (TRAM) TrustRAM 63 */
#endif /* (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/* ========== Instance Parameter definitions for TRAM peripheral ========== */
#define TRAM_INSTANCE_ID 77
#endif /* _SAML10_TRAM_INSTANCE_ */

View File

@ -0,0 +1,58 @@
/**
* \file
*
* \brief Instance description for TRNG
*
* Copyright (c) 2018 Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* 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
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
/* file generated from device description version 2018-08-31T13:51:50Z */
#ifndef _SAML10_TRNG_INSTANCE_H_
#define _SAML10_TRNG_INSTANCE_H_
/* ========== Register definition for TRNG peripheral ========== */
#if (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
#define REG_TRNG_CTRLA (0x42002800) /**< (TRNG) Control A */
#define REG_TRNG_EVCTRL (0x42002804) /**< (TRNG) Event Control */
#define REG_TRNG_INTENCLR (0x42002808) /**< (TRNG) Interrupt Enable Clear */
#define REG_TRNG_INTENSET (0x42002809) /**< (TRNG) Interrupt Enable Set */
#define REG_TRNG_INTFLAG (0x4200280A) /**< (TRNG) Interrupt Flag Status and Clear */
#define REG_TRNG_DATA (0x42002820) /**< (TRNG) Output Data */
#else
#define REG_TRNG_CTRLA (*(__IO uint8_t*)0x42002800U) /**< (TRNG) Control A */
#define REG_TRNG_EVCTRL (*(__IO uint8_t*)0x42002804U) /**< (TRNG) Event Control */
#define REG_TRNG_INTENCLR (*(__IO uint8_t*)0x42002808U) /**< (TRNG) Interrupt Enable Clear */
#define REG_TRNG_INTENSET (*(__IO uint8_t*)0x42002809U) /**< (TRNG) Interrupt Enable Set */
#define REG_TRNG_INTFLAG (*(__IO uint8_t*)0x4200280AU) /**< (TRNG) Interrupt Flag Status and Clear */
#define REG_TRNG_DATA (*(__I uint32_t*)0x42002820U) /**< (TRNG) Output Data */
#endif /* (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/* ========== Instance Parameter definitions for TRNG peripheral ========== */
#define TRNG_INSTANCE_ID 74
#endif /* _SAML10_TRNG_INSTANCE_ */

View File

@ -0,0 +1,62 @@
/**
* \file
*
* \brief Instance description for WDT
*
* Copyright (c) 2018 Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* 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
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
/* file generated from device description version 2018-08-31T13:51:50Z */
#ifndef _SAML10_WDT_INSTANCE_H_
#define _SAML10_WDT_INSTANCE_H_
/* ========== Register definition for WDT peripheral ========== */
#if (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
#define REG_WDT_CTRLA (0x40002000) /**< (WDT) Control */
#define REG_WDT_CONFIG (0x40002001) /**< (WDT) Configuration */
#define REG_WDT_EWCTRL (0x40002002) /**< (WDT) Early Warning Interrupt Control */
#define REG_WDT_INTENCLR (0x40002004) /**< (WDT) Interrupt Enable Clear */
#define REG_WDT_INTENSET (0x40002005) /**< (WDT) Interrupt Enable Set */
#define REG_WDT_INTFLAG (0x40002006) /**< (WDT) Interrupt Flag Status and Clear */
#define REG_WDT_SYNCBUSY (0x40002008) /**< (WDT) Synchronization Busy */
#define REG_WDT_CLEAR (0x4000200C) /**< (WDT) Clear */
#else
#define REG_WDT_CTRLA (*(__IO uint8_t*)0x40002000U) /**< (WDT) Control */
#define REG_WDT_CONFIG (*(__IO uint8_t*)0x40002001U) /**< (WDT) Configuration */
#define REG_WDT_EWCTRL (*(__IO uint8_t*)0x40002002U) /**< (WDT) Early Warning Interrupt Control */
#define REG_WDT_INTENCLR (*(__IO uint8_t*)0x40002004U) /**< (WDT) Interrupt Enable Clear */
#define REG_WDT_INTENSET (*(__IO uint8_t*)0x40002005U) /**< (WDT) Interrupt Enable Set */
#define REG_WDT_INTFLAG (*(__IO uint8_t*)0x40002006U) /**< (WDT) Interrupt Flag Status and Clear */
#define REG_WDT_SYNCBUSY (*(__I uint32_t*)0x40002008U) /**< (WDT) Synchronization Busy */
#define REG_WDT_CLEAR (*(__O uint8_t*)0x4000200CU) /**< (WDT) Clear */
#endif /* (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/* ========== Instance Parameter definitions for WDT peripheral ========== */
#define WDT_INSTANCE_ID 8
#endif /* _SAML10_WDT_INSTANCE_ */

View File

@ -0,0 +1,834 @@
/**
* \file
*
* \brief Peripheral I/O description for SAML10D14A
*
* Copyright (c) 2018 Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* 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
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
/* file generated from device description version 2018-08-31T13:51:49Z */
#ifndef _SAML10D14A_PIO_H_
#define _SAML10D14A_PIO_H_
/* ========== Peripheral I/O pin numbers ========== */
#define PIN_PA00 ( 0) /**< Pin Number for PA00 */
#define PIN_PA01 ( 1) /**< Pin Number for PA01 */
#define PIN_PA02 ( 2) /**< Pin Number for PA02 */
#define PIN_PA03 ( 3) /**< Pin Number for PA03 */
#define PIN_PA04 ( 4) /**< Pin Number for PA04 */
#define PIN_PA05 ( 5) /**< Pin Number for PA05 */
#define PIN_PA08 ( 8) /**< Pin Number for PA08 */
#define PIN_PA14 ( 14) /**< Pin Number for PA14 */
#define PIN_PA15 ( 15) /**< Pin Number for PA15 */
#define PIN_PA16 ( 16) /**< Pin Number for PA16 */
#define PIN_PA17 ( 17) /**< Pin Number for PA17 */
#define PIN_PA18 ( 18) /**< Pin Number for PA18 */
#define PIN_PA19 ( 19) /**< Pin Number for PA19 */
#define PIN_PA22 ( 22) /**< Pin Number for PA22 */
#define PIN_PA23 ( 23) /**< Pin Number for PA23 */
#define PIN_PA30 ( 30) /**< Pin Number for PA30 */
#define PIN_PA31 ( 31) /**< Pin Number for PA31 */
/* ========== Peripheral I/O masks ========== */
#define PORT_PA00 (_U_(1) << 0) /**< PORT Mask for PA00 */
#define PORT_PA01 (_U_(1) << 1) /**< PORT Mask for PA01 */
#define PORT_PA02 (_U_(1) << 2) /**< PORT Mask for PA02 */
#define PORT_PA03 (_U_(1) << 3) /**< PORT Mask for PA03 */
#define PORT_PA04 (_U_(1) << 4) /**< PORT Mask for PA04 */
#define PORT_PA05 (_U_(1) << 5) /**< PORT Mask for PA05 */
#define PORT_PA08 (_U_(1) << 8) /**< PORT Mask for PA08 */
#define PORT_PA14 (_U_(1) << 14) /**< PORT Mask for PA14 */
#define PORT_PA15 (_U_(1) << 15) /**< PORT Mask for PA15 */
#define PORT_PA16 (_U_(1) << 16) /**< PORT Mask for PA16 */
#define PORT_PA17 (_U_(1) << 17) /**< PORT Mask for PA17 */
#define PORT_PA18 (_U_(1) << 18) /**< PORT Mask for PA18 */
#define PORT_PA19 (_U_(1) << 19) /**< PORT Mask for PA19 */
#define PORT_PA22 (_U_(1) << 22) /**< PORT Mask for PA22 */
#define PORT_PA23 (_U_(1) << 23) /**< PORT Mask for PA23 */
#define PORT_PA30 (_U_(1) << 30) /**< PORT Mask for PA30 */
#define PORT_PA31 (_U_(1) << 31) /**< PORT Mask for PA31 */
/* ========== Peripheral I/O indexes ========== */
#define PORT_PA00_IDX ( 0) /**< PORT Index Number for PA00 */
#define PORT_PA01_IDX ( 1) /**< PORT Index Number for PA01 */
#define PORT_PA02_IDX ( 2) /**< PORT Index Number for PA02 */
#define PORT_PA03_IDX ( 3) /**< PORT Index Number for PA03 */
#define PORT_PA04_IDX ( 4) /**< PORT Index Number for PA04 */
#define PORT_PA05_IDX ( 5) /**< PORT Index Number for PA05 */
#define PORT_PA08_IDX ( 8) /**< PORT Index Number for PA08 */
#define PORT_PA14_IDX ( 14) /**< PORT Index Number for PA14 */
#define PORT_PA15_IDX ( 15) /**< PORT Index Number for PA15 */
#define PORT_PA16_IDX ( 16) /**< PORT Index Number for PA16 */
#define PORT_PA17_IDX ( 17) /**< PORT Index Number for PA17 */
#define PORT_PA18_IDX ( 18) /**< PORT Index Number for PA18 */
#define PORT_PA19_IDX ( 19) /**< PORT Index Number for PA19 */
#define PORT_PA22_IDX ( 22) /**< PORT Index Number for PA22 */
#define PORT_PA23_IDX ( 23) /**< PORT Index Number for PA23 */
#define PORT_PA30_IDX ( 30) /**< PORT Index Number for PA30 */
#define PORT_PA31_IDX ( 31) /**< PORT Index Number for PA31 */
/* ========== PORT definition for AC peripheral ========== */
#define PIN_PA04B_AC_AIN0 _L_(4) /**< AC signal: AIN0 on PA04 mux B*/
#define MUX_PA04B_AC_AIN0 _L_(1)
#define PINMUX_PA04B_AC_AIN0 ((PIN_PA04B_AC_AIN0 << 16) | MUX_PA04B_AC_AIN0)
#define PORT_PA04B_AC_AIN0 (_UL_(1) << 4)
#define PIN_PA05B_AC_AIN1 _L_(5) /**< AC signal: AIN1 on PA05 mux B*/
#define MUX_PA05B_AC_AIN1 _L_(1)
#define PINMUX_PA05B_AC_AIN1 ((PIN_PA05B_AC_AIN1 << 16) | MUX_PA05B_AC_AIN1)
#define PORT_PA05B_AC_AIN1 (_UL_(1) << 5)
#define PIN_PA18H_AC_CMP0 _L_(18) /**< AC signal: CMP0 on PA18 mux H*/
#define MUX_PA18H_AC_CMP0 _L_(7)
#define PINMUX_PA18H_AC_CMP0 ((PIN_PA18H_AC_CMP0 << 16) | MUX_PA18H_AC_CMP0)
#define PORT_PA18H_AC_CMP0 (_UL_(1) << 18)
#define PIN_PA19H_AC_CMP1 _L_(19) /**< AC signal: CMP1 on PA19 mux H*/
#define MUX_PA19H_AC_CMP1 _L_(7)
#define PINMUX_PA19H_AC_CMP1 ((PIN_PA19H_AC_CMP1 << 16) | MUX_PA19H_AC_CMP1)
#define PORT_PA19H_AC_CMP1 (_UL_(1) << 19)
/* ========== PORT definition for ADC peripheral ========== */
#define PIN_PA02B_ADC_AIN0 _L_(2) /**< ADC signal: AIN0 on PA02 mux B*/
#define MUX_PA02B_ADC_AIN0 _L_(1)
#define PINMUX_PA02B_ADC_AIN0 ((PIN_PA02B_ADC_AIN0 << 16) | MUX_PA02B_ADC_AIN0)
#define PORT_PA02B_ADC_AIN0 (_UL_(1) << 2)
#define PIN_PA03B_ADC_AIN1 _L_(3) /**< ADC signal: AIN1 on PA03 mux B*/
#define MUX_PA03B_ADC_AIN1 _L_(1)
#define PINMUX_PA03B_ADC_AIN1 ((PIN_PA03B_ADC_AIN1 << 16) | MUX_PA03B_ADC_AIN1)
#define PORT_PA03B_ADC_AIN1 (_UL_(1) << 3)
#define PIN_PA04B_ADC_AIN2 _L_(4) /**< ADC signal: AIN2 on PA04 mux B*/
#define MUX_PA04B_ADC_AIN2 _L_(1)
#define PINMUX_PA04B_ADC_AIN2 ((PIN_PA04B_ADC_AIN2 << 16) | MUX_PA04B_ADC_AIN2)
#define PORT_PA04B_ADC_AIN2 (_UL_(1) << 4)
#define PIN_PA05B_ADC_AIN3 _L_(5) /**< ADC signal: AIN3 on PA05 mux B*/
#define MUX_PA05B_ADC_AIN3 _L_(1)
#define PINMUX_PA05B_ADC_AIN3 ((PIN_PA05B_ADC_AIN3 << 16) | MUX_PA05B_ADC_AIN3)
#define PORT_PA05B_ADC_AIN3 (_UL_(1) << 5)
#define PIN_PA08B_ADC_AIN6 _L_(8) /**< ADC signal: AIN6 on PA08 mux B*/
#define MUX_PA08B_ADC_AIN6 _L_(1)
#define PINMUX_PA08B_ADC_AIN6 ((PIN_PA08B_ADC_AIN6 << 16) | MUX_PA08B_ADC_AIN6)
#define PORT_PA08B_ADC_AIN6 (_UL_(1) << 8)
#define PIN_PA04B_ADC_VREFP _L_(4) /**< ADC signal: VREFP on PA04 mux B*/
#define MUX_PA04B_ADC_VREFP _L_(1)
#define PINMUX_PA04B_ADC_VREFP ((PIN_PA04B_ADC_VREFP << 16) | MUX_PA04B_ADC_VREFP)
#define PORT_PA04B_ADC_VREFP (_UL_(1) << 4)
/* ========== PORT definition for CCL peripheral ========== */
#define PIN_PA04I_CCL_IN0 _L_(4) /**< CCL signal: IN0 on PA04 mux I*/
#define MUX_PA04I_CCL_IN0 _L_(8)
#define PINMUX_PA04I_CCL_IN0 ((PIN_PA04I_CCL_IN0 << 16) | MUX_PA04I_CCL_IN0)
#define PORT_PA04I_CCL_IN0 (_UL_(1) << 4)
#define PIN_PA16I_CCL_IN0 _L_(16) /**< CCL signal: IN0 on PA16 mux I*/
#define MUX_PA16I_CCL_IN0 _L_(8)
#define PINMUX_PA16I_CCL_IN0 ((PIN_PA16I_CCL_IN0 << 16) | MUX_PA16I_CCL_IN0)
#define PORT_PA16I_CCL_IN0 (_UL_(1) << 16)
#define PIN_PA05I_CCL_IN1 _L_(5) /**< CCL signal: IN1 on PA05 mux I*/
#define MUX_PA05I_CCL_IN1 _L_(8)
#define PINMUX_PA05I_CCL_IN1 ((PIN_PA05I_CCL_IN1 << 16) | MUX_PA05I_CCL_IN1)
#define PORT_PA05I_CCL_IN1 (_UL_(1) << 5)
#define PIN_PA17I_CCL_IN1 _L_(17) /**< CCL signal: IN1 on PA17 mux I*/
#define MUX_PA17I_CCL_IN1 _L_(8)
#define PINMUX_PA17I_CCL_IN1 ((PIN_PA17I_CCL_IN1 << 16) | MUX_PA17I_CCL_IN1)
#define PORT_PA17I_CCL_IN1 (_UL_(1) << 17)
#define PIN_PA18I_CCL_IN2 _L_(18) /**< CCL signal: IN2 on PA18 mux I*/
#define MUX_PA18I_CCL_IN2 _L_(8)
#define PINMUX_PA18I_CCL_IN2 ((PIN_PA18I_CCL_IN2 << 16) | MUX_PA18I_CCL_IN2)
#define PORT_PA18I_CCL_IN2 (_UL_(1) << 18)
#define PIN_PA08I_CCL_IN3 _L_(8) /**< CCL signal: IN3 on PA08 mux I*/
#define MUX_PA08I_CCL_IN3 _L_(8)
#define PINMUX_PA08I_CCL_IN3 ((PIN_PA08I_CCL_IN3 << 16) | MUX_PA08I_CCL_IN3)
#define PORT_PA08I_CCL_IN3 (_UL_(1) << 8)
#define PIN_PA30I_CCL_IN3 _L_(30) /**< CCL signal: IN3 on PA30 mux I*/
#define MUX_PA30I_CCL_IN3 _L_(8)
#define PINMUX_PA30I_CCL_IN3 ((PIN_PA30I_CCL_IN3 << 16) | MUX_PA30I_CCL_IN3)
#define PORT_PA30I_CCL_IN3 (_UL_(1) << 30)
#define PIN_PA19I_CCL_OUT0 _L_(19) /**< CCL signal: OUT0 on PA19 mux I*/
#define MUX_PA19I_CCL_OUT0 _L_(8)
#define PINMUX_PA19I_CCL_OUT0 ((PIN_PA19I_CCL_OUT0 << 16) | MUX_PA19I_CCL_OUT0)
#define PORT_PA19I_CCL_OUT0 (_UL_(1) << 19)
#define PIN_PA31I_CCL_OUT1 _L_(31) /**< CCL signal: OUT1 on PA31 mux I*/
#define MUX_PA31I_CCL_OUT1 _L_(8)
#define PINMUX_PA31I_CCL_OUT1 ((PIN_PA31I_CCL_OUT1 << 16) | MUX_PA31I_CCL_OUT1)
#define PORT_PA31I_CCL_OUT1 (_UL_(1) << 31)
/* ========== PORT definition for DAC peripheral ========== */
#define PIN_PA02B_DAC_VOUT _L_(2) /**< DAC signal: VOUT on PA02 mux B*/
#define MUX_PA02B_DAC_VOUT _L_(1)
#define PINMUX_PA02B_DAC_VOUT ((PIN_PA02B_DAC_VOUT << 16) | MUX_PA02B_DAC_VOUT)
#define PORT_PA02B_DAC_VOUT (_UL_(1) << 2)
#define PIN_PA03B_DAC_VREFP _L_(3) /**< DAC signal: VREFP on PA03 mux B*/
#define MUX_PA03B_DAC_VREFP _L_(1)
#define PINMUX_PA03B_DAC_VREFP ((PIN_PA03B_DAC_VREFP << 16) | MUX_PA03B_DAC_VREFP)
#define PORT_PA03B_DAC_VREFP (_UL_(1) << 3)
/* ========== PORT definition for EIC peripheral ========== */
#define PIN_PA19A_EIC_EXTINT0 _L_(19) /**< EIC signal: EXTINT0 on PA19 mux A*/
#define MUX_PA19A_EIC_EXTINT0 _L_(0)
#define PINMUX_PA19A_EIC_EXTINT0 ((PIN_PA19A_EIC_EXTINT0 << 16) | MUX_PA19A_EIC_EXTINT0)
#define PORT_PA19A_EIC_EXTINT0 (_UL_(1) << 19)
#define PIN_PA19A_EIC_EXTINT_NUM _L_(0) /**< EIC signal: PIN_PA19 External Interrupt Line */
#define PIN_PA00A_EIC_EXTINT0 _L_(0) /**< EIC signal: EXTINT0 on PA00 mux A*/
#define MUX_PA00A_EIC_EXTINT0 _L_(0)
#define PINMUX_PA00A_EIC_EXTINT0 ((PIN_PA00A_EIC_EXTINT0 << 16) | MUX_PA00A_EIC_EXTINT0)
#define PORT_PA00A_EIC_EXTINT0 (_UL_(1) << 0)
#define PIN_PA00A_EIC_EXTINT_NUM _L_(0) /**< EIC signal: PIN_PA00 External Interrupt Line */
#define PIN_PA22A_EIC_EXTINT1 _L_(22) /**< EIC signal: EXTINT1 on PA22 mux A*/
#define MUX_PA22A_EIC_EXTINT1 _L_(0)
#define PINMUX_PA22A_EIC_EXTINT1 ((PIN_PA22A_EIC_EXTINT1 << 16) | MUX_PA22A_EIC_EXTINT1)
#define PORT_PA22A_EIC_EXTINT1 (_UL_(1) << 22)
#define PIN_PA22A_EIC_EXTINT_NUM _L_(1) /**< EIC signal: PIN_PA22 External Interrupt Line */
#define PIN_PA01A_EIC_EXTINT1 _L_(1) /**< EIC signal: EXTINT1 on PA01 mux A*/
#define MUX_PA01A_EIC_EXTINT1 _L_(0)
#define PINMUX_PA01A_EIC_EXTINT1 ((PIN_PA01A_EIC_EXTINT1 << 16) | MUX_PA01A_EIC_EXTINT1)
#define PORT_PA01A_EIC_EXTINT1 (_UL_(1) << 1)
#define PIN_PA01A_EIC_EXTINT_NUM _L_(1) /**< EIC signal: PIN_PA01 External Interrupt Line */
#define PIN_PA02A_EIC_EXTINT2 _L_(2) /**< EIC signal: EXTINT2 on PA02 mux A*/
#define MUX_PA02A_EIC_EXTINT2 _L_(0)
#define PINMUX_PA02A_EIC_EXTINT2 ((PIN_PA02A_EIC_EXTINT2 << 16) | MUX_PA02A_EIC_EXTINT2)
#define PORT_PA02A_EIC_EXTINT2 (_UL_(1) << 2)
#define PIN_PA02A_EIC_EXTINT_NUM _L_(2) /**< EIC signal: PIN_PA02 External Interrupt Line */
#define PIN_PA23A_EIC_EXTINT2 _L_(23) /**< EIC signal: EXTINT2 on PA23 mux A*/
#define MUX_PA23A_EIC_EXTINT2 _L_(0)
#define PINMUX_PA23A_EIC_EXTINT2 ((PIN_PA23A_EIC_EXTINT2 << 16) | MUX_PA23A_EIC_EXTINT2)
#define PORT_PA23A_EIC_EXTINT2 (_UL_(1) << 23)
#define PIN_PA23A_EIC_EXTINT_NUM _L_(2) /**< EIC signal: PIN_PA23 External Interrupt Line */
#define PIN_PA03A_EIC_EXTINT3 _L_(3) /**< EIC signal: EXTINT3 on PA03 mux A*/
#define MUX_PA03A_EIC_EXTINT3 _L_(0)
#define PINMUX_PA03A_EIC_EXTINT3 ((PIN_PA03A_EIC_EXTINT3 << 16) | MUX_PA03A_EIC_EXTINT3)
#define PORT_PA03A_EIC_EXTINT3 (_UL_(1) << 3)
#define PIN_PA03A_EIC_EXTINT_NUM _L_(3) /**< EIC signal: PIN_PA03 External Interrupt Line */
#define PIN_PA14A_EIC_EXTINT3 _L_(14) /**< EIC signal: EXTINT3 on PA14 mux A*/
#define MUX_PA14A_EIC_EXTINT3 _L_(0)
#define PINMUX_PA14A_EIC_EXTINT3 ((PIN_PA14A_EIC_EXTINT3 << 16) | MUX_PA14A_EIC_EXTINT3)
#define PORT_PA14A_EIC_EXTINT3 (_UL_(1) << 14)
#define PIN_PA14A_EIC_EXTINT_NUM _L_(3) /**< EIC signal: PIN_PA14 External Interrupt Line */
#define PIN_PA04A_EIC_EXTINT4 _L_(4) /**< EIC signal: EXTINT4 on PA04 mux A*/
#define MUX_PA04A_EIC_EXTINT4 _L_(0)
#define PINMUX_PA04A_EIC_EXTINT4 ((PIN_PA04A_EIC_EXTINT4 << 16) | MUX_PA04A_EIC_EXTINT4)
#define PORT_PA04A_EIC_EXTINT4 (_UL_(1) << 4)
#define PIN_PA04A_EIC_EXTINT_NUM _L_(4) /**< EIC signal: PIN_PA04 External Interrupt Line */
#define PIN_PA15A_EIC_EXTINT4 _L_(15) /**< EIC signal: EXTINT4 on PA15 mux A*/
#define MUX_PA15A_EIC_EXTINT4 _L_(0)
#define PINMUX_PA15A_EIC_EXTINT4 ((PIN_PA15A_EIC_EXTINT4 << 16) | MUX_PA15A_EIC_EXTINT4)
#define PORT_PA15A_EIC_EXTINT4 (_UL_(1) << 15)
#define PIN_PA15A_EIC_EXTINT_NUM _L_(4) /**< EIC signal: PIN_PA15 External Interrupt Line */
#define PIN_PA05A_EIC_EXTINT5 _L_(5) /**< EIC signal: EXTINT5 on PA05 mux A*/
#define MUX_PA05A_EIC_EXTINT5 _L_(0)
#define PINMUX_PA05A_EIC_EXTINT5 ((PIN_PA05A_EIC_EXTINT5 << 16) | MUX_PA05A_EIC_EXTINT5)
#define PORT_PA05A_EIC_EXTINT5 (_UL_(1) << 5)
#define PIN_PA05A_EIC_EXTINT_NUM _L_(5) /**< EIC signal: PIN_PA05 External Interrupt Line */
#define PIN_PA16A_EIC_EXTINT5 _L_(16) /**< EIC signal: EXTINT5 on PA16 mux A*/
#define MUX_PA16A_EIC_EXTINT5 _L_(0)
#define PINMUX_PA16A_EIC_EXTINT5 ((PIN_PA16A_EIC_EXTINT5 << 16) | MUX_PA16A_EIC_EXTINT5)
#define PORT_PA16A_EIC_EXTINT5 (_UL_(1) << 16)
#define PIN_PA16A_EIC_EXTINT_NUM _L_(5) /**< EIC signal: PIN_PA16 External Interrupt Line */
#define PIN_PA17A_EIC_EXTINT6 _L_(17) /**< EIC signal: EXTINT6 on PA17 mux A*/
#define MUX_PA17A_EIC_EXTINT6 _L_(0)
#define PINMUX_PA17A_EIC_EXTINT6 ((PIN_PA17A_EIC_EXTINT6 << 16) | MUX_PA17A_EIC_EXTINT6)
#define PORT_PA17A_EIC_EXTINT6 (_UL_(1) << 17)
#define PIN_PA17A_EIC_EXTINT_NUM _L_(6) /**< EIC signal: PIN_PA17 External Interrupt Line */
#define PIN_PA30A_EIC_EXTINT6 _L_(30) /**< EIC signal: EXTINT6 on PA30 mux A*/
#define MUX_PA30A_EIC_EXTINT6 _L_(0)
#define PINMUX_PA30A_EIC_EXTINT6 ((PIN_PA30A_EIC_EXTINT6 << 16) | MUX_PA30A_EIC_EXTINT6)
#define PORT_PA30A_EIC_EXTINT6 (_UL_(1) << 30)
#define PIN_PA30A_EIC_EXTINT_NUM _L_(6) /**< EIC signal: PIN_PA30 External Interrupt Line */
#define PIN_PA18A_EIC_EXTINT7 _L_(18) /**< EIC signal: EXTINT7 on PA18 mux A*/
#define MUX_PA18A_EIC_EXTINT7 _L_(0)
#define PINMUX_PA18A_EIC_EXTINT7 ((PIN_PA18A_EIC_EXTINT7 << 16) | MUX_PA18A_EIC_EXTINT7)
#define PORT_PA18A_EIC_EXTINT7 (_UL_(1) << 18)
#define PIN_PA18A_EIC_EXTINT_NUM _L_(7) /**< EIC signal: PIN_PA18 External Interrupt Line */
#define PIN_PA31A_EIC_EXTINT7 _L_(31) /**< EIC signal: EXTINT7 on PA31 mux A*/
#define MUX_PA31A_EIC_EXTINT7 _L_(0)
#define PINMUX_PA31A_EIC_EXTINT7 ((PIN_PA31A_EIC_EXTINT7 << 16) | MUX_PA31A_EIC_EXTINT7)
#define PORT_PA31A_EIC_EXTINT7 (_UL_(1) << 31)
#define PIN_PA31A_EIC_EXTINT_NUM _L_(7) /**< EIC signal: PIN_PA31 External Interrupt Line */
#define PIN_PA08A_EIC_NMI _L_(8) /**< EIC signal: NMI on PA08 mux A*/
#define MUX_PA08A_EIC_NMI _L_(0)
#define PINMUX_PA08A_EIC_NMI ((PIN_PA08A_EIC_NMI << 16) | MUX_PA08A_EIC_NMI)
#define PORT_PA08A_EIC_NMI (_UL_(1) << 8)
/* ========== PORT definition for GCLK peripheral ========== */
#define PIN_PA30H_GCLK_IO0 _L_(30) /**< GCLK signal: IO0 on PA30 mux H*/
#define MUX_PA30H_GCLK_IO0 _L_(7)
#define PINMUX_PA30H_GCLK_IO0 ((PIN_PA30H_GCLK_IO0 << 16) | MUX_PA30H_GCLK_IO0)
#define PORT_PA30H_GCLK_IO0 (_UL_(1) << 30)
#define PIN_PA14H_GCLK_IO0 _L_(14) /**< GCLK signal: IO0 on PA14 mux H*/
#define MUX_PA14H_GCLK_IO0 _L_(7)
#define PINMUX_PA14H_GCLK_IO0 ((PIN_PA14H_GCLK_IO0 << 16) | MUX_PA14H_GCLK_IO0)
#define PORT_PA14H_GCLK_IO0 (_UL_(1) << 14)
#define PIN_PA23H_GCLK_IO1 _L_(23) /**< GCLK signal: IO1 on PA23 mux H*/
#define MUX_PA23H_GCLK_IO1 _L_(7)
#define PINMUX_PA23H_GCLK_IO1 ((PIN_PA23H_GCLK_IO1 << 16) | MUX_PA23H_GCLK_IO1)
#define PORT_PA23H_GCLK_IO1 (_UL_(1) << 23)
#define PIN_PA15H_GCLK_IO1 _L_(15) /**< GCLK signal: IO1 on PA15 mux H*/
#define MUX_PA15H_GCLK_IO1 _L_(7)
#define PINMUX_PA15H_GCLK_IO1 ((PIN_PA15H_GCLK_IO1 << 16) | MUX_PA15H_GCLK_IO1)
#define PORT_PA15H_GCLK_IO1 (_UL_(1) << 15)
#define PIN_PA16H_GCLK_IO2 _L_(16) /**< GCLK signal: IO2 on PA16 mux H*/
#define MUX_PA16H_GCLK_IO2 _L_(7)
#define PINMUX_PA16H_GCLK_IO2 ((PIN_PA16H_GCLK_IO2 << 16) | MUX_PA16H_GCLK_IO2)
#define PORT_PA16H_GCLK_IO2 (_UL_(1) << 16)
#define PIN_PA22H_GCLK_IO2 _L_(22) /**< GCLK signal: IO2 on PA22 mux H*/
#define MUX_PA22H_GCLK_IO2 _L_(7)
#define PINMUX_PA22H_GCLK_IO2 ((PIN_PA22H_GCLK_IO2 << 16) | MUX_PA22H_GCLK_IO2)
#define PORT_PA22H_GCLK_IO2 (_UL_(1) << 22)
#define PIN_PA17H_GCLK_IO3 _L_(17) /**< GCLK signal: IO3 on PA17 mux H*/
#define MUX_PA17H_GCLK_IO3 _L_(7)
#define PINMUX_PA17H_GCLK_IO3 ((PIN_PA17H_GCLK_IO3 << 16) | MUX_PA17H_GCLK_IO3)
#define PORT_PA17H_GCLK_IO3 (_UL_(1) << 17)
/* ========== PORT definition for OPAMP peripheral ========== */
#define PIN_PA02B_OPAMP_OANEG0 _L_(2) /**< OPAMP signal: OANEG0 on PA02 mux B*/
#define MUX_PA02B_OPAMP_OANEG0 _L_(1)
#define PINMUX_PA02B_OPAMP_OANEG0 ((PIN_PA02B_OPAMP_OANEG0 << 16) | MUX_PA02B_OPAMP_OANEG0)
#define PORT_PA02B_OPAMP_OANEG0 (_UL_(1) << 2)
#define PIN_PA00B_OPAMP_OANEG1 _L_(0) /**< OPAMP signal: OANEG1 on PA00 mux B*/
#define MUX_PA00B_OPAMP_OANEG1 _L_(1)
#define PINMUX_PA00B_OPAMP_OANEG1 ((PIN_PA00B_OPAMP_OANEG1 << 16) | MUX_PA00B_OPAMP_OANEG1)
#define PORT_PA00B_OPAMP_OANEG1 (_UL_(1) << 0)
#define PIN_PA03B_OPAMP_OANEG2 _L_(3) /**< OPAMP signal: OANEG2 on PA03 mux B*/
#define MUX_PA03B_OPAMP_OANEG2 _L_(1)
#define PINMUX_PA03B_OPAMP_OANEG2 ((PIN_PA03B_OPAMP_OANEG2 << 16) | MUX_PA03B_OPAMP_OANEG2)
#define PORT_PA03B_OPAMP_OANEG2 (_UL_(1) << 3)
#define PIN_PA04B_OPAMP_OAOUT2 _L_(4) /**< OPAMP signal: OAOUT2 on PA04 mux B*/
#define MUX_PA04B_OPAMP_OAOUT2 _L_(1)
#define PINMUX_PA04B_OPAMP_OAOUT2 ((PIN_PA04B_OPAMP_OAOUT2 << 16) | MUX_PA04B_OPAMP_OAOUT2)
#define PORT_PA04B_OPAMP_OAOUT2 (_UL_(1) << 4)
#define PIN_PA01B_OPAMP_OAPOS1 _L_(1) /**< OPAMP signal: OAPOS1 on PA01 mux B*/
#define MUX_PA01B_OPAMP_OAPOS1 _L_(1)
#define PINMUX_PA01B_OPAMP_OAPOS1 ((PIN_PA01B_OPAMP_OAPOS1 << 16) | MUX_PA01B_OPAMP_OAPOS1)
#define PORT_PA01B_OPAMP_OAPOS1 (_UL_(1) << 1)
#define PIN_PA05B_OPAMP_OAPOS2 _L_(5) /**< OPAMP signal: OAPOS2 on PA05 mux B*/
#define MUX_PA05B_OPAMP_OAPOS2 _L_(1)
#define PINMUX_PA05B_OPAMP_OAPOS2 ((PIN_PA05B_OPAMP_OAPOS2 << 16) | MUX_PA05B_OPAMP_OAPOS2)
#define PORT_PA05B_OPAMP_OAPOS2 (_UL_(1) << 5)
/* ========== PORT definition for PTC peripheral ========== */
#define PIN_PA00F_PTC_DRV0 _L_(0) /**< PTC signal: DRV0 on PA00 mux F*/
#define MUX_PA00F_PTC_DRV0 _L_(5)
#define PINMUX_PA00F_PTC_DRV0 ((PIN_PA00F_PTC_DRV0 << 16) | MUX_PA00F_PTC_DRV0)
#define PORT_PA00F_PTC_DRV0 (_UL_(1) << 0)
#define PIN_PA01F_PTC_DRV1 _L_(1) /**< PTC signal: DRV1 on PA01 mux F*/
#define MUX_PA01F_PTC_DRV1 _L_(5)
#define PINMUX_PA01F_PTC_DRV1 ((PIN_PA01F_PTC_DRV1 << 16) | MUX_PA01F_PTC_DRV1)
#define PORT_PA01F_PTC_DRV1 (_UL_(1) << 1)
#define PIN_PA02F_PTC_DRV2 _L_(2) /**< PTC signal: DRV2 on PA02 mux F*/
#define MUX_PA02F_PTC_DRV2 _L_(5)
#define PINMUX_PA02F_PTC_DRV2 ((PIN_PA02F_PTC_DRV2 << 16) | MUX_PA02F_PTC_DRV2)
#define PORT_PA02F_PTC_DRV2 (_UL_(1) << 2)
#define PIN_PA03F_PTC_DRV3 _L_(3) /**< PTC signal: DRV3 on PA03 mux F*/
#define MUX_PA03F_PTC_DRV3 _L_(5)
#define PINMUX_PA03F_PTC_DRV3 ((PIN_PA03F_PTC_DRV3 << 16) | MUX_PA03F_PTC_DRV3)
#define PORT_PA03F_PTC_DRV3 (_UL_(1) << 3)
#define PIN_PA05F_PTC_DRV4 _L_(5) /**< PTC signal: DRV4 on PA05 mux F*/
#define MUX_PA05F_PTC_DRV4 _L_(5)
#define PINMUX_PA05F_PTC_DRV4 ((PIN_PA05F_PTC_DRV4 << 16) | MUX_PA05F_PTC_DRV4)
#define PORT_PA05F_PTC_DRV4 (_UL_(1) << 5)
#define PIN_PA08F_PTC_DRV6 _L_(8) /**< PTC signal: DRV6 on PA08 mux F*/
#define MUX_PA08F_PTC_DRV6 _L_(5)
#define PINMUX_PA08F_PTC_DRV6 ((PIN_PA08F_PTC_DRV6 << 16) | MUX_PA08F_PTC_DRV6)
#define PORT_PA08F_PTC_DRV6 (_UL_(1) << 8)
#define PIN_PA14F_PTC_DRV10 _L_(14) /**< PTC signal: DRV10 on PA14 mux F*/
#define MUX_PA14F_PTC_DRV10 _L_(5)
#define PINMUX_PA14F_PTC_DRV10 ((PIN_PA14F_PTC_DRV10 << 16) | MUX_PA14F_PTC_DRV10)
#define PORT_PA14F_PTC_DRV10 (_UL_(1) << 14)
#define PIN_PA15F_PTC_DRV11 _L_(15) /**< PTC signal: DRV11 on PA15 mux F*/
#define MUX_PA15F_PTC_DRV11 _L_(5)
#define PINMUX_PA15F_PTC_DRV11 ((PIN_PA15F_PTC_DRV11 << 16) | MUX_PA15F_PTC_DRV11)
#define PORT_PA15F_PTC_DRV11 (_UL_(1) << 15)
#define PIN_PA16F_PTC_DRV12 _L_(16) /**< PTC signal: DRV12 on PA16 mux F*/
#define MUX_PA16F_PTC_DRV12 _L_(5)
#define PINMUX_PA16F_PTC_DRV12 ((PIN_PA16F_PTC_DRV12 << 16) | MUX_PA16F_PTC_DRV12)
#define PORT_PA16F_PTC_DRV12 (_UL_(1) << 16)
#define PIN_PA17F_PTC_DRV13 _L_(17) /**< PTC signal: DRV13 on PA17 mux F*/
#define MUX_PA17F_PTC_DRV13 _L_(5)
#define PINMUX_PA17F_PTC_DRV13 ((PIN_PA17F_PTC_DRV13 << 16) | MUX_PA17F_PTC_DRV13)
#define PORT_PA17F_PTC_DRV13 (_UL_(1) << 17)
#define PIN_PA18F_PTC_DRV14 _L_(18) /**< PTC signal: DRV14 on PA18 mux F*/
#define MUX_PA18F_PTC_DRV14 _L_(5)
#define PINMUX_PA18F_PTC_DRV14 ((PIN_PA18F_PTC_DRV14 << 16) | MUX_PA18F_PTC_DRV14)
#define PORT_PA18F_PTC_DRV14 (_UL_(1) << 18)
#define PIN_PA19F_PTC_DRV15 _L_(19) /**< PTC signal: DRV15 on PA19 mux F*/
#define MUX_PA19F_PTC_DRV15 _L_(5)
#define PINMUX_PA19F_PTC_DRV15 ((PIN_PA19F_PTC_DRV15 << 16) | MUX_PA19F_PTC_DRV15)
#define PORT_PA19F_PTC_DRV15 (_UL_(1) << 19)
#define PIN_PA22F_PTC_DRV16 _L_(22) /**< PTC signal: DRV16 on PA22 mux F*/
#define MUX_PA22F_PTC_DRV16 _L_(5)
#define PINMUX_PA22F_PTC_DRV16 ((PIN_PA22F_PTC_DRV16 << 16) | MUX_PA22F_PTC_DRV16)
#define PORT_PA22F_PTC_DRV16 (_UL_(1) << 22)
#define PIN_PA23F_PTC_DRV17 _L_(23) /**< PTC signal: DRV17 on PA23 mux F*/
#define MUX_PA23F_PTC_DRV17 _L_(5)
#define PINMUX_PA23F_PTC_DRV17 ((PIN_PA23F_PTC_DRV17 << 16) | MUX_PA23F_PTC_DRV17)
#define PORT_PA23F_PTC_DRV17 (_UL_(1) << 23)
#define PIN_PA30F_PTC_DRV18 _L_(30) /**< PTC signal: DRV18 on PA30 mux F*/
#define MUX_PA30F_PTC_DRV18 _L_(5)
#define PINMUX_PA30F_PTC_DRV18 ((PIN_PA30F_PTC_DRV18 << 16) | MUX_PA30F_PTC_DRV18)
#define PORT_PA30F_PTC_DRV18 (_UL_(1) << 30)
#define PIN_PA31F_PTC_DRV19 _L_(31) /**< PTC signal: DRV19 on PA31 mux F*/
#define MUX_PA31F_PTC_DRV19 _L_(5)
#define PINMUX_PA31F_PTC_DRV19 ((PIN_PA31F_PTC_DRV19 << 16) | MUX_PA31F_PTC_DRV19)
#define PORT_PA31F_PTC_DRV19 (_UL_(1) << 31)
#define PIN_PA03B_PTC_ECI0 _L_(3) /**< PTC signal: ECI0 on PA03 mux B*/
#define MUX_PA03B_PTC_ECI0 _L_(1)
#define PINMUX_PA03B_PTC_ECI0 ((PIN_PA03B_PTC_ECI0 << 16) | MUX_PA03B_PTC_ECI0)
#define PORT_PA03B_PTC_ECI0 (_UL_(1) << 3)
#define PIN_PA04B_PTC_ECI1 _L_(4) /**< PTC signal: ECI1 on PA04 mux B*/
#define MUX_PA04B_PTC_ECI1 _L_(1)
#define PINMUX_PA04B_PTC_ECI1 ((PIN_PA04B_PTC_ECI1 << 16) | MUX_PA04B_PTC_ECI1)
#define PORT_PA04B_PTC_ECI1 (_UL_(1) << 4)
#define PIN_PA05B_PTC_ECI2 _L_(5) /**< PTC signal: ECI2 on PA05 mux B*/
#define MUX_PA05B_PTC_ECI2 _L_(1)
#define PINMUX_PA05B_PTC_ECI2 ((PIN_PA05B_PTC_ECI2 << 16) | MUX_PA05B_PTC_ECI2)
#define PORT_PA05B_PTC_ECI2 (_UL_(1) << 5)
#define PIN_PA00B_PTC_X0 _L_(0) /**< PTC signal: X0 on PA00 mux B*/
#define MUX_PA00B_PTC_X0 _L_(1)
#define PINMUX_PA00B_PTC_X0 ((PIN_PA00B_PTC_X0 << 16) | MUX_PA00B_PTC_X0)
#define PORT_PA00B_PTC_X0 (_UL_(1) << 0)
#define PIN_PA00B_PTC_Y0 _L_(0) /**< PTC signal: Y0 on PA00 mux B*/
#define MUX_PA00B_PTC_Y0 _L_(1)
#define PINMUX_PA00B_PTC_Y0 ((PIN_PA00B_PTC_Y0 << 16) | MUX_PA00B_PTC_Y0)
#define PORT_PA00B_PTC_Y0 (_UL_(1) << 0)
#define PIN_PA01B_PTC_X1 _L_(1) /**< PTC signal: X1 on PA01 mux B*/
#define MUX_PA01B_PTC_X1 _L_(1)
#define PINMUX_PA01B_PTC_X1 ((PIN_PA01B_PTC_X1 << 16) | MUX_PA01B_PTC_X1)
#define PORT_PA01B_PTC_X1 (_UL_(1) << 1)
#define PIN_PA01B_PTC_Y1 _L_(1) /**< PTC signal: Y1 on PA01 mux B*/
#define MUX_PA01B_PTC_Y1 _L_(1)
#define PINMUX_PA01B_PTC_Y1 ((PIN_PA01B_PTC_Y1 << 16) | MUX_PA01B_PTC_Y1)
#define PORT_PA01B_PTC_Y1 (_UL_(1) << 1)
#define PIN_PA02B_PTC_X2 _L_(2) /**< PTC signal: X2 on PA02 mux B*/
#define MUX_PA02B_PTC_X2 _L_(1)
#define PINMUX_PA02B_PTC_X2 ((PIN_PA02B_PTC_X2 << 16) | MUX_PA02B_PTC_X2)
#define PORT_PA02B_PTC_X2 (_UL_(1) << 2)
#define PIN_PA02B_PTC_Y2 _L_(2) /**< PTC signal: Y2 on PA02 mux B*/
#define MUX_PA02B_PTC_Y2 _L_(1)
#define PINMUX_PA02B_PTC_Y2 ((PIN_PA02B_PTC_Y2 << 16) | MUX_PA02B_PTC_Y2)
#define PORT_PA02B_PTC_Y2 (_UL_(1) << 2)
#define PIN_PA03B_PTC_X3 _L_(3) /**< PTC signal: X3 on PA03 mux B*/
#define MUX_PA03B_PTC_X3 _L_(1)
#define PINMUX_PA03B_PTC_X3 ((PIN_PA03B_PTC_X3 << 16) | MUX_PA03B_PTC_X3)
#define PORT_PA03B_PTC_X3 (_UL_(1) << 3)
#define PIN_PA03B_PTC_Y3 _L_(3) /**< PTC signal: Y3 on PA03 mux B*/
#define MUX_PA03B_PTC_Y3 _L_(1)
#define PINMUX_PA03B_PTC_Y3 ((PIN_PA03B_PTC_Y3 << 16) | MUX_PA03B_PTC_Y3)
#define PORT_PA03B_PTC_Y3 (_UL_(1) << 3)
#define PIN_PA05B_PTC_X4 _L_(5) /**< PTC signal: X4 on PA05 mux B*/
#define MUX_PA05B_PTC_X4 _L_(1)
#define PINMUX_PA05B_PTC_X4 ((PIN_PA05B_PTC_X4 << 16) | MUX_PA05B_PTC_X4)
#define PORT_PA05B_PTC_X4 (_UL_(1) << 5)
#define PIN_PA05B_PTC_Y4 _L_(5) /**< PTC signal: Y4 on PA05 mux B*/
#define MUX_PA05B_PTC_Y4 _L_(1)
#define PINMUX_PA05B_PTC_Y4 ((PIN_PA05B_PTC_Y4 << 16) | MUX_PA05B_PTC_Y4)
#define PORT_PA05B_PTC_Y4 (_UL_(1) << 5)
#define PIN_PA08B_PTC_X6 _L_(8) /**< PTC signal: X6 on PA08 mux B*/
#define MUX_PA08B_PTC_X6 _L_(1)
#define PINMUX_PA08B_PTC_X6 ((PIN_PA08B_PTC_X6 << 16) | MUX_PA08B_PTC_X6)
#define PORT_PA08B_PTC_X6 (_UL_(1) << 8)
#define PIN_PA08B_PTC_Y6 _L_(8) /**< PTC signal: Y6 on PA08 mux B*/
#define MUX_PA08B_PTC_Y6 _L_(1)
#define PINMUX_PA08B_PTC_Y6 ((PIN_PA08B_PTC_Y6 << 16) | MUX_PA08B_PTC_Y6)
#define PORT_PA08B_PTC_Y6 (_UL_(1) << 8)
#define PIN_PA14B_PTC_X10 _L_(14) /**< PTC signal: X10 on PA14 mux B*/
#define MUX_PA14B_PTC_X10 _L_(1)
#define PINMUX_PA14B_PTC_X10 ((PIN_PA14B_PTC_X10 << 16) | MUX_PA14B_PTC_X10)
#define PORT_PA14B_PTC_X10 (_UL_(1) << 14)
#define PIN_PA14B_PTC_Y10 _L_(14) /**< PTC signal: Y10 on PA14 mux B*/
#define MUX_PA14B_PTC_Y10 _L_(1)
#define PINMUX_PA14B_PTC_Y10 ((PIN_PA14B_PTC_Y10 << 16) | MUX_PA14B_PTC_Y10)
#define PORT_PA14B_PTC_Y10 (_UL_(1) << 14)
#define PIN_PA15B_PTC_X11 _L_(15) /**< PTC signal: X11 on PA15 mux B*/
#define MUX_PA15B_PTC_X11 _L_(1)
#define PINMUX_PA15B_PTC_X11 ((PIN_PA15B_PTC_X11 << 16) | MUX_PA15B_PTC_X11)
#define PORT_PA15B_PTC_X11 (_UL_(1) << 15)
#define PIN_PA15B_PTC_Y11 _L_(15) /**< PTC signal: Y11 on PA15 mux B*/
#define MUX_PA15B_PTC_Y11 _L_(1)
#define PINMUX_PA15B_PTC_Y11 ((PIN_PA15B_PTC_Y11 << 16) | MUX_PA15B_PTC_Y11)
#define PORT_PA15B_PTC_Y11 (_UL_(1) << 15)
#define PIN_PA16B_PTC_X12 _L_(16) /**< PTC signal: X12 on PA16 mux B*/
#define MUX_PA16B_PTC_X12 _L_(1)
#define PINMUX_PA16B_PTC_X12 ((PIN_PA16B_PTC_X12 << 16) | MUX_PA16B_PTC_X12)
#define PORT_PA16B_PTC_X12 (_UL_(1) << 16)
#define PIN_PA16B_PTC_Y12 _L_(16) /**< PTC signal: Y12 on PA16 mux B*/
#define MUX_PA16B_PTC_Y12 _L_(1)
#define PINMUX_PA16B_PTC_Y12 ((PIN_PA16B_PTC_Y12 << 16) | MUX_PA16B_PTC_Y12)
#define PORT_PA16B_PTC_Y12 (_UL_(1) << 16)
#define PIN_PA17B_PTC_X13 _L_(17) /**< PTC signal: X13 on PA17 mux B*/
#define MUX_PA17B_PTC_X13 _L_(1)
#define PINMUX_PA17B_PTC_X13 ((PIN_PA17B_PTC_X13 << 16) | MUX_PA17B_PTC_X13)
#define PORT_PA17B_PTC_X13 (_UL_(1) << 17)
#define PIN_PA17B_PTC_Y13 _L_(17) /**< PTC signal: Y13 on PA17 mux B*/
#define MUX_PA17B_PTC_Y13 _L_(1)
#define PINMUX_PA17B_PTC_Y13 ((PIN_PA17B_PTC_Y13 << 16) | MUX_PA17B_PTC_Y13)
#define PORT_PA17B_PTC_Y13 (_UL_(1) << 17)
#define PIN_PA18B_PTC_X14 _L_(18) /**< PTC signal: X14 on PA18 mux B*/
#define MUX_PA18B_PTC_X14 _L_(1)
#define PINMUX_PA18B_PTC_X14 ((PIN_PA18B_PTC_X14 << 16) | MUX_PA18B_PTC_X14)
#define PORT_PA18B_PTC_X14 (_UL_(1) << 18)
#define PIN_PA18B_PTC_Y14 _L_(18) /**< PTC signal: Y14 on PA18 mux B*/
#define MUX_PA18B_PTC_Y14 _L_(1)
#define PINMUX_PA18B_PTC_Y14 ((PIN_PA18B_PTC_Y14 << 16) | MUX_PA18B_PTC_Y14)
#define PORT_PA18B_PTC_Y14 (_UL_(1) << 18)
#define PIN_PA19B_PTC_X15 _L_(19) /**< PTC signal: X15 on PA19 mux B*/
#define MUX_PA19B_PTC_X15 _L_(1)
#define PINMUX_PA19B_PTC_X15 ((PIN_PA19B_PTC_X15 << 16) | MUX_PA19B_PTC_X15)
#define PORT_PA19B_PTC_X15 (_UL_(1) << 19)
#define PIN_PA19B_PTC_Y15 _L_(19) /**< PTC signal: Y15 on PA19 mux B*/
#define MUX_PA19B_PTC_Y15 _L_(1)
#define PINMUX_PA19B_PTC_Y15 ((PIN_PA19B_PTC_Y15 << 16) | MUX_PA19B_PTC_Y15)
#define PORT_PA19B_PTC_Y15 (_UL_(1) << 19)
#define PIN_PA22B_PTC_X16 _L_(22) /**< PTC signal: X16 on PA22 mux B*/
#define MUX_PA22B_PTC_X16 _L_(1)
#define PINMUX_PA22B_PTC_X16 ((PIN_PA22B_PTC_X16 << 16) | MUX_PA22B_PTC_X16)
#define PORT_PA22B_PTC_X16 (_UL_(1) << 22)
#define PIN_PA22B_PTC_Y16 _L_(22) /**< PTC signal: Y16 on PA22 mux B*/
#define MUX_PA22B_PTC_Y16 _L_(1)
#define PINMUX_PA22B_PTC_Y16 ((PIN_PA22B_PTC_Y16 << 16) | MUX_PA22B_PTC_Y16)
#define PORT_PA22B_PTC_Y16 (_UL_(1) << 22)
#define PIN_PA23B_PTC_X17 _L_(23) /**< PTC signal: X17 on PA23 mux B*/
#define MUX_PA23B_PTC_X17 _L_(1)
#define PINMUX_PA23B_PTC_X17 ((PIN_PA23B_PTC_X17 << 16) | MUX_PA23B_PTC_X17)
#define PORT_PA23B_PTC_X17 (_UL_(1) << 23)
#define PIN_PA23B_PTC_Y17 _L_(23) /**< PTC signal: Y17 on PA23 mux B*/
#define MUX_PA23B_PTC_Y17 _L_(1)
#define PINMUX_PA23B_PTC_Y17 ((PIN_PA23B_PTC_Y17 << 16) | MUX_PA23B_PTC_Y17)
#define PORT_PA23B_PTC_Y17 (_UL_(1) << 23)
#define PIN_PA30B_PTC_X18 _L_(30) /**< PTC signal: X18 on PA30 mux B*/
#define MUX_PA30B_PTC_X18 _L_(1)
#define PINMUX_PA30B_PTC_X18 ((PIN_PA30B_PTC_X18 << 16) | MUX_PA30B_PTC_X18)
#define PORT_PA30B_PTC_X18 (_UL_(1) << 30)
#define PIN_PA30B_PTC_Y18 _L_(30) /**< PTC signal: Y18 on PA30 mux B*/
#define MUX_PA30B_PTC_Y18 _L_(1)
#define PINMUX_PA30B_PTC_Y18 ((PIN_PA30B_PTC_Y18 << 16) | MUX_PA30B_PTC_Y18)
#define PORT_PA30B_PTC_Y18 (_UL_(1) << 30)
#define PIN_PA31B_PTC_X19 _L_(31) /**< PTC signal: X19 on PA31 mux B*/
#define MUX_PA31B_PTC_X19 _L_(1)
#define PINMUX_PA31B_PTC_X19 ((PIN_PA31B_PTC_X19 << 16) | MUX_PA31B_PTC_X19)
#define PORT_PA31B_PTC_X19 (_UL_(1) << 31)
#define PIN_PA31B_PTC_Y19 _L_(31) /**< PTC signal: Y19 on PA31 mux B*/
#define MUX_PA31B_PTC_Y19 _L_(1)
#define PINMUX_PA31B_PTC_Y19 ((PIN_PA31B_PTC_Y19 << 16) | MUX_PA31B_PTC_Y19)
#define PORT_PA31B_PTC_Y19 (_UL_(1) << 31)
/* ========== PORT definition for RTC peripheral ========== */
#define PIN_PA08G_RTC_IN0 _L_(8) /**< RTC signal: IN0 on PA08 mux G*/
#define MUX_PA08G_RTC_IN0 _L_(6)
#define PINMUX_PA08G_RTC_IN0 ((PIN_PA08G_RTC_IN0 << 16) | MUX_PA08G_RTC_IN0)
#define PORT_PA08G_RTC_IN0 (_UL_(1) << 8)
#define PIN_PA16G_RTC_IN2 _L_(16) /**< RTC signal: IN2 on PA16 mux G*/
#define MUX_PA16G_RTC_IN2 _L_(6)
#define PINMUX_PA16G_RTC_IN2 ((PIN_PA16G_RTC_IN2 << 16) | MUX_PA16G_RTC_IN2)
#define PORT_PA16G_RTC_IN2 (_UL_(1) << 16)
#define PIN_PA17G_RTC_IN3 _L_(17) /**< RTC signal: IN3 on PA17 mux G*/
#define MUX_PA17G_RTC_IN3 _L_(6)
#define PINMUX_PA17G_RTC_IN3 ((PIN_PA17G_RTC_IN3 << 16) | MUX_PA17G_RTC_IN3)
#define PORT_PA17G_RTC_IN3 (_UL_(1) << 17)
#define PIN_PA18G_RTC_OUT0 _L_(18) /**< RTC signal: OUT0 on PA18 mux G*/
#define MUX_PA18G_RTC_OUT0 _L_(6)
#define PINMUX_PA18G_RTC_OUT0 ((PIN_PA18G_RTC_OUT0 << 16) | MUX_PA18G_RTC_OUT0)
#define PORT_PA18G_RTC_OUT0 (_UL_(1) << 18)
#define PIN_PA19G_RTC_OUT1 _L_(19) /**< RTC signal: OUT1 on PA19 mux G*/
#define MUX_PA19G_RTC_OUT1 _L_(6)
#define PINMUX_PA19G_RTC_OUT1 ((PIN_PA19G_RTC_OUT1 << 16) | MUX_PA19G_RTC_OUT1)
#define PORT_PA19G_RTC_OUT1 (_UL_(1) << 19)
#define PIN_PA22G_RTC_OUT2 _L_(22) /**< RTC signal: OUT2 on PA22 mux G*/
#define MUX_PA22G_RTC_OUT2 _L_(6)
#define PINMUX_PA22G_RTC_OUT2 ((PIN_PA22G_RTC_OUT2 << 16) | MUX_PA22G_RTC_OUT2)
#define PORT_PA22G_RTC_OUT2 (_UL_(1) << 22)
#define PIN_PA23G_RTC_OUT3 _L_(23) /**< RTC signal: OUT3 on PA23 mux G*/
#define MUX_PA23G_RTC_OUT3 _L_(6)
#define PINMUX_PA23G_RTC_OUT3 ((PIN_PA23G_RTC_OUT3 << 16) | MUX_PA23G_RTC_OUT3)
#define PORT_PA23G_RTC_OUT3 (_UL_(1) << 23)
/* ========== PORT definition for SERCOM0 peripheral ========== */
#define PIN_PA04D_SERCOM0_PAD0 _L_(4) /**< SERCOM0 signal: PAD0 on PA04 mux D*/
#define MUX_PA04D_SERCOM0_PAD0 _L_(3)
#define PINMUX_PA04D_SERCOM0_PAD0 ((PIN_PA04D_SERCOM0_PAD0 << 16) | MUX_PA04D_SERCOM0_PAD0)
#define PORT_PA04D_SERCOM0_PAD0 (_UL_(1) << 4)
#define PIN_PA16D_SERCOM0_PAD0 _L_(16) /**< SERCOM0 signal: PAD0 on PA16 mux D*/
#define MUX_PA16D_SERCOM0_PAD0 _L_(3)
#define PINMUX_PA16D_SERCOM0_PAD0 ((PIN_PA16D_SERCOM0_PAD0 << 16) | MUX_PA16D_SERCOM0_PAD0)
#define PORT_PA16D_SERCOM0_PAD0 (_UL_(1) << 16)
#define PIN_PA22C_SERCOM0_PAD0 _L_(22) /**< SERCOM0 signal: PAD0 on PA22 mux C*/
#define MUX_PA22C_SERCOM0_PAD0 _L_(2)
#define PINMUX_PA22C_SERCOM0_PAD0 ((PIN_PA22C_SERCOM0_PAD0 << 16) | MUX_PA22C_SERCOM0_PAD0)
#define PORT_PA22C_SERCOM0_PAD0 (_UL_(1) << 22)
#define PIN_PA05D_SERCOM0_PAD1 _L_(5) /**< SERCOM0 signal: PAD1 on PA05 mux D*/
#define MUX_PA05D_SERCOM0_PAD1 _L_(3)
#define PINMUX_PA05D_SERCOM0_PAD1 ((PIN_PA05D_SERCOM0_PAD1 << 16) | MUX_PA05D_SERCOM0_PAD1)
#define PORT_PA05D_SERCOM0_PAD1 (_UL_(1) << 5)
#define PIN_PA17D_SERCOM0_PAD1 _L_(17) /**< SERCOM0 signal: PAD1 on PA17 mux D*/
#define MUX_PA17D_SERCOM0_PAD1 _L_(3)
#define PINMUX_PA17D_SERCOM0_PAD1 ((PIN_PA17D_SERCOM0_PAD1 << 16) | MUX_PA17D_SERCOM0_PAD1)
#define PORT_PA17D_SERCOM0_PAD1 (_UL_(1) << 17)
#define PIN_PA23C_SERCOM0_PAD1 _L_(23) /**< SERCOM0 signal: PAD1 on PA23 mux C*/
#define MUX_PA23C_SERCOM0_PAD1 _L_(2)
#define PINMUX_PA23C_SERCOM0_PAD1 ((PIN_PA23C_SERCOM0_PAD1 << 16) | MUX_PA23C_SERCOM0_PAD1)
#define PORT_PA23C_SERCOM0_PAD1 (_UL_(1) << 23)
#define PIN_PA14D_SERCOM0_PAD2 _L_(14) /**< SERCOM0 signal: PAD2 on PA14 mux D*/
#define MUX_PA14D_SERCOM0_PAD2 _L_(3)
#define PINMUX_PA14D_SERCOM0_PAD2 ((PIN_PA14D_SERCOM0_PAD2 << 16) | MUX_PA14D_SERCOM0_PAD2)
#define PORT_PA14D_SERCOM0_PAD2 (_UL_(1) << 14)
#define PIN_PA18D_SERCOM0_PAD2 _L_(18) /**< SERCOM0 signal: PAD2 on PA18 mux D*/
#define MUX_PA18D_SERCOM0_PAD2 _L_(3)
#define PINMUX_PA18D_SERCOM0_PAD2 ((PIN_PA18D_SERCOM0_PAD2 << 16) | MUX_PA18D_SERCOM0_PAD2)
#define PORT_PA18D_SERCOM0_PAD2 (_UL_(1) << 18)
#define PIN_PA02D_SERCOM0_PAD2 _L_(2) /**< SERCOM0 signal: PAD2 on PA02 mux D*/
#define MUX_PA02D_SERCOM0_PAD2 _L_(3)
#define PINMUX_PA02D_SERCOM0_PAD2 ((PIN_PA02D_SERCOM0_PAD2 << 16) | MUX_PA02D_SERCOM0_PAD2)
#define PORT_PA02D_SERCOM0_PAD2 (_UL_(1) << 2)
#define PIN_PA15D_SERCOM0_PAD3 _L_(15) /**< SERCOM0 signal: PAD3 on PA15 mux D*/
#define MUX_PA15D_SERCOM0_PAD3 _L_(3)
#define PINMUX_PA15D_SERCOM0_PAD3 ((PIN_PA15D_SERCOM0_PAD3 << 16) | MUX_PA15D_SERCOM0_PAD3)
#define PORT_PA15D_SERCOM0_PAD3 (_UL_(1) << 15)
#define PIN_PA19D_SERCOM0_PAD3 _L_(19) /**< SERCOM0 signal: PAD3 on PA19 mux D*/
#define MUX_PA19D_SERCOM0_PAD3 _L_(3)
#define PINMUX_PA19D_SERCOM0_PAD3 ((PIN_PA19D_SERCOM0_PAD3 << 16) | MUX_PA19D_SERCOM0_PAD3)
#define PORT_PA19D_SERCOM0_PAD3 (_UL_(1) << 19)
#define PIN_PA03D_SERCOM0_PAD3 _L_(3) /**< SERCOM0 signal: PAD3 on PA03 mux D*/
#define MUX_PA03D_SERCOM0_PAD3 _L_(3)
#define PINMUX_PA03D_SERCOM0_PAD3 ((PIN_PA03D_SERCOM0_PAD3 << 16) | MUX_PA03D_SERCOM0_PAD3)
#define PORT_PA03D_SERCOM0_PAD3 (_UL_(1) << 3)
/* ========== PORT definition for SERCOM1 peripheral ========== */
#define PIN_PA16C_SERCOM1_PAD0 _L_(16) /**< SERCOM1 signal: PAD0 on PA16 mux C*/
#define MUX_PA16C_SERCOM1_PAD0 _L_(2)
#define PINMUX_PA16C_SERCOM1_PAD0 ((PIN_PA16C_SERCOM1_PAD0 << 16) | MUX_PA16C_SERCOM1_PAD0)
#define PORT_PA16C_SERCOM1_PAD0 (_UL_(1) << 16)
#define PIN_PA08C_SERCOM1_PAD0 _L_(8) /**< SERCOM1 signal: PAD0 on PA08 mux C*/
#define MUX_PA08C_SERCOM1_PAD0 _L_(2)
#define PINMUX_PA08C_SERCOM1_PAD0 ((PIN_PA08C_SERCOM1_PAD0 << 16) | MUX_PA08C_SERCOM1_PAD0)
#define PORT_PA08C_SERCOM1_PAD0 (_UL_(1) << 8)
#define PIN_PA00D_SERCOM1_PAD0 _L_(0) /**< SERCOM1 signal: PAD0 on PA00 mux D*/
#define MUX_PA00D_SERCOM1_PAD0 _L_(3)
#define PINMUX_PA00D_SERCOM1_PAD0 ((PIN_PA00D_SERCOM1_PAD0 << 16) | MUX_PA00D_SERCOM1_PAD0)
#define PORT_PA00D_SERCOM1_PAD0 (_UL_(1) << 0)
#define PIN_PA17C_SERCOM1_PAD1 _L_(17) /**< SERCOM1 signal: PAD1 on PA17 mux C*/
#define MUX_PA17C_SERCOM1_PAD1 _L_(2)
#define PINMUX_PA17C_SERCOM1_PAD1 ((PIN_PA17C_SERCOM1_PAD1 << 16) | MUX_PA17C_SERCOM1_PAD1)
#define PORT_PA17C_SERCOM1_PAD1 (_UL_(1) << 17)
#define PIN_PA01D_SERCOM1_PAD1 _L_(1) /**< SERCOM1 signal: PAD1 on PA01 mux D*/
#define MUX_PA01D_SERCOM1_PAD1 _L_(3)
#define PINMUX_PA01D_SERCOM1_PAD1 ((PIN_PA01D_SERCOM1_PAD1 << 16) | MUX_PA01D_SERCOM1_PAD1)
#define PORT_PA01D_SERCOM1_PAD1 (_UL_(1) << 1)
#define PIN_PA18C_SERCOM1_PAD2 _L_(18) /**< SERCOM1 signal: PAD2 on PA18 mux C*/
#define MUX_PA18C_SERCOM1_PAD2 _L_(2)
#define PINMUX_PA18C_SERCOM1_PAD2 ((PIN_PA18C_SERCOM1_PAD2 << 16) | MUX_PA18C_SERCOM1_PAD2)
#define PORT_PA18C_SERCOM1_PAD2 (_UL_(1) << 18)
#define PIN_PA30D_SERCOM1_PAD2 _L_(30) /**< SERCOM1 signal: PAD2 on PA30 mux D*/
#define MUX_PA30D_SERCOM1_PAD2 _L_(3)
#define PINMUX_PA30D_SERCOM1_PAD2 ((PIN_PA30D_SERCOM1_PAD2 << 16) | MUX_PA30D_SERCOM1_PAD2)
#define PORT_PA30D_SERCOM1_PAD2 (_UL_(1) << 30)
#define PIN_PA19C_SERCOM1_PAD3 _L_(19) /**< SERCOM1 signal: PAD3 on PA19 mux C*/
#define MUX_PA19C_SERCOM1_PAD3 _L_(2)
#define PINMUX_PA19C_SERCOM1_PAD3 ((PIN_PA19C_SERCOM1_PAD3 << 16) | MUX_PA19C_SERCOM1_PAD3)
#define PORT_PA19C_SERCOM1_PAD3 (_UL_(1) << 19)
#define PIN_PA31D_SERCOM1_PAD3 _L_(31) /**< SERCOM1 signal: PAD3 on PA31 mux D*/
#define MUX_PA31D_SERCOM1_PAD3 _L_(3)
#define PINMUX_PA31D_SERCOM1_PAD3 ((PIN_PA31D_SERCOM1_PAD3 << 16) | MUX_PA31D_SERCOM1_PAD3)
#define PORT_PA31D_SERCOM1_PAD3 (_UL_(1) << 31)
/* ========== PORT definition for TC0 peripheral ========== */
#define PIN_PA04E_TC0_WO0 _L_(4) /**< TC0 signal: WO0 on PA04 mux E*/
#define MUX_PA04E_TC0_WO0 _L_(4)
#define PINMUX_PA04E_TC0_WO0 ((PIN_PA04E_TC0_WO0 << 16) | MUX_PA04E_TC0_WO0)
#define PORT_PA04E_TC0_WO0 (_UL_(1) << 4)
#define PIN_PA14E_TC0_WO0 _L_(14) /**< TC0 signal: WO0 on PA14 mux E*/
#define MUX_PA14E_TC0_WO0 _L_(4)
#define PINMUX_PA14E_TC0_WO0 ((PIN_PA14E_TC0_WO0 << 16) | MUX_PA14E_TC0_WO0)
#define PORT_PA14E_TC0_WO0 (_UL_(1) << 14)
#define PIN_PA22E_TC0_WO0 _L_(22) /**< TC0 signal: WO0 on PA22 mux E*/
#define MUX_PA22E_TC0_WO0 _L_(4)
#define PINMUX_PA22E_TC0_WO0 ((PIN_PA22E_TC0_WO0 << 16) | MUX_PA22E_TC0_WO0)
#define PORT_PA22E_TC0_WO0 (_UL_(1) << 22)
#define PIN_PA05E_TC0_WO1 _L_(5) /**< TC0 signal: WO1 on PA05 mux E*/
#define MUX_PA05E_TC0_WO1 _L_(4)
#define PINMUX_PA05E_TC0_WO1 ((PIN_PA05E_TC0_WO1 << 16) | MUX_PA05E_TC0_WO1)
#define PORT_PA05E_TC0_WO1 (_UL_(1) << 5)
#define PIN_PA15E_TC0_WO1 _L_(15) /**< TC0 signal: WO1 on PA15 mux E*/
#define MUX_PA15E_TC0_WO1 _L_(4)
#define PINMUX_PA15E_TC0_WO1 ((PIN_PA15E_TC0_WO1 << 16) | MUX_PA15E_TC0_WO1)
#define PORT_PA15E_TC0_WO1 (_UL_(1) << 15)
#define PIN_PA23E_TC0_WO1 _L_(23) /**< TC0 signal: WO1 on PA23 mux E*/
#define MUX_PA23E_TC0_WO1 _L_(4)
#define PINMUX_PA23E_TC0_WO1 ((PIN_PA23E_TC0_WO1 << 16) | MUX_PA23E_TC0_WO1)
#define PORT_PA23E_TC0_WO1 (_UL_(1) << 23)
/* ========== PORT definition for TC1 peripheral ========== */
#define PIN_PA30E_TC1_WO0 _L_(30) /**< TC1 signal: WO0 on PA30 mux E*/
#define MUX_PA30E_TC1_WO0 _L_(4)
#define PINMUX_PA30E_TC1_WO0 ((PIN_PA30E_TC1_WO0 << 16) | MUX_PA30E_TC1_WO0)
#define PORT_PA30E_TC1_WO0 (_UL_(1) << 30)
#define PIN_PA31E_TC1_WO1 _L_(31) /**< TC1 signal: WO1 on PA31 mux E*/
#define MUX_PA31E_TC1_WO1 _L_(4)
#define PINMUX_PA31E_TC1_WO1 ((PIN_PA31E_TC1_WO1 << 16) | MUX_PA31E_TC1_WO1)
#define PORT_PA31E_TC1_WO1 (_UL_(1) << 31)
/* ========== PORT definition for TC2 peripheral ========== */
#define PIN_PA00E_TC2_WO0 _L_(0) /**< TC2 signal: WO0 on PA00 mux E*/
#define MUX_PA00E_TC2_WO0 _L_(4)
#define PINMUX_PA00E_TC2_WO0 ((PIN_PA00E_TC2_WO0 << 16) | MUX_PA00E_TC2_WO0)
#define PORT_PA00E_TC2_WO0 (_UL_(1) << 0)
#define PIN_PA18E_TC2_WO0 _L_(18) /**< TC2 signal: WO0 on PA18 mux E*/
#define MUX_PA18E_TC2_WO0 _L_(4)
#define PINMUX_PA18E_TC2_WO0 ((PIN_PA18E_TC2_WO0 << 16) | MUX_PA18E_TC2_WO0)
#define PORT_PA18E_TC2_WO0 (_UL_(1) << 18)
#define PIN_PA01E_TC2_WO1 _L_(1) /**< TC2 signal: WO1 on PA01 mux E*/
#define MUX_PA01E_TC2_WO1 _L_(4)
#define PINMUX_PA01E_TC2_WO1 ((PIN_PA01E_TC2_WO1 << 16) | MUX_PA01E_TC2_WO1)
#define PORT_PA01E_TC2_WO1 (_UL_(1) << 1)
#define PIN_PA19E_TC2_WO1 _L_(19) /**< TC2 signal: WO1 on PA19 mux E*/
#define MUX_PA19E_TC2_WO1 _L_(4)
#define PINMUX_PA19E_TC2_WO1 ((PIN_PA19E_TC2_WO1 << 16) | MUX_PA19E_TC2_WO1)
#define PORT_PA19E_TC2_WO1 (_UL_(1) << 19)
#endif /* _SAML10D14A_PIO_H_ */

View File

@ -0,0 +1,834 @@
/**
* \file
*
* \brief Peripheral I/O description for SAML10D15A
*
* Copyright (c) 2018 Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* 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
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
/* file generated from device description version 2018-08-31T13:51:50Z */
#ifndef _SAML10D15A_PIO_H_
#define _SAML10D15A_PIO_H_
/* ========== Peripheral I/O pin numbers ========== */
#define PIN_PA00 ( 0) /**< Pin Number for PA00 */
#define PIN_PA01 ( 1) /**< Pin Number for PA01 */
#define PIN_PA02 ( 2) /**< Pin Number for PA02 */
#define PIN_PA03 ( 3) /**< Pin Number for PA03 */
#define PIN_PA04 ( 4) /**< Pin Number for PA04 */
#define PIN_PA05 ( 5) /**< Pin Number for PA05 */
#define PIN_PA08 ( 8) /**< Pin Number for PA08 */
#define PIN_PA14 ( 14) /**< Pin Number for PA14 */
#define PIN_PA15 ( 15) /**< Pin Number for PA15 */
#define PIN_PA16 ( 16) /**< Pin Number for PA16 */
#define PIN_PA17 ( 17) /**< Pin Number for PA17 */
#define PIN_PA18 ( 18) /**< Pin Number for PA18 */
#define PIN_PA19 ( 19) /**< Pin Number for PA19 */
#define PIN_PA22 ( 22) /**< Pin Number for PA22 */
#define PIN_PA23 ( 23) /**< Pin Number for PA23 */
#define PIN_PA30 ( 30) /**< Pin Number for PA30 */
#define PIN_PA31 ( 31) /**< Pin Number for PA31 */
/* ========== Peripheral I/O masks ========== */
#define PORT_PA00 (_U_(1) << 0) /**< PORT Mask for PA00 */
#define PORT_PA01 (_U_(1) << 1) /**< PORT Mask for PA01 */
#define PORT_PA02 (_U_(1) << 2) /**< PORT Mask for PA02 */
#define PORT_PA03 (_U_(1) << 3) /**< PORT Mask for PA03 */
#define PORT_PA04 (_U_(1) << 4) /**< PORT Mask for PA04 */
#define PORT_PA05 (_U_(1) << 5) /**< PORT Mask for PA05 */
#define PORT_PA08 (_U_(1) << 8) /**< PORT Mask for PA08 */
#define PORT_PA14 (_U_(1) << 14) /**< PORT Mask for PA14 */
#define PORT_PA15 (_U_(1) << 15) /**< PORT Mask for PA15 */
#define PORT_PA16 (_U_(1) << 16) /**< PORT Mask for PA16 */
#define PORT_PA17 (_U_(1) << 17) /**< PORT Mask for PA17 */
#define PORT_PA18 (_U_(1) << 18) /**< PORT Mask for PA18 */
#define PORT_PA19 (_U_(1) << 19) /**< PORT Mask for PA19 */
#define PORT_PA22 (_U_(1) << 22) /**< PORT Mask for PA22 */
#define PORT_PA23 (_U_(1) << 23) /**< PORT Mask for PA23 */
#define PORT_PA30 (_U_(1) << 30) /**< PORT Mask for PA30 */
#define PORT_PA31 (_U_(1) << 31) /**< PORT Mask for PA31 */
/* ========== Peripheral I/O indexes ========== */
#define PORT_PA00_IDX ( 0) /**< PORT Index Number for PA00 */
#define PORT_PA01_IDX ( 1) /**< PORT Index Number for PA01 */
#define PORT_PA02_IDX ( 2) /**< PORT Index Number for PA02 */
#define PORT_PA03_IDX ( 3) /**< PORT Index Number for PA03 */
#define PORT_PA04_IDX ( 4) /**< PORT Index Number for PA04 */
#define PORT_PA05_IDX ( 5) /**< PORT Index Number for PA05 */
#define PORT_PA08_IDX ( 8) /**< PORT Index Number for PA08 */
#define PORT_PA14_IDX ( 14) /**< PORT Index Number for PA14 */
#define PORT_PA15_IDX ( 15) /**< PORT Index Number for PA15 */
#define PORT_PA16_IDX ( 16) /**< PORT Index Number for PA16 */
#define PORT_PA17_IDX ( 17) /**< PORT Index Number for PA17 */
#define PORT_PA18_IDX ( 18) /**< PORT Index Number for PA18 */
#define PORT_PA19_IDX ( 19) /**< PORT Index Number for PA19 */
#define PORT_PA22_IDX ( 22) /**< PORT Index Number for PA22 */
#define PORT_PA23_IDX ( 23) /**< PORT Index Number for PA23 */
#define PORT_PA30_IDX ( 30) /**< PORT Index Number for PA30 */
#define PORT_PA31_IDX ( 31) /**< PORT Index Number for PA31 */
/* ========== PORT definition for AC peripheral ========== */
#define PIN_PA04B_AC_AIN0 _L_(4) /**< AC signal: AIN0 on PA04 mux B*/
#define MUX_PA04B_AC_AIN0 _L_(1)
#define PINMUX_PA04B_AC_AIN0 ((PIN_PA04B_AC_AIN0 << 16) | MUX_PA04B_AC_AIN0)
#define PORT_PA04B_AC_AIN0 (_UL_(1) << 4)
#define PIN_PA05B_AC_AIN1 _L_(5) /**< AC signal: AIN1 on PA05 mux B*/
#define MUX_PA05B_AC_AIN1 _L_(1)
#define PINMUX_PA05B_AC_AIN1 ((PIN_PA05B_AC_AIN1 << 16) | MUX_PA05B_AC_AIN1)
#define PORT_PA05B_AC_AIN1 (_UL_(1) << 5)
#define PIN_PA18H_AC_CMP0 _L_(18) /**< AC signal: CMP0 on PA18 mux H*/
#define MUX_PA18H_AC_CMP0 _L_(7)
#define PINMUX_PA18H_AC_CMP0 ((PIN_PA18H_AC_CMP0 << 16) | MUX_PA18H_AC_CMP0)
#define PORT_PA18H_AC_CMP0 (_UL_(1) << 18)
#define PIN_PA19H_AC_CMP1 _L_(19) /**< AC signal: CMP1 on PA19 mux H*/
#define MUX_PA19H_AC_CMP1 _L_(7)
#define PINMUX_PA19H_AC_CMP1 ((PIN_PA19H_AC_CMP1 << 16) | MUX_PA19H_AC_CMP1)
#define PORT_PA19H_AC_CMP1 (_UL_(1) << 19)
/* ========== PORT definition for ADC peripheral ========== */
#define PIN_PA02B_ADC_AIN0 _L_(2) /**< ADC signal: AIN0 on PA02 mux B*/
#define MUX_PA02B_ADC_AIN0 _L_(1)
#define PINMUX_PA02B_ADC_AIN0 ((PIN_PA02B_ADC_AIN0 << 16) | MUX_PA02B_ADC_AIN0)
#define PORT_PA02B_ADC_AIN0 (_UL_(1) << 2)
#define PIN_PA03B_ADC_AIN1 _L_(3) /**< ADC signal: AIN1 on PA03 mux B*/
#define MUX_PA03B_ADC_AIN1 _L_(1)
#define PINMUX_PA03B_ADC_AIN1 ((PIN_PA03B_ADC_AIN1 << 16) | MUX_PA03B_ADC_AIN1)
#define PORT_PA03B_ADC_AIN1 (_UL_(1) << 3)
#define PIN_PA04B_ADC_AIN2 _L_(4) /**< ADC signal: AIN2 on PA04 mux B*/
#define MUX_PA04B_ADC_AIN2 _L_(1)
#define PINMUX_PA04B_ADC_AIN2 ((PIN_PA04B_ADC_AIN2 << 16) | MUX_PA04B_ADC_AIN2)
#define PORT_PA04B_ADC_AIN2 (_UL_(1) << 4)
#define PIN_PA05B_ADC_AIN3 _L_(5) /**< ADC signal: AIN3 on PA05 mux B*/
#define MUX_PA05B_ADC_AIN3 _L_(1)
#define PINMUX_PA05B_ADC_AIN3 ((PIN_PA05B_ADC_AIN3 << 16) | MUX_PA05B_ADC_AIN3)
#define PORT_PA05B_ADC_AIN3 (_UL_(1) << 5)
#define PIN_PA08B_ADC_AIN6 _L_(8) /**< ADC signal: AIN6 on PA08 mux B*/
#define MUX_PA08B_ADC_AIN6 _L_(1)
#define PINMUX_PA08B_ADC_AIN6 ((PIN_PA08B_ADC_AIN6 << 16) | MUX_PA08B_ADC_AIN6)
#define PORT_PA08B_ADC_AIN6 (_UL_(1) << 8)
#define PIN_PA04B_ADC_VREFP _L_(4) /**< ADC signal: VREFP on PA04 mux B*/
#define MUX_PA04B_ADC_VREFP _L_(1)
#define PINMUX_PA04B_ADC_VREFP ((PIN_PA04B_ADC_VREFP << 16) | MUX_PA04B_ADC_VREFP)
#define PORT_PA04B_ADC_VREFP (_UL_(1) << 4)
/* ========== PORT definition for CCL peripheral ========== */
#define PIN_PA04I_CCL_IN0 _L_(4) /**< CCL signal: IN0 on PA04 mux I*/
#define MUX_PA04I_CCL_IN0 _L_(8)
#define PINMUX_PA04I_CCL_IN0 ((PIN_PA04I_CCL_IN0 << 16) | MUX_PA04I_CCL_IN0)
#define PORT_PA04I_CCL_IN0 (_UL_(1) << 4)
#define PIN_PA16I_CCL_IN0 _L_(16) /**< CCL signal: IN0 on PA16 mux I*/
#define MUX_PA16I_CCL_IN0 _L_(8)
#define PINMUX_PA16I_CCL_IN0 ((PIN_PA16I_CCL_IN0 << 16) | MUX_PA16I_CCL_IN0)
#define PORT_PA16I_CCL_IN0 (_UL_(1) << 16)
#define PIN_PA05I_CCL_IN1 _L_(5) /**< CCL signal: IN1 on PA05 mux I*/
#define MUX_PA05I_CCL_IN1 _L_(8)
#define PINMUX_PA05I_CCL_IN1 ((PIN_PA05I_CCL_IN1 << 16) | MUX_PA05I_CCL_IN1)
#define PORT_PA05I_CCL_IN1 (_UL_(1) << 5)
#define PIN_PA17I_CCL_IN1 _L_(17) /**< CCL signal: IN1 on PA17 mux I*/
#define MUX_PA17I_CCL_IN1 _L_(8)
#define PINMUX_PA17I_CCL_IN1 ((PIN_PA17I_CCL_IN1 << 16) | MUX_PA17I_CCL_IN1)
#define PORT_PA17I_CCL_IN1 (_UL_(1) << 17)
#define PIN_PA18I_CCL_IN2 _L_(18) /**< CCL signal: IN2 on PA18 mux I*/
#define MUX_PA18I_CCL_IN2 _L_(8)
#define PINMUX_PA18I_CCL_IN2 ((PIN_PA18I_CCL_IN2 << 16) | MUX_PA18I_CCL_IN2)
#define PORT_PA18I_CCL_IN2 (_UL_(1) << 18)
#define PIN_PA08I_CCL_IN3 _L_(8) /**< CCL signal: IN3 on PA08 mux I*/
#define MUX_PA08I_CCL_IN3 _L_(8)
#define PINMUX_PA08I_CCL_IN3 ((PIN_PA08I_CCL_IN3 << 16) | MUX_PA08I_CCL_IN3)
#define PORT_PA08I_CCL_IN3 (_UL_(1) << 8)
#define PIN_PA30I_CCL_IN3 _L_(30) /**< CCL signal: IN3 on PA30 mux I*/
#define MUX_PA30I_CCL_IN3 _L_(8)
#define PINMUX_PA30I_CCL_IN3 ((PIN_PA30I_CCL_IN3 << 16) | MUX_PA30I_CCL_IN3)
#define PORT_PA30I_CCL_IN3 (_UL_(1) << 30)
#define PIN_PA19I_CCL_OUT0 _L_(19) /**< CCL signal: OUT0 on PA19 mux I*/
#define MUX_PA19I_CCL_OUT0 _L_(8)
#define PINMUX_PA19I_CCL_OUT0 ((PIN_PA19I_CCL_OUT0 << 16) | MUX_PA19I_CCL_OUT0)
#define PORT_PA19I_CCL_OUT0 (_UL_(1) << 19)
#define PIN_PA31I_CCL_OUT1 _L_(31) /**< CCL signal: OUT1 on PA31 mux I*/
#define MUX_PA31I_CCL_OUT1 _L_(8)
#define PINMUX_PA31I_CCL_OUT1 ((PIN_PA31I_CCL_OUT1 << 16) | MUX_PA31I_CCL_OUT1)
#define PORT_PA31I_CCL_OUT1 (_UL_(1) << 31)
/* ========== PORT definition for DAC peripheral ========== */
#define PIN_PA02B_DAC_VOUT _L_(2) /**< DAC signal: VOUT on PA02 mux B*/
#define MUX_PA02B_DAC_VOUT _L_(1)
#define PINMUX_PA02B_DAC_VOUT ((PIN_PA02B_DAC_VOUT << 16) | MUX_PA02B_DAC_VOUT)
#define PORT_PA02B_DAC_VOUT (_UL_(1) << 2)
#define PIN_PA03B_DAC_VREFP _L_(3) /**< DAC signal: VREFP on PA03 mux B*/
#define MUX_PA03B_DAC_VREFP _L_(1)
#define PINMUX_PA03B_DAC_VREFP ((PIN_PA03B_DAC_VREFP << 16) | MUX_PA03B_DAC_VREFP)
#define PORT_PA03B_DAC_VREFP (_UL_(1) << 3)
/* ========== PORT definition for EIC peripheral ========== */
#define PIN_PA19A_EIC_EXTINT0 _L_(19) /**< EIC signal: EXTINT0 on PA19 mux A*/
#define MUX_PA19A_EIC_EXTINT0 _L_(0)
#define PINMUX_PA19A_EIC_EXTINT0 ((PIN_PA19A_EIC_EXTINT0 << 16) | MUX_PA19A_EIC_EXTINT0)
#define PORT_PA19A_EIC_EXTINT0 (_UL_(1) << 19)
#define PIN_PA19A_EIC_EXTINT_NUM _L_(0) /**< EIC signal: PIN_PA19 External Interrupt Line */
#define PIN_PA00A_EIC_EXTINT0 _L_(0) /**< EIC signal: EXTINT0 on PA00 mux A*/
#define MUX_PA00A_EIC_EXTINT0 _L_(0)
#define PINMUX_PA00A_EIC_EXTINT0 ((PIN_PA00A_EIC_EXTINT0 << 16) | MUX_PA00A_EIC_EXTINT0)
#define PORT_PA00A_EIC_EXTINT0 (_UL_(1) << 0)
#define PIN_PA00A_EIC_EXTINT_NUM _L_(0) /**< EIC signal: PIN_PA00 External Interrupt Line */
#define PIN_PA22A_EIC_EXTINT1 _L_(22) /**< EIC signal: EXTINT1 on PA22 mux A*/
#define MUX_PA22A_EIC_EXTINT1 _L_(0)
#define PINMUX_PA22A_EIC_EXTINT1 ((PIN_PA22A_EIC_EXTINT1 << 16) | MUX_PA22A_EIC_EXTINT1)
#define PORT_PA22A_EIC_EXTINT1 (_UL_(1) << 22)
#define PIN_PA22A_EIC_EXTINT_NUM _L_(1) /**< EIC signal: PIN_PA22 External Interrupt Line */
#define PIN_PA01A_EIC_EXTINT1 _L_(1) /**< EIC signal: EXTINT1 on PA01 mux A*/
#define MUX_PA01A_EIC_EXTINT1 _L_(0)
#define PINMUX_PA01A_EIC_EXTINT1 ((PIN_PA01A_EIC_EXTINT1 << 16) | MUX_PA01A_EIC_EXTINT1)
#define PORT_PA01A_EIC_EXTINT1 (_UL_(1) << 1)
#define PIN_PA01A_EIC_EXTINT_NUM _L_(1) /**< EIC signal: PIN_PA01 External Interrupt Line */
#define PIN_PA02A_EIC_EXTINT2 _L_(2) /**< EIC signal: EXTINT2 on PA02 mux A*/
#define MUX_PA02A_EIC_EXTINT2 _L_(0)
#define PINMUX_PA02A_EIC_EXTINT2 ((PIN_PA02A_EIC_EXTINT2 << 16) | MUX_PA02A_EIC_EXTINT2)
#define PORT_PA02A_EIC_EXTINT2 (_UL_(1) << 2)
#define PIN_PA02A_EIC_EXTINT_NUM _L_(2) /**< EIC signal: PIN_PA02 External Interrupt Line */
#define PIN_PA23A_EIC_EXTINT2 _L_(23) /**< EIC signal: EXTINT2 on PA23 mux A*/
#define MUX_PA23A_EIC_EXTINT2 _L_(0)
#define PINMUX_PA23A_EIC_EXTINT2 ((PIN_PA23A_EIC_EXTINT2 << 16) | MUX_PA23A_EIC_EXTINT2)
#define PORT_PA23A_EIC_EXTINT2 (_UL_(1) << 23)
#define PIN_PA23A_EIC_EXTINT_NUM _L_(2) /**< EIC signal: PIN_PA23 External Interrupt Line */
#define PIN_PA03A_EIC_EXTINT3 _L_(3) /**< EIC signal: EXTINT3 on PA03 mux A*/
#define MUX_PA03A_EIC_EXTINT3 _L_(0)
#define PINMUX_PA03A_EIC_EXTINT3 ((PIN_PA03A_EIC_EXTINT3 << 16) | MUX_PA03A_EIC_EXTINT3)
#define PORT_PA03A_EIC_EXTINT3 (_UL_(1) << 3)
#define PIN_PA03A_EIC_EXTINT_NUM _L_(3) /**< EIC signal: PIN_PA03 External Interrupt Line */
#define PIN_PA14A_EIC_EXTINT3 _L_(14) /**< EIC signal: EXTINT3 on PA14 mux A*/
#define MUX_PA14A_EIC_EXTINT3 _L_(0)
#define PINMUX_PA14A_EIC_EXTINT3 ((PIN_PA14A_EIC_EXTINT3 << 16) | MUX_PA14A_EIC_EXTINT3)
#define PORT_PA14A_EIC_EXTINT3 (_UL_(1) << 14)
#define PIN_PA14A_EIC_EXTINT_NUM _L_(3) /**< EIC signal: PIN_PA14 External Interrupt Line */
#define PIN_PA04A_EIC_EXTINT4 _L_(4) /**< EIC signal: EXTINT4 on PA04 mux A*/
#define MUX_PA04A_EIC_EXTINT4 _L_(0)
#define PINMUX_PA04A_EIC_EXTINT4 ((PIN_PA04A_EIC_EXTINT4 << 16) | MUX_PA04A_EIC_EXTINT4)
#define PORT_PA04A_EIC_EXTINT4 (_UL_(1) << 4)
#define PIN_PA04A_EIC_EXTINT_NUM _L_(4) /**< EIC signal: PIN_PA04 External Interrupt Line */
#define PIN_PA15A_EIC_EXTINT4 _L_(15) /**< EIC signal: EXTINT4 on PA15 mux A*/
#define MUX_PA15A_EIC_EXTINT4 _L_(0)
#define PINMUX_PA15A_EIC_EXTINT4 ((PIN_PA15A_EIC_EXTINT4 << 16) | MUX_PA15A_EIC_EXTINT4)
#define PORT_PA15A_EIC_EXTINT4 (_UL_(1) << 15)
#define PIN_PA15A_EIC_EXTINT_NUM _L_(4) /**< EIC signal: PIN_PA15 External Interrupt Line */
#define PIN_PA05A_EIC_EXTINT5 _L_(5) /**< EIC signal: EXTINT5 on PA05 mux A*/
#define MUX_PA05A_EIC_EXTINT5 _L_(0)
#define PINMUX_PA05A_EIC_EXTINT5 ((PIN_PA05A_EIC_EXTINT5 << 16) | MUX_PA05A_EIC_EXTINT5)
#define PORT_PA05A_EIC_EXTINT5 (_UL_(1) << 5)
#define PIN_PA05A_EIC_EXTINT_NUM _L_(5) /**< EIC signal: PIN_PA05 External Interrupt Line */
#define PIN_PA16A_EIC_EXTINT5 _L_(16) /**< EIC signal: EXTINT5 on PA16 mux A*/
#define MUX_PA16A_EIC_EXTINT5 _L_(0)
#define PINMUX_PA16A_EIC_EXTINT5 ((PIN_PA16A_EIC_EXTINT5 << 16) | MUX_PA16A_EIC_EXTINT5)
#define PORT_PA16A_EIC_EXTINT5 (_UL_(1) << 16)
#define PIN_PA16A_EIC_EXTINT_NUM _L_(5) /**< EIC signal: PIN_PA16 External Interrupt Line */
#define PIN_PA17A_EIC_EXTINT6 _L_(17) /**< EIC signal: EXTINT6 on PA17 mux A*/
#define MUX_PA17A_EIC_EXTINT6 _L_(0)
#define PINMUX_PA17A_EIC_EXTINT6 ((PIN_PA17A_EIC_EXTINT6 << 16) | MUX_PA17A_EIC_EXTINT6)
#define PORT_PA17A_EIC_EXTINT6 (_UL_(1) << 17)
#define PIN_PA17A_EIC_EXTINT_NUM _L_(6) /**< EIC signal: PIN_PA17 External Interrupt Line */
#define PIN_PA30A_EIC_EXTINT6 _L_(30) /**< EIC signal: EXTINT6 on PA30 mux A*/
#define MUX_PA30A_EIC_EXTINT6 _L_(0)
#define PINMUX_PA30A_EIC_EXTINT6 ((PIN_PA30A_EIC_EXTINT6 << 16) | MUX_PA30A_EIC_EXTINT6)
#define PORT_PA30A_EIC_EXTINT6 (_UL_(1) << 30)
#define PIN_PA30A_EIC_EXTINT_NUM _L_(6) /**< EIC signal: PIN_PA30 External Interrupt Line */
#define PIN_PA18A_EIC_EXTINT7 _L_(18) /**< EIC signal: EXTINT7 on PA18 mux A*/
#define MUX_PA18A_EIC_EXTINT7 _L_(0)
#define PINMUX_PA18A_EIC_EXTINT7 ((PIN_PA18A_EIC_EXTINT7 << 16) | MUX_PA18A_EIC_EXTINT7)
#define PORT_PA18A_EIC_EXTINT7 (_UL_(1) << 18)
#define PIN_PA18A_EIC_EXTINT_NUM _L_(7) /**< EIC signal: PIN_PA18 External Interrupt Line */
#define PIN_PA31A_EIC_EXTINT7 _L_(31) /**< EIC signal: EXTINT7 on PA31 mux A*/
#define MUX_PA31A_EIC_EXTINT7 _L_(0)
#define PINMUX_PA31A_EIC_EXTINT7 ((PIN_PA31A_EIC_EXTINT7 << 16) | MUX_PA31A_EIC_EXTINT7)
#define PORT_PA31A_EIC_EXTINT7 (_UL_(1) << 31)
#define PIN_PA31A_EIC_EXTINT_NUM _L_(7) /**< EIC signal: PIN_PA31 External Interrupt Line */
#define PIN_PA08A_EIC_NMI _L_(8) /**< EIC signal: NMI on PA08 mux A*/
#define MUX_PA08A_EIC_NMI _L_(0)
#define PINMUX_PA08A_EIC_NMI ((PIN_PA08A_EIC_NMI << 16) | MUX_PA08A_EIC_NMI)
#define PORT_PA08A_EIC_NMI (_UL_(1) << 8)
/* ========== PORT definition for GCLK peripheral ========== */
#define PIN_PA30H_GCLK_IO0 _L_(30) /**< GCLK signal: IO0 on PA30 mux H*/
#define MUX_PA30H_GCLK_IO0 _L_(7)
#define PINMUX_PA30H_GCLK_IO0 ((PIN_PA30H_GCLK_IO0 << 16) | MUX_PA30H_GCLK_IO0)
#define PORT_PA30H_GCLK_IO0 (_UL_(1) << 30)
#define PIN_PA14H_GCLK_IO0 _L_(14) /**< GCLK signal: IO0 on PA14 mux H*/
#define MUX_PA14H_GCLK_IO0 _L_(7)
#define PINMUX_PA14H_GCLK_IO0 ((PIN_PA14H_GCLK_IO0 << 16) | MUX_PA14H_GCLK_IO0)
#define PORT_PA14H_GCLK_IO0 (_UL_(1) << 14)
#define PIN_PA23H_GCLK_IO1 _L_(23) /**< GCLK signal: IO1 on PA23 mux H*/
#define MUX_PA23H_GCLK_IO1 _L_(7)
#define PINMUX_PA23H_GCLK_IO1 ((PIN_PA23H_GCLK_IO1 << 16) | MUX_PA23H_GCLK_IO1)
#define PORT_PA23H_GCLK_IO1 (_UL_(1) << 23)
#define PIN_PA15H_GCLK_IO1 _L_(15) /**< GCLK signal: IO1 on PA15 mux H*/
#define MUX_PA15H_GCLK_IO1 _L_(7)
#define PINMUX_PA15H_GCLK_IO1 ((PIN_PA15H_GCLK_IO1 << 16) | MUX_PA15H_GCLK_IO1)
#define PORT_PA15H_GCLK_IO1 (_UL_(1) << 15)
#define PIN_PA16H_GCLK_IO2 _L_(16) /**< GCLK signal: IO2 on PA16 mux H*/
#define MUX_PA16H_GCLK_IO2 _L_(7)
#define PINMUX_PA16H_GCLK_IO2 ((PIN_PA16H_GCLK_IO2 << 16) | MUX_PA16H_GCLK_IO2)
#define PORT_PA16H_GCLK_IO2 (_UL_(1) << 16)
#define PIN_PA22H_GCLK_IO2 _L_(22) /**< GCLK signal: IO2 on PA22 mux H*/
#define MUX_PA22H_GCLK_IO2 _L_(7)
#define PINMUX_PA22H_GCLK_IO2 ((PIN_PA22H_GCLK_IO2 << 16) | MUX_PA22H_GCLK_IO2)
#define PORT_PA22H_GCLK_IO2 (_UL_(1) << 22)
#define PIN_PA17H_GCLK_IO3 _L_(17) /**< GCLK signal: IO3 on PA17 mux H*/
#define MUX_PA17H_GCLK_IO3 _L_(7)
#define PINMUX_PA17H_GCLK_IO3 ((PIN_PA17H_GCLK_IO3 << 16) | MUX_PA17H_GCLK_IO3)
#define PORT_PA17H_GCLK_IO3 (_UL_(1) << 17)
/* ========== PORT definition for OPAMP peripheral ========== */
#define PIN_PA02B_OPAMP_OANEG0 _L_(2) /**< OPAMP signal: OANEG0 on PA02 mux B*/
#define MUX_PA02B_OPAMP_OANEG0 _L_(1)
#define PINMUX_PA02B_OPAMP_OANEG0 ((PIN_PA02B_OPAMP_OANEG0 << 16) | MUX_PA02B_OPAMP_OANEG0)
#define PORT_PA02B_OPAMP_OANEG0 (_UL_(1) << 2)
#define PIN_PA00B_OPAMP_OANEG1 _L_(0) /**< OPAMP signal: OANEG1 on PA00 mux B*/
#define MUX_PA00B_OPAMP_OANEG1 _L_(1)
#define PINMUX_PA00B_OPAMP_OANEG1 ((PIN_PA00B_OPAMP_OANEG1 << 16) | MUX_PA00B_OPAMP_OANEG1)
#define PORT_PA00B_OPAMP_OANEG1 (_UL_(1) << 0)
#define PIN_PA03B_OPAMP_OANEG2 _L_(3) /**< OPAMP signal: OANEG2 on PA03 mux B*/
#define MUX_PA03B_OPAMP_OANEG2 _L_(1)
#define PINMUX_PA03B_OPAMP_OANEG2 ((PIN_PA03B_OPAMP_OANEG2 << 16) | MUX_PA03B_OPAMP_OANEG2)
#define PORT_PA03B_OPAMP_OANEG2 (_UL_(1) << 3)
#define PIN_PA04B_OPAMP_OAOUT2 _L_(4) /**< OPAMP signal: OAOUT2 on PA04 mux B*/
#define MUX_PA04B_OPAMP_OAOUT2 _L_(1)
#define PINMUX_PA04B_OPAMP_OAOUT2 ((PIN_PA04B_OPAMP_OAOUT2 << 16) | MUX_PA04B_OPAMP_OAOUT2)
#define PORT_PA04B_OPAMP_OAOUT2 (_UL_(1) << 4)
#define PIN_PA01B_OPAMP_OAPOS1 _L_(1) /**< OPAMP signal: OAPOS1 on PA01 mux B*/
#define MUX_PA01B_OPAMP_OAPOS1 _L_(1)
#define PINMUX_PA01B_OPAMP_OAPOS1 ((PIN_PA01B_OPAMP_OAPOS1 << 16) | MUX_PA01B_OPAMP_OAPOS1)
#define PORT_PA01B_OPAMP_OAPOS1 (_UL_(1) << 1)
#define PIN_PA05B_OPAMP_OAPOS2 _L_(5) /**< OPAMP signal: OAPOS2 on PA05 mux B*/
#define MUX_PA05B_OPAMP_OAPOS2 _L_(1)
#define PINMUX_PA05B_OPAMP_OAPOS2 ((PIN_PA05B_OPAMP_OAPOS2 << 16) | MUX_PA05B_OPAMP_OAPOS2)
#define PORT_PA05B_OPAMP_OAPOS2 (_UL_(1) << 5)
/* ========== PORT definition for PTC peripheral ========== */
#define PIN_PA00F_PTC_DRV0 _L_(0) /**< PTC signal: DRV0 on PA00 mux F*/
#define MUX_PA00F_PTC_DRV0 _L_(5)
#define PINMUX_PA00F_PTC_DRV0 ((PIN_PA00F_PTC_DRV0 << 16) | MUX_PA00F_PTC_DRV0)
#define PORT_PA00F_PTC_DRV0 (_UL_(1) << 0)
#define PIN_PA01F_PTC_DRV1 _L_(1) /**< PTC signal: DRV1 on PA01 mux F*/
#define MUX_PA01F_PTC_DRV1 _L_(5)
#define PINMUX_PA01F_PTC_DRV1 ((PIN_PA01F_PTC_DRV1 << 16) | MUX_PA01F_PTC_DRV1)
#define PORT_PA01F_PTC_DRV1 (_UL_(1) << 1)
#define PIN_PA02F_PTC_DRV2 _L_(2) /**< PTC signal: DRV2 on PA02 mux F*/
#define MUX_PA02F_PTC_DRV2 _L_(5)
#define PINMUX_PA02F_PTC_DRV2 ((PIN_PA02F_PTC_DRV2 << 16) | MUX_PA02F_PTC_DRV2)
#define PORT_PA02F_PTC_DRV2 (_UL_(1) << 2)
#define PIN_PA03F_PTC_DRV3 _L_(3) /**< PTC signal: DRV3 on PA03 mux F*/
#define MUX_PA03F_PTC_DRV3 _L_(5)
#define PINMUX_PA03F_PTC_DRV3 ((PIN_PA03F_PTC_DRV3 << 16) | MUX_PA03F_PTC_DRV3)
#define PORT_PA03F_PTC_DRV3 (_UL_(1) << 3)
#define PIN_PA05F_PTC_DRV4 _L_(5) /**< PTC signal: DRV4 on PA05 mux F*/
#define MUX_PA05F_PTC_DRV4 _L_(5)
#define PINMUX_PA05F_PTC_DRV4 ((PIN_PA05F_PTC_DRV4 << 16) | MUX_PA05F_PTC_DRV4)
#define PORT_PA05F_PTC_DRV4 (_UL_(1) << 5)
#define PIN_PA08F_PTC_DRV6 _L_(8) /**< PTC signal: DRV6 on PA08 mux F*/
#define MUX_PA08F_PTC_DRV6 _L_(5)
#define PINMUX_PA08F_PTC_DRV6 ((PIN_PA08F_PTC_DRV6 << 16) | MUX_PA08F_PTC_DRV6)
#define PORT_PA08F_PTC_DRV6 (_UL_(1) << 8)
#define PIN_PA14F_PTC_DRV10 _L_(14) /**< PTC signal: DRV10 on PA14 mux F*/
#define MUX_PA14F_PTC_DRV10 _L_(5)
#define PINMUX_PA14F_PTC_DRV10 ((PIN_PA14F_PTC_DRV10 << 16) | MUX_PA14F_PTC_DRV10)
#define PORT_PA14F_PTC_DRV10 (_UL_(1) << 14)
#define PIN_PA15F_PTC_DRV11 _L_(15) /**< PTC signal: DRV11 on PA15 mux F*/
#define MUX_PA15F_PTC_DRV11 _L_(5)
#define PINMUX_PA15F_PTC_DRV11 ((PIN_PA15F_PTC_DRV11 << 16) | MUX_PA15F_PTC_DRV11)
#define PORT_PA15F_PTC_DRV11 (_UL_(1) << 15)
#define PIN_PA16F_PTC_DRV12 _L_(16) /**< PTC signal: DRV12 on PA16 mux F*/
#define MUX_PA16F_PTC_DRV12 _L_(5)
#define PINMUX_PA16F_PTC_DRV12 ((PIN_PA16F_PTC_DRV12 << 16) | MUX_PA16F_PTC_DRV12)
#define PORT_PA16F_PTC_DRV12 (_UL_(1) << 16)
#define PIN_PA17F_PTC_DRV13 _L_(17) /**< PTC signal: DRV13 on PA17 mux F*/
#define MUX_PA17F_PTC_DRV13 _L_(5)
#define PINMUX_PA17F_PTC_DRV13 ((PIN_PA17F_PTC_DRV13 << 16) | MUX_PA17F_PTC_DRV13)
#define PORT_PA17F_PTC_DRV13 (_UL_(1) << 17)
#define PIN_PA18F_PTC_DRV14 _L_(18) /**< PTC signal: DRV14 on PA18 mux F*/
#define MUX_PA18F_PTC_DRV14 _L_(5)
#define PINMUX_PA18F_PTC_DRV14 ((PIN_PA18F_PTC_DRV14 << 16) | MUX_PA18F_PTC_DRV14)
#define PORT_PA18F_PTC_DRV14 (_UL_(1) << 18)
#define PIN_PA19F_PTC_DRV15 _L_(19) /**< PTC signal: DRV15 on PA19 mux F*/
#define MUX_PA19F_PTC_DRV15 _L_(5)
#define PINMUX_PA19F_PTC_DRV15 ((PIN_PA19F_PTC_DRV15 << 16) | MUX_PA19F_PTC_DRV15)
#define PORT_PA19F_PTC_DRV15 (_UL_(1) << 19)
#define PIN_PA22F_PTC_DRV16 _L_(22) /**< PTC signal: DRV16 on PA22 mux F*/
#define MUX_PA22F_PTC_DRV16 _L_(5)
#define PINMUX_PA22F_PTC_DRV16 ((PIN_PA22F_PTC_DRV16 << 16) | MUX_PA22F_PTC_DRV16)
#define PORT_PA22F_PTC_DRV16 (_UL_(1) << 22)
#define PIN_PA23F_PTC_DRV17 _L_(23) /**< PTC signal: DRV17 on PA23 mux F*/
#define MUX_PA23F_PTC_DRV17 _L_(5)
#define PINMUX_PA23F_PTC_DRV17 ((PIN_PA23F_PTC_DRV17 << 16) | MUX_PA23F_PTC_DRV17)
#define PORT_PA23F_PTC_DRV17 (_UL_(1) << 23)
#define PIN_PA30F_PTC_DRV18 _L_(30) /**< PTC signal: DRV18 on PA30 mux F*/
#define MUX_PA30F_PTC_DRV18 _L_(5)
#define PINMUX_PA30F_PTC_DRV18 ((PIN_PA30F_PTC_DRV18 << 16) | MUX_PA30F_PTC_DRV18)
#define PORT_PA30F_PTC_DRV18 (_UL_(1) << 30)
#define PIN_PA31F_PTC_DRV19 _L_(31) /**< PTC signal: DRV19 on PA31 mux F*/
#define MUX_PA31F_PTC_DRV19 _L_(5)
#define PINMUX_PA31F_PTC_DRV19 ((PIN_PA31F_PTC_DRV19 << 16) | MUX_PA31F_PTC_DRV19)
#define PORT_PA31F_PTC_DRV19 (_UL_(1) << 31)
#define PIN_PA03B_PTC_ECI0 _L_(3) /**< PTC signal: ECI0 on PA03 mux B*/
#define MUX_PA03B_PTC_ECI0 _L_(1)
#define PINMUX_PA03B_PTC_ECI0 ((PIN_PA03B_PTC_ECI0 << 16) | MUX_PA03B_PTC_ECI0)
#define PORT_PA03B_PTC_ECI0 (_UL_(1) << 3)
#define PIN_PA04B_PTC_ECI1 _L_(4) /**< PTC signal: ECI1 on PA04 mux B*/
#define MUX_PA04B_PTC_ECI1 _L_(1)
#define PINMUX_PA04B_PTC_ECI1 ((PIN_PA04B_PTC_ECI1 << 16) | MUX_PA04B_PTC_ECI1)
#define PORT_PA04B_PTC_ECI1 (_UL_(1) << 4)
#define PIN_PA05B_PTC_ECI2 _L_(5) /**< PTC signal: ECI2 on PA05 mux B*/
#define MUX_PA05B_PTC_ECI2 _L_(1)
#define PINMUX_PA05B_PTC_ECI2 ((PIN_PA05B_PTC_ECI2 << 16) | MUX_PA05B_PTC_ECI2)
#define PORT_PA05B_PTC_ECI2 (_UL_(1) << 5)
#define PIN_PA00B_PTC_X0 _L_(0) /**< PTC signal: X0 on PA00 mux B*/
#define MUX_PA00B_PTC_X0 _L_(1)
#define PINMUX_PA00B_PTC_X0 ((PIN_PA00B_PTC_X0 << 16) | MUX_PA00B_PTC_X0)
#define PORT_PA00B_PTC_X0 (_UL_(1) << 0)
#define PIN_PA00B_PTC_Y0 _L_(0) /**< PTC signal: Y0 on PA00 mux B*/
#define MUX_PA00B_PTC_Y0 _L_(1)
#define PINMUX_PA00B_PTC_Y0 ((PIN_PA00B_PTC_Y0 << 16) | MUX_PA00B_PTC_Y0)
#define PORT_PA00B_PTC_Y0 (_UL_(1) << 0)
#define PIN_PA01B_PTC_X1 _L_(1) /**< PTC signal: X1 on PA01 mux B*/
#define MUX_PA01B_PTC_X1 _L_(1)
#define PINMUX_PA01B_PTC_X1 ((PIN_PA01B_PTC_X1 << 16) | MUX_PA01B_PTC_X1)
#define PORT_PA01B_PTC_X1 (_UL_(1) << 1)
#define PIN_PA01B_PTC_Y1 _L_(1) /**< PTC signal: Y1 on PA01 mux B*/
#define MUX_PA01B_PTC_Y1 _L_(1)
#define PINMUX_PA01B_PTC_Y1 ((PIN_PA01B_PTC_Y1 << 16) | MUX_PA01B_PTC_Y1)
#define PORT_PA01B_PTC_Y1 (_UL_(1) << 1)
#define PIN_PA02B_PTC_X2 _L_(2) /**< PTC signal: X2 on PA02 mux B*/
#define MUX_PA02B_PTC_X2 _L_(1)
#define PINMUX_PA02B_PTC_X2 ((PIN_PA02B_PTC_X2 << 16) | MUX_PA02B_PTC_X2)
#define PORT_PA02B_PTC_X2 (_UL_(1) << 2)
#define PIN_PA02B_PTC_Y2 _L_(2) /**< PTC signal: Y2 on PA02 mux B*/
#define MUX_PA02B_PTC_Y2 _L_(1)
#define PINMUX_PA02B_PTC_Y2 ((PIN_PA02B_PTC_Y2 << 16) | MUX_PA02B_PTC_Y2)
#define PORT_PA02B_PTC_Y2 (_UL_(1) << 2)
#define PIN_PA03B_PTC_X3 _L_(3) /**< PTC signal: X3 on PA03 mux B*/
#define MUX_PA03B_PTC_X3 _L_(1)
#define PINMUX_PA03B_PTC_X3 ((PIN_PA03B_PTC_X3 << 16) | MUX_PA03B_PTC_X3)
#define PORT_PA03B_PTC_X3 (_UL_(1) << 3)
#define PIN_PA03B_PTC_Y3 _L_(3) /**< PTC signal: Y3 on PA03 mux B*/
#define MUX_PA03B_PTC_Y3 _L_(1)
#define PINMUX_PA03B_PTC_Y3 ((PIN_PA03B_PTC_Y3 << 16) | MUX_PA03B_PTC_Y3)
#define PORT_PA03B_PTC_Y3 (_UL_(1) << 3)
#define PIN_PA05B_PTC_X4 _L_(5) /**< PTC signal: X4 on PA05 mux B*/
#define MUX_PA05B_PTC_X4 _L_(1)
#define PINMUX_PA05B_PTC_X4 ((PIN_PA05B_PTC_X4 << 16) | MUX_PA05B_PTC_X4)
#define PORT_PA05B_PTC_X4 (_UL_(1) << 5)
#define PIN_PA05B_PTC_Y4 _L_(5) /**< PTC signal: Y4 on PA05 mux B*/
#define MUX_PA05B_PTC_Y4 _L_(1)
#define PINMUX_PA05B_PTC_Y4 ((PIN_PA05B_PTC_Y4 << 16) | MUX_PA05B_PTC_Y4)
#define PORT_PA05B_PTC_Y4 (_UL_(1) << 5)
#define PIN_PA08B_PTC_X6 _L_(8) /**< PTC signal: X6 on PA08 mux B*/
#define MUX_PA08B_PTC_X6 _L_(1)
#define PINMUX_PA08B_PTC_X6 ((PIN_PA08B_PTC_X6 << 16) | MUX_PA08B_PTC_X6)
#define PORT_PA08B_PTC_X6 (_UL_(1) << 8)
#define PIN_PA08B_PTC_Y6 _L_(8) /**< PTC signal: Y6 on PA08 mux B*/
#define MUX_PA08B_PTC_Y6 _L_(1)
#define PINMUX_PA08B_PTC_Y6 ((PIN_PA08B_PTC_Y6 << 16) | MUX_PA08B_PTC_Y6)
#define PORT_PA08B_PTC_Y6 (_UL_(1) << 8)
#define PIN_PA14B_PTC_X10 _L_(14) /**< PTC signal: X10 on PA14 mux B*/
#define MUX_PA14B_PTC_X10 _L_(1)
#define PINMUX_PA14B_PTC_X10 ((PIN_PA14B_PTC_X10 << 16) | MUX_PA14B_PTC_X10)
#define PORT_PA14B_PTC_X10 (_UL_(1) << 14)
#define PIN_PA14B_PTC_Y10 _L_(14) /**< PTC signal: Y10 on PA14 mux B*/
#define MUX_PA14B_PTC_Y10 _L_(1)
#define PINMUX_PA14B_PTC_Y10 ((PIN_PA14B_PTC_Y10 << 16) | MUX_PA14B_PTC_Y10)
#define PORT_PA14B_PTC_Y10 (_UL_(1) << 14)
#define PIN_PA15B_PTC_X11 _L_(15) /**< PTC signal: X11 on PA15 mux B*/
#define MUX_PA15B_PTC_X11 _L_(1)
#define PINMUX_PA15B_PTC_X11 ((PIN_PA15B_PTC_X11 << 16) | MUX_PA15B_PTC_X11)
#define PORT_PA15B_PTC_X11 (_UL_(1) << 15)
#define PIN_PA15B_PTC_Y11 _L_(15) /**< PTC signal: Y11 on PA15 mux B*/
#define MUX_PA15B_PTC_Y11 _L_(1)
#define PINMUX_PA15B_PTC_Y11 ((PIN_PA15B_PTC_Y11 << 16) | MUX_PA15B_PTC_Y11)
#define PORT_PA15B_PTC_Y11 (_UL_(1) << 15)
#define PIN_PA16B_PTC_X12 _L_(16) /**< PTC signal: X12 on PA16 mux B*/
#define MUX_PA16B_PTC_X12 _L_(1)
#define PINMUX_PA16B_PTC_X12 ((PIN_PA16B_PTC_X12 << 16) | MUX_PA16B_PTC_X12)
#define PORT_PA16B_PTC_X12 (_UL_(1) << 16)
#define PIN_PA16B_PTC_Y12 _L_(16) /**< PTC signal: Y12 on PA16 mux B*/
#define MUX_PA16B_PTC_Y12 _L_(1)
#define PINMUX_PA16B_PTC_Y12 ((PIN_PA16B_PTC_Y12 << 16) | MUX_PA16B_PTC_Y12)
#define PORT_PA16B_PTC_Y12 (_UL_(1) << 16)
#define PIN_PA17B_PTC_X13 _L_(17) /**< PTC signal: X13 on PA17 mux B*/
#define MUX_PA17B_PTC_X13 _L_(1)
#define PINMUX_PA17B_PTC_X13 ((PIN_PA17B_PTC_X13 << 16) | MUX_PA17B_PTC_X13)
#define PORT_PA17B_PTC_X13 (_UL_(1) << 17)
#define PIN_PA17B_PTC_Y13 _L_(17) /**< PTC signal: Y13 on PA17 mux B*/
#define MUX_PA17B_PTC_Y13 _L_(1)
#define PINMUX_PA17B_PTC_Y13 ((PIN_PA17B_PTC_Y13 << 16) | MUX_PA17B_PTC_Y13)
#define PORT_PA17B_PTC_Y13 (_UL_(1) << 17)
#define PIN_PA18B_PTC_X14 _L_(18) /**< PTC signal: X14 on PA18 mux B*/
#define MUX_PA18B_PTC_X14 _L_(1)
#define PINMUX_PA18B_PTC_X14 ((PIN_PA18B_PTC_X14 << 16) | MUX_PA18B_PTC_X14)
#define PORT_PA18B_PTC_X14 (_UL_(1) << 18)
#define PIN_PA18B_PTC_Y14 _L_(18) /**< PTC signal: Y14 on PA18 mux B*/
#define MUX_PA18B_PTC_Y14 _L_(1)
#define PINMUX_PA18B_PTC_Y14 ((PIN_PA18B_PTC_Y14 << 16) | MUX_PA18B_PTC_Y14)
#define PORT_PA18B_PTC_Y14 (_UL_(1) << 18)
#define PIN_PA19B_PTC_X15 _L_(19) /**< PTC signal: X15 on PA19 mux B*/
#define MUX_PA19B_PTC_X15 _L_(1)
#define PINMUX_PA19B_PTC_X15 ((PIN_PA19B_PTC_X15 << 16) | MUX_PA19B_PTC_X15)
#define PORT_PA19B_PTC_X15 (_UL_(1) << 19)
#define PIN_PA19B_PTC_Y15 _L_(19) /**< PTC signal: Y15 on PA19 mux B*/
#define MUX_PA19B_PTC_Y15 _L_(1)
#define PINMUX_PA19B_PTC_Y15 ((PIN_PA19B_PTC_Y15 << 16) | MUX_PA19B_PTC_Y15)
#define PORT_PA19B_PTC_Y15 (_UL_(1) << 19)
#define PIN_PA22B_PTC_X16 _L_(22) /**< PTC signal: X16 on PA22 mux B*/
#define MUX_PA22B_PTC_X16 _L_(1)
#define PINMUX_PA22B_PTC_X16 ((PIN_PA22B_PTC_X16 << 16) | MUX_PA22B_PTC_X16)
#define PORT_PA22B_PTC_X16 (_UL_(1) << 22)
#define PIN_PA22B_PTC_Y16 _L_(22) /**< PTC signal: Y16 on PA22 mux B*/
#define MUX_PA22B_PTC_Y16 _L_(1)
#define PINMUX_PA22B_PTC_Y16 ((PIN_PA22B_PTC_Y16 << 16) | MUX_PA22B_PTC_Y16)
#define PORT_PA22B_PTC_Y16 (_UL_(1) << 22)
#define PIN_PA23B_PTC_X17 _L_(23) /**< PTC signal: X17 on PA23 mux B*/
#define MUX_PA23B_PTC_X17 _L_(1)
#define PINMUX_PA23B_PTC_X17 ((PIN_PA23B_PTC_X17 << 16) | MUX_PA23B_PTC_X17)
#define PORT_PA23B_PTC_X17 (_UL_(1) << 23)
#define PIN_PA23B_PTC_Y17 _L_(23) /**< PTC signal: Y17 on PA23 mux B*/
#define MUX_PA23B_PTC_Y17 _L_(1)
#define PINMUX_PA23B_PTC_Y17 ((PIN_PA23B_PTC_Y17 << 16) | MUX_PA23B_PTC_Y17)
#define PORT_PA23B_PTC_Y17 (_UL_(1) << 23)
#define PIN_PA30B_PTC_X18 _L_(30) /**< PTC signal: X18 on PA30 mux B*/
#define MUX_PA30B_PTC_X18 _L_(1)
#define PINMUX_PA30B_PTC_X18 ((PIN_PA30B_PTC_X18 << 16) | MUX_PA30B_PTC_X18)
#define PORT_PA30B_PTC_X18 (_UL_(1) << 30)
#define PIN_PA30B_PTC_Y18 _L_(30) /**< PTC signal: Y18 on PA30 mux B*/
#define MUX_PA30B_PTC_Y18 _L_(1)
#define PINMUX_PA30B_PTC_Y18 ((PIN_PA30B_PTC_Y18 << 16) | MUX_PA30B_PTC_Y18)
#define PORT_PA30B_PTC_Y18 (_UL_(1) << 30)
#define PIN_PA31B_PTC_X19 _L_(31) /**< PTC signal: X19 on PA31 mux B*/
#define MUX_PA31B_PTC_X19 _L_(1)
#define PINMUX_PA31B_PTC_X19 ((PIN_PA31B_PTC_X19 << 16) | MUX_PA31B_PTC_X19)
#define PORT_PA31B_PTC_X19 (_UL_(1) << 31)
#define PIN_PA31B_PTC_Y19 _L_(31) /**< PTC signal: Y19 on PA31 mux B*/
#define MUX_PA31B_PTC_Y19 _L_(1)
#define PINMUX_PA31B_PTC_Y19 ((PIN_PA31B_PTC_Y19 << 16) | MUX_PA31B_PTC_Y19)
#define PORT_PA31B_PTC_Y19 (_UL_(1) << 31)
/* ========== PORT definition for RTC peripheral ========== */
#define PIN_PA08G_RTC_IN0 _L_(8) /**< RTC signal: IN0 on PA08 mux G*/
#define MUX_PA08G_RTC_IN0 _L_(6)
#define PINMUX_PA08G_RTC_IN0 ((PIN_PA08G_RTC_IN0 << 16) | MUX_PA08G_RTC_IN0)
#define PORT_PA08G_RTC_IN0 (_UL_(1) << 8)
#define PIN_PA16G_RTC_IN2 _L_(16) /**< RTC signal: IN2 on PA16 mux G*/
#define MUX_PA16G_RTC_IN2 _L_(6)
#define PINMUX_PA16G_RTC_IN2 ((PIN_PA16G_RTC_IN2 << 16) | MUX_PA16G_RTC_IN2)
#define PORT_PA16G_RTC_IN2 (_UL_(1) << 16)
#define PIN_PA17G_RTC_IN3 _L_(17) /**< RTC signal: IN3 on PA17 mux G*/
#define MUX_PA17G_RTC_IN3 _L_(6)
#define PINMUX_PA17G_RTC_IN3 ((PIN_PA17G_RTC_IN3 << 16) | MUX_PA17G_RTC_IN3)
#define PORT_PA17G_RTC_IN3 (_UL_(1) << 17)
#define PIN_PA18G_RTC_OUT0 _L_(18) /**< RTC signal: OUT0 on PA18 mux G*/
#define MUX_PA18G_RTC_OUT0 _L_(6)
#define PINMUX_PA18G_RTC_OUT0 ((PIN_PA18G_RTC_OUT0 << 16) | MUX_PA18G_RTC_OUT0)
#define PORT_PA18G_RTC_OUT0 (_UL_(1) << 18)
#define PIN_PA19G_RTC_OUT1 _L_(19) /**< RTC signal: OUT1 on PA19 mux G*/
#define MUX_PA19G_RTC_OUT1 _L_(6)
#define PINMUX_PA19G_RTC_OUT1 ((PIN_PA19G_RTC_OUT1 << 16) | MUX_PA19G_RTC_OUT1)
#define PORT_PA19G_RTC_OUT1 (_UL_(1) << 19)
#define PIN_PA22G_RTC_OUT2 _L_(22) /**< RTC signal: OUT2 on PA22 mux G*/
#define MUX_PA22G_RTC_OUT2 _L_(6)
#define PINMUX_PA22G_RTC_OUT2 ((PIN_PA22G_RTC_OUT2 << 16) | MUX_PA22G_RTC_OUT2)
#define PORT_PA22G_RTC_OUT2 (_UL_(1) << 22)
#define PIN_PA23G_RTC_OUT3 _L_(23) /**< RTC signal: OUT3 on PA23 mux G*/
#define MUX_PA23G_RTC_OUT3 _L_(6)
#define PINMUX_PA23G_RTC_OUT3 ((PIN_PA23G_RTC_OUT3 << 16) | MUX_PA23G_RTC_OUT3)
#define PORT_PA23G_RTC_OUT3 (_UL_(1) << 23)
/* ========== PORT definition for SERCOM0 peripheral ========== */
#define PIN_PA04D_SERCOM0_PAD0 _L_(4) /**< SERCOM0 signal: PAD0 on PA04 mux D*/
#define MUX_PA04D_SERCOM0_PAD0 _L_(3)
#define PINMUX_PA04D_SERCOM0_PAD0 ((PIN_PA04D_SERCOM0_PAD0 << 16) | MUX_PA04D_SERCOM0_PAD0)
#define PORT_PA04D_SERCOM0_PAD0 (_UL_(1) << 4)
#define PIN_PA16D_SERCOM0_PAD0 _L_(16) /**< SERCOM0 signal: PAD0 on PA16 mux D*/
#define MUX_PA16D_SERCOM0_PAD0 _L_(3)
#define PINMUX_PA16D_SERCOM0_PAD0 ((PIN_PA16D_SERCOM0_PAD0 << 16) | MUX_PA16D_SERCOM0_PAD0)
#define PORT_PA16D_SERCOM0_PAD0 (_UL_(1) << 16)
#define PIN_PA22C_SERCOM0_PAD0 _L_(22) /**< SERCOM0 signal: PAD0 on PA22 mux C*/
#define MUX_PA22C_SERCOM0_PAD0 _L_(2)
#define PINMUX_PA22C_SERCOM0_PAD0 ((PIN_PA22C_SERCOM0_PAD0 << 16) | MUX_PA22C_SERCOM0_PAD0)
#define PORT_PA22C_SERCOM0_PAD0 (_UL_(1) << 22)
#define PIN_PA05D_SERCOM0_PAD1 _L_(5) /**< SERCOM0 signal: PAD1 on PA05 mux D*/
#define MUX_PA05D_SERCOM0_PAD1 _L_(3)
#define PINMUX_PA05D_SERCOM0_PAD1 ((PIN_PA05D_SERCOM0_PAD1 << 16) | MUX_PA05D_SERCOM0_PAD1)
#define PORT_PA05D_SERCOM0_PAD1 (_UL_(1) << 5)
#define PIN_PA17D_SERCOM0_PAD1 _L_(17) /**< SERCOM0 signal: PAD1 on PA17 mux D*/
#define MUX_PA17D_SERCOM0_PAD1 _L_(3)
#define PINMUX_PA17D_SERCOM0_PAD1 ((PIN_PA17D_SERCOM0_PAD1 << 16) | MUX_PA17D_SERCOM0_PAD1)
#define PORT_PA17D_SERCOM0_PAD1 (_UL_(1) << 17)
#define PIN_PA23C_SERCOM0_PAD1 _L_(23) /**< SERCOM0 signal: PAD1 on PA23 mux C*/
#define MUX_PA23C_SERCOM0_PAD1 _L_(2)
#define PINMUX_PA23C_SERCOM0_PAD1 ((PIN_PA23C_SERCOM0_PAD1 << 16) | MUX_PA23C_SERCOM0_PAD1)
#define PORT_PA23C_SERCOM0_PAD1 (_UL_(1) << 23)
#define PIN_PA14D_SERCOM0_PAD2 _L_(14) /**< SERCOM0 signal: PAD2 on PA14 mux D*/
#define MUX_PA14D_SERCOM0_PAD2 _L_(3)
#define PINMUX_PA14D_SERCOM0_PAD2 ((PIN_PA14D_SERCOM0_PAD2 << 16) | MUX_PA14D_SERCOM0_PAD2)
#define PORT_PA14D_SERCOM0_PAD2 (_UL_(1) << 14)
#define PIN_PA18D_SERCOM0_PAD2 _L_(18) /**< SERCOM0 signal: PAD2 on PA18 mux D*/
#define MUX_PA18D_SERCOM0_PAD2 _L_(3)
#define PINMUX_PA18D_SERCOM0_PAD2 ((PIN_PA18D_SERCOM0_PAD2 << 16) | MUX_PA18D_SERCOM0_PAD2)
#define PORT_PA18D_SERCOM0_PAD2 (_UL_(1) << 18)
#define PIN_PA02D_SERCOM0_PAD2 _L_(2) /**< SERCOM0 signal: PAD2 on PA02 mux D*/
#define MUX_PA02D_SERCOM0_PAD2 _L_(3)
#define PINMUX_PA02D_SERCOM0_PAD2 ((PIN_PA02D_SERCOM0_PAD2 << 16) | MUX_PA02D_SERCOM0_PAD2)
#define PORT_PA02D_SERCOM0_PAD2 (_UL_(1) << 2)
#define PIN_PA15D_SERCOM0_PAD3 _L_(15) /**< SERCOM0 signal: PAD3 on PA15 mux D*/
#define MUX_PA15D_SERCOM0_PAD3 _L_(3)
#define PINMUX_PA15D_SERCOM0_PAD3 ((PIN_PA15D_SERCOM0_PAD3 << 16) | MUX_PA15D_SERCOM0_PAD3)
#define PORT_PA15D_SERCOM0_PAD3 (_UL_(1) << 15)
#define PIN_PA19D_SERCOM0_PAD3 _L_(19) /**< SERCOM0 signal: PAD3 on PA19 mux D*/
#define MUX_PA19D_SERCOM0_PAD3 _L_(3)
#define PINMUX_PA19D_SERCOM0_PAD3 ((PIN_PA19D_SERCOM0_PAD3 << 16) | MUX_PA19D_SERCOM0_PAD3)
#define PORT_PA19D_SERCOM0_PAD3 (_UL_(1) << 19)
#define PIN_PA03D_SERCOM0_PAD3 _L_(3) /**< SERCOM0 signal: PAD3 on PA03 mux D*/
#define MUX_PA03D_SERCOM0_PAD3 _L_(3)
#define PINMUX_PA03D_SERCOM0_PAD3 ((PIN_PA03D_SERCOM0_PAD3 << 16) | MUX_PA03D_SERCOM0_PAD3)
#define PORT_PA03D_SERCOM0_PAD3 (_UL_(1) << 3)
/* ========== PORT definition for SERCOM1 peripheral ========== */
#define PIN_PA16C_SERCOM1_PAD0 _L_(16) /**< SERCOM1 signal: PAD0 on PA16 mux C*/
#define MUX_PA16C_SERCOM1_PAD0 _L_(2)
#define PINMUX_PA16C_SERCOM1_PAD0 ((PIN_PA16C_SERCOM1_PAD0 << 16) | MUX_PA16C_SERCOM1_PAD0)
#define PORT_PA16C_SERCOM1_PAD0 (_UL_(1) << 16)
#define PIN_PA08C_SERCOM1_PAD0 _L_(8) /**< SERCOM1 signal: PAD0 on PA08 mux C*/
#define MUX_PA08C_SERCOM1_PAD0 _L_(2)
#define PINMUX_PA08C_SERCOM1_PAD0 ((PIN_PA08C_SERCOM1_PAD0 << 16) | MUX_PA08C_SERCOM1_PAD0)
#define PORT_PA08C_SERCOM1_PAD0 (_UL_(1) << 8)
#define PIN_PA00D_SERCOM1_PAD0 _L_(0) /**< SERCOM1 signal: PAD0 on PA00 mux D*/
#define MUX_PA00D_SERCOM1_PAD0 _L_(3)
#define PINMUX_PA00D_SERCOM1_PAD0 ((PIN_PA00D_SERCOM1_PAD0 << 16) | MUX_PA00D_SERCOM1_PAD0)
#define PORT_PA00D_SERCOM1_PAD0 (_UL_(1) << 0)
#define PIN_PA17C_SERCOM1_PAD1 _L_(17) /**< SERCOM1 signal: PAD1 on PA17 mux C*/
#define MUX_PA17C_SERCOM1_PAD1 _L_(2)
#define PINMUX_PA17C_SERCOM1_PAD1 ((PIN_PA17C_SERCOM1_PAD1 << 16) | MUX_PA17C_SERCOM1_PAD1)
#define PORT_PA17C_SERCOM1_PAD1 (_UL_(1) << 17)
#define PIN_PA01D_SERCOM1_PAD1 _L_(1) /**< SERCOM1 signal: PAD1 on PA01 mux D*/
#define MUX_PA01D_SERCOM1_PAD1 _L_(3)
#define PINMUX_PA01D_SERCOM1_PAD1 ((PIN_PA01D_SERCOM1_PAD1 << 16) | MUX_PA01D_SERCOM1_PAD1)
#define PORT_PA01D_SERCOM1_PAD1 (_UL_(1) << 1)
#define PIN_PA18C_SERCOM1_PAD2 _L_(18) /**< SERCOM1 signal: PAD2 on PA18 mux C*/
#define MUX_PA18C_SERCOM1_PAD2 _L_(2)
#define PINMUX_PA18C_SERCOM1_PAD2 ((PIN_PA18C_SERCOM1_PAD2 << 16) | MUX_PA18C_SERCOM1_PAD2)
#define PORT_PA18C_SERCOM1_PAD2 (_UL_(1) << 18)
#define PIN_PA30D_SERCOM1_PAD2 _L_(30) /**< SERCOM1 signal: PAD2 on PA30 mux D*/
#define MUX_PA30D_SERCOM1_PAD2 _L_(3)
#define PINMUX_PA30D_SERCOM1_PAD2 ((PIN_PA30D_SERCOM1_PAD2 << 16) | MUX_PA30D_SERCOM1_PAD2)
#define PORT_PA30D_SERCOM1_PAD2 (_UL_(1) << 30)
#define PIN_PA19C_SERCOM1_PAD3 _L_(19) /**< SERCOM1 signal: PAD3 on PA19 mux C*/
#define MUX_PA19C_SERCOM1_PAD3 _L_(2)
#define PINMUX_PA19C_SERCOM1_PAD3 ((PIN_PA19C_SERCOM1_PAD3 << 16) | MUX_PA19C_SERCOM1_PAD3)
#define PORT_PA19C_SERCOM1_PAD3 (_UL_(1) << 19)
#define PIN_PA31D_SERCOM1_PAD3 _L_(31) /**< SERCOM1 signal: PAD3 on PA31 mux D*/
#define MUX_PA31D_SERCOM1_PAD3 _L_(3)
#define PINMUX_PA31D_SERCOM1_PAD3 ((PIN_PA31D_SERCOM1_PAD3 << 16) | MUX_PA31D_SERCOM1_PAD3)
#define PORT_PA31D_SERCOM1_PAD3 (_UL_(1) << 31)
/* ========== PORT definition for TC0 peripheral ========== */
#define PIN_PA04E_TC0_WO0 _L_(4) /**< TC0 signal: WO0 on PA04 mux E*/
#define MUX_PA04E_TC0_WO0 _L_(4)
#define PINMUX_PA04E_TC0_WO0 ((PIN_PA04E_TC0_WO0 << 16) | MUX_PA04E_TC0_WO0)
#define PORT_PA04E_TC0_WO0 (_UL_(1) << 4)
#define PIN_PA14E_TC0_WO0 _L_(14) /**< TC0 signal: WO0 on PA14 mux E*/
#define MUX_PA14E_TC0_WO0 _L_(4)
#define PINMUX_PA14E_TC0_WO0 ((PIN_PA14E_TC0_WO0 << 16) | MUX_PA14E_TC0_WO0)
#define PORT_PA14E_TC0_WO0 (_UL_(1) << 14)
#define PIN_PA22E_TC0_WO0 _L_(22) /**< TC0 signal: WO0 on PA22 mux E*/
#define MUX_PA22E_TC0_WO0 _L_(4)
#define PINMUX_PA22E_TC0_WO0 ((PIN_PA22E_TC0_WO0 << 16) | MUX_PA22E_TC0_WO0)
#define PORT_PA22E_TC0_WO0 (_UL_(1) << 22)
#define PIN_PA05E_TC0_WO1 _L_(5) /**< TC0 signal: WO1 on PA05 mux E*/
#define MUX_PA05E_TC0_WO1 _L_(4)
#define PINMUX_PA05E_TC0_WO1 ((PIN_PA05E_TC0_WO1 << 16) | MUX_PA05E_TC0_WO1)
#define PORT_PA05E_TC0_WO1 (_UL_(1) << 5)
#define PIN_PA15E_TC0_WO1 _L_(15) /**< TC0 signal: WO1 on PA15 mux E*/
#define MUX_PA15E_TC0_WO1 _L_(4)
#define PINMUX_PA15E_TC0_WO1 ((PIN_PA15E_TC0_WO1 << 16) | MUX_PA15E_TC0_WO1)
#define PORT_PA15E_TC0_WO1 (_UL_(1) << 15)
#define PIN_PA23E_TC0_WO1 _L_(23) /**< TC0 signal: WO1 on PA23 mux E*/
#define MUX_PA23E_TC0_WO1 _L_(4)
#define PINMUX_PA23E_TC0_WO1 ((PIN_PA23E_TC0_WO1 << 16) | MUX_PA23E_TC0_WO1)
#define PORT_PA23E_TC0_WO1 (_UL_(1) << 23)
/* ========== PORT definition for TC1 peripheral ========== */
#define PIN_PA30E_TC1_WO0 _L_(30) /**< TC1 signal: WO0 on PA30 mux E*/
#define MUX_PA30E_TC1_WO0 _L_(4)
#define PINMUX_PA30E_TC1_WO0 ((PIN_PA30E_TC1_WO0 << 16) | MUX_PA30E_TC1_WO0)
#define PORT_PA30E_TC1_WO0 (_UL_(1) << 30)
#define PIN_PA31E_TC1_WO1 _L_(31) /**< TC1 signal: WO1 on PA31 mux E*/
#define MUX_PA31E_TC1_WO1 _L_(4)
#define PINMUX_PA31E_TC1_WO1 ((PIN_PA31E_TC1_WO1 << 16) | MUX_PA31E_TC1_WO1)
#define PORT_PA31E_TC1_WO1 (_UL_(1) << 31)
/* ========== PORT definition for TC2 peripheral ========== */
#define PIN_PA00E_TC2_WO0 _L_(0) /**< TC2 signal: WO0 on PA00 mux E*/
#define MUX_PA00E_TC2_WO0 _L_(4)
#define PINMUX_PA00E_TC2_WO0 ((PIN_PA00E_TC2_WO0 << 16) | MUX_PA00E_TC2_WO0)
#define PORT_PA00E_TC2_WO0 (_UL_(1) << 0)
#define PIN_PA18E_TC2_WO0 _L_(18) /**< TC2 signal: WO0 on PA18 mux E*/
#define MUX_PA18E_TC2_WO0 _L_(4)
#define PINMUX_PA18E_TC2_WO0 ((PIN_PA18E_TC2_WO0 << 16) | MUX_PA18E_TC2_WO0)
#define PORT_PA18E_TC2_WO0 (_UL_(1) << 18)
#define PIN_PA01E_TC2_WO1 _L_(1) /**< TC2 signal: WO1 on PA01 mux E*/
#define MUX_PA01E_TC2_WO1 _L_(4)
#define PINMUX_PA01E_TC2_WO1 ((PIN_PA01E_TC2_WO1 << 16) | MUX_PA01E_TC2_WO1)
#define PORT_PA01E_TC2_WO1 (_UL_(1) << 1)
#define PIN_PA19E_TC2_WO1 _L_(19) /**< TC2 signal: WO1 on PA19 mux E*/
#define MUX_PA19E_TC2_WO1 _L_(4)
#define PINMUX_PA19E_TC2_WO1 ((PIN_PA19E_TC2_WO1 << 16) | MUX_PA19E_TC2_WO1)
#define PORT_PA19E_TC2_WO1 (_UL_(1) << 19)
#endif /* _SAML10D15A_PIO_H_ */

View File

@ -0,0 +1,834 @@
/**
* \file
*
* \brief Peripheral I/O description for SAML10D16A
*
* Copyright (c) 2018 Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* 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
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
/* file generated from device description version 2018-08-31T13:51:50Z */
#ifndef _SAML10D16A_PIO_H_
#define _SAML10D16A_PIO_H_
/* ========== Peripheral I/O pin numbers ========== */
#define PIN_PA00 ( 0) /**< Pin Number for PA00 */
#define PIN_PA01 ( 1) /**< Pin Number for PA01 */
#define PIN_PA02 ( 2) /**< Pin Number for PA02 */
#define PIN_PA03 ( 3) /**< Pin Number for PA03 */
#define PIN_PA04 ( 4) /**< Pin Number for PA04 */
#define PIN_PA05 ( 5) /**< Pin Number for PA05 */
#define PIN_PA08 ( 8) /**< Pin Number for PA08 */
#define PIN_PA14 ( 14) /**< Pin Number for PA14 */
#define PIN_PA15 ( 15) /**< Pin Number for PA15 */
#define PIN_PA16 ( 16) /**< Pin Number for PA16 */
#define PIN_PA17 ( 17) /**< Pin Number for PA17 */
#define PIN_PA18 ( 18) /**< Pin Number for PA18 */
#define PIN_PA19 ( 19) /**< Pin Number for PA19 */
#define PIN_PA22 ( 22) /**< Pin Number for PA22 */
#define PIN_PA23 ( 23) /**< Pin Number for PA23 */
#define PIN_PA30 ( 30) /**< Pin Number for PA30 */
#define PIN_PA31 ( 31) /**< Pin Number for PA31 */
/* ========== Peripheral I/O masks ========== */
#define PORT_PA00 (_U_(1) << 0) /**< PORT Mask for PA00 */
#define PORT_PA01 (_U_(1) << 1) /**< PORT Mask for PA01 */
#define PORT_PA02 (_U_(1) << 2) /**< PORT Mask for PA02 */
#define PORT_PA03 (_U_(1) << 3) /**< PORT Mask for PA03 */
#define PORT_PA04 (_U_(1) << 4) /**< PORT Mask for PA04 */
#define PORT_PA05 (_U_(1) << 5) /**< PORT Mask for PA05 */
#define PORT_PA08 (_U_(1) << 8) /**< PORT Mask for PA08 */
#define PORT_PA14 (_U_(1) << 14) /**< PORT Mask for PA14 */
#define PORT_PA15 (_U_(1) << 15) /**< PORT Mask for PA15 */
#define PORT_PA16 (_U_(1) << 16) /**< PORT Mask for PA16 */
#define PORT_PA17 (_U_(1) << 17) /**< PORT Mask for PA17 */
#define PORT_PA18 (_U_(1) << 18) /**< PORT Mask for PA18 */
#define PORT_PA19 (_U_(1) << 19) /**< PORT Mask for PA19 */
#define PORT_PA22 (_U_(1) << 22) /**< PORT Mask for PA22 */
#define PORT_PA23 (_U_(1) << 23) /**< PORT Mask for PA23 */
#define PORT_PA30 (_U_(1) << 30) /**< PORT Mask for PA30 */
#define PORT_PA31 (_U_(1) << 31) /**< PORT Mask for PA31 */
/* ========== Peripheral I/O indexes ========== */
#define PORT_PA00_IDX ( 0) /**< PORT Index Number for PA00 */
#define PORT_PA01_IDX ( 1) /**< PORT Index Number for PA01 */
#define PORT_PA02_IDX ( 2) /**< PORT Index Number for PA02 */
#define PORT_PA03_IDX ( 3) /**< PORT Index Number for PA03 */
#define PORT_PA04_IDX ( 4) /**< PORT Index Number for PA04 */
#define PORT_PA05_IDX ( 5) /**< PORT Index Number for PA05 */
#define PORT_PA08_IDX ( 8) /**< PORT Index Number for PA08 */
#define PORT_PA14_IDX ( 14) /**< PORT Index Number for PA14 */
#define PORT_PA15_IDX ( 15) /**< PORT Index Number for PA15 */
#define PORT_PA16_IDX ( 16) /**< PORT Index Number for PA16 */
#define PORT_PA17_IDX ( 17) /**< PORT Index Number for PA17 */
#define PORT_PA18_IDX ( 18) /**< PORT Index Number for PA18 */
#define PORT_PA19_IDX ( 19) /**< PORT Index Number for PA19 */
#define PORT_PA22_IDX ( 22) /**< PORT Index Number for PA22 */
#define PORT_PA23_IDX ( 23) /**< PORT Index Number for PA23 */
#define PORT_PA30_IDX ( 30) /**< PORT Index Number for PA30 */
#define PORT_PA31_IDX ( 31) /**< PORT Index Number for PA31 */
/* ========== PORT definition for AC peripheral ========== */
#define PIN_PA04B_AC_AIN0 _L_(4) /**< AC signal: AIN0 on PA04 mux B*/
#define MUX_PA04B_AC_AIN0 _L_(1)
#define PINMUX_PA04B_AC_AIN0 ((PIN_PA04B_AC_AIN0 << 16) | MUX_PA04B_AC_AIN0)
#define PORT_PA04B_AC_AIN0 (_UL_(1) << 4)
#define PIN_PA05B_AC_AIN1 _L_(5) /**< AC signal: AIN1 on PA05 mux B*/
#define MUX_PA05B_AC_AIN1 _L_(1)
#define PINMUX_PA05B_AC_AIN1 ((PIN_PA05B_AC_AIN1 << 16) | MUX_PA05B_AC_AIN1)
#define PORT_PA05B_AC_AIN1 (_UL_(1) << 5)
#define PIN_PA18H_AC_CMP0 _L_(18) /**< AC signal: CMP0 on PA18 mux H*/
#define MUX_PA18H_AC_CMP0 _L_(7)
#define PINMUX_PA18H_AC_CMP0 ((PIN_PA18H_AC_CMP0 << 16) | MUX_PA18H_AC_CMP0)
#define PORT_PA18H_AC_CMP0 (_UL_(1) << 18)
#define PIN_PA19H_AC_CMP1 _L_(19) /**< AC signal: CMP1 on PA19 mux H*/
#define MUX_PA19H_AC_CMP1 _L_(7)
#define PINMUX_PA19H_AC_CMP1 ((PIN_PA19H_AC_CMP1 << 16) | MUX_PA19H_AC_CMP1)
#define PORT_PA19H_AC_CMP1 (_UL_(1) << 19)
/* ========== PORT definition for ADC peripheral ========== */
#define PIN_PA02B_ADC_AIN0 _L_(2) /**< ADC signal: AIN0 on PA02 mux B*/
#define MUX_PA02B_ADC_AIN0 _L_(1)
#define PINMUX_PA02B_ADC_AIN0 ((PIN_PA02B_ADC_AIN0 << 16) | MUX_PA02B_ADC_AIN0)
#define PORT_PA02B_ADC_AIN0 (_UL_(1) << 2)
#define PIN_PA03B_ADC_AIN1 _L_(3) /**< ADC signal: AIN1 on PA03 mux B*/
#define MUX_PA03B_ADC_AIN1 _L_(1)
#define PINMUX_PA03B_ADC_AIN1 ((PIN_PA03B_ADC_AIN1 << 16) | MUX_PA03B_ADC_AIN1)
#define PORT_PA03B_ADC_AIN1 (_UL_(1) << 3)
#define PIN_PA04B_ADC_AIN2 _L_(4) /**< ADC signal: AIN2 on PA04 mux B*/
#define MUX_PA04B_ADC_AIN2 _L_(1)
#define PINMUX_PA04B_ADC_AIN2 ((PIN_PA04B_ADC_AIN2 << 16) | MUX_PA04B_ADC_AIN2)
#define PORT_PA04B_ADC_AIN2 (_UL_(1) << 4)
#define PIN_PA05B_ADC_AIN3 _L_(5) /**< ADC signal: AIN3 on PA05 mux B*/
#define MUX_PA05B_ADC_AIN3 _L_(1)
#define PINMUX_PA05B_ADC_AIN3 ((PIN_PA05B_ADC_AIN3 << 16) | MUX_PA05B_ADC_AIN3)
#define PORT_PA05B_ADC_AIN3 (_UL_(1) << 5)
#define PIN_PA08B_ADC_AIN6 _L_(8) /**< ADC signal: AIN6 on PA08 mux B*/
#define MUX_PA08B_ADC_AIN6 _L_(1)
#define PINMUX_PA08B_ADC_AIN6 ((PIN_PA08B_ADC_AIN6 << 16) | MUX_PA08B_ADC_AIN6)
#define PORT_PA08B_ADC_AIN6 (_UL_(1) << 8)
#define PIN_PA04B_ADC_VREFP _L_(4) /**< ADC signal: VREFP on PA04 mux B*/
#define MUX_PA04B_ADC_VREFP _L_(1)
#define PINMUX_PA04B_ADC_VREFP ((PIN_PA04B_ADC_VREFP << 16) | MUX_PA04B_ADC_VREFP)
#define PORT_PA04B_ADC_VREFP (_UL_(1) << 4)
/* ========== PORT definition for CCL peripheral ========== */
#define PIN_PA04I_CCL_IN0 _L_(4) /**< CCL signal: IN0 on PA04 mux I*/
#define MUX_PA04I_CCL_IN0 _L_(8)
#define PINMUX_PA04I_CCL_IN0 ((PIN_PA04I_CCL_IN0 << 16) | MUX_PA04I_CCL_IN0)
#define PORT_PA04I_CCL_IN0 (_UL_(1) << 4)
#define PIN_PA16I_CCL_IN0 _L_(16) /**< CCL signal: IN0 on PA16 mux I*/
#define MUX_PA16I_CCL_IN0 _L_(8)
#define PINMUX_PA16I_CCL_IN0 ((PIN_PA16I_CCL_IN0 << 16) | MUX_PA16I_CCL_IN0)
#define PORT_PA16I_CCL_IN0 (_UL_(1) << 16)
#define PIN_PA05I_CCL_IN1 _L_(5) /**< CCL signal: IN1 on PA05 mux I*/
#define MUX_PA05I_CCL_IN1 _L_(8)
#define PINMUX_PA05I_CCL_IN1 ((PIN_PA05I_CCL_IN1 << 16) | MUX_PA05I_CCL_IN1)
#define PORT_PA05I_CCL_IN1 (_UL_(1) << 5)
#define PIN_PA17I_CCL_IN1 _L_(17) /**< CCL signal: IN1 on PA17 mux I*/
#define MUX_PA17I_CCL_IN1 _L_(8)
#define PINMUX_PA17I_CCL_IN1 ((PIN_PA17I_CCL_IN1 << 16) | MUX_PA17I_CCL_IN1)
#define PORT_PA17I_CCL_IN1 (_UL_(1) << 17)
#define PIN_PA18I_CCL_IN2 _L_(18) /**< CCL signal: IN2 on PA18 mux I*/
#define MUX_PA18I_CCL_IN2 _L_(8)
#define PINMUX_PA18I_CCL_IN2 ((PIN_PA18I_CCL_IN2 << 16) | MUX_PA18I_CCL_IN2)
#define PORT_PA18I_CCL_IN2 (_UL_(1) << 18)
#define PIN_PA08I_CCL_IN3 _L_(8) /**< CCL signal: IN3 on PA08 mux I*/
#define MUX_PA08I_CCL_IN3 _L_(8)
#define PINMUX_PA08I_CCL_IN3 ((PIN_PA08I_CCL_IN3 << 16) | MUX_PA08I_CCL_IN3)
#define PORT_PA08I_CCL_IN3 (_UL_(1) << 8)
#define PIN_PA30I_CCL_IN3 _L_(30) /**< CCL signal: IN3 on PA30 mux I*/
#define MUX_PA30I_CCL_IN3 _L_(8)
#define PINMUX_PA30I_CCL_IN3 ((PIN_PA30I_CCL_IN3 << 16) | MUX_PA30I_CCL_IN3)
#define PORT_PA30I_CCL_IN3 (_UL_(1) << 30)
#define PIN_PA19I_CCL_OUT0 _L_(19) /**< CCL signal: OUT0 on PA19 mux I*/
#define MUX_PA19I_CCL_OUT0 _L_(8)
#define PINMUX_PA19I_CCL_OUT0 ((PIN_PA19I_CCL_OUT0 << 16) | MUX_PA19I_CCL_OUT0)
#define PORT_PA19I_CCL_OUT0 (_UL_(1) << 19)
#define PIN_PA31I_CCL_OUT1 _L_(31) /**< CCL signal: OUT1 on PA31 mux I*/
#define MUX_PA31I_CCL_OUT1 _L_(8)
#define PINMUX_PA31I_CCL_OUT1 ((PIN_PA31I_CCL_OUT1 << 16) | MUX_PA31I_CCL_OUT1)
#define PORT_PA31I_CCL_OUT1 (_UL_(1) << 31)
/* ========== PORT definition for DAC peripheral ========== */
#define PIN_PA02B_DAC_VOUT _L_(2) /**< DAC signal: VOUT on PA02 mux B*/
#define MUX_PA02B_DAC_VOUT _L_(1)
#define PINMUX_PA02B_DAC_VOUT ((PIN_PA02B_DAC_VOUT << 16) | MUX_PA02B_DAC_VOUT)
#define PORT_PA02B_DAC_VOUT (_UL_(1) << 2)
#define PIN_PA03B_DAC_VREFP _L_(3) /**< DAC signal: VREFP on PA03 mux B*/
#define MUX_PA03B_DAC_VREFP _L_(1)
#define PINMUX_PA03B_DAC_VREFP ((PIN_PA03B_DAC_VREFP << 16) | MUX_PA03B_DAC_VREFP)
#define PORT_PA03B_DAC_VREFP (_UL_(1) << 3)
/* ========== PORT definition for EIC peripheral ========== */
#define PIN_PA19A_EIC_EXTINT0 _L_(19) /**< EIC signal: EXTINT0 on PA19 mux A*/
#define MUX_PA19A_EIC_EXTINT0 _L_(0)
#define PINMUX_PA19A_EIC_EXTINT0 ((PIN_PA19A_EIC_EXTINT0 << 16) | MUX_PA19A_EIC_EXTINT0)
#define PORT_PA19A_EIC_EXTINT0 (_UL_(1) << 19)
#define PIN_PA19A_EIC_EXTINT_NUM _L_(0) /**< EIC signal: PIN_PA19 External Interrupt Line */
#define PIN_PA00A_EIC_EXTINT0 _L_(0) /**< EIC signal: EXTINT0 on PA00 mux A*/
#define MUX_PA00A_EIC_EXTINT0 _L_(0)
#define PINMUX_PA00A_EIC_EXTINT0 ((PIN_PA00A_EIC_EXTINT0 << 16) | MUX_PA00A_EIC_EXTINT0)
#define PORT_PA00A_EIC_EXTINT0 (_UL_(1) << 0)
#define PIN_PA00A_EIC_EXTINT_NUM _L_(0) /**< EIC signal: PIN_PA00 External Interrupt Line */
#define PIN_PA22A_EIC_EXTINT1 _L_(22) /**< EIC signal: EXTINT1 on PA22 mux A*/
#define MUX_PA22A_EIC_EXTINT1 _L_(0)
#define PINMUX_PA22A_EIC_EXTINT1 ((PIN_PA22A_EIC_EXTINT1 << 16) | MUX_PA22A_EIC_EXTINT1)
#define PORT_PA22A_EIC_EXTINT1 (_UL_(1) << 22)
#define PIN_PA22A_EIC_EXTINT_NUM _L_(1) /**< EIC signal: PIN_PA22 External Interrupt Line */
#define PIN_PA01A_EIC_EXTINT1 _L_(1) /**< EIC signal: EXTINT1 on PA01 mux A*/
#define MUX_PA01A_EIC_EXTINT1 _L_(0)
#define PINMUX_PA01A_EIC_EXTINT1 ((PIN_PA01A_EIC_EXTINT1 << 16) | MUX_PA01A_EIC_EXTINT1)
#define PORT_PA01A_EIC_EXTINT1 (_UL_(1) << 1)
#define PIN_PA01A_EIC_EXTINT_NUM _L_(1) /**< EIC signal: PIN_PA01 External Interrupt Line */
#define PIN_PA02A_EIC_EXTINT2 _L_(2) /**< EIC signal: EXTINT2 on PA02 mux A*/
#define MUX_PA02A_EIC_EXTINT2 _L_(0)
#define PINMUX_PA02A_EIC_EXTINT2 ((PIN_PA02A_EIC_EXTINT2 << 16) | MUX_PA02A_EIC_EXTINT2)
#define PORT_PA02A_EIC_EXTINT2 (_UL_(1) << 2)
#define PIN_PA02A_EIC_EXTINT_NUM _L_(2) /**< EIC signal: PIN_PA02 External Interrupt Line */
#define PIN_PA23A_EIC_EXTINT2 _L_(23) /**< EIC signal: EXTINT2 on PA23 mux A*/
#define MUX_PA23A_EIC_EXTINT2 _L_(0)
#define PINMUX_PA23A_EIC_EXTINT2 ((PIN_PA23A_EIC_EXTINT2 << 16) | MUX_PA23A_EIC_EXTINT2)
#define PORT_PA23A_EIC_EXTINT2 (_UL_(1) << 23)
#define PIN_PA23A_EIC_EXTINT_NUM _L_(2) /**< EIC signal: PIN_PA23 External Interrupt Line */
#define PIN_PA03A_EIC_EXTINT3 _L_(3) /**< EIC signal: EXTINT3 on PA03 mux A*/
#define MUX_PA03A_EIC_EXTINT3 _L_(0)
#define PINMUX_PA03A_EIC_EXTINT3 ((PIN_PA03A_EIC_EXTINT3 << 16) | MUX_PA03A_EIC_EXTINT3)
#define PORT_PA03A_EIC_EXTINT3 (_UL_(1) << 3)
#define PIN_PA03A_EIC_EXTINT_NUM _L_(3) /**< EIC signal: PIN_PA03 External Interrupt Line */
#define PIN_PA14A_EIC_EXTINT3 _L_(14) /**< EIC signal: EXTINT3 on PA14 mux A*/
#define MUX_PA14A_EIC_EXTINT3 _L_(0)
#define PINMUX_PA14A_EIC_EXTINT3 ((PIN_PA14A_EIC_EXTINT3 << 16) | MUX_PA14A_EIC_EXTINT3)
#define PORT_PA14A_EIC_EXTINT3 (_UL_(1) << 14)
#define PIN_PA14A_EIC_EXTINT_NUM _L_(3) /**< EIC signal: PIN_PA14 External Interrupt Line */
#define PIN_PA04A_EIC_EXTINT4 _L_(4) /**< EIC signal: EXTINT4 on PA04 mux A*/
#define MUX_PA04A_EIC_EXTINT4 _L_(0)
#define PINMUX_PA04A_EIC_EXTINT4 ((PIN_PA04A_EIC_EXTINT4 << 16) | MUX_PA04A_EIC_EXTINT4)
#define PORT_PA04A_EIC_EXTINT4 (_UL_(1) << 4)
#define PIN_PA04A_EIC_EXTINT_NUM _L_(4) /**< EIC signal: PIN_PA04 External Interrupt Line */
#define PIN_PA15A_EIC_EXTINT4 _L_(15) /**< EIC signal: EXTINT4 on PA15 mux A*/
#define MUX_PA15A_EIC_EXTINT4 _L_(0)
#define PINMUX_PA15A_EIC_EXTINT4 ((PIN_PA15A_EIC_EXTINT4 << 16) | MUX_PA15A_EIC_EXTINT4)
#define PORT_PA15A_EIC_EXTINT4 (_UL_(1) << 15)
#define PIN_PA15A_EIC_EXTINT_NUM _L_(4) /**< EIC signal: PIN_PA15 External Interrupt Line */
#define PIN_PA05A_EIC_EXTINT5 _L_(5) /**< EIC signal: EXTINT5 on PA05 mux A*/
#define MUX_PA05A_EIC_EXTINT5 _L_(0)
#define PINMUX_PA05A_EIC_EXTINT5 ((PIN_PA05A_EIC_EXTINT5 << 16) | MUX_PA05A_EIC_EXTINT5)
#define PORT_PA05A_EIC_EXTINT5 (_UL_(1) << 5)
#define PIN_PA05A_EIC_EXTINT_NUM _L_(5) /**< EIC signal: PIN_PA05 External Interrupt Line */
#define PIN_PA16A_EIC_EXTINT5 _L_(16) /**< EIC signal: EXTINT5 on PA16 mux A*/
#define MUX_PA16A_EIC_EXTINT5 _L_(0)
#define PINMUX_PA16A_EIC_EXTINT5 ((PIN_PA16A_EIC_EXTINT5 << 16) | MUX_PA16A_EIC_EXTINT5)
#define PORT_PA16A_EIC_EXTINT5 (_UL_(1) << 16)
#define PIN_PA16A_EIC_EXTINT_NUM _L_(5) /**< EIC signal: PIN_PA16 External Interrupt Line */
#define PIN_PA17A_EIC_EXTINT6 _L_(17) /**< EIC signal: EXTINT6 on PA17 mux A*/
#define MUX_PA17A_EIC_EXTINT6 _L_(0)
#define PINMUX_PA17A_EIC_EXTINT6 ((PIN_PA17A_EIC_EXTINT6 << 16) | MUX_PA17A_EIC_EXTINT6)
#define PORT_PA17A_EIC_EXTINT6 (_UL_(1) << 17)
#define PIN_PA17A_EIC_EXTINT_NUM _L_(6) /**< EIC signal: PIN_PA17 External Interrupt Line */
#define PIN_PA30A_EIC_EXTINT6 _L_(30) /**< EIC signal: EXTINT6 on PA30 mux A*/
#define MUX_PA30A_EIC_EXTINT6 _L_(0)
#define PINMUX_PA30A_EIC_EXTINT6 ((PIN_PA30A_EIC_EXTINT6 << 16) | MUX_PA30A_EIC_EXTINT6)
#define PORT_PA30A_EIC_EXTINT6 (_UL_(1) << 30)
#define PIN_PA30A_EIC_EXTINT_NUM _L_(6) /**< EIC signal: PIN_PA30 External Interrupt Line */
#define PIN_PA18A_EIC_EXTINT7 _L_(18) /**< EIC signal: EXTINT7 on PA18 mux A*/
#define MUX_PA18A_EIC_EXTINT7 _L_(0)
#define PINMUX_PA18A_EIC_EXTINT7 ((PIN_PA18A_EIC_EXTINT7 << 16) | MUX_PA18A_EIC_EXTINT7)
#define PORT_PA18A_EIC_EXTINT7 (_UL_(1) << 18)
#define PIN_PA18A_EIC_EXTINT_NUM _L_(7) /**< EIC signal: PIN_PA18 External Interrupt Line */
#define PIN_PA31A_EIC_EXTINT7 _L_(31) /**< EIC signal: EXTINT7 on PA31 mux A*/
#define MUX_PA31A_EIC_EXTINT7 _L_(0)
#define PINMUX_PA31A_EIC_EXTINT7 ((PIN_PA31A_EIC_EXTINT7 << 16) | MUX_PA31A_EIC_EXTINT7)
#define PORT_PA31A_EIC_EXTINT7 (_UL_(1) << 31)
#define PIN_PA31A_EIC_EXTINT_NUM _L_(7) /**< EIC signal: PIN_PA31 External Interrupt Line */
#define PIN_PA08A_EIC_NMI _L_(8) /**< EIC signal: NMI on PA08 mux A*/
#define MUX_PA08A_EIC_NMI _L_(0)
#define PINMUX_PA08A_EIC_NMI ((PIN_PA08A_EIC_NMI << 16) | MUX_PA08A_EIC_NMI)
#define PORT_PA08A_EIC_NMI (_UL_(1) << 8)
/* ========== PORT definition for GCLK peripheral ========== */
#define PIN_PA30H_GCLK_IO0 _L_(30) /**< GCLK signal: IO0 on PA30 mux H*/
#define MUX_PA30H_GCLK_IO0 _L_(7)
#define PINMUX_PA30H_GCLK_IO0 ((PIN_PA30H_GCLK_IO0 << 16) | MUX_PA30H_GCLK_IO0)
#define PORT_PA30H_GCLK_IO0 (_UL_(1) << 30)
#define PIN_PA14H_GCLK_IO0 _L_(14) /**< GCLK signal: IO0 on PA14 mux H*/
#define MUX_PA14H_GCLK_IO0 _L_(7)
#define PINMUX_PA14H_GCLK_IO0 ((PIN_PA14H_GCLK_IO0 << 16) | MUX_PA14H_GCLK_IO0)
#define PORT_PA14H_GCLK_IO0 (_UL_(1) << 14)
#define PIN_PA23H_GCLK_IO1 _L_(23) /**< GCLK signal: IO1 on PA23 mux H*/
#define MUX_PA23H_GCLK_IO1 _L_(7)
#define PINMUX_PA23H_GCLK_IO1 ((PIN_PA23H_GCLK_IO1 << 16) | MUX_PA23H_GCLK_IO1)
#define PORT_PA23H_GCLK_IO1 (_UL_(1) << 23)
#define PIN_PA15H_GCLK_IO1 _L_(15) /**< GCLK signal: IO1 on PA15 mux H*/
#define MUX_PA15H_GCLK_IO1 _L_(7)
#define PINMUX_PA15H_GCLK_IO1 ((PIN_PA15H_GCLK_IO1 << 16) | MUX_PA15H_GCLK_IO1)
#define PORT_PA15H_GCLK_IO1 (_UL_(1) << 15)
#define PIN_PA16H_GCLK_IO2 _L_(16) /**< GCLK signal: IO2 on PA16 mux H*/
#define MUX_PA16H_GCLK_IO2 _L_(7)
#define PINMUX_PA16H_GCLK_IO2 ((PIN_PA16H_GCLK_IO2 << 16) | MUX_PA16H_GCLK_IO2)
#define PORT_PA16H_GCLK_IO2 (_UL_(1) << 16)
#define PIN_PA22H_GCLK_IO2 _L_(22) /**< GCLK signal: IO2 on PA22 mux H*/
#define MUX_PA22H_GCLK_IO2 _L_(7)
#define PINMUX_PA22H_GCLK_IO2 ((PIN_PA22H_GCLK_IO2 << 16) | MUX_PA22H_GCLK_IO2)
#define PORT_PA22H_GCLK_IO2 (_UL_(1) << 22)
#define PIN_PA17H_GCLK_IO3 _L_(17) /**< GCLK signal: IO3 on PA17 mux H*/
#define MUX_PA17H_GCLK_IO3 _L_(7)
#define PINMUX_PA17H_GCLK_IO3 ((PIN_PA17H_GCLK_IO3 << 16) | MUX_PA17H_GCLK_IO3)
#define PORT_PA17H_GCLK_IO3 (_UL_(1) << 17)
/* ========== PORT definition for OPAMP peripheral ========== */
#define PIN_PA02B_OPAMP_OANEG0 _L_(2) /**< OPAMP signal: OANEG0 on PA02 mux B*/
#define MUX_PA02B_OPAMP_OANEG0 _L_(1)
#define PINMUX_PA02B_OPAMP_OANEG0 ((PIN_PA02B_OPAMP_OANEG0 << 16) | MUX_PA02B_OPAMP_OANEG0)
#define PORT_PA02B_OPAMP_OANEG0 (_UL_(1) << 2)
#define PIN_PA00B_OPAMP_OANEG1 _L_(0) /**< OPAMP signal: OANEG1 on PA00 mux B*/
#define MUX_PA00B_OPAMP_OANEG1 _L_(1)
#define PINMUX_PA00B_OPAMP_OANEG1 ((PIN_PA00B_OPAMP_OANEG1 << 16) | MUX_PA00B_OPAMP_OANEG1)
#define PORT_PA00B_OPAMP_OANEG1 (_UL_(1) << 0)
#define PIN_PA03B_OPAMP_OANEG2 _L_(3) /**< OPAMP signal: OANEG2 on PA03 mux B*/
#define MUX_PA03B_OPAMP_OANEG2 _L_(1)
#define PINMUX_PA03B_OPAMP_OANEG2 ((PIN_PA03B_OPAMP_OANEG2 << 16) | MUX_PA03B_OPAMP_OANEG2)
#define PORT_PA03B_OPAMP_OANEG2 (_UL_(1) << 3)
#define PIN_PA04B_OPAMP_OAOUT2 _L_(4) /**< OPAMP signal: OAOUT2 on PA04 mux B*/
#define MUX_PA04B_OPAMP_OAOUT2 _L_(1)
#define PINMUX_PA04B_OPAMP_OAOUT2 ((PIN_PA04B_OPAMP_OAOUT2 << 16) | MUX_PA04B_OPAMP_OAOUT2)
#define PORT_PA04B_OPAMP_OAOUT2 (_UL_(1) << 4)
#define PIN_PA01B_OPAMP_OAPOS1 _L_(1) /**< OPAMP signal: OAPOS1 on PA01 mux B*/
#define MUX_PA01B_OPAMP_OAPOS1 _L_(1)
#define PINMUX_PA01B_OPAMP_OAPOS1 ((PIN_PA01B_OPAMP_OAPOS1 << 16) | MUX_PA01B_OPAMP_OAPOS1)
#define PORT_PA01B_OPAMP_OAPOS1 (_UL_(1) << 1)
#define PIN_PA05B_OPAMP_OAPOS2 _L_(5) /**< OPAMP signal: OAPOS2 on PA05 mux B*/
#define MUX_PA05B_OPAMP_OAPOS2 _L_(1)
#define PINMUX_PA05B_OPAMP_OAPOS2 ((PIN_PA05B_OPAMP_OAPOS2 << 16) | MUX_PA05B_OPAMP_OAPOS2)
#define PORT_PA05B_OPAMP_OAPOS2 (_UL_(1) << 5)
/* ========== PORT definition for PTC peripheral ========== */
#define PIN_PA00F_PTC_DRV0 _L_(0) /**< PTC signal: DRV0 on PA00 mux F*/
#define MUX_PA00F_PTC_DRV0 _L_(5)
#define PINMUX_PA00F_PTC_DRV0 ((PIN_PA00F_PTC_DRV0 << 16) | MUX_PA00F_PTC_DRV0)
#define PORT_PA00F_PTC_DRV0 (_UL_(1) << 0)
#define PIN_PA01F_PTC_DRV1 _L_(1) /**< PTC signal: DRV1 on PA01 mux F*/
#define MUX_PA01F_PTC_DRV1 _L_(5)
#define PINMUX_PA01F_PTC_DRV1 ((PIN_PA01F_PTC_DRV1 << 16) | MUX_PA01F_PTC_DRV1)
#define PORT_PA01F_PTC_DRV1 (_UL_(1) << 1)
#define PIN_PA02F_PTC_DRV2 _L_(2) /**< PTC signal: DRV2 on PA02 mux F*/
#define MUX_PA02F_PTC_DRV2 _L_(5)
#define PINMUX_PA02F_PTC_DRV2 ((PIN_PA02F_PTC_DRV2 << 16) | MUX_PA02F_PTC_DRV2)
#define PORT_PA02F_PTC_DRV2 (_UL_(1) << 2)
#define PIN_PA03F_PTC_DRV3 _L_(3) /**< PTC signal: DRV3 on PA03 mux F*/
#define MUX_PA03F_PTC_DRV3 _L_(5)
#define PINMUX_PA03F_PTC_DRV3 ((PIN_PA03F_PTC_DRV3 << 16) | MUX_PA03F_PTC_DRV3)
#define PORT_PA03F_PTC_DRV3 (_UL_(1) << 3)
#define PIN_PA05F_PTC_DRV4 _L_(5) /**< PTC signal: DRV4 on PA05 mux F*/
#define MUX_PA05F_PTC_DRV4 _L_(5)
#define PINMUX_PA05F_PTC_DRV4 ((PIN_PA05F_PTC_DRV4 << 16) | MUX_PA05F_PTC_DRV4)
#define PORT_PA05F_PTC_DRV4 (_UL_(1) << 5)
#define PIN_PA08F_PTC_DRV6 _L_(8) /**< PTC signal: DRV6 on PA08 mux F*/
#define MUX_PA08F_PTC_DRV6 _L_(5)
#define PINMUX_PA08F_PTC_DRV6 ((PIN_PA08F_PTC_DRV6 << 16) | MUX_PA08F_PTC_DRV6)
#define PORT_PA08F_PTC_DRV6 (_UL_(1) << 8)
#define PIN_PA14F_PTC_DRV10 _L_(14) /**< PTC signal: DRV10 on PA14 mux F*/
#define MUX_PA14F_PTC_DRV10 _L_(5)
#define PINMUX_PA14F_PTC_DRV10 ((PIN_PA14F_PTC_DRV10 << 16) | MUX_PA14F_PTC_DRV10)
#define PORT_PA14F_PTC_DRV10 (_UL_(1) << 14)
#define PIN_PA15F_PTC_DRV11 _L_(15) /**< PTC signal: DRV11 on PA15 mux F*/
#define MUX_PA15F_PTC_DRV11 _L_(5)
#define PINMUX_PA15F_PTC_DRV11 ((PIN_PA15F_PTC_DRV11 << 16) | MUX_PA15F_PTC_DRV11)
#define PORT_PA15F_PTC_DRV11 (_UL_(1) << 15)
#define PIN_PA16F_PTC_DRV12 _L_(16) /**< PTC signal: DRV12 on PA16 mux F*/
#define MUX_PA16F_PTC_DRV12 _L_(5)
#define PINMUX_PA16F_PTC_DRV12 ((PIN_PA16F_PTC_DRV12 << 16) | MUX_PA16F_PTC_DRV12)
#define PORT_PA16F_PTC_DRV12 (_UL_(1) << 16)
#define PIN_PA17F_PTC_DRV13 _L_(17) /**< PTC signal: DRV13 on PA17 mux F*/
#define MUX_PA17F_PTC_DRV13 _L_(5)
#define PINMUX_PA17F_PTC_DRV13 ((PIN_PA17F_PTC_DRV13 << 16) | MUX_PA17F_PTC_DRV13)
#define PORT_PA17F_PTC_DRV13 (_UL_(1) << 17)
#define PIN_PA18F_PTC_DRV14 _L_(18) /**< PTC signal: DRV14 on PA18 mux F*/
#define MUX_PA18F_PTC_DRV14 _L_(5)
#define PINMUX_PA18F_PTC_DRV14 ((PIN_PA18F_PTC_DRV14 << 16) | MUX_PA18F_PTC_DRV14)
#define PORT_PA18F_PTC_DRV14 (_UL_(1) << 18)
#define PIN_PA19F_PTC_DRV15 _L_(19) /**< PTC signal: DRV15 on PA19 mux F*/
#define MUX_PA19F_PTC_DRV15 _L_(5)
#define PINMUX_PA19F_PTC_DRV15 ((PIN_PA19F_PTC_DRV15 << 16) | MUX_PA19F_PTC_DRV15)
#define PORT_PA19F_PTC_DRV15 (_UL_(1) << 19)
#define PIN_PA22F_PTC_DRV16 _L_(22) /**< PTC signal: DRV16 on PA22 mux F*/
#define MUX_PA22F_PTC_DRV16 _L_(5)
#define PINMUX_PA22F_PTC_DRV16 ((PIN_PA22F_PTC_DRV16 << 16) | MUX_PA22F_PTC_DRV16)
#define PORT_PA22F_PTC_DRV16 (_UL_(1) << 22)
#define PIN_PA23F_PTC_DRV17 _L_(23) /**< PTC signal: DRV17 on PA23 mux F*/
#define MUX_PA23F_PTC_DRV17 _L_(5)
#define PINMUX_PA23F_PTC_DRV17 ((PIN_PA23F_PTC_DRV17 << 16) | MUX_PA23F_PTC_DRV17)
#define PORT_PA23F_PTC_DRV17 (_UL_(1) << 23)
#define PIN_PA30F_PTC_DRV18 _L_(30) /**< PTC signal: DRV18 on PA30 mux F*/
#define MUX_PA30F_PTC_DRV18 _L_(5)
#define PINMUX_PA30F_PTC_DRV18 ((PIN_PA30F_PTC_DRV18 << 16) | MUX_PA30F_PTC_DRV18)
#define PORT_PA30F_PTC_DRV18 (_UL_(1) << 30)
#define PIN_PA31F_PTC_DRV19 _L_(31) /**< PTC signal: DRV19 on PA31 mux F*/
#define MUX_PA31F_PTC_DRV19 _L_(5)
#define PINMUX_PA31F_PTC_DRV19 ((PIN_PA31F_PTC_DRV19 << 16) | MUX_PA31F_PTC_DRV19)
#define PORT_PA31F_PTC_DRV19 (_UL_(1) << 31)
#define PIN_PA03B_PTC_ECI0 _L_(3) /**< PTC signal: ECI0 on PA03 mux B*/
#define MUX_PA03B_PTC_ECI0 _L_(1)
#define PINMUX_PA03B_PTC_ECI0 ((PIN_PA03B_PTC_ECI0 << 16) | MUX_PA03B_PTC_ECI0)
#define PORT_PA03B_PTC_ECI0 (_UL_(1) << 3)
#define PIN_PA04B_PTC_ECI1 _L_(4) /**< PTC signal: ECI1 on PA04 mux B*/
#define MUX_PA04B_PTC_ECI1 _L_(1)
#define PINMUX_PA04B_PTC_ECI1 ((PIN_PA04B_PTC_ECI1 << 16) | MUX_PA04B_PTC_ECI1)
#define PORT_PA04B_PTC_ECI1 (_UL_(1) << 4)
#define PIN_PA05B_PTC_ECI2 _L_(5) /**< PTC signal: ECI2 on PA05 mux B*/
#define MUX_PA05B_PTC_ECI2 _L_(1)
#define PINMUX_PA05B_PTC_ECI2 ((PIN_PA05B_PTC_ECI2 << 16) | MUX_PA05B_PTC_ECI2)
#define PORT_PA05B_PTC_ECI2 (_UL_(1) << 5)
#define PIN_PA00B_PTC_X0 _L_(0) /**< PTC signal: X0 on PA00 mux B*/
#define MUX_PA00B_PTC_X0 _L_(1)
#define PINMUX_PA00B_PTC_X0 ((PIN_PA00B_PTC_X0 << 16) | MUX_PA00B_PTC_X0)
#define PORT_PA00B_PTC_X0 (_UL_(1) << 0)
#define PIN_PA00B_PTC_Y0 _L_(0) /**< PTC signal: Y0 on PA00 mux B*/
#define MUX_PA00B_PTC_Y0 _L_(1)
#define PINMUX_PA00B_PTC_Y0 ((PIN_PA00B_PTC_Y0 << 16) | MUX_PA00B_PTC_Y0)
#define PORT_PA00B_PTC_Y0 (_UL_(1) << 0)
#define PIN_PA01B_PTC_X1 _L_(1) /**< PTC signal: X1 on PA01 mux B*/
#define MUX_PA01B_PTC_X1 _L_(1)
#define PINMUX_PA01B_PTC_X1 ((PIN_PA01B_PTC_X1 << 16) | MUX_PA01B_PTC_X1)
#define PORT_PA01B_PTC_X1 (_UL_(1) << 1)
#define PIN_PA01B_PTC_Y1 _L_(1) /**< PTC signal: Y1 on PA01 mux B*/
#define MUX_PA01B_PTC_Y1 _L_(1)
#define PINMUX_PA01B_PTC_Y1 ((PIN_PA01B_PTC_Y1 << 16) | MUX_PA01B_PTC_Y1)
#define PORT_PA01B_PTC_Y1 (_UL_(1) << 1)
#define PIN_PA02B_PTC_X2 _L_(2) /**< PTC signal: X2 on PA02 mux B*/
#define MUX_PA02B_PTC_X2 _L_(1)
#define PINMUX_PA02B_PTC_X2 ((PIN_PA02B_PTC_X2 << 16) | MUX_PA02B_PTC_X2)
#define PORT_PA02B_PTC_X2 (_UL_(1) << 2)
#define PIN_PA02B_PTC_Y2 _L_(2) /**< PTC signal: Y2 on PA02 mux B*/
#define MUX_PA02B_PTC_Y2 _L_(1)
#define PINMUX_PA02B_PTC_Y2 ((PIN_PA02B_PTC_Y2 << 16) | MUX_PA02B_PTC_Y2)
#define PORT_PA02B_PTC_Y2 (_UL_(1) << 2)
#define PIN_PA03B_PTC_X3 _L_(3) /**< PTC signal: X3 on PA03 mux B*/
#define MUX_PA03B_PTC_X3 _L_(1)
#define PINMUX_PA03B_PTC_X3 ((PIN_PA03B_PTC_X3 << 16) | MUX_PA03B_PTC_X3)
#define PORT_PA03B_PTC_X3 (_UL_(1) << 3)
#define PIN_PA03B_PTC_Y3 _L_(3) /**< PTC signal: Y3 on PA03 mux B*/
#define MUX_PA03B_PTC_Y3 _L_(1)
#define PINMUX_PA03B_PTC_Y3 ((PIN_PA03B_PTC_Y3 << 16) | MUX_PA03B_PTC_Y3)
#define PORT_PA03B_PTC_Y3 (_UL_(1) << 3)
#define PIN_PA05B_PTC_X4 _L_(5) /**< PTC signal: X4 on PA05 mux B*/
#define MUX_PA05B_PTC_X4 _L_(1)
#define PINMUX_PA05B_PTC_X4 ((PIN_PA05B_PTC_X4 << 16) | MUX_PA05B_PTC_X4)
#define PORT_PA05B_PTC_X4 (_UL_(1) << 5)
#define PIN_PA05B_PTC_Y4 _L_(5) /**< PTC signal: Y4 on PA05 mux B*/
#define MUX_PA05B_PTC_Y4 _L_(1)
#define PINMUX_PA05B_PTC_Y4 ((PIN_PA05B_PTC_Y4 << 16) | MUX_PA05B_PTC_Y4)
#define PORT_PA05B_PTC_Y4 (_UL_(1) << 5)
#define PIN_PA08B_PTC_X6 _L_(8) /**< PTC signal: X6 on PA08 mux B*/
#define MUX_PA08B_PTC_X6 _L_(1)
#define PINMUX_PA08B_PTC_X6 ((PIN_PA08B_PTC_X6 << 16) | MUX_PA08B_PTC_X6)
#define PORT_PA08B_PTC_X6 (_UL_(1) << 8)
#define PIN_PA08B_PTC_Y6 _L_(8) /**< PTC signal: Y6 on PA08 mux B*/
#define MUX_PA08B_PTC_Y6 _L_(1)
#define PINMUX_PA08B_PTC_Y6 ((PIN_PA08B_PTC_Y6 << 16) | MUX_PA08B_PTC_Y6)
#define PORT_PA08B_PTC_Y6 (_UL_(1) << 8)
#define PIN_PA14B_PTC_X10 _L_(14) /**< PTC signal: X10 on PA14 mux B*/
#define MUX_PA14B_PTC_X10 _L_(1)
#define PINMUX_PA14B_PTC_X10 ((PIN_PA14B_PTC_X10 << 16) | MUX_PA14B_PTC_X10)
#define PORT_PA14B_PTC_X10 (_UL_(1) << 14)
#define PIN_PA14B_PTC_Y10 _L_(14) /**< PTC signal: Y10 on PA14 mux B*/
#define MUX_PA14B_PTC_Y10 _L_(1)
#define PINMUX_PA14B_PTC_Y10 ((PIN_PA14B_PTC_Y10 << 16) | MUX_PA14B_PTC_Y10)
#define PORT_PA14B_PTC_Y10 (_UL_(1) << 14)
#define PIN_PA15B_PTC_X11 _L_(15) /**< PTC signal: X11 on PA15 mux B*/
#define MUX_PA15B_PTC_X11 _L_(1)
#define PINMUX_PA15B_PTC_X11 ((PIN_PA15B_PTC_X11 << 16) | MUX_PA15B_PTC_X11)
#define PORT_PA15B_PTC_X11 (_UL_(1) << 15)
#define PIN_PA15B_PTC_Y11 _L_(15) /**< PTC signal: Y11 on PA15 mux B*/
#define MUX_PA15B_PTC_Y11 _L_(1)
#define PINMUX_PA15B_PTC_Y11 ((PIN_PA15B_PTC_Y11 << 16) | MUX_PA15B_PTC_Y11)
#define PORT_PA15B_PTC_Y11 (_UL_(1) << 15)
#define PIN_PA16B_PTC_X12 _L_(16) /**< PTC signal: X12 on PA16 mux B*/
#define MUX_PA16B_PTC_X12 _L_(1)
#define PINMUX_PA16B_PTC_X12 ((PIN_PA16B_PTC_X12 << 16) | MUX_PA16B_PTC_X12)
#define PORT_PA16B_PTC_X12 (_UL_(1) << 16)
#define PIN_PA16B_PTC_Y12 _L_(16) /**< PTC signal: Y12 on PA16 mux B*/
#define MUX_PA16B_PTC_Y12 _L_(1)
#define PINMUX_PA16B_PTC_Y12 ((PIN_PA16B_PTC_Y12 << 16) | MUX_PA16B_PTC_Y12)
#define PORT_PA16B_PTC_Y12 (_UL_(1) << 16)
#define PIN_PA17B_PTC_X13 _L_(17) /**< PTC signal: X13 on PA17 mux B*/
#define MUX_PA17B_PTC_X13 _L_(1)
#define PINMUX_PA17B_PTC_X13 ((PIN_PA17B_PTC_X13 << 16) | MUX_PA17B_PTC_X13)
#define PORT_PA17B_PTC_X13 (_UL_(1) << 17)
#define PIN_PA17B_PTC_Y13 _L_(17) /**< PTC signal: Y13 on PA17 mux B*/
#define MUX_PA17B_PTC_Y13 _L_(1)
#define PINMUX_PA17B_PTC_Y13 ((PIN_PA17B_PTC_Y13 << 16) | MUX_PA17B_PTC_Y13)
#define PORT_PA17B_PTC_Y13 (_UL_(1) << 17)
#define PIN_PA18B_PTC_X14 _L_(18) /**< PTC signal: X14 on PA18 mux B*/
#define MUX_PA18B_PTC_X14 _L_(1)
#define PINMUX_PA18B_PTC_X14 ((PIN_PA18B_PTC_X14 << 16) | MUX_PA18B_PTC_X14)
#define PORT_PA18B_PTC_X14 (_UL_(1) << 18)
#define PIN_PA18B_PTC_Y14 _L_(18) /**< PTC signal: Y14 on PA18 mux B*/
#define MUX_PA18B_PTC_Y14 _L_(1)
#define PINMUX_PA18B_PTC_Y14 ((PIN_PA18B_PTC_Y14 << 16) | MUX_PA18B_PTC_Y14)
#define PORT_PA18B_PTC_Y14 (_UL_(1) << 18)
#define PIN_PA19B_PTC_X15 _L_(19) /**< PTC signal: X15 on PA19 mux B*/
#define MUX_PA19B_PTC_X15 _L_(1)
#define PINMUX_PA19B_PTC_X15 ((PIN_PA19B_PTC_X15 << 16) | MUX_PA19B_PTC_X15)
#define PORT_PA19B_PTC_X15 (_UL_(1) << 19)
#define PIN_PA19B_PTC_Y15 _L_(19) /**< PTC signal: Y15 on PA19 mux B*/
#define MUX_PA19B_PTC_Y15 _L_(1)
#define PINMUX_PA19B_PTC_Y15 ((PIN_PA19B_PTC_Y15 << 16) | MUX_PA19B_PTC_Y15)
#define PORT_PA19B_PTC_Y15 (_UL_(1) << 19)
#define PIN_PA22B_PTC_X16 _L_(22) /**< PTC signal: X16 on PA22 mux B*/
#define MUX_PA22B_PTC_X16 _L_(1)
#define PINMUX_PA22B_PTC_X16 ((PIN_PA22B_PTC_X16 << 16) | MUX_PA22B_PTC_X16)
#define PORT_PA22B_PTC_X16 (_UL_(1) << 22)
#define PIN_PA22B_PTC_Y16 _L_(22) /**< PTC signal: Y16 on PA22 mux B*/
#define MUX_PA22B_PTC_Y16 _L_(1)
#define PINMUX_PA22B_PTC_Y16 ((PIN_PA22B_PTC_Y16 << 16) | MUX_PA22B_PTC_Y16)
#define PORT_PA22B_PTC_Y16 (_UL_(1) << 22)
#define PIN_PA23B_PTC_X17 _L_(23) /**< PTC signal: X17 on PA23 mux B*/
#define MUX_PA23B_PTC_X17 _L_(1)
#define PINMUX_PA23B_PTC_X17 ((PIN_PA23B_PTC_X17 << 16) | MUX_PA23B_PTC_X17)
#define PORT_PA23B_PTC_X17 (_UL_(1) << 23)
#define PIN_PA23B_PTC_Y17 _L_(23) /**< PTC signal: Y17 on PA23 mux B*/
#define MUX_PA23B_PTC_Y17 _L_(1)
#define PINMUX_PA23B_PTC_Y17 ((PIN_PA23B_PTC_Y17 << 16) | MUX_PA23B_PTC_Y17)
#define PORT_PA23B_PTC_Y17 (_UL_(1) << 23)
#define PIN_PA30B_PTC_X18 _L_(30) /**< PTC signal: X18 on PA30 mux B*/
#define MUX_PA30B_PTC_X18 _L_(1)
#define PINMUX_PA30B_PTC_X18 ((PIN_PA30B_PTC_X18 << 16) | MUX_PA30B_PTC_X18)
#define PORT_PA30B_PTC_X18 (_UL_(1) << 30)
#define PIN_PA30B_PTC_Y18 _L_(30) /**< PTC signal: Y18 on PA30 mux B*/
#define MUX_PA30B_PTC_Y18 _L_(1)
#define PINMUX_PA30B_PTC_Y18 ((PIN_PA30B_PTC_Y18 << 16) | MUX_PA30B_PTC_Y18)
#define PORT_PA30B_PTC_Y18 (_UL_(1) << 30)
#define PIN_PA31B_PTC_X19 _L_(31) /**< PTC signal: X19 on PA31 mux B*/
#define MUX_PA31B_PTC_X19 _L_(1)
#define PINMUX_PA31B_PTC_X19 ((PIN_PA31B_PTC_X19 << 16) | MUX_PA31B_PTC_X19)
#define PORT_PA31B_PTC_X19 (_UL_(1) << 31)
#define PIN_PA31B_PTC_Y19 _L_(31) /**< PTC signal: Y19 on PA31 mux B*/
#define MUX_PA31B_PTC_Y19 _L_(1)
#define PINMUX_PA31B_PTC_Y19 ((PIN_PA31B_PTC_Y19 << 16) | MUX_PA31B_PTC_Y19)
#define PORT_PA31B_PTC_Y19 (_UL_(1) << 31)
/* ========== PORT definition for RTC peripheral ========== */
#define PIN_PA08G_RTC_IN0 _L_(8) /**< RTC signal: IN0 on PA08 mux G*/
#define MUX_PA08G_RTC_IN0 _L_(6)
#define PINMUX_PA08G_RTC_IN0 ((PIN_PA08G_RTC_IN0 << 16) | MUX_PA08G_RTC_IN0)
#define PORT_PA08G_RTC_IN0 (_UL_(1) << 8)
#define PIN_PA16G_RTC_IN2 _L_(16) /**< RTC signal: IN2 on PA16 mux G*/
#define MUX_PA16G_RTC_IN2 _L_(6)
#define PINMUX_PA16G_RTC_IN2 ((PIN_PA16G_RTC_IN2 << 16) | MUX_PA16G_RTC_IN2)
#define PORT_PA16G_RTC_IN2 (_UL_(1) << 16)
#define PIN_PA17G_RTC_IN3 _L_(17) /**< RTC signal: IN3 on PA17 mux G*/
#define MUX_PA17G_RTC_IN3 _L_(6)
#define PINMUX_PA17G_RTC_IN3 ((PIN_PA17G_RTC_IN3 << 16) | MUX_PA17G_RTC_IN3)
#define PORT_PA17G_RTC_IN3 (_UL_(1) << 17)
#define PIN_PA18G_RTC_OUT0 _L_(18) /**< RTC signal: OUT0 on PA18 mux G*/
#define MUX_PA18G_RTC_OUT0 _L_(6)
#define PINMUX_PA18G_RTC_OUT0 ((PIN_PA18G_RTC_OUT0 << 16) | MUX_PA18G_RTC_OUT0)
#define PORT_PA18G_RTC_OUT0 (_UL_(1) << 18)
#define PIN_PA19G_RTC_OUT1 _L_(19) /**< RTC signal: OUT1 on PA19 mux G*/
#define MUX_PA19G_RTC_OUT1 _L_(6)
#define PINMUX_PA19G_RTC_OUT1 ((PIN_PA19G_RTC_OUT1 << 16) | MUX_PA19G_RTC_OUT1)
#define PORT_PA19G_RTC_OUT1 (_UL_(1) << 19)
#define PIN_PA22G_RTC_OUT2 _L_(22) /**< RTC signal: OUT2 on PA22 mux G*/
#define MUX_PA22G_RTC_OUT2 _L_(6)
#define PINMUX_PA22G_RTC_OUT2 ((PIN_PA22G_RTC_OUT2 << 16) | MUX_PA22G_RTC_OUT2)
#define PORT_PA22G_RTC_OUT2 (_UL_(1) << 22)
#define PIN_PA23G_RTC_OUT3 _L_(23) /**< RTC signal: OUT3 on PA23 mux G*/
#define MUX_PA23G_RTC_OUT3 _L_(6)
#define PINMUX_PA23G_RTC_OUT3 ((PIN_PA23G_RTC_OUT3 << 16) | MUX_PA23G_RTC_OUT3)
#define PORT_PA23G_RTC_OUT3 (_UL_(1) << 23)
/* ========== PORT definition for SERCOM0 peripheral ========== */
#define PIN_PA04D_SERCOM0_PAD0 _L_(4) /**< SERCOM0 signal: PAD0 on PA04 mux D*/
#define MUX_PA04D_SERCOM0_PAD0 _L_(3)
#define PINMUX_PA04D_SERCOM0_PAD0 ((PIN_PA04D_SERCOM0_PAD0 << 16) | MUX_PA04D_SERCOM0_PAD0)
#define PORT_PA04D_SERCOM0_PAD0 (_UL_(1) << 4)
#define PIN_PA16D_SERCOM0_PAD0 _L_(16) /**< SERCOM0 signal: PAD0 on PA16 mux D*/
#define MUX_PA16D_SERCOM0_PAD0 _L_(3)
#define PINMUX_PA16D_SERCOM0_PAD0 ((PIN_PA16D_SERCOM0_PAD0 << 16) | MUX_PA16D_SERCOM0_PAD0)
#define PORT_PA16D_SERCOM0_PAD0 (_UL_(1) << 16)
#define PIN_PA22C_SERCOM0_PAD0 _L_(22) /**< SERCOM0 signal: PAD0 on PA22 mux C*/
#define MUX_PA22C_SERCOM0_PAD0 _L_(2)
#define PINMUX_PA22C_SERCOM0_PAD0 ((PIN_PA22C_SERCOM0_PAD0 << 16) | MUX_PA22C_SERCOM0_PAD0)
#define PORT_PA22C_SERCOM0_PAD0 (_UL_(1) << 22)
#define PIN_PA05D_SERCOM0_PAD1 _L_(5) /**< SERCOM0 signal: PAD1 on PA05 mux D*/
#define MUX_PA05D_SERCOM0_PAD1 _L_(3)
#define PINMUX_PA05D_SERCOM0_PAD1 ((PIN_PA05D_SERCOM0_PAD1 << 16) | MUX_PA05D_SERCOM0_PAD1)
#define PORT_PA05D_SERCOM0_PAD1 (_UL_(1) << 5)
#define PIN_PA17D_SERCOM0_PAD1 _L_(17) /**< SERCOM0 signal: PAD1 on PA17 mux D*/
#define MUX_PA17D_SERCOM0_PAD1 _L_(3)
#define PINMUX_PA17D_SERCOM0_PAD1 ((PIN_PA17D_SERCOM0_PAD1 << 16) | MUX_PA17D_SERCOM0_PAD1)
#define PORT_PA17D_SERCOM0_PAD1 (_UL_(1) << 17)
#define PIN_PA23C_SERCOM0_PAD1 _L_(23) /**< SERCOM0 signal: PAD1 on PA23 mux C*/
#define MUX_PA23C_SERCOM0_PAD1 _L_(2)
#define PINMUX_PA23C_SERCOM0_PAD1 ((PIN_PA23C_SERCOM0_PAD1 << 16) | MUX_PA23C_SERCOM0_PAD1)
#define PORT_PA23C_SERCOM0_PAD1 (_UL_(1) << 23)
#define PIN_PA14D_SERCOM0_PAD2 _L_(14) /**< SERCOM0 signal: PAD2 on PA14 mux D*/
#define MUX_PA14D_SERCOM0_PAD2 _L_(3)
#define PINMUX_PA14D_SERCOM0_PAD2 ((PIN_PA14D_SERCOM0_PAD2 << 16) | MUX_PA14D_SERCOM0_PAD2)
#define PORT_PA14D_SERCOM0_PAD2 (_UL_(1) << 14)
#define PIN_PA18D_SERCOM0_PAD2 _L_(18) /**< SERCOM0 signal: PAD2 on PA18 mux D*/
#define MUX_PA18D_SERCOM0_PAD2 _L_(3)
#define PINMUX_PA18D_SERCOM0_PAD2 ((PIN_PA18D_SERCOM0_PAD2 << 16) | MUX_PA18D_SERCOM0_PAD2)
#define PORT_PA18D_SERCOM0_PAD2 (_UL_(1) << 18)
#define PIN_PA02D_SERCOM0_PAD2 _L_(2) /**< SERCOM0 signal: PAD2 on PA02 mux D*/
#define MUX_PA02D_SERCOM0_PAD2 _L_(3)
#define PINMUX_PA02D_SERCOM0_PAD2 ((PIN_PA02D_SERCOM0_PAD2 << 16) | MUX_PA02D_SERCOM0_PAD2)
#define PORT_PA02D_SERCOM0_PAD2 (_UL_(1) << 2)
#define PIN_PA15D_SERCOM0_PAD3 _L_(15) /**< SERCOM0 signal: PAD3 on PA15 mux D*/
#define MUX_PA15D_SERCOM0_PAD3 _L_(3)
#define PINMUX_PA15D_SERCOM0_PAD3 ((PIN_PA15D_SERCOM0_PAD3 << 16) | MUX_PA15D_SERCOM0_PAD3)
#define PORT_PA15D_SERCOM0_PAD3 (_UL_(1) << 15)
#define PIN_PA19D_SERCOM0_PAD3 _L_(19) /**< SERCOM0 signal: PAD3 on PA19 mux D*/
#define MUX_PA19D_SERCOM0_PAD3 _L_(3)
#define PINMUX_PA19D_SERCOM0_PAD3 ((PIN_PA19D_SERCOM0_PAD3 << 16) | MUX_PA19D_SERCOM0_PAD3)
#define PORT_PA19D_SERCOM0_PAD3 (_UL_(1) << 19)
#define PIN_PA03D_SERCOM0_PAD3 _L_(3) /**< SERCOM0 signal: PAD3 on PA03 mux D*/
#define MUX_PA03D_SERCOM0_PAD3 _L_(3)
#define PINMUX_PA03D_SERCOM0_PAD3 ((PIN_PA03D_SERCOM0_PAD3 << 16) | MUX_PA03D_SERCOM0_PAD3)
#define PORT_PA03D_SERCOM0_PAD3 (_UL_(1) << 3)
/* ========== PORT definition for SERCOM1 peripheral ========== */
#define PIN_PA16C_SERCOM1_PAD0 _L_(16) /**< SERCOM1 signal: PAD0 on PA16 mux C*/
#define MUX_PA16C_SERCOM1_PAD0 _L_(2)
#define PINMUX_PA16C_SERCOM1_PAD0 ((PIN_PA16C_SERCOM1_PAD0 << 16) | MUX_PA16C_SERCOM1_PAD0)
#define PORT_PA16C_SERCOM1_PAD0 (_UL_(1) << 16)
#define PIN_PA08C_SERCOM1_PAD0 _L_(8) /**< SERCOM1 signal: PAD0 on PA08 mux C*/
#define MUX_PA08C_SERCOM1_PAD0 _L_(2)
#define PINMUX_PA08C_SERCOM1_PAD0 ((PIN_PA08C_SERCOM1_PAD0 << 16) | MUX_PA08C_SERCOM1_PAD0)
#define PORT_PA08C_SERCOM1_PAD0 (_UL_(1) << 8)
#define PIN_PA00D_SERCOM1_PAD0 _L_(0) /**< SERCOM1 signal: PAD0 on PA00 mux D*/
#define MUX_PA00D_SERCOM1_PAD0 _L_(3)
#define PINMUX_PA00D_SERCOM1_PAD0 ((PIN_PA00D_SERCOM1_PAD0 << 16) | MUX_PA00D_SERCOM1_PAD0)
#define PORT_PA00D_SERCOM1_PAD0 (_UL_(1) << 0)
#define PIN_PA17C_SERCOM1_PAD1 _L_(17) /**< SERCOM1 signal: PAD1 on PA17 mux C*/
#define MUX_PA17C_SERCOM1_PAD1 _L_(2)
#define PINMUX_PA17C_SERCOM1_PAD1 ((PIN_PA17C_SERCOM1_PAD1 << 16) | MUX_PA17C_SERCOM1_PAD1)
#define PORT_PA17C_SERCOM1_PAD1 (_UL_(1) << 17)
#define PIN_PA01D_SERCOM1_PAD1 _L_(1) /**< SERCOM1 signal: PAD1 on PA01 mux D*/
#define MUX_PA01D_SERCOM1_PAD1 _L_(3)
#define PINMUX_PA01D_SERCOM1_PAD1 ((PIN_PA01D_SERCOM1_PAD1 << 16) | MUX_PA01D_SERCOM1_PAD1)
#define PORT_PA01D_SERCOM1_PAD1 (_UL_(1) << 1)
#define PIN_PA18C_SERCOM1_PAD2 _L_(18) /**< SERCOM1 signal: PAD2 on PA18 mux C*/
#define MUX_PA18C_SERCOM1_PAD2 _L_(2)
#define PINMUX_PA18C_SERCOM1_PAD2 ((PIN_PA18C_SERCOM1_PAD2 << 16) | MUX_PA18C_SERCOM1_PAD2)
#define PORT_PA18C_SERCOM1_PAD2 (_UL_(1) << 18)
#define PIN_PA30D_SERCOM1_PAD2 _L_(30) /**< SERCOM1 signal: PAD2 on PA30 mux D*/
#define MUX_PA30D_SERCOM1_PAD2 _L_(3)
#define PINMUX_PA30D_SERCOM1_PAD2 ((PIN_PA30D_SERCOM1_PAD2 << 16) | MUX_PA30D_SERCOM1_PAD2)
#define PORT_PA30D_SERCOM1_PAD2 (_UL_(1) << 30)
#define PIN_PA19C_SERCOM1_PAD3 _L_(19) /**< SERCOM1 signal: PAD3 on PA19 mux C*/
#define MUX_PA19C_SERCOM1_PAD3 _L_(2)
#define PINMUX_PA19C_SERCOM1_PAD3 ((PIN_PA19C_SERCOM1_PAD3 << 16) | MUX_PA19C_SERCOM1_PAD3)
#define PORT_PA19C_SERCOM1_PAD3 (_UL_(1) << 19)
#define PIN_PA31D_SERCOM1_PAD3 _L_(31) /**< SERCOM1 signal: PAD3 on PA31 mux D*/
#define MUX_PA31D_SERCOM1_PAD3 _L_(3)
#define PINMUX_PA31D_SERCOM1_PAD3 ((PIN_PA31D_SERCOM1_PAD3 << 16) | MUX_PA31D_SERCOM1_PAD3)
#define PORT_PA31D_SERCOM1_PAD3 (_UL_(1) << 31)
/* ========== PORT definition for TC0 peripheral ========== */
#define PIN_PA04E_TC0_WO0 _L_(4) /**< TC0 signal: WO0 on PA04 mux E*/
#define MUX_PA04E_TC0_WO0 _L_(4)
#define PINMUX_PA04E_TC0_WO0 ((PIN_PA04E_TC0_WO0 << 16) | MUX_PA04E_TC0_WO0)
#define PORT_PA04E_TC0_WO0 (_UL_(1) << 4)
#define PIN_PA14E_TC0_WO0 _L_(14) /**< TC0 signal: WO0 on PA14 mux E*/
#define MUX_PA14E_TC0_WO0 _L_(4)
#define PINMUX_PA14E_TC0_WO0 ((PIN_PA14E_TC0_WO0 << 16) | MUX_PA14E_TC0_WO0)
#define PORT_PA14E_TC0_WO0 (_UL_(1) << 14)
#define PIN_PA22E_TC0_WO0 _L_(22) /**< TC0 signal: WO0 on PA22 mux E*/
#define MUX_PA22E_TC0_WO0 _L_(4)
#define PINMUX_PA22E_TC0_WO0 ((PIN_PA22E_TC0_WO0 << 16) | MUX_PA22E_TC0_WO0)
#define PORT_PA22E_TC0_WO0 (_UL_(1) << 22)
#define PIN_PA05E_TC0_WO1 _L_(5) /**< TC0 signal: WO1 on PA05 mux E*/
#define MUX_PA05E_TC0_WO1 _L_(4)
#define PINMUX_PA05E_TC0_WO1 ((PIN_PA05E_TC0_WO1 << 16) | MUX_PA05E_TC0_WO1)
#define PORT_PA05E_TC0_WO1 (_UL_(1) << 5)
#define PIN_PA15E_TC0_WO1 _L_(15) /**< TC0 signal: WO1 on PA15 mux E*/
#define MUX_PA15E_TC0_WO1 _L_(4)
#define PINMUX_PA15E_TC0_WO1 ((PIN_PA15E_TC0_WO1 << 16) | MUX_PA15E_TC0_WO1)
#define PORT_PA15E_TC0_WO1 (_UL_(1) << 15)
#define PIN_PA23E_TC0_WO1 _L_(23) /**< TC0 signal: WO1 on PA23 mux E*/
#define MUX_PA23E_TC0_WO1 _L_(4)
#define PINMUX_PA23E_TC0_WO1 ((PIN_PA23E_TC0_WO1 << 16) | MUX_PA23E_TC0_WO1)
#define PORT_PA23E_TC0_WO1 (_UL_(1) << 23)
/* ========== PORT definition for TC1 peripheral ========== */
#define PIN_PA30E_TC1_WO0 _L_(30) /**< TC1 signal: WO0 on PA30 mux E*/
#define MUX_PA30E_TC1_WO0 _L_(4)
#define PINMUX_PA30E_TC1_WO0 ((PIN_PA30E_TC1_WO0 << 16) | MUX_PA30E_TC1_WO0)
#define PORT_PA30E_TC1_WO0 (_UL_(1) << 30)
#define PIN_PA31E_TC1_WO1 _L_(31) /**< TC1 signal: WO1 on PA31 mux E*/
#define MUX_PA31E_TC1_WO1 _L_(4)
#define PINMUX_PA31E_TC1_WO1 ((PIN_PA31E_TC1_WO1 << 16) | MUX_PA31E_TC1_WO1)
#define PORT_PA31E_TC1_WO1 (_UL_(1) << 31)
/* ========== PORT definition for TC2 peripheral ========== */
#define PIN_PA00E_TC2_WO0 _L_(0) /**< TC2 signal: WO0 on PA00 mux E*/
#define MUX_PA00E_TC2_WO0 _L_(4)
#define PINMUX_PA00E_TC2_WO0 ((PIN_PA00E_TC2_WO0 << 16) | MUX_PA00E_TC2_WO0)
#define PORT_PA00E_TC2_WO0 (_UL_(1) << 0)
#define PIN_PA18E_TC2_WO0 _L_(18) /**< TC2 signal: WO0 on PA18 mux E*/
#define MUX_PA18E_TC2_WO0 _L_(4)
#define PINMUX_PA18E_TC2_WO0 ((PIN_PA18E_TC2_WO0 << 16) | MUX_PA18E_TC2_WO0)
#define PORT_PA18E_TC2_WO0 (_UL_(1) << 18)
#define PIN_PA01E_TC2_WO1 _L_(1) /**< TC2 signal: WO1 on PA01 mux E*/
#define MUX_PA01E_TC2_WO1 _L_(4)
#define PINMUX_PA01E_TC2_WO1 ((PIN_PA01E_TC2_WO1 << 16) | MUX_PA01E_TC2_WO1)
#define PORT_PA01E_TC2_WO1 (_UL_(1) << 1)
#define PIN_PA19E_TC2_WO1 _L_(19) /**< TC2 signal: WO1 on PA19 mux E*/
#define MUX_PA19E_TC2_WO1 _L_(4)
#define PINMUX_PA19E_TC2_WO1 ((PIN_PA19E_TC2_WO1 << 16) | MUX_PA19E_TC2_WO1)
#define PORT_PA19E_TC2_WO1 (_UL_(1) << 19)
#endif /* _SAML10D16A_PIO_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,50 @@
/**
* \file
*
* \brief Top level header file
*
* Copyright (c) 2018 Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* 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
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
#ifndef _SAM_
#define _SAM_
#if defined(__SAML10D14A__) || defined(__ATSAML10D14A__)
#include "saml10d14a.h"
#elif defined(__SAML10D15A__) || defined(__ATSAML10D15A__)
#include "saml10d15a.h"
#elif defined(__SAML10D16A__) || defined(__ATSAML10D16A__)
#include "saml10d16a.h"
#elif defined(__SAML10E14A__) || defined(__ATSAML10E14A__)
#include "saml10e14a.h"
#elif defined(__SAML10E15A__) || defined(__ATSAML10E15A__)
#include "saml10e15a.h"
#elif defined(__SAML10E16A__) || defined(__ATSAML10E16A__)
#include "saml10e16a.h"
#else
#error Library does not support the specified device
#endif
#endif /* _SAM_ */

View File

@ -0,0 +1,789 @@
/**
* \file
*
* \brief Header file for ATSAML10D14A
*
* Copyright (c) 2018 Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* 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
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
/* file generated from device description version 2018-08-31T13:51:49Z */
#ifndef _SAML10D14A_H_
#define _SAML10D14A_H_
/** \addtogroup SAML10D14A_definitions SAML10D14A definitions
This file defines all structures and symbols for SAML10D14A:
- registers and bitfields
- peripheral base address
- peripheral ID
- PIO definitions
* @{
*/
#ifdef __cplusplus
extern "C" {
#endif
/** \defgroup Atmel_glob_defs Atmel Global Defines
<strong>IO Type Qualifiers</strong> are used
\li to specify the access to peripheral variables.
\li for automatic generation of peripheral register debug information.
\remark
CMSIS core has a syntax that differs from this using i.e. __I, __O, or __IO followed by 'uint<size>_t' respective types.
Default the header files will follow the CMSIS core syntax.
* @{
*/
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
#include <stdint.h>
/* IO definitions (access restrictions to peripheral registers) */
#ifndef __cplusplus
typedef volatile const uint32_t RoReg; /**< Read only 32-bit register (volatile const unsigned int) */
typedef volatile const uint16_t RoReg16; /**< Read only 16-bit register (volatile const unsigned int) */
typedef volatile const uint8_t RoReg8; /**< Read only 8-bit register (volatile const unsigned int) */
#else
typedef volatile uint32_t RoReg; /**< Read only 32-bit register (volatile const unsigned int) */
typedef volatile uint16_t RoReg16; /**< Read only 16-bit register (volatile const unsigned int) */
typedef volatile uint8_t RoReg8; /**< Read only 8-bit register (volatile const unsigned int) */
#endif
typedef volatile uint32_t WoReg; /**< Write only 32-bit register (volatile unsigned int) */
typedef volatile uint16_t WoReg16; /**< Write only 16-bit register (volatile unsigned int) */
typedef volatile uint8_t WoReg8; /**< Write only 8-bit register (volatile unsigned int) */
typedef volatile uint32_t RwReg; /**< Read-Write 32-bit register (volatile unsigned int) */
typedef volatile uint16_t RwReg16; /**< Read-Write 16-bit register (volatile unsigned int) */
typedef volatile uint8_t RwReg8; /**< Read-Write 8-bit register (volatile unsigned int) */
#define CAST(type, value) ((type *)(value)) /**< Pointer Type Conversion Macro for C/C++ */
#define REG_ACCESS(type, address) (*(type*)(address)) /**< C code: Register value */
#else /* Assembler */
#define CAST(type, value) (value) /**< Pointer Type Conversion Macro for Assembler */
#define REG_ACCESS(type, address) (address) /**< Assembly code: Register address */
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#if !defined(SKIP_INTEGER_LITERALS)
#if defined(_U_) || defined(_L_) || defined(_UL_)
#error "Integer Literals macros already defined elsewhere"
#endif
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
/* Macros that deal with adding suffixes to integer literal constants for C/C++ */
#define _U_(x) x ## U /**< C code: Unsigned integer literal constant value */
#define _L_(x) x ## L /**< C code: Long integer literal constant value */
#define _UL_(x) x ## UL /**< C code: Unsigned Long integer literal constant value */
#else /* Assembler */
#define _U_(x) x /**< Assembler: Unsigned integer literal constant value */
#define _L_(x) x /**< Assembler: Long integer literal constant value */
#define _UL_(x) x /**< Assembler: Unsigned Long integer literal constant value */
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#endif /* SKIP_INTEGER_LITERALS */
/** @} end of Atmel Global Defines */
/** \addtogroup SAML10D14A_cmsis CMSIS Definitions
* @{
*/
/* ************************************************************************** */
/* CMSIS DEFINITIONS FOR SAML10D14A */
/* ************************************************************************** */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
/** Interrupt Number Definition */
typedef enum IRQn
{
/****** CORTEX-M23 Processor Exceptions Numbers ******************************/
Reset_IRQn = -15, /**< 1 Reset Vector, invoked on Power up and warm reset */
NonMaskableInt_IRQn = -14, /**< 2 Non maskable Interrupt, cannot be stopped or preempted */
HardFault_IRQn = -13, /**< 3 Hard Fault, all classes of Fault */
SVCall_IRQn = -5 , /**< 11 System Service Call via SVC instruction */
PendSV_IRQn = -2 , /**< 14 Pendable request for system service */
SysTick_IRQn = -1 , /**< 15 System Tick Timer */
/****** SAML10D14A specific Interrupt Numbers ***********************************/
SYSTEM_IRQn = 0 , /**< 0 SAML10D14A Main Clock (MCLK) */
WDT_IRQn = 1 , /**< 1 SAML10D14A Watchdog Timer (WDT) */
RTC_IRQn = 2 , /**< 2 SAML10D14A Real-Time Counter (RTC) */
EIC_0_IRQn = 3 , /**< 3 SAML10D14A External Interrupt Controller (EIC) */
EIC_1_IRQn = 4 , /**< 4 SAML10D14A External Interrupt Controller (EIC) */
EIC_2_IRQn = 5 , /**< 5 SAML10D14A External Interrupt Controller (EIC) */
EIC_3_IRQn = 6 , /**< 6 SAML10D14A External Interrupt Controller (EIC) */
EIC_OTHER_IRQn = 7 , /**< 7 SAML10D14A External Interrupt Controller (EIC) */
FREQM_IRQn = 8 , /**< 8 SAML10D14A Frequency Meter (FREQM) */
NVMCTRL_IRQn = 9 , /**< 9 SAML10D14A Non-Volatile Memory Controller (NVMCTRL) */
PORT_IRQn = 10 , /**< 10 SAML10D14A Port Module (PORT) */
DMAC_0_IRQn = 11 , /**< 11 SAML10D14A Direct Memory Access Controller (DMAC) */
DMAC_1_IRQn = 12 , /**< 12 SAML10D14A Direct Memory Access Controller (DMAC) */
DMAC_2_IRQn = 13 , /**< 13 SAML10D14A Direct Memory Access Controller (DMAC) */
DMAC_3_IRQn = 14 , /**< 14 SAML10D14A Direct Memory Access Controller (DMAC) */
DMAC_OTHER_IRQn = 15 , /**< 15 SAML10D14A Direct Memory Access Controller (DMAC) */
EVSYS_0_IRQn = 16 , /**< 16 SAML10D14A Event System Interface (EVSYS) */
EVSYS_1_IRQn = 17 , /**< 17 SAML10D14A Event System Interface (EVSYS) */
EVSYS_2_IRQn = 18 , /**< 18 SAML10D14A Event System Interface (EVSYS) */
EVSYS_3_IRQn = 19 , /**< 19 SAML10D14A Event System Interface (EVSYS) */
EVSYS_NSCHK_IRQn = 20 , /**< 20 SAML10D14A Event System Interface (EVSYS) */
PAC_IRQn = 21 , /**< 21 SAML10D14A Peripheral Access Controller (PAC) */
SERCOM0_0_IRQn = 22 , /**< 22 SAML10D14A Serial Communication Interface (SERCOM0) */
SERCOM0_1_IRQn = 23 , /**< 23 SAML10D14A Serial Communication Interface (SERCOM0) */
SERCOM0_2_IRQn = 24 , /**< 24 SAML10D14A Serial Communication Interface (SERCOM0) */
SERCOM0_OTHER_IRQn = 25 , /**< 25 SAML10D14A Serial Communication Interface (SERCOM0) */
SERCOM1_0_IRQn = 26 , /**< 26 SAML10D14A Serial Communication Interface (SERCOM1) */
SERCOM1_1_IRQn = 27 , /**< 27 SAML10D14A Serial Communication Interface (SERCOM1) */
SERCOM1_2_IRQn = 28 , /**< 28 SAML10D14A Serial Communication Interface (SERCOM1) */
SERCOM1_OTHER_IRQn = 29 , /**< 29 SAML10D14A Serial Communication Interface (SERCOM1) */
TC0_IRQn = 34 , /**< 34 SAML10D14A Basic Timer Counter (TC0) */
TC1_IRQn = 35 , /**< 35 SAML10D14A Basic Timer Counter (TC1) */
TC2_IRQn = 36 , /**< 36 SAML10D14A Basic Timer Counter (TC2) */
ADC_OTHER_IRQn = 37 , /**< 37 SAML10D14A Analog Digital Converter (ADC) */
ADC_RESRDY_IRQn = 38 , /**< 38 SAML10D14A Analog Digital Converter (ADC) */
AC_IRQn = 39 , /**< 39 SAML10D14A Analog Comparators (AC) */
DAC_UNDERRUN_A_IRQn = 40 , /**< 40 SAML10D14A Digital Analog Converter (DAC) */
DAC_EMPTY_IRQn = 41 , /**< 41 SAML10D14A Digital Analog Converter (DAC) */
PTC_IRQn = 42 , /**< 42 SAML10D14A Peripheral Touch Controller (PTC) */
TRNG_IRQn = 43 , /**< 43 SAML10D14A True Random Generator (TRNG) */
TRAM_IRQn = 44 , /**< 44 SAML10D14A TrustRAM (TRAM) */
PERIPH_COUNT_IRQn = 45 /**< Number of peripheral IDs */
} IRQn_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef struct _DeviceVectors
{
/* Stack pointer */
void* pvStack;
/* Cortex-M handlers */
void* pfnReset_Handler; /* -15 Reset Vector, invoked on Power up and warm reset */
void* pfnNonMaskableInt_Handler; /* -14 Non maskable Interrupt, cannot be stopped or preempted */
void* pfnHardFault_Handler; /* -13 Hard Fault, all classes of Fault */
void* pvReservedC12;
void* pvReservedC11;
void* pvReservedC10;
void* pvReservedC9;
void* pvReservedC8;
void* pvReservedC7;
void* pvReservedC6;
void* pfnSVCall_Handler; /* -5 System Service Call via SVC instruction */
void* pvReservedC4;
void* pvReservedC3;
void* pfnPendSV_Handler; /* -2 Pendable request for system service */
void* pfnSysTick_Handler; /* -1 System Tick Timer */
/* Peripheral handlers */
void* pfnSYSTEM_Handler; /* 0 SAML10D14A Main Clock (MCLK) */
void* pfnWDT_Handler; /* 1 SAML10D14A Watchdog Timer (WDT) */
void* pfnRTC_Handler; /* 2 SAML10D14A Real-Time Counter (RTC) */
void* pfnEIC_0_Handler; /* 3 SAML10D14A External Interrupt Controller (EIC) */
void* pfnEIC_1_Handler; /* 4 SAML10D14A External Interrupt Controller (EIC) */
void* pfnEIC_2_Handler; /* 5 SAML10D14A External Interrupt Controller (EIC) */
void* pfnEIC_3_Handler; /* 6 SAML10D14A External Interrupt Controller (EIC) */
void* pfnEIC_OTHER_Handler; /* 7 SAML10D14A External Interrupt Controller (EIC) */
void* pfnFREQM_Handler; /* 8 SAML10D14A Frequency Meter (FREQM) */
void* pfnNVMCTRL_Handler; /* 9 SAML10D14A Non-Volatile Memory Controller (NVMCTRL) */
void* pfnPORT_Handler; /* 10 SAML10D14A Port Module (PORT) */
void* pfnDMAC_0_Handler; /* 11 SAML10D14A Direct Memory Access Controller (DMAC) */
void* pfnDMAC_1_Handler; /* 12 SAML10D14A Direct Memory Access Controller (DMAC) */
void* pfnDMAC_2_Handler; /* 13 SAML10D14A Direct Memory Access Controller (DMAC) */
void* pfnDMAC_3_Handler; /* 14 SAML10D14A Direct Memory Access Controller (DMAC) */
void* pfnDMAC_OTHER_Handler; /* 15 SAML10D14A Direct Memory Access Controller (DMAC) */
void* pfnEVSYS_0_Handler; /* 16 SAML10D14A Event System Interface (EVSYS) */
void* pfnEVSYS_1_Handler; /* 17 SAML10D14A Event System Interface (EVSYS) */
void* pfnEVSYS_2_Handler; /* 18 SAML10D14A Event System Interface (EVSYS) */
void* pfnEVSYS_3_Handler; /* 19 SAML10D14A Event System Interface (EVSYS) */
void* pfnEVSYS_NSCHK_Handler; /* 20 SAML10D14A Event System Interface (EVSYS) */
void* pfnPAC_Handler; /* 21 SAML10D14A Peripheral Access Controller (PAC) */
void* pfnSERCOM0_0_Handler; /* 22 SAML10D14A Serial Communication Interface (SERCOM0) */
void* pfnSERCOM0_1_Handler; /* 23 SAML10D14A Serial Communication Interface (SERCOM0) */
void* pfnSERCOM0_2_Handler; /* 24 SAML10D14A Serial Communication Interface (SERCOM0) */
void* pfnSERCOM0_OTHER_Handler; /* 25 SAML10D14A Serial Communication Interface (SERCOM0) */
void* pfnSERCOM1_0_Handler; /* 26 SAML10D14A Serial Communication Interface (SERCOM1) */
void* pfnSERCOM1_1_Handler; /* 27 SAML10D14A Serial Communication Interface (SERCOM1) */
void* pfnSERCOM1_2_Handler; /* 28 SAML10D14A Serial Communication Interface (SERCOM1) */
void* pfnSERCOM1_OTHER_Handler; /* 29 SAML10D14A Serial Communication Interface (SERCOM1) */
void* pvReserved30;
void* pvReserved31;
void* pvReserved32;
void* pvReserved33;
void* pfnTC0_Handler; /* 34 SAML10D14A Basic Timer Counter (TC0) */
void* pfnTC1_Handler; /* 35 SAML10D14A Basic Timer Counter (TC1) */
void* pfnTC2_Handler; /* 36 SAML10D14A Basic Timer Counter (TC2) */
void* pfnADC_OTHER_Handler; /* 37 SAML10D14A Analog Digital Converter (ADC) */
void* pfnADC_RESRDY_Handler; /* 38 SAML10D14A Analog Digital Converter (ADC) */
void* pfnAC_Handler; /* 39 SAML10D14A Analog Comparators (AC) */
void* pfnDAC_UNDERRUN_A_Handler; /* 40 SAML10D14A Digital Analog Converter (DAC) */
void* pfnDAC_EMPTY_Handler; /* 41 SAML10D14A Digital Analog Converter (DAC) */
void* pfnPTC_Handler; /* 42 SAML10D14A Peripheral Touch Controller (PTC) */
void* pfnTRNG_Handler; /* 43 SAML10D14A True Random Generator (TRNG) */
void* pfnTRAM_Handler; /* 44 SAML10D14A TrustRAM (TRAM) */
} DeviceVectors;
/* Defines for Deprecated Interrupt and Exceptions handler names */
#define pfnMemManage_Handler pfnMemoryManagement_Handler /**< \deprecated Backward compatibility for ASF */
#define pfnDebugMon_Handler pfnDebugMonitor_Handler /**< \deprecated Backward compatibility for ASF */
#define pfnNMI_Handler pfnNonMaskableInt_Handler /**< \deprecated Backward compatibility for ASF */
#define pfnSVC_Handler pfnSVCall_Handler /**< \deprecated Backward compatibility for ASF */
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
#if !defined DONT_USE_PREDEFINED_CORE_HANDLERS
/* CORTEX-M23 core handlers */
void Reset_Handler ( void );
void NonMaskableInt_Handler ( void );
void HardFault_Handler ( void );
void SVCall_Handler ( void );
void PendSV_Handler ( void );
void SysTick_Handler ( void );
#endif /* DONT_USE_PREDEFINED_CORE_HANDLERS */
#if !defined DONT_USE_PREDEFINED_PERIPHERALS_HANDLERS
/* Peripherals handlers */
void AC_Handler ( void );
void ADC_OTHER_Handler ( void );
void ADC_RESRDY_Handler ( void );
void DAC_EMPTY_Handler ( void );
void DAC_UNDERRUN_A_Handler ( void );
void DMAC_0_Handler ( void );
void DMAC_1_Handler ( void );
void DMAC_2_Handler ( void );
void DMAC_3_Handler ( void );
void DMAC_OTHER_Handler ( void );
void EIC_0_Handler ( void );
void EIC_1_Handler ( void );
void EIC_2_Handler ( void );
void EIC_3_Handler ( void );
void EIC_OTHER_Handler ( void );
void EVSYS_0_Handler ( void );
void EVSYS_1_Handler ( void );
void EVSYS_2_Handler ( void );
void EVSYS_3_Handler ( void );
void EVSYS_NSCHK_Handler ( void );
void FREQM_Handler ( void );
void NVMCTRL_Handler ( void );
void PAC_Handler ( void );
void PORT_Handler ( void );
void PTC_Handler ( void );
void RTC_Handler ( void );
void SERCOM0_0_Handler ( void );
void SERCOM0_1_Handler ( void );
void SERCOM0_2_Handler ( void );
void SERCOM0_OTHER_Handler ( void );
void SERCOM1_0_Handler ( void );
void SERCOM1_1_Handler ( void );
void SERCOM1_2_Handler ( void );
void SERCOM1_OTHER_Handler ( void );
void SYSTEM_Handler ( void );
void TC0_Handler ( void );
void TC1_Handler ( void );
void TC2_Handler ( void );
void TRAM_Handler ( void );
void TRNG_Handler ( void );
void WDT_Handler ( void );
#endif /* DONT_USE_PREDEFINED_PERIPHERALS_HANDLERS */
/* Defines for Deprecated Interrupt and Exceptions handler names */
#define MemManage_Handler MemoryManagement_Handler /**< \deprecated Backward compatibility for ASF */
#define DebugMon_Handler DebugMonitor_Handler /**< \deprecated Backward compatibility for ASF */
#define NMI_Handler NonMaskableInt_Handler /**< \deprecated Backward compatibility for ASF */
#define SVC_Handler SVCall_Handler /**< \deprecated Backward compatibility for ASF */
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/*
* \brief Configuration of the CORTEX-M23 Processor and Core Peripherals
*/
#define NUM_IRQ 45 /**< Number of interrupt request lines */
#define __ARMv8MBL_REV 0x0000 /**< Cortex-M23 Core Revision */
#define __ETM_PRESENT 0 /**< ETM present or not */
#define __FPU_PRESENT 0 /**< FPU present or not */
#define __MPU_PRESENT 1 /**< MPU present or not */
#define __MTB_PRESENT 0 /**< MTB present or not */
#define __NVIC_PRIO_BITS 2 /**< Number of Bits used for Priority Levels */
#define __SAU_PRESENT 0 /**< SAU present or not */
#define __SEC_ENABLED 0 /**< TrustZone-M enabled or not */
#define __VTOR_PRESENT 1 /**< Vector Table Offset Register present or not */
#define __Vendor_SysTickConfig 0 /**< Set to 1 if different SysTick Config is used */
#define __ARCH_ARM 1
#define __ARCH_ARM_CORTEX_M 1
#define __DEVICE_IS_SAM 1
/*
* \brief CMSIS includes
*/
#include <core_cm23.h>
#if !defined DONT_USE_CMSIS_INIT
#include "system_saml10.h"
#endif /* DONT_USE_CMSIS_INIT */
/** @} end of SAML10D14A_cmsis CMSIS Definitions */
/** \defgroup SAML10D14A_api Peripheral Software API
* @{
*/
/* ************************************************************************** */
/** SOFTWARE PERIPHERAL API DEFINITION FOR SAML10D14A */
/* ************************************************************************** */
#include "component/ac.h"
#include "component/adc.h"
#include "component/ccl.h"
#include "component/dac.h"
#include "component/dmac.h"
#include "component/dsu.h"
#include "component/eic.h"
#include "component/evsys.h"
#include "component/freqm.h"
#include "component/gclk.h"
#include "component/idau.h"
#include "component/mclk.h"
#include "component/nvmctrl.h"
#include "component/opamp.h"
#include "component/oscctrl.h"
#include "component/osc32kctrl.h"
#include "component/pac.h"
#include "component/pm.h"
#include "component/port.h"
#include "component/ptc.h"
#include "component/rstc.h"
#include "component/rtc.h"
#include "component/sercom.h"
#include "component/supc.h"
#include "component/tc.h"
#include "component/tram.h"
#include "component/trng.h"
#include "component/wdt.h"
/** @} end of Peripheral Software API */
/** \defgroup SAML10D14A_reg Registers Access Definitions
* @{
*/
/* ************************************************************************** */
/* REGISTER ACCESS DEFINITIONS FOR SAML10D14A */
/* ************************************************************************** */
#include "instance/ac.h"
#include "instance/adc.h"
#include "instance/ccl.h"
#include "instance/dac.h"
#include "instance/dmac.h"
#include "instance/dsu.h"
#include "instance/eic.h"
#include "instance/evsys.h"
#include "instance/freqm.h"
#include "instance/gclk.h"
#include "instance/idau.h"
#include "instance/mclk.h"
#include "instance/nvmctrl.h"
#include "instance/opamp.h"
#include "instance/oscctrl.h"
#include "instance/osc32kctrl.h"
#include "instance/pac.h"
#include "instance/pm.h"
#include "instance/port.h"
#include "instance/ptc.h"
#include "instance/rstc.h"
#include "instance/rtc.h"
#include "instance/sercom0.h"
#include "instance/sercom1.h"
#include "instance/supc.h"
#include "instance/tc0.h"
#include "instance/tc1.h"
#include "instance/tc2.h"
#include "instance/tram.h"
#include "instance/trng.h"
#include "instance/wdt.h"
/** @} end of Registers Access Definitions */
/** \addtogroup SAML10D14A_id Peripheral Ids Definitions
* @{
*/
/* ************************************************************************** */
/* PERIPHERAL ID DEFINITIONS FOR SAML10D14A */
/* ************************************************************************** */
#define ID_PAC ( 0) /**< \brief Peripheral Access Controller (PAC) */
#define ID_PM ( 1) /**< \brief Power Manager (PM) */
#define ID_MCLK ( 2) /**< \brief Main Clock (MCLK) */
#define ID_RSTC ( 3) /**< \brief Reset Controller (RSTC) */
#define ID_OSCCTRL ( 4) /**< \brief Oscillators Control (OSCCTRL) */
#define ID_OSC32KCTRL ( 5) /**< \brief 32k Oscillators Control (OSC32KCTRL) */
#define ID_SUPC ( 6) /**< \brief Supply Controller (SUPC) */
#define ID_GCLK ( 7) /**< \brief Generic Clock Generator (GCLK) */
#define ID_WDT ( 8) /**< \brief Watchdog Timer (WDT) */
#define ID_RTC ( 9) /**< \brief Real-Time Counter (RTC) */
#define ID_EIC ( 10) /**< \brief External Interrupt Controller (EIC) */
#define ID_FREQM ( 11) /**< \brief Frequency Meter (FREQM) */
#define ID_PORT ( 12) /**< \brief Port Module (PORT) */
#define ID_AC ( 13) /**< \brief Analog Comparators (AC) */
#define ID_IDAU ( 32) /**< \brief Implementation Defined Attribution Unit (IDAU) */
#define ID_DSU ( 33) /**< \brief Device Service Unit (DSU) */
#define ID_NVMCTRL ( 34) /**< \brief Non-Volatile Memory Controller (NVMCTRL) */
#define ID_DMAC ( 35) /**< \brief Direct Memory Access Controller (DMAC) */
#define ID_EVSYS ( 64) /**< \brief Event System Interface (EVSYS) */
#define ID_SERCOM0 ( 65) /**< \brief Serial Communication Interface (SERCOM0) */
#define ID_SERCOM1 ( 66) /**< \brief Serial Communication Interface (SERCOM1) */
#define ID_TC0 ( 68) /**< \brief Basic Timer Counter (TC0) */
#define ID_TC1 ( 69) /**< \brief Basic Timer Counter (TC1) */
#define ID_TC2 ( 70) /**< \brief Basic Timer Counter (TC2) */
#define ID_ADC ( 71) /**< \brief Analog Digital Converter (ADC) */
#define ID_DAC ( 72) /**< \brief Digital Analog Converter (DAC) */
#define ID_PTC ( 73) /**< \brief Peripheral Touch Controller (PTC) */
#define ID_TRNG ( 74) /**< \brief True Random Generator (TRNG) */
#define ID_CCL ( 75) /**< \brief Configurable Custom Logic (CCL) */
#define ID_OPAMP ( 76) /**< \brief Operational Amplifier (OPAMP) */
#define ID_TRAM ( 77) /**< \brief TrustRAM (TRAM) */
#define ID_PERIPH_COUNT ( 78) /**< \brief Number of peripheral IDs */
/** @} end of Peripheral Ids Definitions */
/** \addtogroup SAML10D14A_base Peripheral Base Address Definitions
* @{
*/
/* ************************************************************************** */
/* BASE ADDRESS DEFINITIONS FOR SAML10D14A */
/* ************************************************************************** */
#if (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
#define AC (0x40003400) /**< \brief (AC ) Base Address */
#define ADC (0x42001C00) /**< \brief (ADC ) Base Address */
#define CCL (0x42002C00) /**< \brief (CCL ) Base Address */
#define DAC (0x42002000) /**< \brief (DAC ) Base Address */
#define DMAC (0x41006000) /**< \brief (DMAC ) Base Address */
#define DSU (0x41002000) /**< \brief (DSU ) Base Address */
#define DSU_EXT (0x41002100) /**< \brief (DSU ) Base Address */
#define EIC (0x40002800) /**< \brief (EIC ) Base Address */
#define EVSYS (0x42000000) /**< \brief (EVSYS ) Base Address */
#define FREQM (0x40002C00) /**< \brief (FREQM ) Base Address */
#define GCLK (0x40001C00) /**< \brief (GCLK ) Base Address */
#define IDAU (0x41000000) /**< \brief (IDAU ) Base Address */
#define MCLK (0x40000800) /**< \brief (MCLK ) Base Address */
#define NVMCTRL (0x41004000) /**< \brief (NVMCTRL ) Base Address */
#define OPAMP (0x42003000) /**< \brief (OPAMP ) Base Address */
#define OSCCTRL (0x40001000) /**< \brief (OSCCTRL ) Base Address */
#define OSC32KCTRL (0x40001400) /**< \brief (OSC32KCTRL) Base Address */
#define PAC (0x40000000) /**< \brief (PAC ) Base Address */
#define PM (0x40000400) /**< \brief (PM ) Base Address */
#define PORT (0x40003000) /**< \brief (PORT ) Base Address */
#define PORT_IOBUS (0x60000000) /**< \brief (PORT ) Base Address */
#define PTC (0x42002400) /**< \brief (PTC ) Base Address */
#define RSTC (0x40000C00) /**< \brief (RSTC ) Base Address */
#define RTC (0x40002400) /**< \brief (RTC ) Base Address */
#define SERCOM0 (0x42000400) /**< \brief (SERCOM0 ) Base Address */
#define SERCOM1 (0x42000800) /**< \brief (SERCOM1 ) Base Address */
#define SUPC (0x40001800) /**< \brief (SUPC ) Base Address */
#define TC0 (0x42001000) /**< \brief (TC0 ) Base Address */
#define TC1 (0x42001400) /**< \brief (TC1 ) Base Address */
#define TC2 (0x42001800) /**< \brief (TC2 ) Base Address */
#define TRAM (0x42003400) /**< \brief (TRAM ) Base Address */
#define TRNG (0x42002800) /**< \brief (TRNG ) Base Address */
#define WDT (0x40002000) /**< \brief (WDT ) Base Address */
#else /* For C/C++ compiler */
#define AC ((Ac *)0x40003400U) /**< \brief (AC ) Base Address */
#define AC_INST_NUM 1 /**< \brief (AC ) Number of instances */
#define AC_INSTS { AC } /**< \brief (AC ) Instances List */
#define ADC ((Adc *)0x42001C00U) /**< \brief (ADC ) Base Address */
#define ADC_INST_NUM 1 /**< \brief (ADC ) Number of instances */
#define ADC_INSTS { ADC } /**< \brief (ADC ) Instances List */
#define CCL ((Ccl *)0x42002C00U) /**< \brief (CCL ) Base Address */
#define CCL_INST_NUM 1 /**< \brief (CCL ) Number of instances */
#define CCL_INSTS { CCL } /**< \brief (CCL ) Instances List */
#define DAC ((Dac *)0x42002000U) /**< \brief (DAC ) Base Address */
#define DAC_INST_NUM 1 /**< \brief (DAC ) Number of instances */
#define DAC_INSTS { DAC } /**< \brief (DAC ) Instances List */
#define DMAC ((Dmac *)0x41006000U) /**< \brief (DMAC ) Base Address */
#define DMAC_INST_NUM 1 /**< \brief (DMAC ) Number of instances */
#define DMAC_INSTS { DMAC } /**< \brief (DMAC ) Instances List */
#define DSU ((Dsu *)0x41002000U) /**< \brief (DSU ) Base Address */
#define DSU_EXT ((Dsu *)0x41002100U) /**< \brief (DSU ) Base Address */
#define DSU_INST_NUM 1 /**< \brief (DSU ) Number of instances */
#define DSU_INSTS { DSU } /**< \brief (DSU ) Instances List */
#define EIC ((Eic *)0x40002800U) /**< \brief (EIC ) Base Address */
#define EIC_INST_NUM 1 /**< \brief (EIC ) Number of instances */
#define EIC_INSTS { EIC } /**< \brief (EIC ) Instances List */
#define EVSYS ((Evsys *)0x42000000U) /**< \brief (EVSYS ) Base Address */
#define EVSYS_INST_NUM 1 /**< \brief (EVSYS ) Number of instances */
#define EVSYS_INSTS { EVSYS } /**< \brief (EVSYS ) Instances List */
#define FREQM ((Freqm *)0x40002C00U) /**< \brief (FREQM ) Base Address */
#define FREQM_INST_NUM 1 /**< \brief (FREQM ) Number of instances */
#define FREQM_INSTS { FREQM } /**< \brief (FREQM ) Instances List */
#define GCLK ((Gclk *)0x40001C00U) /**< \brief (GCLK ) Base Address */
#define GCLK_INST_NUM 1 /**< \brief (GCLK ) Number of instances */
#define GCLK_INSTS { GCLK } /**< \brief (GCLK ) Instances List */
#define IDAU ((Idau *)0x41000000U) /**< \brief (IDAU ) Base Address */
#define IDAU_INST_NUM 1 /**< \brief (IDAU ) Number of instances */
#define IDAU_INSTS { IDAU } /**< \brief (IDAU ) Instances List */
#define MCLK ((Mclk *)0x40000800U) /**< \brief (MCLK ) Base Address */
#define MCLK_INST_NUM 1 /**< \brief (MCLK ) Number of instances */
#define MCLK_INSTS { MCLK } /**< \brief (MCLK ) Instances List */
#define NVMCTRL ((Nvmctrl *)0x41004000U) /**< \brief (NVMCTRL ) Base Address */
#define NVMCTRL_INST_NUM 1 /**< \brief (NVMCTRL ) Number of instances */
#define NVMCTRL_INSTS { NVMCTRL } /**< \brief (NVMCTRL ) Instances List */
#define OPAMP ((Opamp *)0x42003000U) /**< \brief (OPAMP ) Base Address */
#define OPAMP_INST_NUM 1 /**< \brief (OPAMP ) Number of instances */
#define OPAMP_INSTS { OPAMP } /**< \brief (OPAMP ) Instances List */
#define OSCCTRL ((Oscctrl *)0x40001000U) /**< \brief (OSCCTRL ) Base Address */
#define OSCCTRL_INST_NUM 1 /**< \brief (OSCCTRL ) Number of instances */
#define OSCCTRL_INSTS { OSCCTRL } /**< \brief (OSCCTRL ) Instances List */
#define OSC32KCTRL ((Osc32kctrl *)0x40001400U) /**< \brief (OSC32KCTRL) Base Address */
#define OSC32KCTRL_INST_NUM 1 /**< \brief (OSC32KCTRL) Number of instances */
#define OSC32KCTRL_INSTS { OSC32KCTRL } /**< \brief (OSC32KCTRL) Instances List */
#define PAC ((Pac *)0x40000000U) /**< \brief (PAC ) Base Address */
#define PAC_INST_NUM 1 /**< \brief (PAC ) Number of instances */
#define PAC_INSTS { PAC } /**< \brief (PAC ) Instances List */
#define PM ((Pm *)0x40000400U) /**< \brief (PM ) Base Address */
#define PM_INST_NUM 1 /**< \brief (PM ) Number of instances */
#define PM_INSTS { PM } /**< \brief (PM ) Instances List */
#define PORT ((Port *)0x40003000U) /**< \brief (PORT ) Base Address */
#define PORT_IOBUS ((Port *)0x60000000U) /**< \brief (PORT ) Base Address */
#define PORT_INST_NUM 1 /**< \brief (PORT ) Number of instances */
#define PORT_INSTS { PORT } /**< \brief (PORT ) Instances List */
#define PTC ((Ptc *)0x42002400U) /**< \brief (PTC ) Base Address */
#define PTC_INST_NUM 1 /**< \brief (PTC ) Number of instances */
#define PTC_INSTS { PTC } /**< \brief (PTC ) Instances List */
#define RSTC ((Rstc *)0x40000C00U) /**< \brief (RSTC ) Base Address */
#define RSTC_INST_NUM 1 /**< \brief (RSTC ) Number of instances */
#define RSTC_INSTS { RSTC } /**< \brief (RSTC ) Instances List */
#define RTC ((Rtc *)0x40002400U) /**< \brief (RTC ) Base Address */
#define RTC_INST_NUM 1 /**< \brief (RTC ) Number of instances */
#define RTC_INSTS { RTC } /**< \brief (RTC ) Instances List */
#define SERCOM0 ((Sercom *)0x42000400U) /**< \brief (SERCOM0 ) Base Address */
#define SERCOM1 ((Sercom *)0x42000800U) /**< \brief (SERCOM1 ) Base Address */
#define SERCOM_INST_NUM 2 /**< \brief (SERCOM ) Number of instances */
#define SERCOM_INSTS { SERCOM0, SERCOM1 } /**< \brief (SERCOM ) Instances List */
#define SUPC ((Supc *)0x40001800U) /**< \brief (SUPC ) Base Address */
#define SUPC_INST_NUM 1 /**< \brief (SUPC ) Number of instances */
#define SUPC_INSTS { SUPC } /**< \brief (SUPC ) Instances List */
#define TC0 ((Tc *)0x42001000U) /**< \brief (TC0 ) Base Address */
#define TC1 ((Tc *)0x42001400U) /**< \brief (TC1 ) Base Address */
#define TC2 ((Tc *)0x42001800U) /**< \brief (TC2 ) Base Address */
#define TC_INST_NUM 3 /**< \brief (TC ) Number of instances */
#define TC_INSTS { TC0, TC1, TC2 } /**< \brief (TC ) Instances List */
#define TRAM ((Tram *)0x42003400U) /**< \brief (TRAM ) Base Address */
#define TRAM_INST_NUM 1 /**< \brief (TRAM ) Number of instances */
#define TRAM_INSTS { TRAM } /**< \brief (TRAM ) Instances List */
#define TRNG ((Trng *)0x42002800U) /**< \brief (TRNG ) Base Address */
#define TRNG_INST_NUM 1 /**< \brief (TRNG ) Number of instances */
#define TRNG_INSTS { TRNG } /**< \brief (TRNG ) Instances List */
#define WDT ((Wdt *)0x40002000U) /**< \brief (WDT ) Base Address */
#define WDT_INST_NUM 1 /**< \brief (WDT ) Number of instances */
#define WDT_INSTS { WDT } /**< \brief (WDT ) Instances List */
#endif /* (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/** @} end of Peripheral Base Address Definitions */
/** \addtogroup SAML10D14A_pio Peripheral Pio Definitions
* @{
*/
/* ************************************************************************** */
/* PIO DEFINITIONS FOR SAML10D14A*/
/* ************************************************************************** */
#include "pio/saml10d14a.h"
/** @} end of Peripheral Pio Definitions */
/* ************************************************************************** */
/* MEMORY MAPPING DEFINITIONS FOR SAML10D14A*/
/* ************************************************************************** */
#define FLASH_SIZE _U_(0x00004000) /* 16kB Memory segment type: flash */
#define FLASH_PAGE_SIZE _U_( 64)
#define FLASH_NB_OF_PAGES _U_( 256)
#define AUX_SIZE _U_(0x00000100) /* 0kB Memory segment type: fuses */
#define AUX_PAGE_SIZE _U_( 64)
#define AUX_NB_OF_PAGES _U_( 4)
#define BOCOR_SIZE _U_(0x00000100) /* 0kB Memory segment type: fuses */
#define BOCOR_PAGE_SIZE _U_( 64)
#define BOCOR_NB_OF_PAGES _U_( 4)
#define DATAFLASH_SIZE _U_(0x00000800) /* 2kB Memory segment type: flash */
#define DATAFLASH_PAGE_SIZE _U_( 64)
#define DATAFLASH_NB_OF_PAGES _U_( 32)
#define SW_CALIB_SIZE _U_(0x00000008) /* 0kB Memory segment type: fuses */
#define TEMP_LOG_SIZE _U_(0x00000008) /* 0kB Memory segment type: fuses */
#define USER_PAGE_SIZE _U_(0x00000100) /* 0kB Memory segment type: user_page */
#define USER_PAGE_PAGE_SIZE _U_( 64)
#define USER_PAGE_NB_OF_PAGES _U_( 4)
#define HSRAM_SIZE _U_(0x00001000) /* 4kB Memory segment type: ram */
#define HPB0_SIZE _U_(0x00008000) /* 32kB Memory segment type: io */
#define HPB1_SIZE _U_(0x00010000) /* 64kB Memory segment type: io */
#define HPB2_SIZE _U_(0x00004000) /* 16kB Memory segment type: io */
#define PPB_SIZE _U_(0x00100000) /* 1024kB Memory segment type: io */
#define SCS_SIZE _U_(0x00001000) /* 4kB Memory segment type: io */
#define PERIPHERALS_SIZE _U_(0x20000000) /* 524288kB Memory segment type: io */
#define FLASH_ADDR _U_(0x00000000) /**< FLASH base address (type: flash)*/
#define AUX_ADDR _U_(0x00806000) /**< AUX base address (type: fuses)*/
#define BOCOR_ADDR _U_(0x0080c000) /**< BOCOR base address (type: fuses)*/
#define DATAFLASH_ADDR _U_(0x00400000) /**< DATAFLASH base address (type: flash)*/
#define SW_CALIB_ADDR _U_(0x00806020) /**< SW_CALIB base address (type: fuses)*/
#define TEMP_LOG_ADDR _U_(0x00806038) /**< TEMP_LOG base address (type: fuses)*/
#define USER_PAGE_ADDR _U_(0x00804000) /**< USER_PAGE base address (type: user_page)*/
#define HSRAM_ADDR _U_(0x20000000) /**< HSRAM base address (type: ram)*/
#define HPB0_ADDR _U_(0x40000000) /**< HPB0 base address (type: io)*/
#define HPB1_ADDR _U_(0x41000000) /**< HPB1 base address (type: io)*/
#define HPB2_ADDR _U_(0x42000000) /**< HPB2 base address (type: io)*/
#define PPB_ADDR _U_(0xe0000000) /**< PPB base address (type: io)*/
#define SCS_ADDR _U_(0xe000e000) /**< SCS base address (type: io)*/
#define PERIPHERALS_ADDR _U_(0x40000000) /**< PERIPHERALS base address (type: io)*/
#define NVMCTRL_AUX AUX_ADDR /**< \brief \deprecated Old style definition. Use AUX_ADDR instead */
#define NVMCTRL_BOCOR BOCOR_ADDR /**< \brief \deprecated Old style definition. Use BOCOR_ADDR instead */
#define NVMCTRL_DATAFLASH DATAFLASH_ADDR /**< \brief \deprecated Old style definition. Use DATAFLASH_ADDR instead */
#define NVMCTRL_SW_CALIB SW_CALIB_ADDR /**< \brief \deprecated Old style definition. Use SW_CALIB_ADDR instead */
#define NVMCTRL_TEMP_LOG TEMP_LOG_ADDR /**< \brief \deprecated Old style definition. Use TEMP_LOG_ADDR instead */
#define NVMCTRL_USER USER_PAGE_ADDR /**< \brief \deprecated Old style definition. Use USER_PAGE_ADDR instead */
/* ************************************************************************** */
/** DEVICE SIGNATURES FOR SAML10D14A */
/* ************************************************************************** */
#define DSU_DID _UL_(0X20840005)
/* ************************************************************************** */
/** ELECTRICAL DEFINITIONS FOR SAML10D14A */
/* ************************************************************************** */
/* ************************************************************************** */
/** Event Generator IDs for SAML10D14A */
/* ************************************************************************** */
#define EVENT_ID_GEN_OSCCTRL_XOSC_FAIL 1 /**< ID for OSCCTRL event generator XOSC_FAIL */
#define EVENT_ID_GEN_OSC32KCTRL_XOSC32K_FAIL 2 /**< ID for OSC32KCTRL event generator XOSC32K_FAIL */
#define EVENT_ID_GEN_SUPC_BOD33DET 3 /**< ID for SUPC event generator BOD33DET */
#define EVENT_ID_GEN_RTC_PER_0 4 /**< ID for RTC event generator PER_0 */
#define EVENT_ID_GEN_RTC_PER_1 5 /**< ID for RTC event generator PER_1 */
#define EVENT_ID_GEN_RTC_PER_2 6 /**< ID for RTC event generator PER_2 */
#define EVENT_ID_GEN_RTC_PER_3 7 /**< ID for RTC event generator PER_3 */
#define EVENT_ID_GEN_RTC_PER_4 8 /**< ID for RTC event generator PER_4 */
#define EVENT_ID_GEN_RTC_PER_5 9 /**< ID for RTC event generator PER_5 */
#define EVENT_ID_GEN_RTC_PER_6 10 /**< ID for RTC event generator PER_6 */
#define EVENT_ID_GEN_RTC_PER_7 11 /**< ID for RTC event generator PER_7 */
#define EVENT_ID_GEN_RTC_CMP_0 12 /**< ID for RTC event generator CMP_0 */
#define EVENT_ID_GEN_RTC_CMP_1 13 /**< ID for RTC event generator CMP_1 */
#define EVENT_ID_GEN_RTC_TAMPER 14 /**< ID for RTC event generator TAMPER */
#define EVENT_ID_GEN_RTC_OVF 15 /**< ID for RTC event generator OVF */
#define EVENT_ID_GEN_RTC_PERD 16 /**< ID for RTC event generator PERD */
#define EVENT_ID_GEN_EIC_EXTINT_0 17 /**< ID for EIC event generator EXTINT_0 */
#define EVENT_ID_GEN_EIC_EXTINT_1 18 /**< ID for EIC event generator EXTINT_1 */
#define EVENT_ID_GEN_EIC_EXTINT_2 19 /**< ID for EIC event generator EXTINT_2 */
#define EVENT_ID_GEN_EIC_EXTINT_3 20 /**< ID for EIC event generator EXTINT_3 */
#define EVENT_ID_GEN_EIC_EXTINT_4 21 /**< ID for EIC event generator EXTINT_4 */
#define EVENT_ID_GEN_EIC_EXTINT_5 22 /**< ID for EIC event generator EXTINT_5 */
#define EVENT_ID_GEN_EIC_EXTINT_6 23 /**< ID for EIC event generator EXTINT_6 */
#define EVENT_ID_GEN_EIC_EXTINT_7 24 /**< ID for EIC event generator EXTINT_7 */
#define EVENT_ID_GEN_DMAC_CH_0 25 /**< ID for DMAC event generator CH_0 */
#define EVENT_ID_GEN_DMAC_CH_1 26 /**< ID for DMAC event generator CH_1 */
#define EVENT_ID_GEN_DMAC_CH_2 27 /**< ID for DMAC event generator CH_2 */
#define EVENT_ID_GEN_DMAC_CH_3 28 /**< ID for DMAC event generator CH_3 */
#define EVENT_ID_GEN_TC0_OVF 29 /**< ID for TC0 event generator OVF */
#define EVENT_ID_GEN_TC0_MCX_0 30 /**< ID for TC0 event generator MCX_0 */
#define EVENT_ID_GEN_TC0_MCX_1 31 /**< ID for TC0 event generator MCX_1 */
#define EVENT_ID_GEN_TC1_OVF 32 /**< ID for TC1 event generator OVF */
#define EVENT_ID_GEN_TC1_MCX_0 33 /**< ID for TC1 event generator MCX_0 */
#define EVENT_ID_GEN_TC1_MCX_1 34 /**< ID for TC1 event generator MCX_1 */
#define EVENT_ID_GEN_TC2_OVF 35 /**< ID for TC2 event generator OVF */
#define EVENT_ID_GEN_TC2_MCX_0 36 /**< ID for TC2 event generator MCX_0 */
#define EVENT_ID_GEN_TC2_MCX_1 37 /**< ID for TC2 event generator MCX_1 */
#define EVENT_ID_GEN_ADC_RESRDY 38 /**< ID for ADC event generator RESRDY */
#define EVENT_ID_GEN_ADC_WINMON 39 /**< ID for ADC event generator WINMON */
#define EVENT_ID_GEN_AC_COMP_0 40 /**< ID for AC event generator COMP_0 */
#define EVENT_ID_GEN_AC_COMP_1 41 /**< ID for AC event generator COMP_1 */
#define EVENT_ID_GEN_AC_WIN_0 42 /**< ID for AC event generator WIN_0 */
#define EVENT_ID_GEN_DAC_EMPTY 43 /**< ID for DAC event generator EMPTY */
#define EVENT_ID_GEN_TRNG_READY 46 /**< ID for TRNG event generator READY */
#define EVENT_ID_GEN_CCL_LUTOUT_0 47 /**< ID for CCL event generator LUTOUT_0 */
#define EVENT_ID_GEN_CCL_LUTOUT_1 48 /**< ID for CCL event generator LUTOUT_1 */
#define EVENT_ID_GEN_PAC_ERR 49 /**< ID for PAC event generator ERR */
/* ************************************************************************** */
/** Event User IDs for SAML10D14A */
/* ************************************************************************** */
#define EVENT_ID_USER_OSCCTRL_TUNE 0 /**< ID for OSCCTRL event user TUNE */
#define EVENT_ID_USER_RTC_TAMPER 1 /**< ID for RTC event user TAMPER */
#define EVENT_ID_USER_NVMCTRL_PAGEW 2 /**< ID for NVMCTRL event user PAGEW */
#define EVENT_ID_USER_PORT_EV_0 3 /**< ID for PORT event user EV_0 */
#define EVENT_ID_USER_PORT_EV_1 4 /**< ID for PORT event user EV_1 */
#define EVENT_ID_USER_PORT_EV_2 5 /**< ID for PORT event user EV_2 */
#define EVENT_ID_USER_PORT_EV_3 6 /**< ID for PORT event user EV_3 */
#define EVENT_ID_USER_DMAC_CH_0 7 /**< ID for DMAC event user CH_0 */
#define EVENT_ID_USER_DMAC_CH_1 8 /**< ID for DMAC event user CH_1 */
#define EVENT_ID_USER_DMAC_CH_2 9 /**< ID for DMAC event user CH_2 */
#define EVENT_ID_USER_DMAC_CH_3 10 /**< ID for DMAC event user CH_3 */
#define EVENT_ID_USER_TC0_EVU 11 /**< ID for TC0 event user EVU */
#define EVENT_ID_USER_TC1_EVU 12 /**< ID for TC1 event user EVU */
#define EVENT_ID_USER_TC2_EVU 13 /**< ID for TC2 event user EVU */
#define EVENT_ID_USER_ADC_START 14 /**< ID for ADC event user START */
#define EVENT_ID_USER_ADC_SYNC 15 /**< ID for ADC event user SYNC */
#define EVENT_ID_USER_AC_SOC_0 16 /**< ID for AC event user SOC_0 */
#define EVENT_ID_USER_AC_SOC_1 17 /**< ID for AC event user SOC_1 */
#define EVENT_ID_USER_DAC_START 18 /**< ID for DAC event user START */
#define EVENT_ID_USER_CCL_LUTIN_0 21 /**< ID for CCL event user LUTIN_0 */
#define EVENT_ID_USER_CCL_LUTIN_1 22 /**< ID for CCL event user LUTIN_1 */
#ifdef __cplusplus
}
#endif
/** @} end of SAML10D14A definitions */
#endif /* _SAML10D14A_H_ */

View File

@ -0,0 +1,789 @@
/**
* \file
*
* \brief Header file for ATSAML10D15A
*
* Copyright (c) 2018 Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* 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
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
/* file generated from device description version 2018-08-31T13:51:50Z */
#ifndef _SAML10D15A_H_
#define _SAML10D15A_H_
/** \addtogroup SAML10D15A_definitions SAML10D15A definitions
This file defines all structures and symbols for SAML10D15A:
- registers and bitfields
- peripheral base address
- peripheral ID
- PIO definitions
* @{
*/
#ifdef __cplusplus
extern "C" {
#endif
/** \defgroup Atmel_glob_defs Atmel Global Defines
<strong>IO Type Qualifiers</strong> are used
\li to specify the access to peripheral variables.
\li for automatic generation of peripheral register debug information.
\remark
CMSIS core has a syntax that differs from this using i.e. __I, __O, or __IO followed by 'uint<size>_t' respective types.
Default the header files will follow the CMSIS core syntax.
* @{
*/
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
#include <stdint.h>
/* IO definitions (access restrictions to peripheral registers) */
#ifndef __cplusplus
typedef volatile const uint32_t RoReg; /**< Read only 32-bit register (volatile const unsigned int) */
typedef volatile const uint16_t RoReg16; /**< Read only 16-bit register (volatile const unsigned int) */
typedef volatile const uint8_t RoReg8; /**< Read only 8-bit register (volatile const unsigned int) */
#else
typedef volatile uint32_t RoReg; /**< Read only 32-bit register (volatile const unsigned int) */
typedef volatile uint16_t RoReg16; /**< Read only 16-bit register (volatile const unsigned int) */
typedef volatile uint8_t RoReg8; /**< Read only 8-bit register (volatile const unsigned int) */
#endif
typedef volatile uint32_t WoReg; /**< Write only 32-bit register (volatile unsigned int) */
typedef volatile uint16_t WoReg16; /**< Write only 16-bit register (volatile unsigned int) */
typedef volatile uint8_t WoReg8; /**< Write only 8-bit register (volatile unsigned int) */
typedef volatile uint32_t RwReg; /**< Read-Write 32-bit register (volatile unsigned int) */
typedef volatile uint16_t RwReg16; /**< Read-Write 16-bit register (volatile unsigned int) */
typedef volatile uint8_t RwReg8; /**< Read-Write 8-bit register (volatile unsigned int) */
#define CAST(type, value) ((type *)(value)) /**< Pointer Type Conversion Macro for C/C++ */
#define REG_ACCESS(type, address) (*(type*)(address)) /**< C code: Register value */
#else /* Assembler */
#define CAST(type, value) (value) /**< Pointer Type Conversion Macro for Assembler */
#define REG_ACCESS(type, address) (address) /**< Assembly code: Register address */
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#if !defined(SKIP_INTEGER_LITERALS)
#if defined(_U_) || defined(_L_) || defined(_UL_)
#error "Integer Literals macros already defined elsewhere"
#endif
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
/* Macros that deal with adding suffixes to integer literal constants for C/C++ */
#define _U_(x) x ## U /**< C code: Unsigned integer literal constant value */
#define _L_(x) x ## L /**< C code: Long integer literal constant value */
#define _UL_(x) x ## UL /**< C code: Unsigned Long integer literal constant value */
#else /* Assembler */
#define _U_(x) x /**< Assembler: Unsigned integer literal constant value */
#define _L_(x) x /**< Assembler: Long integer literal constant value */
#define _UL_(x) x /**< Assembler: Unsigned Long integer literal constant value */
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#endif /* SKIP_INTEGER_LITERALS */
/** @} end of Atmel Global Defines */
/** \addtogroup SAML10D15A_cmsis CMSIS Definitions
* @{
*/
/* ************************************************************************** */
/* CMSIS DEFINITIONS FOR SAML10D15A */
/* ************************************************************************** */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
/** Interrupt Number Definition */
typedef enum IRQn
{
/****** CORTEX-M23 Processor Exceptions Numbers ******************************/
Reset_IRQn = -15, /**< 1 Reset Vector, invoked on Power up and warm reset */
NonMaskableInt_IRQn = -14, /**< 2 Non maskable Interrupt, cannot be stopped or preempted */
HardFault_IRQn = -13, /**< 3 Hard Fault, all classes of Fault */
SVCall_IRQn = -5 , /**< 11 System Service Call via SVC instruction */
PendSV_IRQn = -2 , /**< 14 Pendable request for system service */
SysTick_IRQn = -1 , /**< 15 System Tick Timer */
/****** SAML10D15A specific Interrupt Numbers ***********************************/
SYSTEM_IRQn = 0 , /**< 0 SAML10D15A Main Clock (MCLK) */
WDT_IRQn = 1 , /**< 1 SAML10D15A Watchdog Timer (WDT) */
RTC_IRQn = 2 , /**< 2 SAML10D15A Real-Time Counter (RTC) */
EIC_0_IRQn = 3 , /**< 3 SAML10D15A External Interrupt Controller (EIC) */
EIC_1_IRQn = 4 , /**< 4 SAML10D15A External Interrupt Controller (EIC) */
EIC_2_IRQn = 5 , /**< 5 SAML10D15A External Interrupt Controller (EIC) */
EIC_3_IRQn = 6 , /**< 6 SAML10D15A External Interrupt Controller (EIC) */
EIC_OTHER_IRQn = 7 , /**< 7 SAML10D15A External Interrupt Controller (EIC) */
FREQM_IRQn = 8 , /**< 8 SAML10D15A Frequency Meter (FREQM) */
NVMCTRL_IRQn = 9 , /**< 9 SAML10D15A Non-Volatile Memory Controller (NVMCTRL) */
PORT_IRQn = 10 , /**< 10 SAML10D15A Port Module (PORT) */
DMAC_0_IRQn = 11 , /**< 11 SAML10D15A Direct Memory Access Controller (DMAC) */
DMAC_1_IRQn = 12 , /**< 12 SAML10D15A Direct Memory Access Controller (DMAC) */
DMAC_2_IRQn = 13 , /**< 13 SAML10D15A Direct Memory Access Controller (DMAC) */
DMAC_3_IRQn = 14 , /**< 14 SAML10D15A Direct Memory Access Controller (DMAC) */
DMAC_OTHER_IRQn = 15 , /**< 15 SAML10D15A Direct Memory Access Controller (DMAC) */
EVSYS_0_IRQn = 16 , /**< 16 SAML10D15A Event System Interface (EVSYS) */
EVSYS_1_IRQn = 17 , /**< 17 SAML10D15A Event System Interface (EVSYS) */
EVSYS_2_IRQn = 18 , /**< 18 SAML10D15A Event System Interface (EVSYS) */
EVSYS_3_IRQn = 19 , /**< 19 SAML10D15A Event System Interface (EVSYS) */
EVSYS_NSCHK_IRQn = 20 , /**< 20 SAML10D15A Event System Interface (EVSYS) */
PAC_IRQn = 21 , /**< 21 SAML10D15A Peripheral Access Controller (PAC) */
SERCOM0_0_IRQn = 22 , /**< 22 SAML10D15A Serial Communication Interface (SERCOM0) */
SERCOM0_1_IRQn = 23 , /**< 23 SAML10D15A Serial Communication Interface (SERCOM0) */
SERCOM0_2_IRQn = 24 , /**< 24 SAML10D15A Serial Communication Interface (SERCOM0) */
SERCOM0_OTHER_IRQn = 25 , /**< 25 SAML10D15A Serial Communication Interface (SERCOM0) */
SERCOM1_0_IRQn = 26 , /**< 26 SAML10D15A Serial Communication Interface (SERCOM1) */
SERCOM1_1_IRQn = 27 , /**< 27 SAML10D15A Serial Communication Interface (SERCOM1) */
SERCOM1_2_IRQn = 28 , /**< 28 SAML10D15A Serial Communication Interface (SERCOM1) */
SERCOM1_OTHER_IRQn = 29 , /**< 29 SAML10D15A Serial Communication Interface (SERCOM1) */
TC0_IRQn = 34 , /**< 34 SAML10D15A Basic Timer Counter (TC0) */
TC1_IRQn = 35 , /**< 35 SAML10D15A Basic Timer Counter (TC1) */
TC2_IRQn = 36 , /**< 36 SAML10D15A Basic Timer Counter (TC2) */
ADC_OTHER_IRQn = 37 , /**< 37 SAML10D15A Analog Digital Converter (ADC) */
ADC_RESRDY_IRQn = 38 , /**< 38 SAML10D15A Analog Digital Converter (ADC) */
AC_IRQn = 39 , /**< 39 SAML10D15A Analog Comparators (AC) */
DAC_UNDERRUN_A_IRQn = 40 , /**< 40 SAML10D15A Digital Analog Converter (DAC) */
DAC_EMPTY_IRQn = 41 , /**< 41 SAML10D15A Digital Analog Converter (DAC) */
PTC_IRQn = 42 , /**< 42 SAML10D15A Peripheral Touch Controller (PTC) */
TRNG_IRQn = 43 , /**< 43 SAML10D15A True Random Generator (TRNG) */
TRAM_IRQn = 44 , /**< 44 SAML10D15A TrustRAM (TRAM) */
PERIPH_COUNT_IRQn = 45 /**< Number of peripheral IDs */
} IRQn_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef struct _DeviceVectors
{
/* Stack pointer */
void* pvStack;
/* Cortex-M handlers */
void* pfnReset_Handler; /* -15 Reset Vector, invoked on Power up and warm reset */
void* pfnNonMaskableInt_Handler; /* -14 Non maskable Interrupt, cannot be stopped or preempted */
void* pfnHardFault_Handler; /* -13 Hard Fault, all classes of Fault */
void* pvReservedC12;
void* pvReservedC11;
void* pvReservedC10;
void* pvReservedC9;
void* pvReservedC8;
void* pvReservedC7;
void* pvReservedC6;
void* pfnSVCall_Handler; /* -5 System Service Call via SVC instruction */
void* pvReservedC4;
void* pvReservedC3;
void* pfnPendSV_Handler; /* -2 Pendable request for system service */
void* pfnSysTick_Handler; /* -1 System Tick Timer */
/* Peripheral handlers */
void* pfnSYSTEM_Handler; /* 0 SAML10D15A Main Clock (MCLK) */
void* pfnWDT_Handler; /* 1 SAML10D15A Watchdog Timer (WDT) */
void* pfnRTC_Handler; /* 2 SAML10D15A Real-Time Counter (RTC) */
void* pfnEIC_0_Handler; /* 3 SAML10D15A External Interrupt Controller (EIC) */
void* pfnEIC_1_Handler; /* 4 SAML10D15A External Interrupt Controller (EIC) */
void* pfnEIC_2_Handler; /* 5 SAML10D15A External Interrupt Controller (EIC) */
void* pfnEIC_3_Handler; /* 6 SAML10D15A External Interrupt Controller (EIC) */
void* pfnEIC_OTHER_Handler; /* 7 SAML10D15A External Interrupt Controller (EIC) */
void* pfnFREQM_Handler; /* 8 SAML10D15A Frequency Meter (FREQM) */
void* pfnNVMCTRL_Handler; /* 9 SAML10D15A Non-Volatile Memory Controller (NVMCTRL) */
void* pfnPORT_Handler; /* 10 SAML10D15A Port Module (PORT) */
void* pfnDMAC_0_Handler; /* 11 SAML10D15A Direct Memory Access Controller (DMAC) */
void* pfnDMAC_1_Handler; /* 12 SAML10D15A Direct Memory Access Controller (DMAC) */
void* pfnDMAC_2_Handler; /* 13 SAML10D15A Direct Memory Access Controller (DMAC) */
void* pfnDMAC_3_Handler; /* 14 SAML10D15A Direct Memory Access Controller (DMAC) */
void* pfnDMAC_OTHER_Handler; /* 15 SAML10D15A Direct Memory Access Controller (DMAC) */
void* pfnEVSYS_0_Handler; /* 16 SAML10D15A Event System Interface (EVSYS) */
void* pfnEVSYS_1_Handler; /* 17 SAML10D15A Event System Interface (EVSYS) */
void* pfnEVSYS_2_Handler; /* 18 SAML10D15A Event System Interface (EVSYS) */
void* pfnEVSYS_3_Handler; /* 19 SAML10D15A Event System Interface (EVSYS) */
void* pfnEVSYS_NSCHK_Handler; /* 20 SAML10D15A Event System Interface (EVSYS) */
void* pfnPAC_Handler; /* 21 SAML10D15A Peripheral Access Controller (PAC) */
void* pfnSERCOM0_0_Handler; /* 22 SAML10D15A Serial Communication Interface (SERCOM0) */
void* pfnSERCOM0_1_Handler; /* 23 SAML10D15A Serial Communication Interface (SERCOM0) */
void* pfnSERCOM0_2_Handler; /* 24 SAML10D15A Serial Communication Interface (SERCOM0) */
void* pfnSERCOM0_OTHER_Handler; /* 25 SAML10D15A Serial Communication Interface (SERCOM0) */
void* pfnSERCOM1_0_Handler; /* 26 SAML10D15A Serial Communication Interface (SERCOM1) */
void* pfnSERCOM1_1_Handler; /* 27 SAML10D15A Serial Communication Interface (SERCOM1) */
void* pfnSERCOM1_2_Handler; /* 28 SAML10D15A Serial Communication Interface (SERCOM1) */
void* pfnSERCOM1_OTHER_Handler; /* 29 SAML10D15A Serial Communication Interface (SERCOM1) */
void* pvReserved30;
void* pvReserved31;
void* pvReserved32;
void* pvReserved33;
void* pfnTC0_Handler; /* 34 SAML10D15A Basic Timer Counter (TC0) */
void* pfnTC1_Handler; /* 35 SAML10D15A Basic Timer Counter (TC1) */
void* pfnTC2_Handler; /* 36 SAML10D15A Basic Timer Counter (TC2) */
void* pfnADC_OTHER_Handler; /* 37 SAML10D15A Analog Digital Converter (ADC) */
void* pfnADC_RESRDY_Handler; /* 38 SAML10D15A Analog Digital Converter (ADC) */
void* pfnAC_Handler; /* 39 SAML10D15A Analog Comparators (AC) */
void* pfnDAC_UNDERRUN_A_Handler; /* 40 SAML10D15A Digital Analog Converter (DAC) */
void* pfnDAC_EMPTY_Handler; /* 41 SAML10D15A Digital Analog Converter (DAC) */
void* pfnPTC_Handler; /* 42 SAML10D15A Peripheral Touch Controller (PTC) */
void* pfnTRNG_Handler; /* 43 SAML10D15A True Random Generator (TRNG) */
void* pfnTRAM_Handler; /* 44 SAML10D15A TrustRAM (TRAM) */
} DeviceVectors;
/* Defines for Deprecated Interrupt and Exceptions handler names */
#define pfnMemManage_Handler pfnMemoryManagement_Handler /**< \deprecated Backward compatibility for ASF */
#define pfnDebugMon_Handler pfnDebugMonitor_Handler /**< \deprecated Backward compatibility for ASF */
#define pfnNMI_Handler pfnNonMaskableInt_Handler /**< \deprecated Backward compatibility for ASF */
#define pfnSVC_Handler pfnSVCall_Handler /**< \deprecated Backward compatibility for ASF */
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
#if !defined DONT_USE_PREDEFINED_CORE_HANDLERS
/* CORTEX-M23 core handlers */
void Reset_Handler ( void );
void NonMaskableInt_Handler ( void );
void HardFault_Handler ( void );
void SVCall_Handler ( void );
void PendSV_Handler ( void );
void SysTick_Handler ( void );
#endif /* DONT_USE_PREDEFINED_CORE_HANDLERS */
#if !defined DONT_USE_PREDEFINED_PERIPHERALS_HANDLERS
/* Peripherals handlers */
void AC_Handler ( void );
void ADC_OTHER_Handler ( void );
void ADC_RESRDY_Handler ( void );
void DAC_EMPTY_Handler ( void );
void DAC_UNDERRUN_A_Handler ( void );
void DMAC_0_Handler ( void );
void DMAC_1_Handler ( void );
void DMAC_2_Handler ( void );
void DMAC_3_Handler ( void );
void DMAC_OTHER_Handler ( void );
void EIC_0_Handler ( void );
void EIC_1_Handler ( void );
void EIC_2_Handler ( void );
void EIC_3_Handler ( void );
void EIC_OTHER_Handler ( void );
void EVSYS_0_Handler ( void );
void EVSYS_1_Handler ( void );
void EVSYS_2_Handler ( void );
void EVSYS_3_Handler ( void );
void EVSYS_NSCHK_Handler ( void );
void FREQM_Handler ( void );
void NVMCTRL_Handler ( void );
void PAC_Handler ( void );
void PORT_Handler ( void );
void PTC_Handler ( void );
void RTC_Handler ( void );
void SERCOM0_0_Handler ( void );
void SERCOM0_1_Handler ( void );
void SERCOM0_2_Handler ( void );
void SERCOM0_OTHER_Handler ( void );
void SERCOM1_0_Handler ( void );
void SERCOM1_1_Handler ( void );
void SERCOM1_2_Handler ( void );
void SERCOM1_OTHER_Handler ( void );
void SYSTEM_Handler ( void );
void TC0_Handler ( void );
void TC1_Handler ( void );
void TC2_Handler ( void );
void TRAM_Handler ( void );
void TRNG_Handler ( void );
void WDT_Handler ( void );
#endif /* DONT_USE_PREDEFINED_PERIPHERALS_HANDLERS */
/* Defines for Deprecated Interrupt and Exceptions handler names */
#define MemManage_Handler MemoryManagement_Handler /**< \deprecated Backward compatibility for ASF */
#define DebugMon_Handler DebugMonitor_Handler /**< \deprecated Backward compatibility for ASF */
#define NMI_Handler NonMaskableInt_Handler /**< \deprecated Backward compatibility for ASF */
#define SVC_Handler SVCall_Handler /**< \deprecated Backward compatibility for ASF */
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/*
* \brief Configuration of the CORTEX-M23 Processor and Core Peripherals
*/
#define NUM_IRQ 45 /**< Number of interrupt request lines */
#define __ARMv8MBL_REV 0x0000 /**< Cortex-M23 Core Revision */
#define __ETM_PRESENT 0 /**< ETM present or not */
#define __FPU_PRESENT 0 /**< FPU present or not */
#define __MPU_PRESENT 1 /**< MPU present or not */
#define __MTB_PRESENT 0 /**< MTB present or not */
#define __NVIC_PRIO_BITS 2 /**< Number of Bits used for Priority Levels */
#define __SAU_PRESENT 0 /**< SAU present or not */
#define __SEC_ENABLED 0 /**< TrustZone-M enabled or not */
#define __VTOR_PRESENT 1 /**< Vector Table Offset Register present or not */
#define __Vendor_SysTickConfig 0 /**< Set to 1 if different SysTick Config is used */
#define __ARCH_ARM 1
#define __ARCH_ARM_CORTEX_M 1
#define __DEVICE_IS_SAM 1
/*
* \brief CMSIS includes
*/
#include <core_cm23.h>
#if !defined DONT_USE_CMSIS_INIT
#include "system_saml10.h"
#endif /* DONT_USE_CMSIS_INIT */
/** @} end of SAML10D15A_cmsis CMSIS Definitions */
/** \defgroup SAML10D15A_api Peripheral Software API
* @{
*/
/* ************************************************************************** */
/** SOFTWARE PERIPHERAL API DEFINITION FOR SAML10D15A */
/* ************************************************************************** */
#include "component/ac.h"
#include "component/adc.h"
#include "component/ccl.h"
#include "component/dac.h"
#include "component/dmac.h"
#include "component/dsu.h"
#include "component/eic.h"
#include "component/evsys.h"
#include "component/freqm.h"
#include "component/gclk.h"
#include "component/idau.h"
#include "component/mclk.h"
#include "component/nvmctrl.h"
#include "component/opamp.h"
#include "component/oscctrl.h"
#include "component/osc32kctrl.h"
#include "component/pac.h"
#include "component/pm.h"
#include "component/port.h"
#include "component/ptc.h"
#include "component/rstc.h"
#include "component/rtc.h"
#include "component/sercom.h"
#include "component/supc.h"
#include "component/tc.h"
#include "component/tram.h"
#include "component/trng.h"
#include "component/wdt.h"
/** @} end of Peripheral Software API */
/** \defgroup SAML10D15A_reg Registers Access Definitions
* @{
*/
/* ************************************************************************** */
/* REGISTER ACCESS DEFINITIONS FOR SAML10D15A */
/* ************************************************************************** */
#include "instance/ac.h"
#include "instance/adc.h"
#include "instance/ccl.h"
#include "instance/dac.h"
#include "instance/dmac.h"
#include "instance/dsu.h"
#include "instance/eic.h"
#include "instance/evsys.h"
#include "instance/freqm.h"
#include "instance/gclk.h"
#include "instance/idau.h"
#include "instance/mclk.h"
#include "instance/nvmctrl.h"
#include "instance/opamp.h"
#include "instance/oscctrl.h"
#include "instance/osc32kctrl.h"
#include "instance/pac.h"
#include "instance/pm.h"
#include "instance/port.h"
#include "instance/ptc.h"
#include "instance/rstc.h"
#include "instance/rtc.h"
#include "instance/sercom0.h"
#include "instance/sercom1.h"
#include "instance/supc.h"
#include "instance/tc0.h"
#include "instance/tc1.h"
#include "instance/tc2.h"
#include "instance/tram.h"
#include "instance/trng.h"
#include "instance/wdt.h"
/** @} end of Registers Access Definitions */
/** \addtogroup SAML10D15A_id Peripheral Ids Definitions
* @{
*/
/* ************************************************************************** */
/* PERIPHERAL ID DEFINITIONS FOR SAML10D15A */
/* ************************************************************************** */
#define ID_PAC ( 0) /**< \brief Peripheral Access Controller (PAC) */
#define ID_PM ( 1) /**< \brief Power Manager (PM) */
#define ID_MCLK ( 2) /**< \brief Main Clock (MCLK) */
#define ID_RSTC ( 3) /**< \brief Reset Controller (RSTC) */
#define ID_OSCCTRL ( 4) /**< \brief Oscillators Control (OSCCTRL) */
#define ID_OSC32KCTRL ( 5) /**< \brief 32k Oscillators Control (OSC32KCTRL) */
#define ID_SUPC ( 6) /**< \brief Supply Controller (SUPC) */
#define ID_GCLK ( 7) /**< \brief Generic Clock Generator (GCLK) */
#define ID_WDT ( 8) /**< \brief Watchdog Timer (WDT) */
#define ID_RTC ( 9) /**< \brief Real-Time Counter (RTC) */
#define ID_EIC ( 10) /**< \brief External Interrupt Controller (EIC) */
#define ID_FREQM ( 11) /**< \brief Frequency Meter (FREQM) */
#define ID_PORT ( 12) /**< \brief Port Module (PORT) */
#define ID_AC ( 13) /**< \brief Analog Comparators (AC) */
#define ID_IDAU ( 32) /**< \brief Implementation Defined Attribution Unit (IDAU) */
#define ID_DSU ( 33) /**< \brief Device Service Unit (DSU) */
#define ID_NVMCTRL ( 34) /**< \brief Non-Volatile Memory Controller (NVMCTRL) */
#define ID_DMAC ( 35) /**< \brief Direct Memory Access Controller (DMAC) */
#define ID_EVSYS ( 64) /**< \brief Event System Interface (EVSYS) */
#define ID_SERCOM0 ( 65) /**< \brief Serial Communication Interface (SERCOM0) */
#define ID_SERCOM1 ( 66) /**< \brief Serial Communication Interface (SERCOM1) */
#define ID_TC0 ( 68) /**< \brief Basic Timer Counter (TC0) */
#define ID_TC1 ( 69) /**< \brief Basic Timer Counter (TC1) */
#define ID_TC2 ( 70) /**< \brief Basic Timer Counter (TC2) */
#define ID_ADC ( 71) /**< \brief Analog Digital Converter (ADC) */
#define ID_DAC ( 72) /**< \brief Digital Analog Converter (DAC) */
#define ID_PTC ( 73) /**< \brief Peripheral Touch Controller (PTC) */
#define ID_TRNG ( 74) /**< \brief True Random Generator (TRNG) */
#define ID_CCL ( 75) /**< \brief Configurable Custom Logic (CCL) */
#define ID_OPAMP ( 76) /**< \brief Operational Amplifier (OPAMP) */
#define ID_TRAM ( 77) /**< \brief TrustRAM (TRAM) */
#define ID_PERIPH_COUNT ( 78) /**< \brief Number of peripheral IDs */
/** @} end of Peripheral Ids Definitions */
/** \addtogroup SAML10D15A_base Peripheral Base Address Definitions
* @{
*/
/* ************************************************************************** */
/* BASE ADDRESS DEFINITIONS FOR SAML10D15A */
/* ************************************************************************** */
#if (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
#define AC (0x40003400) /**< \brief (AC ) Base Address */
#define ADC (0x42001C00) /**< \brief (ADC ) Base Address */
#define CCL (0x42002C00) /**< \brief (CCL ) Base Address */
#define DAC (0x42002000) /**< \brief (DAC ) Base Address */
#define DMAC (0x41006000) /**< \brief (DMAC ) Base Address */
#define DSU (0x41002000) /**< \brief (DSU ) Base Address */
#define DSU_EXT (0x41002100) /**< \brief (DSU ) Base Address */
#define EIC (0x40002800) /**< \brief (EIC ) Base Address */
#define EVSYS (0x42000000) /**< \brief (EVSYS ) Base Address */
#define FREQM (0x40002C00) /**< \brief (FREQM ) Base Address */
#define GCLK (0x40001C00) /**< \brief (GCLK ) Base Address */
#define IDAU (0x41000000) /**< \brief (IDAU ) Base Address */
#define MCLK (0x40000800) /**< \brief (MCLK ) Base Address */
#define NVMCTRL (0x41004000) /**< \brief (NVMCTRL ) Base Address */
#define OPAMP (0x42003000) /**< \brief (OPAMP ) Base Address */
#define OSCCTRL (0x40001000) /**< \brief (OSCCTRL ) Base Address */
#define OSC32KCTRL (0x40001400) /**< \brief (OSC32KCTRL) Base Address */
#define PAC (0x40000000) /**< \brief (PAC ) Base Address */
#define PM (0x40000400) /**< \brief (PM ) Base Address */
#define PORT (0x40003000) /**< \brief (PORT ) Base Address */
#define PORT_IOBUS (0x60000000) /**< \brief (PORT ) Base Address */
#define PTC (0x42002400) /**< \brief (PTC ) Base Address */
#define RSTC (0x40000C00) /**< \brief (RSTC ) Base Address */
#define RTC (0x40002400) /**< \brief (RTC ) Base Address */
#define SERCOM0 (0x42000400) /**< \brief (SERCOM0 ) Base Address */
#define SERCOM1 (0x42000800) /**< \brief (SERCOM1 ) Base Address */
#define SUPC (0x40001800) /**< \brief (SUPC ) Base Address */
#define TC0 (0x42001000) /**< \brief (TC0 ) Base Address */
#define TC1 (0x42001400) /**< \brief (TC1 ) Base Address */
#define TC2 (0x42001800) /**< \brief (TC2 ) Base Address */
#define TRAM (0x42003400) /**< \brief (TRAM ) Base Address */
#define TRNG (0x42002800) /**< \brief (TRNG ) Base Address */
#define WDT (0x40002000) /**< \brief (WDT ) Base Address */
#else /* For C/C++ compiler */
#define AC ((Ac *)0x40003400U) /**< \brief (AC ) Base Address */
#define AC_INST_NUM 1 /**< \brief (AC ) Number of instances */
#define AC_INSTS { AC } /**< \brief (AC ) Instances List */
#define ADC ((Adc *)0x42001C00U) /**< \brief (ADC ) Base Address */
#define ADC_INST_NUM 1 /**< \brief (ADC ) Number of instances */
#define ADC_INSTS { ADC } /**< \brief (ADC ) Instances List */
#define CCL ((Ccl *)0x42002C00U) /**< \brief (CCL ) Base Address */
#define CCL_INST_NUM 1 /**< \brief (CCL ) Number of instances */
#define CCL_INSTS { CCL } /**< \brief (CCL ) Instances List */
#define DAC ((Dac *)0x42002000U) /**< \brief (DAC ) Base Address */
#define DAC_INST_NUM 1 /**< \brief (DAC ) Number of instances */
#define DAC_INSTS { DAC } /**< \brief (DAC ) Instances List */
#define DMAC ((Dmac *)0x41006000U) /**< \brief (DMAC ) Base Address */
#define DMAC_INST_NUM 1 /**< \brief (DMAC ) Number of instances */
#define DMAC_INSTS { DMAC } /**< \brief (DMAC ) Instances List */
#define DSU ((Dsu *)0x41002000U) /**< \brief (DSU ) Base Address */
#define DSU_EXT ((Dsu *)0x41002100U) /**< \brief (DSU ) Base Address */
#define DSU_INST_NUM 1 /**< \brief (DSU ) Number of instances */
#define DSU_INSTS { DSU } /**< \brief (DSU ) Instances List */
#define EIC ((Eic *)0x40002800U) /**< \brief (EIC ) Base Address */
#define EIC_INST_NUM 1 /**< \brief (EIC ) Number of instances */
#define EIC_INSTS { EIC } /**< \brief (EIC ) Instances List */
#define EVSYS ((Evsys *)0x42000000U) /**< \brief (EVSYS ) Base Address */
#define EVSYS_INST_NUM 1 /**< \brief (EVSYS ) Number of instances */
#define EVSYS_INSTS { EVSYS } /**< \brief (EVSYS ) Instances List */
#define FREQM ((Freqm *)0x40002C00U) /**< \brief (FREQM ) Base Address */
#define FREQM_INST_NUM 1 /**< \brief (FREQM ) Number of instances */
#define FREQM_INSTS { FREQM } /**< \brief (FREQM ) Instances List */
#define GCLK ((Gclk *)0x40001C00U) /**< \brief (GCLK ) Base Address */
#define GCLK_INST_NUM 1 /**< \brief (GCLK ) Number of instances */
#define GCLK_INSTS { GCLK } /**< \brief (GCLK ) Instances List */
#define IDAU ((Idau *)0x41000000U) /**< \brief (IDAU ) Base Address */
#define IDAU_INST_NUM 1 /**< \brief (IDAU ) Number of instances */
#define IDAU_INSTS { IDAU } /**< \brief (IDAU ) Instances List */
#define MCLK ((Mclk *)0x40000800U) /**< \brief (MCLK ) Base Address */
#define MCLK_INST_NUM 1 /**< \brief (MCLK ) Number of instances */
#define MCLK_INSTS { MCLK } /**< \brief (MCLK ) Instances List */
#define NVMCTRL ((Nvmctrl *)0x41004000U) /**< \brief (NVMCTRL ) Base Address */
#define NVMCTRL_INST_NUM 1 /**< \brief (NVMCTRL ) Number of instances */
#define NVMCTRL_INSTS { NVMCTRL } /**< \brief (NVMCTRL ) Instances List */
#define OPAMP ((Opamp *)0x42003000U) /**< \brief (OPAMP ) Base Address */
#define OPAMP_INST_NUM 1 /**< \brief (OPAMP ) Number of instances */
#define OPAMP_INSTS { OPAMP } /**< \brief (OPAMP ) Instances List */
#define OSCCTRL ((Oscctrl *)0x40001000U) /**< \brief (OSCCTRL ) Base Address */
#define OSCCTRL_INST_NUM 1 /**< \brief (OSCCTRL ) Number of instances */
#define OSCCTRL_INSTS { OSCCTRL } /**< \brief (OSCCTRL ) Instances List */
#define OSC32KCTRL ((Osc32kctrl *)0x40001400U) /**< \brief (OSC32KCTRL) Base Address */
#define OSC32KCTRL_INST_NUM 1 /**< \brief (OSC32KCTRL) Number of instances */
#define OSC32KCTRL_INSTS { OSC32KCTRL } /**< \brief (OSC32KCTRL) Instances List */
#define PAC ((Pac *)0x40000000U) /**< \brief (PAC ) Base Address */
#define PAC_INST_NUM 1 /**< \brief (PAC ) Number of instances */
#define PAC_INSTS { PAC } /**< \brief (PAC ) Instances List */
#define PM ((Pm *)0x40000400U) /**< \brief (PM ) Base Address */
#define PM_INST_NUM 1 /**< \brief (PM ) Number of instances */
#define PM_INSTS { PM } /**< \brief (PM ) Instances List */
#define PORT ((Port *)0x40003000U) /**< \brief (PORT ) Base Address */
#define PORT_IOBUS ((Port *)0x60000000U) /**< \brief (PORT ) Base Address */
#define PORT_INST_NUM 1 /**< \brief (PORT ) Number of instances */
#define PORT_INSTS { PORT } /**< \brief (PORT ) Instances List */
#define PTC ((Ptc *)0x42002400U) /**< \brief (PTC ) Base Address */
#define PTC_INST_NUM 1 /**< \brief (PTC ) Number of instances */
#define PTC_INSTS { PTC } /**< \brief (PTC ) Instances List */
#define RSTC ((Rstc *)0x40000C00U) /**< \brief (RSTC ) Base Address */
#define RSTC_INST_NUM 1 /**< \brief (RSTC ) Number of instances */
#define RSTC_INSTS { RSTC } /**< \brief (RSTC ) Instances List */
#define RTC ((Rtc *)0x40002400U) /**< \brief (RTC ) Base Address */
#define RTC_INST_NUM 1 /**< \brief (RTC ) Number of instances */
#define RTC_INSTS { RTC } /**< \brief (RTC ) Instances List */
#define SERCOM0 ((Sercom *)0x42000400U) /**< \brief (SERCOM0 ) Base Address */
#define SERCOM1 ((Sercom *)0x42000800U) /**< \brief (SERCOM1 ) Base Address */
#define SERCOM_INST_NUM 2 /**< \brief (SERCOM ) Number of instances */
#define SERCOM_INSTS { SERCOM0, SERCOM1 } /**< \brief (SERCOM ) Instances List */
#define SUPC ((Supc *)0x40001800U) /**< \brief (SUPC ) Base Address */
#define SUPC_INST_NUM 1 /**< \brief (SUPC ) Number of instances */
#define SUPC_INSTS { SUPC } /**< \brief (SUPC ) Instances List */
#define TC0 ((Tc *)0x42001000U) /**< \brief (TC0 ) Base Address */
#define TC1 ((Tc *)0x42001400U) /**< \brief (TC1 ) Base Address */
#define TC2 ((Tc *)0x42001800U) /**< \brief (TC2 ) Base Address */
#define TC_INST_NUM 3 /**< \brief (TC ) Number of instances */
#define TC_INSTS { TC0, TC1, TC2 } /**< \brief (TC ) Instances List */
#define TRAM ((Tram *)0x42003400U) /**< \brief (TRAM ) Base Address */
#define TRAM_INST_NUM 1 /**< \brief (TRAM ) Number of instances */
#define TRAM_INSTS { TRAM } /**< \brief (TRAM ) Instances List */
#define TRNG ((Trng *)0x42002800U) /**< \brief (TRNG ) Base Address */
#define TRNG_INST_NUM 1 /**< \brief (TRNG ) Number of instances */
#define TRNG_INSTS { TRNG } /**< \brief (TRNG ) Instances List */
#define WDT ((Wdt *)0x40002000U) /**< \brief (WDT ) Base Address */
#define WDT_INST_NUM 1 /**< \brief (WDT ) Number of instances */
#define WDT_INSTS { WDT } /**< \brief (WDT ) Instances List */
#endif /* (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/** @} end of Peripheral Base Address Definitions */
/** \addtogroup SAML10D15A_pio Peripheral Pio Definitions
* @{
*/
/* ************************************************************************** */
/* PIO DEFINITIONS FOR SAML10D15A*/
/* ************************************************************************** */
#include "pio/saml10d15a.h"
/** @} end of Peripheral Pio Definitions */
/* ************************************************************************** */
/* MEMORY MAPPING DEFINITIONS FOR SAML10D15A*/
/* ************************************************************************** */
#define FLASH_SIZE _U_(0x00008000) /* 32kB Memory segment type: flash */
#define FLASH_PAGE_SIZE _U_( 64)
#define FLASH_NB_OF_PAGES _U_( 512)
#define AUX_SIZE _U_(0x00000100) /* 0kB Memory segment type: fuses */
#define AUX_PAGE_SIZE _U_( 64)
#define AUX_NB_OF_PAGES _U_( 4)
#define BOCOR_SIZE _U_(0x00000100) /* 0kB Memory segment type: fuses */
#define BOCOR_PAGE_SIZE _U_( 64)
#define BOCOR_NB_OF_PAGES _U_( 4)
#define DATAFLASH_SIZE _U_(0x00000800) /* 2kB Memory segment type: flash */
#define DATAFLASH_PAGE_SIZE _U_( 64)
#define DATAFLASH_NB_OF_PAGES _U_( 32)
#define SW_CALIB_SIZE _U_(0x00000008) /* 0kB Memory segment type: fuses */
#define TEMP_LOG_SIZE _U_(0x00000008) /* 0kB Memory segment type: fuses */
#define USER_PAGE_SIZE _U_(0x00000100) /* 0kB Memory segment type: user_page */
#define USER_PAGE_PAGE_SIZE _U_( 64)
#define USER_PAGE_NB_OF_PAGES _U_( 4)
#define HSRAM_SIZE _U_(0x00002000) /* 8kB Memory segment type: ram */
#define HPB0_SIZE _U_(0x00008000) /* 32kB Memory segment type: io */
#define HPB1_SIZE _U_(0x00010000) /* 64kB Memory segment type: io */
#define HPB2_SIZE _U_(0x00004000) /* 16kB Memory segment type: io */
#define PPB_SIZE _U_(0x00100000) /* 1024kB Memory segment type: io */
#define SCS_SIZE _U_(0x00001000) /* 4kB Memory segment type: io */
#define PERIPHERALS_SIZE _U_(0x20000000) /* 524288kB Memory segment type: io */
#define FLASH_ADDR _U_(0x00000000) /**< FLASH base address (type: flash)*/
#define AUX_ADDR _U_(0x00806000) /**< AUX base address (type: fuses)*/
#define BOCOR_ADDR _U_(0x0080c000) /**< BOCOR base address (type: fuses)*/
#define DATAFLASH_ADDR _U_(0x00400000) /**< DATAFLASH base address (type: flash)*/
#define SW_CALIB_ADDR _U_(0x00806020) /**< SW_CALIB base address (type: fuses)*/
#define TEMP_LOG_ADDR _U_(0x00806038) /**< TEMP_LOG base address (type: fuses)*/
#define USER_PAGE_ADDR _U_(0x00804000) /**< USER_PAGE base address (type: user_page)*/
#define HSRAM_ADDR _U_(0x20000000) /**< HSRAM base address (type: ram)*/
#define HPB0_ADDR _U_(0x40000000) /**< HPB0 base address (type: io)*/
#define HPB1_ADDR _U_(0x41000000) /**< HPB1 base address (type: io)*/
#define HPB2_ADDR _U_(0x42000000) /**< HPB2 base address (type: io)*/
#define PPB_ADDR _U_(0xe0000000) /**< PPB base address (type: io)*/
#define SCS_ADDR _U_(0xe000e000) /**< SCS base address (type: io)*/
#define PERIPHERALS_ADDR _U_(0x40000000) /**< PERIPHERALS base address (type: io)*/
#define NVMCTRL_AUX AUX_ADDR /**< \brief \deprecated Old style definition. Use AUX_ADDR instead */
#define NVMCTRL_BOCOR BOCOR_ADDR /**< \brief \deprecated Old style definition. Use BOCOR_ADDR instead */
#define NVMCTRL_DATAFLASH DATAFLASH_ADDR /**< \brief \deprecated Old style definition. Use DATAFLASH_ADDR instead */
#define NVMCTRL_SW_CALIB SW_CALIB_ADDR /**< \brief \deprecated Old style definition. Use SW_CALIB_ADDR instead */
#define NVMCTRL_TEMP_LOG TEMP_LOG_ADDR /**< \brief \deprecated Old style definition. Use TEMP_LOG_ADDR instead */
#define NVMCTRL_USER USER_PAGE_ADDR /**< \brief \deprecated Old style definition. Use USER_PAGE_ADDR instead */
/* ************************************************************************** */
/** DEVICE SIGNATURES FOR SAML10D15A */
/* ************************************************************************** */
#define DSU_DID _UL_(0X20840004)
/* ************************************************************************** */
/** ELECTRICAL DEFINITIONS FOR SAML10D15A */
/* ************************************************************************** */
/* ************************************************************************** */
/** Event Generator IDs for SAML10D15A */
/* ************************************************************************** */
#define EVENT_ID_GEN_OSCCTRL_XOSC_FAIL 1 /**< ID for OSCCTRL event generator XOSC_FAIL */
#define EVENT_ID_GEN_OSC32KCTRL_XOSC32K_FAIL 2 /**< ID for OSC32KCTRL event generator XOSC32K_FAIL */
#define EVENT_ID_GEN_SUPC_BOD33DET 3 /**< ID for SUPC event generator BOD33DET */
#define EVENT_ID_GEN_RTC_PER_0 4 /**< ID for RTC event generator PER_0 */
#define EVENT_ID_GEN_RTC_PER_1 5 /**< ID for RTC event generator PER_1 */
#define EVENT_ID_GEN_RTC_PER_2 6 /**< ID for RTC event generator PER_2 */
#define EVENT_ID_GEN_RTC_PER_3 7 /**< ID for RTC event generator PER_3 */
#define EVENT_ID_GEN_RTC_PER_4 8 /**< ID for RTC event generator PER_4 */
#define EVENT_ID_GEN_RTC_PER_5 9 /**< ID for RTC event generator PER_5 */
#define EVENT_ID_GEN_RTC_PER_6 10 /**< ID for RTC event generator PER_6 */
#define EVENT_ID_GEN_RTC_PER_7 11 /**< ID for RTC event generator PER_7 */
#define EVENT_ID_GEN_RTC_CMP_0 12 /**< ID for RTC event generator CMP_0 */
#define EVENT_ID_GEN_RTC_CMP_1 13 /**< ID for RTC event generator CMP_1 */
#define EVENT_ID_GEN_RTC_TAMPER 14 /**< ID for RTC event generator TAMPER */
#define EVENT_ID_GEN_RTC_OVF 15 /**< ID for RTC event generator OVF */
#define EVENT_ID_GEN_RTC_PERD 16 /**< ID for RTC event generator PERD */
#define EVENT_ID_GEN_EIC_EXTINT_0 17 /**< ID for EIC event generator EXTINT_0 */
#define EVENT_ID_GEN_EIC_EXTINT_1 18 /**< ID for EIC event generator EXTINT_1 */
#define EVENT_ID_GEN_EIC_EXTINT_2 19 /**< ID for EIC event generator EXTINT_2 */
#define EVENT_ID_GEN_EIC_EXTINT_3 20 /**< ID for EIC event generator EXTINT_3 */
#define EVENT_ID_GEN_EIC_EXTINT_4 21 /**< ID for EIC event generator EXTINT_4 */
#define EVENT_ID_GEN_EIC_EXTINT_5 22 /**< ID for EIC event generator EXTINT_5 */
#define EVENT_ID_GEN_EIC_EXTINT_6 23 /**< ID for EIC event generator EXTINT_6 */
#define EVENT_ID_GEN_EIC_EXTINT_7 24 /**< ID for EIC event generator EXTINT_7 */
#define EVENT_ID_GEN_DMAC_CH_0 25 /**< ID for DMAC event generator CH_0 */
#define EVENT_ID_GEN_DMAC_CH_1 26 /**< ID for DMAC event generator CH_1 */
#define EVENT_ID_GEN_DMAC_CH_2 27 /**< ID for DMAC event generator CH_2 */
#define EVENT_ID_GEN_DMAC_CH_3 28 /**< ID for DMAC event generator CH_3 */
#define EVENT_ID_GEN_TC0_OVF 29 /**< ID for TC0 event generator OVF */
#define EVENT_ID_GEN_TC0_MCX_0 30 /**< ID for TC0 event generator MCX_0 */
#define EVENT_ID_GEN_TC0_MCX_1 31 /**< ID for TC0 event generator MCX_1 */
#define EVENT_ID_GEN_TC1_OVF 32 /**< ID for TC1 event generator OVF */
#define EVENT_ID_GEN_TC1_MCX_0 33 /**< ID for TC1 event generator MCX_0 */
#define EVENT_ID_GEN_TC1_MCX_1 34 /**< ID for TC1 event generator MCX_1 */
#define EVENT_ID_GEN_TC2_OVF 35 /**< ID for TC2 event generator OVF */
#define EVENT_ID_GEN_TC2_MCX_0 36 /**< ID for TC2 event generator MCX_0 */
#define EVENT_ID_GEN_TC2_MCX_1 37 /**< ID for TC2 event generator MCX_1 */
#define EVENT_ID_GEN_ADC_RESRDY 38 /**< ID for ADC event generator RESRDY */
#define EVENT_ID_GEN_ADC_WINMON 39 /**< ID for ADC event generator WINMON */
#define EVENT_ID_GEN_AC_COMP_0 40 /**< ID for AC event generator COMP_0 */
#define EVENT_ID_GEN_AC_COMP_1 41 /**< ID for AC event generator COMP_1 */
#define EVENT_ID_GEN_AC_WIN_0 42 /**< ID for AC event generator WIN_0 */
#define EVENT_ID_GEN_DAC_EMPTY 43 /**< ID for DAC event generator EMPTY */
#define EVENT_ID_GEN_TRNG_READY 46 /**< ID for TRNG event generator READY */
#define EVENT_ID_GEN_CCL_LUTOUT_0 47 /**< ID for CCL event generator LUTOUT_0 */
#define EVENT_ID_GEN_CCL_LUTOUT_1 48 /**< ID for CCL event generator LUTOUT_1 */
#define EVENT_ID_GEN_PAC_ERR 49 /**< ID for PAC event generator ERR */
/* ************************************************************************** */
/** Event User IDs for SAML10D15A */
/* ************************************************************************** */
#define EVENT_ID_USER_OSCCTRL_TUNE 0 /**< ID for OSCCTRL event user TUNE */
#define EVENT_ID_USER_RTC_TAMPER 1 /**< ID for RTC event user TAMPER */
#define EVENT_ID_USER_NVMCTRL_PAGEW 2 /**< ID for NVMCTRL event user PAGEW */
#define EVENT_ID_USER_PORT_EV_0 3 /**< ID for PORT event user EV_0 */
#define EVENT_ID_USER_PORT_EV_1 4 /**< ID for PORT event user EV_1 */
#define EVENT_ID_USER_PORT_EV_2 5 /**< ID for PORT event user EV_2 */
#define EVENT_ID_USER_PORT_EV_3 6 /**< ID for PORT event user EV_3 */
#define EVENT_ID_USER_DMAC_CH_0 7 /**< ID for DMAC event user CH_0 */
#define EVENT_ID_USER_DMAC_CH_1 8 /**< ID for DMAC event user CH_1 */
#define EVENT_ID_USER_DMAC_CH_2 9 /**< ID for DMAC event user CH_2 */
#define EVENT_ID_USER_DMAC_CH_3 10 /**< ID for DMAC event user CH_3 */
#define EVENT_ID_USER_TC0_EVU 11 /**< ID for TC0 event user EVU */
#define EVENT_ID_USER_TC1_EVU 12 /**< ID for TC1 event user EVU */
#define EVENT_ID_USER_TC2_EVU 13 /**< ID for TC2 event user EVU */
#define EVENT_ID_USER_ADC_START 14 /**< ID for ADC event user START */
#define EVENT_ID_USER_ADC_SYNC 15 /**< ID for ADC event user SYNC */
#define EVENT_ID_USER_AC_SOC_0 16 /**< ID for AC event user SOC_0 */
#define EVENT_ID_USER_AC_SOC_1 17 /**< ID for AC event user SOC_1 */
#define EVENT_ID_USER_DAC_START 18 /**< ID for DAC event user START */
#define EVENT_ID_USER_CCL_LUTIN_0 21 /**< ID for CCL event user LUTIN_0 */
#define EVENT_ID_USER_CCL_LUTIN_1 22 /**< ID for CCL event user LUTIN_1 */
#ifdef __cplusplus
}
#endif
/** @} end of SAML10D15A definitions */
#endif /* _SAML10D15A_H_ */

View File

@ -0,0 +1,789 @@
/**
* \file
*
* \brief Header file for ATSAML10D16A
*
* Copyright (c) 2018 Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* 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
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
/* file generated from device description version 2018-08-31T13:51:50Z */
#ifndef _SAML10D16A_H_
#define _SAML10D16A_H_
/** \addtogroup SAML10D16A_definitions SAML10D16A definitions
This file defines all structures and symbols for SAML10D16A:
- registers and bitfields
- peripheral base address
- peripheral ID
- PIO definitions
* @{
*/
#ifdef __cplusplus
extern "C" {
#endif
/** \defgroup Atmel_glob_defs Atmel Global Defines
<strong>IO Type Qualifiers</strong> are used
\li to specify the access to peripheral variables.
\li for automatic generation of peripheral register debug information.
\remark
CMSIS core has a syntax that differs from this using i.e. __I, __O, or __IO followed by 'uint<size>_t' respective types.
Default the header files will follow the CMSIS core syntax.
* @{
*/
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
#include <stdint.h>
/* IO definitions (access restrictions to peripheral registers) */
#ifndef __cplusplus
typedef volatile const uint32_t RoReg; /**< Read only 32-bit register (volatile const unsigned int) */
typedef volatile const uint16_t RoReg16; /**< Read only 16-bit register (volatile const unsigned int) */
typedef volatile const uint8_t RoReg8; /**< Read only 8-bit register (volatile const unsigned int) */
#else
typedef volatile uint32_t RoReg; /**< Read only 32-bit register (volatile const unsigned int) */
typedef volatile uint16_t RoReg16; /**< Read only 16-bit register (volatile const unsigned int) */
typedef volatile uint8_t RoReg8; /**< Read only 8-bit register (volatile const unsigned int) */
#endif
typedef volatile uint32_t WoReg; /**< Write only 32-bit register (volatile unsigned int) */
typedef volatile uint16_t WoReg16; /**< Write only 16-bit register (volatile unsigned int) */
typedef volatile uint8_t WoReg8; /**< Write only 8-bit register (volatile unsigned int) */
typedef volatile uint32_t RwReg; /**< Read-Write 32-bit register (volatile unsigned int) */
typedef volatile uint16_t RwReg16; /**< Read-Write 16-bit register (volatile unsigned int) */
typedef volatile uint8_t RwReg8; /**< Read-Write 8-bit register (volatile unsigned int) */
#define CAST(type, value) ((type *)(value)) /**< Pointer Type Conversion Macro for C/C++ */
#define REG_ACCESS(type, address) (*(type*)(address)) /**< C code: Register value */
#else /* Assembler */
#define CAST(type, value) (value) /**< Pointer Type Conversion Macro for Assembler */
#define REG_ACCESS(type, address) (address) /**< Assembly code: Register address */
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#if !defined(SKIP_INTEGER_LITERALS)
#if defined(_U_) || defined(_L_) || defined(_UL_)
#error "Integer Literals macros already defined elsewhere"
#endif
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
/* Macros that deal with adding suffixes to integer literal constants for C/C++ */
#define _U_(x) x ## U /**< C code: Unsigned integer literal constant value */
#define _L_(x) x ## L /**< C code: Long integer literal constant value */
#define _UL_(x) x ## UL /**< C code: Unsigned Long integer literal constant value */
#else /* Assembler */
#define _U_(x) x /**< Assembler: Unsigned integer literal constant value */
#define _L_(x) x /**< Assembler: Long integer literal constant value */
#define _UL_(x) x /**< Assembler: Unsigned Long integer literal constant value */
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#endif /* SKIP_INTEGER_LITERALS */
/** @} end of Atmel Global Defines */
/** \addtogroup SAML10D16A_cmsis CMSIS Definitions
* @{
*/
/* ************************************************************************** */
/* CMSIS DEFINITIONS FOR SAML10D16A */
/* ************************************************************************** */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
/** Interrupt Number Definition */
typedef enum IRQn
{
/****** CORTEX-M23 Processor Exceptions Numbers ******************************/
Reset_IRQn = -15, /**< 1 Reset Vector, invoked on Power up and warm reset */
NonMaskableInt_IRQn = -14, /**< 2 Non maskable Interrupt, cannot be stopped or preempted */
HardFault_IRQn = -13, /**< 3 Hard Fault, all classes of Fault */
SVCall_IRQn = -5 , /**< 11 System Service Call via SVC instruction */
PendSV_IRQn = -2 , /**< 14 Pendable request for system service */
SysTick_IRQn = -1 , /**< 15 System Tick Timer */
/****** SAML10D16A specific Interrupt Numbers ***********************************/
SYSTEM_IRQn = 0 , /**< 0 SAML10D16A Main Clock (MCLK) */
WDT_IRQn = 1 , /**< 1 SAML10D16A Watchdog Timer (WDT) */
RTC_IRQn = 2 , /**< 2 SAML10D16A Real-Time Counter (RTC) */
EIC_0_IRQn = 3 , /**< 3 SAML10D16A External Interrupt Controller (EIC) */
EIC_1_IRQn = 4 , /**< 4 SAML10D16A External Interrupt Controller (EIC) */
EIC_2_IRQn = 5 , /**< 5 SAML10D16A External Interrupt Controller (EIC) */
EIC_3_IRQn = 6 , /**< 6 SAML10D16A External Interrupt Controller (EIC) */
EIC_OTHER_IRQn = 7 , /**< 7 SAML10D16A External Interrupt Controller (EIC) */
FREQM_IRQn = 8 , /**< 8 SAML10D16A Frequency Meter (FREQM) */
NVMCTRL_IRQn = 9 , /**< 9 SAML10D16A Non-Volatile Memory Controller (NVMCTRL) */
PORT_IRQn = 10 , /**< 10 SAML10D16A Port Module (PORT) */
DMAC_0_IRQn = 11 , /**< 11 SAML10D16A Direct Memory Access Controller (DMAC) */
DMAC_1_IRQn = 12 , /**< 12 SAML10D16A Direct Memory Access Controller (DMAC) */
DMAC_2_IRQn = 13 , /**< 13 SAML10D16A Direct Memory Access Controller (DMAC) */
DMAC_3_IRQn = 14 , /**< 14 SAML10D16A Direct Memory Access Controller (DMAC) */
DMAC_OTHER_IRQn = 15 , /**< 15 SAML10D16A Direct Memory Access Controller (DMAC) */
EVSYS_0_IRQn = 16 , /**< 16 SAML10D16A Event System Interface (EVSYS) */
EVSYS_1_IRQn = 17 , /**< 17 SAML10D16A Event System Interface (EVSYS) */
EVSYS_2_IRQn = 18 , /**< 18 SAML10D16A Event System Interface (EVSYS) */
EVSYS_3_IRQn = 19 , /**< 19 SAML10D16A Event System Interface (EVSYS) */
EVSYS_NSCHK_IRQn = 20 , /**< 20 SAML10D16A Event System Interface (EVSYS) */
PAC_IRQn = 21 , /**< 21 SAML10D16A Peripheral Access Controller (PAC) */
SERCOM0_0_IRQn = 22 , /**< 22 SAML10D16A Serial Communication Interface (SERCOM0) */
SERCOM0_1_IRQn = 23 , /**< 23 SAML10D16A Serial Communication Interface (SERCOM0) */
SERCOM0_2_IRQn = 24 , /**< 24 SAML10D16A Serial Communication Interface (SERCOM0) */
SERCOM0_OTHER_IRQn = 25 , /**< 25 SAML10D16A Serial Communication Interface (SERCOM0) */
SERCOM1_0_IRQn = 26 , /**< 26 SAML10D16A Serial Communication Interface (SERCOM1) */
SERCOM1_1_IRQn = 27 , /**< 27 SAML10D16A Serial Communication Interface (SERCOM1) */
SERCOM1_2_IRQn = 28 , /**< 28 SAML10D16A Serial Communication Interface (SERCOM1) */
SERCOM1_OTHER_IRQn = 29 , /**< 29 SAML10D16A Serial Communication Interface (SERCOM1) */
TC0_IRQn = 34 , /**< 34 SAML10D16A Basic Timer Counter (TC0) */
TC1_IRQn = 35 , /**< 35 SAML10D16A Basic Timer Counter (TC1) */
TC2_IRQn = 36 , /**< 36 SAML10D16A Basic Timer Counter (TC2) */
ADC_OTHER_IRQn = 37 , /**< 37 SAML10D16A Analog Digital Converter (ADC) */
ADC_RESRDY_IRQn = 38 , /**< 38 SAML10D16A Analog Digital Converter (ADC) */
AC_IRQn = 39 , /**< 39 SAML10D16A Analog Comparators (AC) */
DAC_UNDERRUN_A_IRQn = 40 , /**< 40 SAML10D16A Digital Analog Converter (DAC) */
DAC_EMPTY_IRQn = 41 , /**< 41 SAML10D16A Digital Analog Converter (DAC) */
PTC_IRQn = 42 , /**< 42 SAML10D16A Peripheral Touch Controller (PTC) */
TRNG_IRQn = 43 , /**< 43 SAML10D16A True Random Generator (TRNG) */
TRAM_IRQn = 44 , /**< 44 SAML10D16A TrustRAM (TRAM) */
PERIPH_COUNT_IRQn = 45 /**< Number of peripheral IDs */
} IRQn_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef struct _DeviceVectors
{
/* Stack pointer */
void* pvStack;
/* Cortex-M handlers */
void* pfnReset_Handler; /* -15 Reset Vector, invoked on Power up and warm reset */
void* pfnNonMaskableInt_Handler; /* -14 Non maskable Interrupt, cannot be stopped or preempted */
void* pfnHardFault_Handler; /* -13 Hard Fault, all classes of Fault */
void* pvReservedC12;
void* pvReservedC11;
void* pvReservedC10;
void* pvReservedC9;
void* pvReservedC8;
void* pvReservedC7;
void* pvReservedC6;
void* pfnSVCall_Handler; /* -5 System Service Call via SVC instruction */
void* pvReservedC4;
void* pvReservedC3;
void* pfnPendSV_Handler; /* -2 Pendable request for system service */
void* pfnSysTick_Handler; /* -1 System Tick Timer */
/* Peripheral handlers */
void* pfnSYSTEM_Handler; /* 0 SAML10D16A Main Clock (MCLK) */
void* pfnWDT_Handler; /* 1 SAML10D16A Watchdog Timer (WDT) */
void* pfnRTC_Handler; /* 2 SAML10D16A Real-Time Counter (RTC) */
void* pfnEIC_0_Handler; /* 3 SAML10D16A External Interrupt Controller (EIC) */
void* pfnEIC_1_Handler; /* 4 SAML10D16A External Interrupt Controller (EIC) */
void* pfnEIC_2_Handler; /* 5 SAML10D16A External Interrupt Controller (EIC) */
void* pfnEIC_3_Handler; /* 6 SAML10D16A External Interrupt Controller (EIC) */
void* pfnEIC_OTHER_Handler; /* 7 SAML10D16A External Interrupt Controller (EIC) */
void* pfnFREQM_Handler; /* 8 SAML10D16A Frequency Meter (FREQM) */
void* pfnNVMCTRL_Handler; /* 9 SAML10D16A Non-Volatile Memory Controller (NVMCTRL) */
void* pfnPORT_Handler; /* 10 SAML10D16A Port Module (PORT) */
void* pfnDMAC_0_Handler; /* 11 SAML10D16A Direct Memory Access Controller (DMAC) */
void* pfnDMAC_1_Handler; /* 12 SAML10D16A Direct Memory Access Controller (DMAC) */
void* pfnDMAC_2_Handler; /* 13 SAML10D16A Direct Memory Access Controller (DMAC) */
void* pfnDMAC_3_Handler; /* 14 SAML10D16A Direct Memory Access Controller (DMAC) */
void* pfnDMAC_OTHER_Handler; /* 15 SAML10D16A Direct Memory Access Controller (DMAC) */
void* pfnEVSYS_0_Handler; /* 16 SAML10D16A Event System Interface (EVSYS) */
void* pfnEVSYS_1_Handler; /* 17 SAML10D16A Event System Interface (EVSYS) */
void* pfnEVSYS_2_Handler; /* 18 SAML10D16A Event System Interface (EVSYS) */
void* pfnEVSYS_3_Handler; /* 19 SAML10D16A Event System Interface (EVSYS) */
void* pfnEVSYS_NSCHK_Handler; /* 20 SAML10D16A Event System Interface (EVSYS) */
void* pfnPAC_Handler; /* 21 SAML10D16A Peripheral Access Controller (PAC) */
void* pfnSERCOM0_0_Handler; /* 22 SAML10D16A Serial Communication Interface (SERCOM0) */
void* pfnSERCOM0_1_Handler; /* 23 SAML10D16A Serial Communication Interface (SERCOM0) */
void* pfnSERCOM0_2_Handler; /* 24 SAML10D16A Serial Communication Interface (SERCOM0) */
void* pfnSERCOM0_OTHER_Handler; /* 25 SAML10D16A Serial Communication Interface (SERCOM0) */
void* pfnSERCOM1_0_Handler; /* 26 SAML10D16A Serial Communication Interface (SERCOM1) */
void* pfnSERCOM1_1_Handler; /* 27 SAML10D16A Serial Communication Interface (SERCOM1) */
void* pfnSERCOM1_2_Handler; /* 28 SAML10D16A Serial Communication Interface (SERCOM1) */
void* pfnSERCOM1_OTHER_Handler; /* 29 SAML10D16A Serial Communication Interface (SERCOM1) */
void* pvReserved30;
void* pvReserved31;
void* pvReserved32;
void* pvReserved33;
void* pfnTC0_Handler; /* 34 SAML10D16A Basic Timer Counter (TC0) */
void* pfnTC1_Handler; /* 35 SAML10D16A Basic Timer Counter (TC1) */
void* pfnTC2_Handler; /* 36 SAML10D16A Basic Timer Counter (TC2) */
void* pfnADC_OTHER_Handler; /* 37 SAML10D16A Analog Digital Converter (ADC) */
void* pfnADC_RESRDY_Handler; /* 38 SAML10D16A Analog Digital Converter (ADC) */
void* pfnAC_Handler; /* 39 SAML10D16A Analog Comparators (AC) */
void* pfnDAC_UNDERRUN_A_Handler; /* 40 SAML10D16A Digital Analog Converter (DAC) */
void* pfnDAC_EMPTY_Handler; /* 41 SAML10D16A Digital Analog Converter (DAC) */
void* pfnPTC_Handler; /* 42 SAML10D16A Peripheral Touch Controller (PTC) */
void* pfnTRNG_Handler; /* 43 SAML10D16A True Random Generator (TRNG) */
void* pfnTRAM_Handler; /* 44 SAML10D16A TrustRAM (TRAM) */
} DeviceVectors;
/* Defines for Deprecated Interrupt and Exceptions handler names */
#define pfnMemManage_Handler pfnMemoryManagement_Handler /**< \deprecated Backward compatibility for ASF */
#define pfnDebugMon_Handler pfnDebugMonitor_Handler /**< \deprecated Backward compatibility for ASF */
#define pfnNMI_Handler pfnNonMaskableInt_Handler /**< \deprecated Backward compatibility for ASF */
#define pfnSVC_Handler pfnSVCall_Handler /**< \deprecated Backward compatibility for ASF */
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
#if !defined DONT_USE_PREDEFINED_CORE_HANDLERS
/* CORTEX-M23 core handlers */
void Reset_Handler ( void );
void NonMaskableInt_Handler ( void );
void HardFault_Handler ( void );
void SVCall_Handler ( void );
void PendSV_Handler ( void );
void SysTick_Handler ( void );
#endif /* DONT_USE_PREDEFINED_CORE_HANDLERS */
#if !defined DONT_USE_PREDEFINED_PERIPHERALS_HANDLERS
/* Peripherals handlers */
void AC_Handler ( void );
void ADC_OTHER_Handler ( void );
void ADC_RESRDY_Handler ( void );
void DAC_EMPTY_Handler ( void );
void DAC_UNDERRUN_A_Handler ( void );
void DMAC_0_Handler ( void );
void DMAC_1_Handler ( void );
void DMAC_2_Handler ( void );
void DMAC_3_Handler ( void );
void DMAC_OTHER_Handler ( void );
void EIC_0_Handler ( void );
void EIC_1_Handler ( void );
void EIC_2_Handler ( void );
void EIC_3_Handler ( void );
void EIC_OTHER_Handler ( void );
void EVSYS_0_Handler ( void );
void EVSYS_1_Handler ( void );
void EVSYS_2_Handler ( void );
void EVSYS_3_Handler ( void );
void EVSYS_NSCHK_Handler ( void );
void FREQM_Handler ( void );
void NVMCTRL_Handler ( void );
void PAC_Handler ( void );
void PORT_Handler ( void );
void PTC_Handler ( void );
void RTC_Handler ( void );
void SERCOM0_0_Handler ( void );
void SERCOM0_1_Handler ( void );
void SERCOM0_2_Handler ( void );
void SERCOM0_OTHER_Handler ( void );
void SERCOM1_0_Handler ( void );
void SERCOM1_1_Handler ( void );
void SERCOM1_2_Handler ( void );
void SERCOM1_OTHER_Handler ( void );
void SYSTEM_Handler ( void );
void TC0_Handler ( void );
void TC1_Handler ( void );
void TC2_Handler ( void );
void TRAM_Handler ( void );
void TRNG_Handler ( void );
void WDT_Handler ( void );
#endif /* DONT_USE_PREDEFINED_PERIPHERALS_HANDLERS */
/* Defines for Deprecated Interrupt and Exceptions handler names */
#define MemManage_Handler MemoryManagement_Handler /**< \deprecated Backward compatibility for ASF */
#define DebugMon_Handler DebugMonitor_Handler /**< \deprecated Backward compatibility for ASF */
#define NMI_Handler NonMaskableInt_Handler /**< \deprecated Backward compatibility for ASF */
#define SVC_Handler SVCall_Handler /**< \deprecated Backward compatibility for ASF */
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/*
* \brief Configuration of the CORTEX-M23 Processor and Core Peripherals
*/
#define NUM_IRQ 45 /**< Number of interrupt request lines */
#define __ARMv8MBL_REV 0x0000 /**< Cortex-M23 Core Revision */
#define __ETM_PRESENT 0 /**< ETM present or not */
#define __FPU_PRESENT 0 /**< FPU present or not */
#define __MPU_PRESENT 1 /**< MPU present or not */
#define __MTB_PRESENT 0 /**< MTB present or not */
#define __NVIC_PRIO_BITS 2 /**< Number of Bits used for Priority Levels */
#define __SAU_PRESENT 0 /**< SAU present or not */
#define __SEC_ENABLED 0 /**< TrustZone-M enabled or not */
#define __VTOR_PRESENT 1 /**< Vector Table Offset Register present or not */
#define __Vendor_SysTickConfig 0 /**< Set to 1 if different SysTick Config is used */
#define __ARCH_ARM 1
#define __ARCH_ARM_CORTEX_M 1
#define __DEVICE_IS_SAM 1
/*
* \brief CMSIS includes
*/
#include <core_cm23.h>
#if !defined DONT_USE_CMSIS_INIT
#include "system_saml10.h"
#endif /* DONT_USE_CMSIS_INIT */
/** @} end of SAML10D16A_cmsis CMSIS Definitions */
/** \defgroup SAML10D16A_api Peripheral Software API
* @{
*/
/* ************************************************************************** */
/** SOFTWARE PERIPHERAL API DEFINITION FOR SAML10D16A */
/* ************************************************************************** */
#include "component/ac.h"
#include "component/adc.h"
#include "component/ccl.h"
#include "component/dac.h"
#include "component/dmac.h"
#include "component/dsu.h"
#include "component/eic.h"
#include "component/evsys.h"
#include "component/freqm.h"
#include "component/gclk.h"
#include "component/idau.h"
#include "component/mclk.h"
#include "component/nvmctrl.h"
#include "component/opamp.h"
#include "component/oscctrl.h"
#include "component/osc32kctrl.h"
#include "component/pac.h"
#include "component/pm.h"
#include "component/port.h"
#include "component/ptc.h"
#include "component/rstc.h"
#include "component/rtc.h"
#include "component/sercom.h"
#include "component/supc.h"
#include "component/tc.h"
#include "component/tram.h"
#include "component/trng.h"
#include "component/wdt.h"
/** @} end of Peripheral Software API */
/** \defgroup SAML10D16A_reg Registers Access Definitions
* @{
*/
/* ************************************************************************** */
/* REGISTER ACCESS DEFINITIONS FOR SAML10D16A */
/* ************************************************************************** */
#include "instance/ac.h"
#include "instance/adc.h"
#include "instance/ccl.h"
#include "instance/dac.h"
#include "instance/dmac.h"
#include "instance/dsu.h"
#include "instance/eic.h"
#include "instance/evsys.h"
#include "instance/freqm.h"
#include "instance/gclk.h"
#include "instance/idau.h"
#include "instance/mclk.h"
#include "instance/nvmctrl.h"
#include "instance/opamp.h"
#include "instance/oscctrl.h"
#include "instance/osc32kctrl.h"
#include "instance/pac.h"
#include "instance/pm.h"
#include "instance/port.h"
#include "instance/ptc.h"
#include "instance/rstc.h"
#include "instance/rtc.h"
#include "instance/sercom0.h"
#include "instance/sercom1.h"
#include "instance/supc.h"
#include "instance/tc0.h"
#include "instance/tc1.h"
#include "instance/tc2.h"
#include "instance/tram.h"
#include "instance/trng.h"
#include "instance/wdt.h"
/** @} end of Registers Access Definitions */
/** \addtogroup SAML10D16A_id Peripheral Ids Definitions
* @{
*/
/* ************************************************************************** */
/* PERIPHERAL ID DEFINITIONS FOR SAML10D16A */
/* ************************************************************************** */
#define ID_PAC ( 0) /**< \brief Peripheral Access Controller (PAC) */
#define ID_PM ( 1) /**< \brief Power Manager (PM) */
#define ID_MCLK ( 2) /**< \brief Main Clock (MCLK) */
#define ID_RSTC ( 3) /**< \brief Reset Controller (RSTC) */
#define ID_OSCCTRL ( 4) /**< \brief Oscillators Control (OSCCTRL) */
#define ID_OSC32KCTRL ( 5) /**< \brief 32k Oscillators Control (OSC32KCTRL) */
#define ID_SUPC ( 6) /**< \brief Supply Controller (SUPC) */
#define ID_GCLK ( 7) /**< \brief Generic Clock Generator (GCLK) */
#define ID_WDT ( 8) /**< \brief Watchdog Timer (WDT) */
#define ID_RTC ( 9) /**< \brief Real-Time Counter (RTC) */
#define ID_EIC ( 10) /**< \brief External Interrupt Controller (EIC) */
#define ID_FREQM ( 11) /**< \brief Frequency Meter (FREQM) */
#define ID_PORT ( 12) /**< \brief Port Module (PORT) */
#define ID_AC ( 13) /**< \brief Analog Comparators (AC) */
#define ID_IDAU ( 32) /**< \brief Implementation Defined Attribution Unit (IDAU) */
#define ID_DSU ( 33) /**< \brief Device Service Unit (DSU) */
#define ID_NVMCTRL ( 34) /**< \brief Non-Volatile Memory Controller (NVMCTRL) */
#define ID_DMAC ( 35) /**< \brief Direct Memory Access Controller (DMAC) */
#define ID_EVSYS ( 64) /**< \brief Event System Interface (EVSYS) */
#define ID_SERCOM0 ( 65) /**< \brief Serial Communication Interface (SERCOM0) */
#define ID_SERCOM1 ( 66) /**< \brief Serial Communication Interface (SERCOM1) */
#define ID_TC0 ( 68) /**< \brief Basic Timer Counter (TC0) */
#define ID_TC1 ( 69) /**< \brief Basic Timer Counter (TC1) */
#define ID_TC2 ( 70) /**< \brief Basic Timer Counter (TC2) */
#define ID_ADC ( 71) /**< \brief Analog Digital Converter (ADC) */
#define ID_DAC ( 72) /**< \brief Digital Analog Converter (DAC) */
#define ID_PTC ( 73) /**< \brief Peripheral Touch Controller (PTC) */
#define ID_TRNG ( 74) /**< \brief True Random Generator (TRNG) */
#define ID_CCL ( 75) /**< \brief Configurable Custom Logic (CCL) */
#define ID_OPAMP ( 76) /**< \brief Operational Amplifier (OPAMP) */
#define ID_TRAM ( 77) /**< \brief TrustRAM (TRAM) */
#define ID_PERIPH_COUNT ( 78) /**< \brief Number of peripheral IDs */
/** @} end of Peripheral Ids Definitions */
/** \addtogroup SAML10D16A_base Peripheral Base Address Definitions
* @{
*/
/* ************************************************************************** */
/* BASE ADDRESS DEFINITIONS FOR SAML10D16A */
/* ************************************************************************** */
#if (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
#define AC (0x40003400) /**< \brief (AC ) Base Address */
#define ADC (0x42001C00) /**< \brief (ADC ) Base Address */
#define CCL (0x42002C00) /**< \brief (CCL ) Base Address */
#define DAC (0x42002000) /**< \brief (DAC ) Base Address */
#define DMAC (0x41006000) /**< \brief (DMAC ) Base Address */
#define DSU (0x41002000) /**< \brief (DSU ) Base Address */
#define DSU_EXT (0x41002100) /**< \brief (DSU ) Base Address */
#define EIC (0x40002800) /**< \brief (EIC ) Base Address */
#define EVSYS (0x42000000) /**< \brief (EVSYS ) Base Address */
#define FREQM (0x40002C00) /**< \brief (FREQM ) Base Address */
#define GCLK (0x40001C00) /**< \brief (GCLK ) Base Address */
#define IDAU (0x41000000) /**< \brief (IDAU ) Base Address */
#define MCLK (0x40000800) /**< \brief (MCLK ) Base Address */
#define NVMCTRL (0x41004000) /**< \brief (NVMCTRL ) Base Address */
#define OPAMP (0x42003000) /**< \brief (OPAMP ) Base Address */
#define OSCCTRL (0x40001000) /**< \brief (OSCCTRL ) Base Address */
#define OSC32KCTRL (0x40001400) /**< \brief (OSC32KCTRL) Base Address */
#define PAC (0x40000000) /**< \brief (PAC ) Base Address */
#define PM (0x40000400) /**< \brief (PM ) Base Address */
#define PORT (0x40003000) /**< \brief (PORT ) Base Address */
#define PORT_IOBUS (0x60000000) /**< \brief (PORT ) Base Address */
#define PTC (0x42002400) /**< \brief (PTC ) Base Address */
#define RSTC (0x40000C00) /**< \brief (RSTC ) Base Address */
#define RTC (0x40002400) /**< \brief (RTC ) Base Address */
#define SERCOM0 (0x42000400) /**< \brief (SERCOM0 ) Base Address */
#define SERCOM1 (0x42000800) /**< \brief (SERCOM1 ) Base Address */
#define SUPC (0x40001800) /**< \brief (SUPC ) Base Address */
#define TC0 (0x42001000) /**< \brief (TC0 ) Base Address */
#define TC1 (0x42001400) /**< \brief (TC1 ) Base Address */
#define TC2 (0x42001800) /**< \brief (TC2 ) Base Address */
#define TRAM (0x42003400) /**< \brief (TRAM ) Base Address */
#define TRNG (0x42002800) /**< \brief (TRNG ) Base Address */
#define WDT (0x40002000) /**< \brief (WDT ) Base Address */
#else /* For C/C++ compiler */
#define AC ((Ac *)0x40003400U) /**< \brief (AC ) Base Address */
#define AC_INST_NUM 1 /**< \brief (AC ) Number of instances */
#define AC_INSTS { AC } /**< \brief (AC ) Instances List */
#define ADC ((Adc *)0x42001C00U) /**< \brief (ADC ) Base Address */
#define ADC_INST_NUM 1 /**< \brief (ADC ) Number of instances */
#define ADC_INSTS { ADC } /**< \brief (ADC ) Instances List */
#define CCL ((Ccl *)0x42002C00U) /**< \brief (CCL ) Base Address */
#define CCL_INST_NUM 1 /**< \brief (CCL ) Number of instances */
#define CCL_INSTS { CCL } /**< \brief (CCL ) Instances List */
#define DAC ((Dac *)0x42002000U) /**< \brief (DAC ) Base Address */
#define DAC_INST_NUM 1 /**< \brief (DAC ) Number of instances */
#define DAC_INSTS { DAC } /**< \brief (DAC ) Instances List */
#define DMAC ((Dmac *)0x41006000U) /**< \brief (DMAC ) Base Address */
#define DMAC_INST_NUM 1 /**< \brief (DMAC ) Number of instances */
#define DMAC_INSTS { DMAC } /**< \brief (DMAC ) Instances List */
#define DSU ((Dsu *)0x41002000U) /**< \brief (DSU ) Base Address */
#define DSU_EXT ((Dsu *)0x41002100U) /**< \brief (DSU ) Base Address */
#define DSU_INST_NUM 1 /**< \brief (DSU ) Number of instances */
#define DSU_INSTS { DSU } /**< \brief (DSU ) Instances List */
#define EIC ((Eic *)0x40002800U) /**< \brief (EIC ) Base Address */
#define EIC_INST_NUM 1 /**< \brief (EIC ) Number of instances */
#define EIC_INSTS { EIC } /**< \brief (EIC ) Instances List */
#define EVSYS ((Evsys *)0x42000000U) /**< \brief (EVSYS ) Base Address */
#define EVSYS_INST_NUM 1 /**< \brief (EVSYS ) Number of instances */
#define EVSYS_INSTS { EVSYS } /**< \brief (EVSYS ) Instances List */
#define FREQM ((Freqm *)0x40002C00U) /**< \brief (FREQM ) Base Address */
#define FREQM_INST_NUM 1 /**< \brief (FREQM ) Number of instances */
#define FREQM_INSTS { FREQM } /**< \brief (FREQM ) Instances List */
#define GCLK ((Gclk *)0x40001C00U) /**< \brief (GCLK ) Base Address */
#define GCLK_INST_NUM 1 /**< \brief (GCLK ) Number of instances */
#define GCLK_INSTS { GCLK } /**< \brief (GCLK ) Instances List */
#define IDAU ((Idau *)0x41000000U) /**< \brief (IDAU ) Base Address */
#define IDAU_INST_NUM 1 /**< \brief (IDAU ) Number of instances */
#define IDAU_INSTS { IDAU } /**< \brief (IDAU ) Instances List */
#define MCLK ((Mclk *)0x40000800U) /**< \brief (MCLK ) Base Address */
#define MCLK_INST_NUM 1 /**< \brief (MCLK ) Number of instances */
#define MCLK_INSTS { MCLK } /**< \brief (MCLK ) Instances List */
#define NVMCTRL ((Nvmctrl *)0x41004000U) /**< \brief (NVMCTRL ) Base Address */
#define NVMCTRL_INST_NUM 1 /**< \brief (NVMCTRL ) Number of instances */
#define NVMCTRL_INSTS { NVMCTRL } /**< \brief (NVMCTRL ) Instances List */
#define OPAMP ((Opamp *)0x42003000U) /**< \brief (OPAMP ) Base Address */
#define OPAMP_INST_NUM 1 /**< \brief (OPAMP ) Number of instances */
#define OPAMP_INSTS { OPAMP } /**< \brief (OPAMP ) Instances List */
#define OSCCTRL ((Oscctrl *)0x40001000U) /**< \brief (OSCCTRL ) Base Address */
#define OSCCTRL_INST_NUM 1 /**< \brief (OSCCTRL ) Number of instances */
#define OSCCTRL_INSTS { OSCCTRL } /**< \brief (OSCCTRL ) Instances List */
#define OSC32KCTRL ((Osc32kctrl *)0x40001400U) /**< \brief (OSC32KCTRL) Base Address */
#define OSC32KCTRL_INST_NUM 1 /**< \brief (OSC32KCTRL) Number of instances */
#define OSC32KCTRL_INSTS { OSC32KCTRL } /**< \brief (OSC32KCTRL) Instances List */
#define PAC ((Pac *)0x40000000U) /**< \brief (PAC ) Base Address */
#define PAC_INST_NUM 1 /**< \brief (PAC ) Number of instances */
#define PAC_INSTS { PAC } /**< \brief (PAC ) Instances List */
#define PM ((Pm *)0x40000400U) /**< \brief (PM ) Base Address */
#define PM_INST_NUM 1 /**< \brief (PM ) Number of instances */
#define PM_INSTS { PM } /**< \brief (PM ) Instances List */
#define PORT ((Port *)0x40003000U) /**< \brief (PORT ) Base Address */
#define PORT_IOBUS ((Port *)0x60000000U) /**< \brief (PORT ) Base Address */
#define PORT_INST_NUM 1 /**< \brief (PORT ) Number of instances */
#define PORT_INSTS { PORT } /**< \brief (PORT ) Instances List */
#define PTC ((Ptc *)0x42002400U) /**< \brief (PTC ) Base Address */
#define PTC_INST_NUM 1 /**< \brief (PTC ) Number of instances */
#define PTC_INSTS { PTC } /**< \brief (PTC ) Instances List */
#define RSTC ((Rstc *)0x40000C00U) /**< \brief (RSTC ) Base Address */
#define RSTC_INST_NUM 1 /**< \brief (RSTC ) Number of instances */
#define RSTC_INSTS { RSTC } /**< \brief (RSTC ) Instances List */
#define RTC ((Rtc *)0x40002400U) /**< \brief (RTC ) Base Address */
#define RTC_INST_NUM 1 /**< \brief (RTC ) Number of instances */
#define RTC_INSTS { RTC } /**< \brief (RTC ) Instances List */
#define SERCOM0 ((Sercom *)0x42000400U) /**< \brief (SERCOM0 ) Base Address */
#define SERCOM1 ((Sercom *)0x42000800U) /**< \brief (SERCOM1 ) Base Address */
#define SERCOM_INST_NUM 2 /**< \brief (SERCOM ) Number of instances */
#define SERCOM_INSTS { SERCOM0, SERCOM1 } /**< \brief (SERCOM ) Instances List */
#define SUPC ((Supc *)0x40001800U) /**< \brief (SUPC ) Base Address */
#define SUPC_INST_NUM 1 /**< \brief (SUPC ) Number of instances */
#define SUPC_INSTS { SUPC } /**< \brief (SUPC ) Instances List */
#define TC0 ((Tc *)0x42001000U) /**< \brief (TC0 ) Base Address */
#define TC1 ((Tc *)0x42001400U) /**< \brief (TC1 ) Base Address */
#define TC2 ((Tc *)0x42001800U) /**< \brief (TC2 ) Base Address */
#define TC_INST_NUM 3 /**< \brief (TC ) Number of instances */
#define TC_INSTS { TC0, TC1, TC2 } /**< \brief (TC ) Instances List */
#define TRAM ((Tram *)0x42003400U) /**< \brief (TRAM ) Base Address */
#define TRAM_INST_NUM 1 /**< \brief (TRAM ) Number of instances */
#define TRAM_INSTS { TRAM } /**< \brief (TRAM ) Instances List */
#define TRNG ((Trng *)0x42002800U) /**< \brief (TRNG ) Base Address */
#define TRNG_INST_NUM 1 /**< \brief (TRNG ) Number of instances */
#define TRNG_INSTS { TRNG } /**< \brief (TRNG ) Instances List */
#define WDT ((Wdt *)0x40002000U) /**< \brief (WDT ) Base Address */
#define WDT_INST_NUM 1 /**< \brief (WDT ) Number of instances */
#define WDT_INSTS { WDT } /**< \brief (WDT ) Instances List */
#endif /* (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/** @} end of Peripheral Base Address Definitions */
/** \addtogroup SAML10D16A_pio Peripheral Pio Definitions
* @{
*/
/* ************************************************************************** */
/* PIO DEFINITIONS FOR SAML10D16A*/
/* ************************************************************************** */
#include "pio/saml10d16a.h"
/** @} end of Peripheral Pio Definitions */
/* ************************************************************************** */
/* MEMORY MAPPING DEFINITIONS FOR SAML10D16A*/
/* ************************************************************************** */
#define FLASH_SIZE _U_(0x00010000) /* 64kB Memory segment type: flash */
#define FLASH_PAGE_SIZE _U_( 64)
#define FLASH_NB_OF_PAGES _U_( 1024)
#define AUX_SIZE _U_(0x00000100) /* 0kB Memory segment type: fuses */
#define AUX_PAGE_SIZE _U_( 64)
#define AUX_NB_OF_PAGES _U_( 4)
#define BOCOR_SIZE _U_(0x00000100) /* 0kB Memory segment type: fuses */
#define BOCOR_PAGE_SIZE _U_( 64)
#define BOCOR_NB_OF_PAGES _U_( 4)
#define DATAFLASH_SIZE _U_(0x00000800) /* 2kB Memory segment type: flash */
#define DATAFLASH_PAGE_SIZE _U_( 64)
#define DATAFLASH_NB_OF_PAGES _U_( 32)
#define SW_CALIB_SIZE _U_(0x00000008) /* 0kB Memory segment type: fuses */
#define TEMP_LOG_SIZE _U_(0x00000008) /* 0kB Memory segment type: fuses */
#define USER_PAGE_SIZE _U_(0x00000100) /* 0kB Memory segment type: user_page */
#define USER_PAGE_PAGE_SIZE _U_( 64)
#define USER_PAGE_NB_OF_PAGES _U_( 4)
#define HSRAM_SIZE _U_(0x00004000) /* 16kB Memory segment type: ram */
#define HPB0_SIZE _U_(0x00008000) /* 32kB Memory segment type: io */
#define HPB1_SIZE _U_(0x00010000) /* 64kB Memory segment type: io */
#define HPB2_SIZE _U_(0x00004000) /* 16kB Memory segment type: io */
#define PPB_SIZE _U_(0x00100000) /* 1024kB Memory segment type: io */
#define SCS_SIZE _U_(0x00001000) /* 4kB Memory segment type: io */
#define PERIPHERALS_SIZE _U_(0x20000000) /* 524288kB Memory segment type: io */
#define FLASH_ADDR _U_(0x00000000) /**< FLASH base address (type: flash)*/
#define AUX_ADDR _U_(0x00806000) /**< AUX base address (type: fuses)*/
#define BOCOR_ADDR _U_(0x0080c000) /**< BOCOR base address (type: fuses)*/
#define DATAFLASH_ADDR _U_(0x00400000) /**< DATAFLASH base address (type: flash)*/
#define SW_CALIB_ADDR _U_(0x00806020) /**< SW_CALIB base address (type: fuses)*/
#define TEMP_LOG_ADDR _U_(0x00806038) /**< TEMP_LOG base address (type: fuses)*/
#define USER_PAGE_ADDR _U_(0x00804000) /**< USER_PAGE base address (type: user_page)*/
#define HSRAM_ADDR _U_(0x20000000) /**< HSRAM base address (type: ram)*/
#define HPB0_ADDR _U_(0x40000000) /**< HPB0 base address (type: io)*/
#define HPB1_ADDR _U_(0x41000000) /**< HPB1 base address (type: io)*/
#define HPB2_ADDR _U_(0x42000000) /**< HPB2 base address (type: io)*/
#define PPB_ADDR _U_(0xe0000000) /**< PPB base address (type: io)*/
#define SCS_ADDR _U_(0xe000e000) /**< SCS base address (type: io)*/
#define PERIPHERALS_ADDR _U_(0x40000000) /**< PERIPHERALS base address (type: io)*/
#define NVMCTRL_AUX AUX_ADDR /**< \brief \deprecated Old style definition. Use AUX_ADDR instead */
#define NVMCTRL_BOCOR BOCOR_ADDR /**< \brief \deprecated Old style definition. Use BOCOR_ADDR instead */
#define NVMCTRL_DATAFLASH DATAFLASH_ADDR /**< \brief \deprecated Old style definition. Use DATAFLASH_ADDR instead */
#define NVMCTRL_SW_CALIB SW_CALIB_ADDR /**< \brief \deprecated Old style definition. Use SW_CALIB_ADDR instead */
#define NVMCTRL_TEMP_LOG TEMP_LOG_ADDR /**< \brief \deprecated Old style definition. Use TEMP_LOG_ADDR instead */
#define NVMCTRL_USER USER_PAGE_ADDR /**< \brief \deprecated Old style definition. Use USER_PAGE_ADDR instead */
/* ************************************************************************** */
/** DEVICE SIGNATURES FOR SAML10D16A */
/* ************************************************************************** */
#define DSU_DID _UL_(0X20840003)
/* ************************************************************************** */
/** ELECTRICAL DEFINITIONS FOR SAML10D16A */
/* ************************************************************************** */
/* ************************************************************************** */
/** Event Generator IDs for SAML10D16A */
/* ************************************************************************** */
#define EVENT_ID_GEN_OSCCTRL_XOSC_FAIL 1 /**< ID for OSCCTRL event generator XOSC_FAIL */
#define EVENT_ID_GEN_OSC32KCTRL_XOSC32K_FAIL 2 /**< ID for OSC32KCTRL event generator XOSC32K_FAIL */
#define EVENT_ID_GEN_SUPC_BOD33DET 3 /**< ID for SUPC event generator BOD33DET */
#define EVENT_ID_GEN_RTC_PER_0 4 /**< ID for RTC event generator PER_0 */
#define EVENT_ID_GEN_RTC_PER_1 5 /**< ID for RTC event generator PER_1 */
#define EVENT_ID_GEN_RTC_PER_2 6 /**< ID for RTC event generator PER_2 */
#define EVENT_ID_GEN_RTC_PER_3 7 /**< ID for RTC event generator PER_3 */
#define EVENT_ID_GEN_RTC_PER_4 8 /**< ID for RTC event generator PER_4 */
#define EVENT_ID_GEN_RTC_PER_5 9 /**< ID for RTC event generator PER_5 */
#define EVENT_ID_GEN_RTC_PER_6 10 /**< ID for RTC event generator PER_6 */
#define EVENT_ID_GEN_RTC_PER_7 11 /**< ID for RTC event generator PER_7 */
#define EVENT_ID_GEN_RTC_CMP_0 12 /**< ID for RTC event generator CMP_0 */
#define EVENT_ID_GEN_RTC_CMP_1 13 /**< ID for RTC event generator CMP_1 */
#define EVENT_ID_GEN_RTC_TAMPER 14 /**< ID for RTC event generator TAMPER */
#define EVENT_ID_GEN_RTC_OVF 15 /**< ID for RTC event generator OVF */
#define EVENT_ID_GEN_RTC_PERD 16 /**< ID for RTC event generator PERD */
#define EVENT_ID_GEN_EIC_EXTINT_0 17 /**< ID for EIC event generator EXTINT_0 */
#define EVENT_ID_GEN_EIC_EXTINT_1 18 /**< ID for EIC event generator EXTINT_1 */
#define EVENT_ID_GEN_EIC_EXTINT_2 19 /**< ID for EIC event generator EXTINT_2 */
#define EVENT_ID_GEN_EIC_EXTINT_3 20 /**< ID for EIC event generator EXTINT_3 */
#define EVENT_ID_GEN_EIC_EXTINT_4 21 /**< ID for EIC event generator EXTINT_4 */
#define EVENT_ID_GEN_EIC_EXTINT_5 22 /**< ID for EIC event generator EXTINT_5 */
#define EVENT_ID_GEN_EIC_EXTINT_6 23 /**< ID for EIC event generator EXTINT_6 */
#define EVENT_ID_GEN_EIC_EXTINT_7 24 /**< ID for EIC event generator EXTINT_7 */
#define EVENT_ID_GEN_DMAC_CH_0 25 /**< ID for DMAC event generator CH_0 */
#define EVENT_ID_GEN_DMAC_CH_1 26 /**< ID for DMAC event generator CH_1 */
#define EVENT_ID_GEN_DMAC_CH_2 27 /**< ID for DMAC event generator CH_2 */
#define EVENT_ID_GEN_DMAC_CH_3 28 /**< ID for DMAC event generator CH_3 */
#define EVENT_ID_GEN_TC0_OVF 29 /**< ID for TC0 event generator OVF */
#define EVENT_ID_GEN_TC0_MCX_0 30 /**< ID for TC0 event generator MCX_0 */
#define EVENT_ID_GEN_TC0_MCX_1 31 /**< ID for TC0 event generator MCX_1 */
#define EVENT_ID_GEN_TC1_OVF 32 /**< ID for TC1 event generator OVF */
#define EVENT_ID_GEN_TC1_MCX_0 33 /**< ID for TC1 event generator MCX_0 */
#define EVENT_ID_GEN_TC1_MCX_1 34 /**< ID for TC1 event generator MCX_1 */
#define EVENT_ID_GEN_TC2_OVF 35 /**< ID for TC2 event generator OVF */
#define EVENT_ID_GEN_TC2_MCX_0 36 /**< ID for TC2 event generator MCX_0 */
#define EVENT_ID_GEN_TC2_MCX_1 37 /**< ID for TC2 event generator MCX_1 */
#define EVENT_ID_GEN_ADC_RESRDY 38 /**< ID for ADC event generator RESRDY */
#define EVENT_ID_GEN_ADC_WINMON 39 /**< ID for ADC event generator WINMON */
#define EVENT_ID_GEN_AC_COMP_0 40 /**< ID for AC event generator COMP_0 */
#define EVENT_ID_GEN_AC_COMP_1 41 /**< ID for AC event generator COMP_1 */
#define EVENT_ID_GEN_AC_WIN_0 42 /**< ID for AC event generator WIN_0 */
#define EVENT_ID_GEN_DAC_EMPTY 43 /**< ID for DAC event generator EMPTY */
#define EVENT_ID_GEN_TRNG_READY 46 /**< ID for TRNG event generator READY */
#define EVENT_ID_GEN_CCL_LUTOUT_0 47 /**< ID for CCL event generator LUTOUT_0 */
#define EVENT_ID_GEN_CCL_LUTOUT_1 48 /**< ID for CCL event generator LUTOUT_1 */
#define EVENT_ID_GEN_PAC_ERR 49 /**< ID for PAC event generator ERR */
/* ************************************************************************** */
/** Event User IDs for SAML10D16A */
/* ************************************************************************** */
#define EVENT_ID_USER_OSCCTRL_TUNE 0 /**< ID for OSCCTRL event user TUNE */
#define EVENT_ID_USER_RTC_TAMPER 1 /**< ID for RTC event user TAMPER */
#define EVENT_ID_USER_NVMCTRL_PAGEW 2 /**< ID for NVMCTRL event user PAGEW */
#define EVENT_ID_USER_PORT_EV_0 3 /**< ID for PORT event user EV_0 */
#define EVENT_ID_USER_PORT_EV_1 4 /**< ID for PORT event user EV_1 */
#define EVENT_ID_USER_PORT_EV_2 5 /**< ID for PORT event user EV_2 */
#define EVENT_ID_USER_PORT_EV_3 6 /**< ID for PORT event user EV_3 */
#define EVENT_ID_USER_DMAC_CH_0 7 /**< ID for DMAC event user CH_0 */
#define EVENT_ID_USER_DMAC_CH_1 8 /**< ID for DMAC event user CH_1 */
#define EVENT_ID_USER_DMAC_CH_2 9 /**< ID for DMAC event user CH_2 */
#define EVENT_ID_USER_DMAC_CH_3 10 /**< ID for DMAC event user CH_3 */
#define EVENT_ID_USER_TC0_EVU 11 /**< ID for TC0 event user EVU */
#define EVENT_ID_USER_TC1_EVU 12 /**< ID for TC1 event user EVU */
#define EVENT_ID_USER_TC2_EVU 13 /**< ID for TC2 event user EVU */
#define EVENT_ID_USER_ADC_START 14 /**< ID for ADC event user START */
#define EVENT_ID_USER_ADC_SYNC 15 /**< ID for ADC event user SYNC */
#define EVENT_ID_USER_AC_SOC_0 16 /**< ID for AC event user SOC_0 */
#define EVENT_ID_USER_AC_SOC_1 17 /**< ID for AC event user SOC_1 */
#define EVENT_ID_USER_DAC_START 18 /**< ID for DAC event user START */
#define EVENT_ID_USER_CCL_LUTIN_0 21 /**< ID for CCL event user LUTIN_0 */
#define EVENT_ID_USER_CCL_LUTIN_1 22 /**< ID for CCL event user LUTIN_1 */
#ifdef __cplusplus
}
#endif
/** @} end of SAML10D16A definitions */
#endif /* _SAML10D16A_H_ */

View File

@ -0,0 +1,801 @@
/**
* \file
*
* \brief Header file for ATSAML10E14A
*
* Copyright (c) 2018 Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* 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
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
/* file generated from device description version 2018-08-31T13:51:50Z */
#ifndef _SAML10E14A_H_
#define _SAML10E14A_H_
/** \addtogroup SAML10E14A_definitions SAML10E14A definitions
This file defines all structures and symbols for SAML10E14A:
- registers and bitfields
- peripheral base address
- peripheral ID
- PIO definitions
* @{
*/
#ifdef __cplusplus
extern "C" {
#endif
/** \defgroup Atmel_glob_defs Atmel Global Defines
<strong>IO Type Qualifiers</strong> are used
\li to specify the access to peripheral variables.
\li for automatic generation of peripheral register debug information.
\remark
CMSIS core has a syntax that differs from this using i.e. __I, __O, or __IO followed by 'uint<size>_t' respective types.
Default the header files will follow the CMSIS core syntax.
* @{
*/
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
#include <stdint.h>
/* IO definitions (access restrictions to peripheral registers) */
#ifndef __cplusplus
typedef volatile const uint32_t RoReg; /**< Read only 32-bit register (volatile const unsigned int) */
typedef volatile const uint16_t RoReg16; /**< Read only 16-bit register (volatile const unsigned int) */
typedef volatile const uint8_t RoReg8; /**< Read only 8-bit register (volatile const unsigned int) */
#else
typedef volatile uint32_t RoReg; /**< Read only 32-bit register (volatile const unsigned int) */
typedef volatile uint16_t RoReg16; /**< Read only 16-bit register (volatile const unsigned int) */
typedef volatile uint8_t RoReg8; /**< Read only 8-bit register (volatile const unsigned int) */
#endif
typedef volatile uint32_t WoReg; /**< Write only 32-bit register (volatile unsigned int) */
typedef volatile uint16_t WoReg16; /**< Write only 16-bit register (volatile unsigned int) */
typedef volatile uint8_t WoReg8; /**< Write only 8-bit register (volatile unsigned int) */
typedef volatile uint32_t RwReg; /**< Read-Write 32-bit register (volatile unsigned int) */
typedef volatile uint16_t RwReg16; /**< Read-Write 16-bit register (volatile unsigned int) */
typedef volatile uint8_t RwReg8; /**< Read-Write 8-bit register (volatile unsigned int) */
#define CAST(type, value) ((type *)(value)) /**< Pointer Type Conversion Macro for C/C++ */
#define REG_ACCESS(type, address) (*(type*)(address)) /**< C code: Register value */
#else /* Assembler */
#define CAST(type, value) (value) /**< Pointer Type Conversion Macro for Assembler */
#define REG_ACCESS(type, address) (address) /**< Assembly code: Register address */
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#if !defined(SKIP_INTEGER_LITERALS)
#if defined(_U_) || defined(_L_) || defined(_UL_)
#error "Integer Literals macros already defined elsewhere"
#endif
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
/* Macros that deal with adding suffixes to integer literal constants for C/C++ */
#define _U_(x) x ## U /**< C code: Unsigned integer literal constant value */
#define _L_(x) x ## L /**< C code: Long integer literal constant value */
#define _UL_(x) x ## UL /**< C code: Unsigned Long integer literal constant value */
#else /* Assembler */
#define _U_(x) x /**< Assembler: Unsigned integer literal constant value */
#define _L_(x) x /**< Assembler: Long integer literal constant value */
#define _UL_(x) x /**< Assembler: Unsigned Long integer literal constant value */
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#endif /* SKIP_INTEGER_LITERALS */
/** @} end of Atmel Global Defines */
/** \addtogroup SAML10E14A_cmsis CMSIS Definitions
* @{
*/
/* ************************************************************************** */
/* CMSIS DEFINITIONS FOR SAML10E14A */
/* ************************************************************************** */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
/** Interrupt Number Definition */
typedef enum IRQn
{
/****** CORTEX-M23 Processor Exceptions Numbers ******************************/
Reset_IRQn = -15, /**< 1 Reset Vector, invoked on Power up and warm reset */
NonMaskableInt_IRQn = -14, /**< 2 Non maskable Interrupt, cannot be stopped or preempted */
HardFault_IRQn = -13, /**< 3 Hard Fault, all classes of Fault */
SVCall_IRQn = -5 , /**< 11 System Service Call via SVC instruction */
PendSV_IRQn = -2 , /**< 14 Pendable request for system service */
SysTick_IRQn = -1 , /**< 15 System Tick Timer */
/****** SAML10E14A specific Interrupt Numbers ***********************************/
SYSTEM_IRQn = 0 , /**< 0 SAML10E14A Main Clock (MCLK) */
WDT_IRQn = 1 , /**< 1 SAML10E14A Watchdog Timer (WDT) */
RTC_IRQn = 2 , /**< 2 SAML10E14A Real-Time Counter (RTC) */
EIC_0_IRQn = 3 , /**< 3 SAML10E14A External Interrupt Controller (EIC) */
EIC_1_IRQn = 4 , /**< 4 SAML10E14A External Interrupt Controller (EIC) */
EIC_2_IRQn = 5 , /**< 5 SAML10E14A External Interrupt Controller (EIC) */
EIC_3_IRQn = 6 , /**< 6 SAML10E14A External Interrupt Controller (EIC) */
EIC_OTHER_IRQn = 7 , /**< 7 SAML10E14A External Interrupt Controller (EIC) */
FREQM_IRQn = 8 , /**< 8 SAML10E14A Frequency Meter (FREQM) */
NVMCTRL_IRQn = 9 , /**< 9 SAML10E14A Non-Volatile Memory Controller (NVMCTRL) */
PORT_IRQn = 10 , /**< 10 SAML10E14A Port Module (PORT) */
DMAC_0_IRQn = 11 , /**< 11 SAML10E14A Direct Memory Access Controller (DMAC) */
DMAC_1_IRQn = 12 , /**< 12 SAML10E14A Direct Memory Access Controller (DMAC) */
DMAC_2_IRQn = 13 , /**< 13 SAML10E14A Direct Memory Access Controller (DMAC) */
DMAC_3_IRQn = 14 , /**< 14 SAML10E14A Direct Memory Access Controller (DMAC) */
DMAC_OTHER_IRQn = 15 , /**< 15 SAML10E14A Direct Memory Access Controller (DMAC) */
EVSYS_0_IRQn = 16 , /**< 16 SAML10E14A Event System Interface (EVSYS) */
EVSYS_1_IRQn = 17 , /**< 17 SAML10E14A Event System Interface (EVSYS) */
EVSYS_2_IRQn = 18 , /**< 18 SAML10E14A Event System Interface (EVSYS) */
EVSYS_3_IRQn = 19 , /**< 19 SAML10E14A Event System Interface (EVSYS) */
EVSYS_NSCHK_IRQn = 20 , /**< 20 SAML10E14A Event System Interface (EVSYS) */
PAC_IRQn = 21 , /**< 21 SAML10E14A Peripheral Access Controller (PAC) */
SERCOM0_0_IRQn = 22 , /**< 22 SAML10E14A Serial Communication Interface (SERCOM0) */
SERCOM0_1_IRQn = 23 , /**< 23 SAML10E14A Serial Communication Interface (SERCOM0) */
SERCOM0_2_IRQn = 24 , /**< 24 SAML10E14A Serial Communication Interface (SERCOM0) */
SERCOM0_OTHER_IRQn = 25 , /**< 25 SAML10E14A Serial Communication Interface (SERCOM0) */
SERCOM1_0_IRQn = 26 , /**< 26 SAML10E14A Serial Communication Interface (SERCOM1) */
SERCOM1_1_IRQn = 27 , /**< 27 SAML10E14A Serial Communication Interface (SERCOM1) */
SERCOM1_2_IRQn = 28 , /**< 28 SAML10E14A Serial Communication Interface (SERCOM1) */
SERCOM1_OTHER_IRQn = 29 , /**< 29 SAML10E14A Serial Communication Interface (SERCOM1) */
SERCOM2_0_IRQn = 30 , /**< 30 SAML10E14A Serial Communication Interface (SERCOM2) */
SERCOM2_1_IRQn = 31 , /**< 31 SAML10E14A Serial Communication Interface (SERCOM2) */
SERCOM2_2_IRQn = 32 , /**< 32 SAML10E14A Serial Communication Interface (SERCOM2) */
SERCOM2_OTHER_IRQn = 33 , /**< 33 SAML10E14A Serial Communication Interface (SERCOM2) */
TC0_IRQn = 34 , /**< 34 SAML10E14A Basic Timer Counter (TC0) */
TC1_IRQn = 35 , /**< 35 SAML10E14A Basic Timer Counter (TC1) */
TC2_IRQn = 36 , /**< 36 SAML10E14A Basic Timer Counter (TC2) */
ADC_OTHER_IRQn = 37 , /**< 37 SAML10E14A Analog Digital Converter (ADC) */
ADC_RESRDY_IRQn = 38 , /**< 38 SAML10E14A Analog Digital Converter (ADC) */
AC_IRQn = 39 , /**< 39 SAML10E14A Analog Comparators (AC) */
DAC_UNDERRUN_A_IRQn = 40 , /**< 40 SAML10E14A Digital Analog Converter (DAC) */
DAC_EMPTY_IRQn = 41 , /**< 41 SAML10E14A Digital Analog Converter (DAC) */
PTC_IRQn = 42 , /**< 42 SAML10E14A Peripheral Touch Controller (PTC) */
TRNG_IRQn = 43 , /**< 43 SAML10E14A True Random Generator (TRNG) */
TRAM_IRQn = 44 , /**< 44 SAML10E14A TrustRAM (TRAM) */
PERIPH_COUNT_IRQn = 45 /**< Number of peripheral IDs */
} IRQn_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef struct _DeviceVectors
{
/* Stack pointer */
void* pvStack;
/* Cortex-M handlers */
void* pfnReset_Handler; /* -15 Reset Vector, invoked on Power up and warm reset */
void* pfnNonMaskableInt_Handler; /* -14 Non maskable Interrupt, cannot be stopped or preempted */
void* pfnHardFault_Handler; /* -13 Hard Fault, all classes of Fault */
void* pvReservedC12;
void* pvReservedC11;
void* pvReservedC10;
void* pvReservedC9;
void* pvReservedC8;
void* pvReservedC7;
void* pvReservedC6;
void* pfnSVCall_Handler; /* -5 System Service Call via SVC instruction */
void* pvReservedC4;
void* pvReservedC3;
void* pfnPendSV_Handler; /* -2 Pendable request for system service */
void* pfnSysTick_Handler; /* -1 System Tick Timer */
/* Peripheral handlers */
void* pfnSYSTEM_Handler; /* 0 SAML10E14A Main Clock (MCLK) */
void* pfnWDT_Handler; /* 1 SAML10E14A Watchdog Timer (WDT) */
void* pfnRTC_Handler; /* 2 SAML10E14A Real-Time Counter (RTC) */
void* pfnEIC_0_Handler; /* 3 SAML10E14A External Interrupt Controller (EIC) */
void* pfnEIC_1_Handler; /* 4 SAML10E14A External Interrupt Controller (EIC) */
void* pfnEIC_2_Handler; /* 5 SAML10E14A External Interrupt Controller (EIC) */
void* pfnEIC_3_Handler; /* 6 SAML10E14A External Interrupt Controller (EIC) */
void* pfnEIC_OTHER_Handler; /* 7 SAML10E14A External Interrupt Controller (EIC) */
void* pfnFREQM_Handler; /* 8 SAML10E14A Frequency Meter (FREQM) */
void* pfnNVMCTRL_Handler; /* 9 SAML10E14A Non-Volatile Memory Controller (NVMCTRL) */
void* pfnPORT_Handler; /* 10 SAML10E14A Port Module (PORT) */
void* pfnDMAC_0_Handler; /* 11 SAML10E14A Direct Memory Access Controller (DMAC) */
void* pfnDMAC_1_Handler; /* 12 SAML10E14A Direct Memory Access Controller (DMAC) */
void* pfnDMAC_2_Handler; /* 13 SAML10E14A Direct Memory Access Controller (DMAC) */
void* pfnDMAC_3_Handler; /* 14 SAML10E14A Direct Memory Access Controller (DMAC) */
void* pfnDMAC_OTHER_Handler; /* 15 SAML10E14A Direct Memory Access Controller (DMAC) */
void* pfnEVSYS_0_Handler; /* 16 SAML10E14A Event System Interface (EVSYS) */
void* pfnEVSYS_1_Handler; /* 17 SAML10E14A Event System Interface (EVSYS) */
void* pfnEVSYS_2_Handler; /* 18 SAML10E14A Event System Interface (EVSYS) */
void* pfnEVSYS_3_Handler; /* 19 SAML10E14A Event System Interface (EVSYS) */
void* pfnEVSYS_NSCHK_Handler; /* 20 SAML10E14A Event System Interface (EVSYS) */
void* pfnPAC_Handler; /* 21 SAML10E14A Peripheral Access Controller (PAC) */
void* pfnSERCOM0_0_Handler; /* 22 SAML10E14A Serial Communication Interface (SERCOM0) */
void* pfnSERCOM0_1_Handler; /* 23 SAML10E14A Serial Communication Interface (SERCOM0) */
void* pfnSERCOM0_2_Handler; /* 24 SAML10E14A Serial Communication Interface (SERCOM0) */
void* pfnSERCOM0_OTHER_Handler; /* 25 SAML10E14A Serial Communication Interface (SERCOM0) */
void* pfnSERCOM1_0_Handler; /* 26 SAML10E14A Serial Communication Interface (SERCOM1) */
void* pfnSERCOM1_1_Handler; /* 27 SAML10E14A Serial Communication Interface (SERCOM1) */
void* pfnSERCOM1_2_Handler; /* 28 SAML10E14A Serial Communication Interface (SERCOM1) */
void* pfnSERCOM1_OTHER_Handler; /* 29 SAML10E14A Serial Communication Interface (SERCOM1) */
void* pfnSERCOM2_0_Handler; /* 30 SAML10E14A Serial Communication Interface (SERCOM2) */
void* pfnSERCOM2_1_Handler; /* 31 SAML10E14A Serial Communication Interface (SERCOM2) */
void* pfnSERCOM2_2_Handler; /* 32 SAML10E14A Serial Communication Interface (SERCOM2) */
void* pfnSERCOM2_OTHER_Handler; /* 33 SAML10E14A Serial Communication Interface (SERCOM2) */
void* pfnTC0_Handler; /* 34 SAML10E14A Basic Timer Counter (TC0) */
void* pfnTC1_Handler; /* 35 SAML10E14A Basic Timer Counter (TC1) */
void* pfnTC2_Handler; /* 36 SAML10E14A Basic Timer Counter (TC2) */
void* pfnADC_OTHER_Handler; /* 37 SAML10E14A Analog Digital Converter (ADC) */
void* pfnADC_RESRDY_Handler; /* 38 SAML10E14A Analog Digital Converter (ADC) */
void* pfnAC_Handler; /* 39 SAML10E14A Analog Comparators (AC) */
void* pfnDAC_UNDERRUN_A_Handler; /* 40 SAML10E14A Digital Analog Converter (DAC) */
void* pfnDAC_EMPTY_Handler; /* 41 SAML10E14A Digital Analog Converter (DAC) */
void* pfnPTC_Handler; /* 42 SAML10E14A Peripheral Touch Controller (PTC) */
void* pfnTRNG_Handler; /* 43 SAML10E14A True Random Generator (TRNG) */
void* pfnTRAM_Handler; /* 44 SAML10E14A TrustRAM (TRAM) */
} DeviceVectors;
/* Defines for Deprecated Interrupt and Exceptions handler names */
#define pfnMemManage_Handler pfnMemoryManagement_Handler /**< \deprecated Backward compatibility for ASF */
#define pfnDebugMon_Handler pfnDebugMonitor_Handler /**< \deprecated Backward compatibility for ASF */
#define pfnNMI_Handler pfnNonMaskableInt_Handler /**< \deprecated Backward compatibility for ASF */
#define pfnSVC_Handler pfnSVCall_Handler /**< \deprecated Backward compatibility for ASF */
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
#if !defined DONT_USE_PREDEFINED_CORE_HANDLERS
/* CORTEX-M23 core handlers */
void Reset_Handler ( void );
void NonMaskableInt_Handler ( void );
void HardFault_Handler ( void );
void SVCall_Handler ( void );
void PendSV_Handler ( void );
void SysTick_Handler ( void );
#endif /* DONT_USE_PREDEFINED_CORE_HANDLERS */
#if !defined DONT_USE_PREDEFINED_PERIPHERALS_HANDLERS
/* Peripherals handlers */
void AC_Handler ( void );
void ADC_OTHER_Handler ( void );
void ADC_RESRDY_Handler ( void );
void DAC_EMPTY_Handler ( void );
void DAC_UNDERRUN_A_Handler ( void );
void DMAC_0_Handler ( void );
void DMAC_1_Handler ( void );
void DMAC_2_Handler ( void );
void DMAC_3_Handler ( void );
void DMAC_OTHER_Handler ( void );
void EIC_0_Handler ( void );
void EIC_1_Handler ( void );
void EIC_2_Handler ( void );
void EIC_3_Handler ( void );
void EIC_OTHER_Handler ( void );
void EVSYS_0_Handler ( void );
void EVSYS_1_Handler ( void );
void EVSYS_2_Handler ( void );
void EVSYS_3_Handler ( void );
void EVSYS_NSCHK_Handler ( void );
void FREQM_Handler ( void );
void NVMCTRL_Handler ( void );
void PAC_Handler ( void );
void PORT_Handler ( void );
void PTC_Handler ( void );
void RTC_Handler ( void );
void SERCOM0_0_Handler ( void );
void SERCOM0_1_Handler ( void );
void SERCOM0_2_Handler ( void );
void SERCOM0_OTHER_Handler ( void );
void SERCOM1_0_Handler ( void );
void SERCOM1_1_Handler ( void );
void SERCOM1_2_Handler ( void );
void SERCOM1_OTHER_Handler ( void );
void SERCOM2_0_Handler ( void );
void SERCOM2_1_Handler ( void );
void SERCOM2_2_Handler ( void );
void SERCOM2_OTHER_Handler ( void );
void SYSTEM_Handler ( void );
void TC0_Handler ( void );
void TC1_Handler ( void );
void TC2_Handler ( void );
void TRAM_Handler ( void );
void TRNG_Handler ( void );
void WDT_Handler ( void );
#endif /* DONT_USE_PREDEFINED_PERIPHERALS_HANDLERS */
/* Defines for Deprecated Interrupt and Exceptions handler names */
#define MemManage_Handler MemoryManagement_Handler /**< \deprecated Backward compatibility for ASF */
#define DebugMon_Handler DebugMonitor_Handler /**< \deprecated Backward compatibility for ASF */
#define NMI_Handler NonMaskableInt_Handler /**< \deprecated Backward compatibility for ASF */
#define SVC_Handler SVCall_Handler /**< \deprecated Backward compatibility for ASF */
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/*
* \brief Configuration of the CORTEX-M23 Processor and Core Peripherals
*/
#define NUM_IRQ 45 /**< Number of interrupt request lines */
#define __ARMv8MBL_REV 0x0000 /**< Cortex-M23 Core Revision */
#define __ETM_PRESENT 0 /**< ETM present or not */
#define __FPU_PRESENT 0 /**< FPU present or not */
#define __MPU_PRESENT 1 /**< MPU present or not */
#define __MTB_PRESENT 0 /**< MTB present or not */
#define __NVIC_PRIO_BITS 2 /**< Number of Bits used for Priority Levels */
#define __SAU_PRESENT 0 /**< SAU present or not */
#define __SEC_ENABLED 0 /**< TrustZone-M enabled or not */
#define __VTOR_PRESENT 1 /**< Vector Table Offset Register present or not */
#define __Vendor_SysTickConfig 0 /**< Set to 1 if different SysTick Config is used */
#define __ARCH_ARM 1
#define __ARCH_ARM_CORTEX_M 1
#define __DEVICE_IS_SAM 1
/*
* \brief CMSIS includes
*/
#include <core_cm23.h>
#if !defined DONT_USE_CMSIS_INIT
#include "system_saml10.h"
#endif /* DONT_USE_CMSIS_INIT */
/** @} end of SAML10E14A_cmsis CMSIS Definitions */
/** \defgroup SAML10E14A_api Peripheral Software API
* @{
*/
/* ************************************************************************** */
/** SOFTWARE PERIPHERAL API DEFINITION FOR SAML10E14A */
/* ************************************************************************** */
#include "component/ac.h"
#include "component/adc.h"
#include "component/ccl.h"
#include "component/dac.h"
#include "component/dmac.h"
#include "component/dsu.h"
#include "component/eic.h"
#include "component/evsys.h"
#include "component/freqm.h"
#include "component/gclk.h"
#include "component/idau.h"
#include "component/mclk.h"
#include "component/nvmctrl.h"
#include "component/opamp.h"
#include "component/oscctrl.h"
#include "component/osc32kctrl.h"
#include "component/pac.h"
#include "component/pm.h"
#include "component/port.h"
#include "component/ptc.h"
#include "component/rstc.h"
#include "component/rtc.h"
#include "component/sercom.h"
#include "component/supc.h"
#include "component/tc.h"
#include "component/tram.h"
#include "component/trng.h"
#include "component/wdt.h"
/** @} end of Peripheral Software API */
/** \defgroup SAML10E14A_reg Registers Access Definitions
* @{
*/
/* ************************************************************************** */
/* REGISTER ACCESS DEFINITIONS FOR SAML10E14A */
/* ************************************************************************** */
#include "instance/ac.h"
#include "instance/adc.h"
#include "instance/ccl.h"
#include "instance/dac.h"
#include "instance/dmac.h"
#include "instance/dsu.h"
#include "instance/eic.h"
#include "instance/evsys.h"
#include "instance/freqm.h"
#include "instance/gclk.h"
#include "instance/idau.h"
#include "instance/mclk.h"
#include "instance/nvmctrl.h"
#include "instance/opamp.h"
#include "instance/oscctrl.h"
#include "instance/osc32kctrl.h"
#include "instance/pac.h"
#include "instance/pm.h"
#include "instance/port.h"
#include "instance/ptc.h"
#include "instance/rstc.h"
#include "instance/rtc.h"
#include "instance/sercom0.h"
#include "instance/sercom1.h"
#include "instance/sercom2.h"
#include "instance/supc.h"
#include "instance/tc0.h"
#include "instance/tc1.h"
#include "instance/tc2.h"
#include "instance/tram.h"
#include "instance/trng.h"
#include "instance/wdt.h"
/** @} end of Registers Access Definitions */
/** \addtogroup SAML10E14A_id Peripheral Ids Definitions
* @{
*/
/* ************************************************************************** */
/* PERIPHERAL ID DEFINITIONS FOR SAML10E14A */
/* ************************************************************************** */
#define ID_PAC ( 0) /**< \brief Peripheral Access Controller (PAC) */
#define ID_PM ( 1) /**< \brief Power Manager (PM) */
#define ID_MCLK ( 2) /**< \brief Main Clock (MCLK) */
#define ID_RSTC ( 3) /**< \brief Reset Controller (RSTC) */
#define ID_OSCCTRL ( 4) /**< \brief Oscillators Control (OSCCTRL) */
#define ID_OSC32KCTRL ( 5) /**< \brief 32k Oscillators Control (OSC32KCTRL) */
#define ID_SUPC ( 6) /**< \brief Supply Controller (SUPC) */
#define ID_GCLK ( 7) /**< \brief Generic Clock Generator (GCLK) */
#define ID_WDT ( 8) /**< \brief Watchdog Timer (WDT) */
#define ID_RTC ( 9) /**< \brief Real-Time Counter (RTC) */
#define ID_EIC ( 10) /**< \brief External Interrupt Controller (EIC) */
#define ID_FREQM ( 11) /**< \brief Frequency Meter (FREQM) */
#define ID_PORT ( 12) /**< \brief Port Module (PORT) */
#define ID_AC ( 13) /**< \brief Analog Comparators (AC) */
#define ID_IDAU ( 32) /**< \brief Implementation Defined Attribution Unit (IDAU) */
#define ID_DSU ( 33) /**< \brief Device Service Unit (DSU) */
#define ID_NVMCTRL ( 34) /**< \brief Non-Volatile Memory Controller (NVMCTRL) */
#define ID_DMAC ( 35) /**< \brief Direct Memory Access Controller (DMAC) */
#define ID_EVSYS ( 64) /**< \brief Event System Interface (EVSYS) */
#define ID_SERCOM0 ( 65) /**< \brief Serial Communication Interface (SERCOM0) */
#define ID_SERCOM1 ( 66) /**< \brief Serial Communication Interface (SERCOM1) */
#define ID_SERCOM2 ( 67) /**< \brief Serial Communication Interface (SERCOM2) */
#define ID_TC0 ( 68) /**< \brief Basic Timer Counter (TC0) */
#define ID_TC1 ( 69) /**< \brief Basic Timer Counter (TC1) */
#define ID_TC2 ( 70) /**< \brief Basic Timer Counter (TC2) */
#define ID_ADC ( 71) /**< \brief Analog Digital Converter (ADC) */
#define ID_DAC ( 72) /**< \brief Digital Analog Converter (DAC) */
#define ID_PTC ( 73) /**< \brief Peripheral Touch Controller (PTC) */
#define ID_TRNG ( 74) /**< \brief True Random Generator (TRNG) */
#define ID_CCL ( 75) /**< \brief Configurable Custom Logic (CCL) */
#define ID_OPAMP ( 76) /**< \brief Operational Amplifier (OPAMP) */
#define ID_TRAM ( 77) /**< \brief TrustRAM (TRAM) */
#define ID_PERIPH_COUNT ( 78) /**< \brief Number of peripheral IDs */
/** @} end of Peripheral Ids Definitions */
/** \addtogroup SAML10E14A_base Peripheral Base Address Definitions
* @{
*/
/* ************************************************************************** */
/* BASE ADDRESS DEFINITIONS FOR SAML10E14A */
/* ************************************************************************** */
#if (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
#define AC (0x40003400) /**< \brief (AC ) Base Address */
#define ADC (0x42001C00) /**< \brief (ADC ) Base Address */
#define CCL (0x42002C00) /**< \brief (CCL ) Base Address */
#define DAC (0x42002000) /**< \brief (DAC ) Base Address */
#define DMAC (0x41006000) /**< \brief (DMAC ) Base Address */
#define DSU (0x41002000) /**< \brief (DSU ) Base Address */
#define DSU_EXT (0x41002100) /**< \brief (DSU ) Base Address */
#define EIC (0x40002800) /**< \brief (EIC ) Base Address */
#define EVSYS (0x42000000) /**< \brief (EVSYS ) Base Address */
#define FREQM (0x40002C00) /**< \brief (FREQM ) Base Address */
#define GCLK (0x40001C00) /**< \brief (GCLK ) Base Address */
#define IDAU (0x41000000) /**< \brief (IDAU ) Base Address */
#define MCLK (0x40000800) /**< \brief (MCLK ) Base Address */
#define NVMCTRL (0x41004000) /**< \brief (NVMCTRL ) Base Address */
#define OPAMP (0x42003000) /**< \brief (OPAMP ) Base Address */
#define OSCCTRL (0x40001000) /**< \brief (OSCCTRL ) Base Address */
#define OSC32KCTRL (0x40001400) /**< \brief (OSC32KCTRL) Base Address */
#define PAC (0x40000000) /**< \brief (PAC ) Base Address */
#define PM (0x40000400) /**< \brief (PM ) Base Address */
#define PORT (0x40003000) /**< \brief (PORT ) Base Address */
#define PORT_IOBUS (0x60000000) /**< \brief (PORT ) Base Address */
#define PTC (0x42002400) /**< \brief (PTC ) Base Address */
#define RSTC (0x40000C00) /**< \brief (RSTC ) Base Address */
#define RTC (0x40002400) /**< \brief (RTC ) Base Address */
#define SERCOM0 (0x42000400) /**< \brief (SERCOM0 ) Base Address */
#define SERCOM1 (0x42000800) /**< \brief (SERCOM1 ) Base Address */
#define SERCOM2 (0x42000C00) /**< \brief (SERCOM2 ) Base Address */
#define SUPC (0x40001800) /**< \brief (SUPC ) Base Address */
#define TC0 (0x42001000) /**< \brief (TC0 ) Base Address */
#define TC1 (0x42001400) /**< \brief (TC1 ) Base Address */
#define TC2 (0x42001800) /**< \brief (TC2 ) Base Address */
#define TRAM (0x42003400) /**< \brief (TRAM ) Base Address */
#define TRNG (0x42002800) /**< \brief (TRNG ) Base Address */
#define WDT (0x40002000) /**< \brief (WDT ) Base Address */
#else /* For C/C++ compiler */
#define AC ((Ac *)0x40003400U) /**< \brief (AC ) Base Address */
#define AC_INST_NUM 1 /**< \brief (AC ) Number of instances */
#define AC_INSTS { AC } /**< \brief (AC ) Instances List */
#define ADC ((Adc *)0x42001C00U) /**< \brief (ADC ) Base Address */
#define ADC_INST_NUM 1 /**< \brief (ADC ) Number of instances */
#define ADC_INSTS { ADC } /**< \brief (ADC ) Instances List */
#define CCL ((Ccl *)0x42002C00U) /**< \brief (CCL ) Base Address */
#define CCL_INST_NUM 1 /**< \brief (CCL ) Number of instances */
#define CCL_INSTS { CCL } /**< \brief (CCL ) Instances List */
#define DAC ((Dac *)0x42002000U) /**< \brief (DAC ) Base Address */
#define DAC_INST_NUM 1 /**< \brief (DAC ) Number of instances */
#define DAC_INSTS { DAC } /**< \brief (DAC ) Instances List */
#define DMAC ((Dmac *)0x41006000U) /**< \brief (DMAC ) Base Address */
#define DMAC_INST_NUM 1 /**< \brief (DMAC ) Number of instances */
#define DMAC_INSTS { DMAC } /**< \brief (DMAC ) Instances List */
#define DSU ((Dsu *)0x41002000U) /**< \brief (DSU ) Base Address */
#define DSU_EXT ((Dsu *)0x41002100U) /**< \brief (DSU ) Base Address */
#define DSU_INST_NUM 1 /**< \brief (DSU ) Number of instances */
#define DSU_INSTS { DSU } /**< \brief (DSU ) Instances List */
#define EIC ((Eic *)0x40002800U) /**< \brief (EIC ) Base Address */
#define EIC_INST_NUM 1 /**< \brief (EIC ) Number of instances */
#define EIC_INSTS { EIC } /**< \brief (EIC ) Instances List */
#define EVSYS ((Evsys *)0x42000000U) /**< \brief (EVSYS ) Base Address */
#define EVSYS_INST_NUM 1 /**< \brief (EVSYS ) Number of instances */
#define EVSYS_INSTS { EVSYS } /**< \brief (EVSYS ) Instances List */
#define FREQM ((Freqm *)0x40002C00U) /**< \brief (FREQM ) Base Address */
#define FREQM_INST_NUM 1 /**< \brief (FREQM ) Number of instances */
#define FREQM_INSTS { FREQM } /**< \brief (FREQM ) Instances List */
#define GCLK ((Gclk *)0x40001C00U) /**< \brief (GCLK ) Base Address */
#define GCLK_INST_NUM 1 /**< \brief (GCLK ) Number of instances */
#define GCLK_INSTS { GCLK } /**< \brief (GCLK ) Instances List */
#define IDAU ((Idau *)0x41000000U) /**< \brief (IDAU ) Base Address */
#define IDAU_INST_NUM 1 /**< \brief (IDAU ) Number of instances */
#define IDAU_INSTS { IDAU } /**< \brief (IDAU ) Instances List */
#define MCLK ((Mclk *)0x40000800U) /**< \brief (MCLK ) Base Address */
#define MCLK_INST_NUM 1 /**< \brief (MCLK ) Number of instances */
#define MCLK_INSTS { MCLK } /**< \brief (MCLK ) Instances List */
#define NVMCTRL ((Nvmctrl *)0x41004000U) /**< \brief (NVMCTRL ) Base Address */
#define NVMCTRL_INST_NUM 1 /**< \brief (NVMCTRL ) Number of instances */
#define NVMCTRL_INSTS { NVMCTRL } /**< \brief (NVMCTRL ) Instances List */
#define OPAMP ((Opamp *)0x42003000U) /**< \brief (OPAMP ) Base Address */
#define OPAMP_INST_NUM 1 /**< \brief (OPAMP ) Number of instances */
#define OPAMP_INSTS { OPAMP } /**< \brief (OPAMP ) Instances List */
#define OSCCTRL ((Oscctrl *)0x40001000U) /**< \brief (OSCCTRL ) Base Address */
#define OSCCTRL_INST_NUM 1 /**< \brief (OSCCTRL ) Number of instances */
#define OSCCTRL_INSTS { OSCCTRL } /**< \brief (OSCCTRL ) Instances List */
#define OSC32KCTRL ((Osc32kctrl *)0x40001400U) /**< \brief (OSC32KCTRL) Base Address */
#define OSC32KCTRL_INST_NUM 1 /**< \brief (OSC32KCTRL) Number of instances */
#define OSC32KCTRL_INSTS { OSC32KCTRL } /**< \brief (OSC32KCTRL) Instances List */
#define PAC ((Pac *)0x40000000U) /**< \brief (PAC ) Base Address */
#define PAC_INST_NUM 1 /**< \brief (PAC ) Number of instances */
#define PAC_INSTS { PAC } /**< \brief (PAC ) Instances List */
#define PM ((Pm *)0x40000400U) /**< \brief (PM ) Base Address */
#define PM_INST_NUM 1 /**< \brief (PM ) Number of instances */
#define PM_INSTS { PM } /**< \brief (PM ) Instances List */
#define PORT ((Port *)0x40003000U) /**< \brief (PORT ) Base Address */
#define PORT_IOBUS ((Port *)0x60000000U) /**< \brief (PORT ) Base Address */
#define PORT_INST_NUM 1 /**< \brief (PORT ) Number of instances */
#define PORT_INSTS { PORT } /**< \brief (PORT ) Instances List */
#define PTC ((Ptc *)0x42002400U) /**< \brief (PTC ) Base Address */
#define PTC_INST_NUM 1 /**< \brief (PTC ) Number of instances */
#define PTC_INSTS { PTC } /**< \brief (PTC ) Instances List */
#define RSTC ((Rstc *)0x40000C00U) /**< \brief (RSTC ) Base Address */
#define RSTC_INST_NUM 1 /**< \brief (RSTC ) Number of instances */
#define RSTC_INSTS { RSTC } /**< \brief (RSTC ) Instances List */
#define RTC ((Rtc *)0x40002400U) /**< \brief (RTC ) Base Address */
#define RTC_INST_NUM 1 /**< \brief (RTC ) Number of instances */
#define RTC_INSTS { RTC } /**< \brief (RTC ) Instances List */
#define SERCOM0 ((Sercom *)0x42000400U) /**< \brief (SERCOM0 ) Base Address */
#define SERCOM1 ((Sercom *)0x42000800U) /**< \brief (SERCOM1 ) Base Address */
#define SERCOM2 ((Sercom *)0x42000C00U) /**< \brief (SERCOM2 ) Base Address */
#define SERCOM_INST_NUM 3 /**< \brief (SERCOM ) Number of instances */
#define SERCOM_INSTS { SERCOM0, SERCOM1, SERCOM2 } /**< \brief (SERCOM ) Instances List */
#define SUPC ((Supc *)0x40001800U) /**< \brief (SUPC ) Base Address */
#define SUPC_INST_NUM 1 /**< \brief (SUPC ) Number of instances */
#define SUPC_INSTS { SUPC } /**< \brief (SUPC ) Instances List */
#define TC0 ((Tc *)0x42001000U) /**< \brief (TC0 ) Base Address */
#define TC1 ((Tc *)0x42001400U) /**< \brief (TC1 ) Base Address */
#define TC2 ((Tc *)0x42001800U) /**< \brief (TC2 ) Base Address */
#define TC_INST_NUM 3 /**< \brief (TC ) Number of instances */
#define TC_INSTS { TC0, TC1, TC2 } /**< \brief (TC ) Instances List */
#define TRAM ((Tram *)0x42003400U) /**< \brief (TRAM ) Base Address */
#define TRAM_INST_NUM 1 /**< \brief (TRAM ) Number of instances */
#define TRAM_INSTS { TRAM } /**< \brief (TRAM ) Instances List */
#define TRNG ((Trng *)0x42002800U) /**< \brief (TRNG ) Base Address */
#define TRNG_INST_NUM 1 /**< \brief (TRNG ) Number of instances */
#define TRNG_INSTS { TRNG } /**< \brief (TRNG ) Instances List */
#define WDT ((Wdt *)0x40002000U) /**< \brief (WDT ) Base Address */
#define WDT_INST_NUM 1 /**< \brief (WDT ) Number of instances */
#define WDT_INSTS { WDT } /**< \brief (WDT ) Instances List */
#endif /* (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/** @} end of Peripheral Base Address Definitions */
/** \addtogroup SAML10E14A_pio Peripheral Pio Definitions
* @{
*/
/* ************************************************************************** */
/* PIO DEFINITIONS FOR SAML10E14A*/
/* ************************************************************************** */
#include "pio/saml10e14a.h"
/** @} end of Peripheral Pio Definitions */
/* ************************************************************************** */
/* MEMORY MAPPING DEFINITIONS FOR SAML10E14A*/
/* ************************************************************************** */
#define FLASH_SIZE _U_(0x00004000) /* 16kB Memory segment type: flash */
#define FLASH_PAGE_SIZE _U_( 64)
#define FLASH_NB_OF_PAGES _U_( 256)
#define AUX_SIZE _U_(0x00000100) /* 0kB Memory segment type: fuses */
#define AUX_PAGE_SIZE _U_( 64)
#define AUX_NB_OF_PAGES _U_( 4)
#define BOCOR_SIZE _U_(0x00000100) /* 0kB Memory segment type: fuses */
#define BOCOR_PAGE_SIZE _U_( 64)
#define BOCOR_NB_OF_PAGES _U_( 4)
#define DATAFLASH_SIZE _U_(0x00000800) /* 2kB Memory segment type: flash */
#define DATAFLASH_PAGE_SIZE _U_( 64)
#define DATAFLASH_NB_OF_PAGES _U_( 32)
#define SW_CALIB_SIZE _U_(0x00000008) /* 0kB Memory segment type: fuses */
#define TEMP_LOG_SIZE _U_(0x00000008) /* 0kB Memory segment type: fuses */
#define USER_PAGE_SIZE _U_(0x00000100) /* 0kB Memory segment type: user_page */
#define USER_PAGE_PAGE_SIZE _U_( 64)
#define USER_PAGE_NB_OF_PAGES _U_( 4)
#define HSRAM_SIZE _U_(0x00001000) /* 4kB Memory segment type: ram */
#define HPB0_SIZE _U_(0x00008000) /* 32kB Memory segment type: io */
#define HPB1_SIZE _U_(0x00010000) /* 64kB Memory segment type: io */
#define HPB2_SIZE _U_(0x00004000) /* 16kB Memory segment type: io */
#define PPB_SIZE _U_(0x00100000) /* 1024kB Memory segment type: io */
#define SCS_SIZE _U_(0x00001000) /* 4kB Memory segment type: io */
#define PERIPHERALS_SIZE _U_(0x20000000) /* 524288kB Memory segment type: io */
#define FLASH_ADDR _U_(0x00000000) /**< FLASH base address (type: flash)*/
#define AUX_ADDR _U_(0x00806000) /**< AUX base address (type: fuses)*/
#define BOCOR_ADDR _U_(0x0080c000) /**< BOCOR base address (type: fuses)*/
#define DATAFLASH_ADDR _U_(0x00400000) /**< DATAFLASH base address (type: flash)*/
#define SW_CALIB_ADDR _U_(0x00806020) /**< SW_CALIB base address (type: fuses)*/
#define TEMP_LOG_ADDR _U_(0x00806038) /**< TEMP_LOG base address (type: fuses)*/
#define USER_PAGE_ADDR _U_(0x00804000) /**< USER_PAGE base address (type: user_page)*/
#define HSRAM_ADDR _U_(0x20000000) /**< HSRAM base address (type: ram)*/
#define HPB0_ADDR _U_(0x40000000) /**< HPB0 base address (type: io)*/
#define HPB1_ADDR _U_(0x41000000) /**< HPB1 base address (type: io)*/
#define HPB2_ADDR _U_(0x42000000) /**< HPB2 base address (type: io)*/
#define PPB_ADDR _U_(0xe0000000) /**< PPB base address (type: io)*/
#define SCS_ADDR _U_(0xe000e000) /**< SCS base address (type: io)*/
#define PERIPHERALS_ADDR _U_(0x40000000) /**< PERIPHERALS base address (type: io)*/
#define NVMCTRL_AUX AUX_ADDR /**< \brief \deprecated Old style definition. Use AUX_ADDR instead */
#define NVMCTRL_BOCOR BOCOR_ADDR /**< \brief \deprecated Old style definition. Use BOCOR_ADDR instead */
#define NVMCTRL_DATAFLASH DATAFLASH_ADDR /**< \brief \deprecated Old style definition. Use DATAFLASH_ADDR instead */
#define NVMCTRL_SW_CALIB SW_CALIB_ADDR /**< \brief \deprecated Old style definition. Use SW_CALIB_ADDR instead */
#define NVMCTRL_TEMP_LOG TEMP_LOG_ADDR /**< \brief \deprecated Old style definition. Use TEMP_LOG_ADDR instead */
#define NVMCTRL_USER USER_PAGE_ADDR /**< \brief \deprecated Old style definition. Use USER_PAGE_ADDR instead */
/* ************************************************************************** */
/** DEVICE SIGNATURES FOR SAML10E14A */
/* ************************************************************************** */
#define DSU_DID _UL_(0X20840002)
/* ************************************************************************** */
/** ELECTRICAL DEFINITIONS FOR SAML10E14A */
/* ************************************************************************** */
/* ************************************************************************** */
/** Event Generator IDs for SAML10E14A */
/* ************************************************************************** */
#define EVENT_ID_GEN_OSCCTRL_XOSC_FAIL 1 /**< ID for OSCCTRL event generator XOSC_FAIL */
#define EVENT_ID_GEN_OSC32KCTRL_XOSC32K_FAIL 2 /**< ID for OSC32KCTRL event generator XOSC32K_FAIL */
#define EVENT_ID_GEN_SUPC_BOD33DET 3 /**< ID for SUPC event generator BOD33DET */
#define EVENT_ID_GEN_RTC_PER_0 4 /**< ID for RTC event generator PER_0 */
#define EVENT_ID_GEN_RTC_PER_1 5 /**< ID for RTC event generator PER_1 */
#define EVENT_ID_GEN_RTC_PER_2 6 /**< ID for RTC event generator PER_2 */
#define EVENT_ID_GEN_RTC_PER_3 7 /**< ID for RTC event generator PER_3 */
#define EVENT_ID_GEN_RTC_PER_4 8 /**< ID for RTC event generator PER_4 */
#define EVENT_ID_GEN_RTC_PER_5 9 /**< ID for RTC event generator PER_5 */
#define EVENT_ID_GEN_RTC_PER_6 10 /**< ID for RTC event generator PER_6 */
#define EVENT_ID_GEN_RTC_PER_7 11 /**< ID for RTC event generator PER_7 */
#define EVENT_ID_GEN_RTC_CMP_0 12 /**< ID for RTC event generator CMP_0 */
#define EVENT_ID_GEN_RTC_CMP_1 13 /**< ID for RTC event generator CMP_1 */
#define EVENT_ID_GEN_RTC_TAMPER 14 /**< ID for RTC event generator TAMPER */
#define EVENT_ID_GEN_RTC_OVF 15 /**< ID for RTC event generator OVF */
#define EVENT_ID_GEN_RTC_PERD 16 /**< ID for RTC event generator PERD */
#define EVENT_ID_GEN_EIC_EXTINT_0 17 /**< ID for EIC event generator EXTINT_0 */
#define EVENT_ID_GEN_EIC_EXTINT_1 18 /**< ID for EIC event generator EXTINT_1 */
#define EVENT_ID_GEN_EIC_EXTINT_2 19 /**< ID for EIC event generator EXTINT_2 */
#define EVENT_ID_GEN_EIC_EXTINT_3 20 /**< ID for EIC event generator EXTINT_3 */
#define EVENT_ID_GEN_EIC_EXTINT_4 21 /**< ID for EIC event generator EXTINT_4 */
#define EVENT_ID_GEN_EIC_EXTINT_5 22 /**< ID for EIC event generator EXTINT_5 */
#define EVENT_ID_GEN_EIC_EXTINT_6 23 /**< ID for EIC event generator EXTINT_6 */
#define EVENT_ID_GEN_EIC_EXTINT_7 24 /**< ID for EIC event generator EXTINT_7 */
#define EVENT_ID_GEN_DMAC_CH_0 25 /**< ID for DMAC event generator CH_0 */
#define EVENT_ID_GEN_DMAC_CH_1 26 /**< ID for DMAC event generator CH_1 */
#define EVENT_ID_GEN_DMAC_CH_2 27 /**< ID for DMAC event generator CH_2 */
#define EVENT_ID_GEN_DMAC_CH_3 28 /**< ID for DMAC event generator CH_3 */
#define EVENT_ID_GEN_TC0_OVF 29 /**< ID for TC0 event generator OVF */
#define EVENT_ID_GEN_TC0_MCX_0 30 /**< ID for TC0 event generator MCX_0 */
#define EVENT_ID_GEN_TC0_MCX_1 31 /**< ID for TC0 event generator MCX_1 */
#define EVENT_ID_GEN_TC1_OVF 32 /**< ID for TC1 event generator OVF */
#define EVENT_ID_GEN_TC1_MCX_0 33 /**< ID for TC1 event generator MCX_0 */
#define EVENT_ID_GEN_TC1_MCX_1 34 /**< ID for TC1 event generator MCX_1 */
#define EVENT_ID_GEN_TC2_OVF 35 /**< ID for TC2 event generator OVF */
#define EVENT_ID_GEN_TC2_MCX_0 36 /**< ID for TC2 event generator MCX_0 */
#define EVENT_ID_GEN_TC2_MCX_1 37 /**< ID for TC2 event generator MCX_1 */
#define EVENT_ID_GEN_ADC_RESRDY 38 /**< ID for ADC event generator RESRDY */
#define EVENT_ID_GEN_ADC_WINMON 39 /**< ID for ADC event generator WINMON */
#define EVENT_ID_GEN_AC_COMP_0 40 /**< ID for AC event generator COMP_0 */
#define EVENT_ID_GEN_AC_COMP_1 41 /**< ID for AC event generator COMP_1 */
#define EVENT_ID_GEN_AC_WIN_0 42 /**< ID for AC event generator WIN_0 */
#define EVENT_ID_GEN_DAC_EMPTY 43 /**< ID for DAC event generator EMPTY */
#define EVENT_ID_GEN_TRNG_READY 46 /**< ID for TRNG event generator READY */
#define EVENT_ID_GEN_CCL_LUTOUT_0 47 /**< ID for CCL event generator LUTOUT_0 */
#define EVENT_ID_GEN_CCL_LUTOUT_1 48 /**< ID for CCL event generator LUTOUT_1 */
#define EVENT_ID_GEN_PAC_ERR 49 /**< ID for PAC event generator ERR */
/* ************************************************************************** */
/** Event User IDs for SAML10E14A */
/* ************************************************************************** */
#define EVENT_ID_USER_OSCCTRL_TUNE 0 /**< ID for OSCCTRL event user TUNE */
#define EVENT_ID_USER_RTC_TAMPER 1 /**< ID for RTC event user TAMPER */
#define EVENT_ID_USER_NVMCTRL_PAGEW 2 /**< ID for NVMCTRL event user PAGEW */
#define EVENT_ID_USER_PORT_EV_0 3 /**< ID for PORT event user EV_0 */
#define EVENT_ID_USER_PORT_EV_1 4 /**< ID for PORT event user EV_1 */
#define EVENT_ID_USER_PORT_EV_2 5 /**< ID for PORT event user EV_2 */
#define EVENT_ID_USER_PORT_EV_3 6 /**< ID for PORT event user EV_3 */
#define EVENT_ID_USER_DMAC_CH_0 7 /**< ID for DMAC event user CH_0 */
#define EVENT_ID_USER_DMAC_CH_1 8 /**< ID for DMAC event user CH_1 */
#define EVENT_ID_USER_DMAC_CH_2 9 /**< ID for DMAC event user CH_2 */
#define EVENT_ID_USER_DMAC_CH_3 10 /**< ID for DMAC event user CH_3 */
#define EVENT_ID_USER_TC0_EVU 11 /**< ID for TC0 event user EVU */
#define EVENT_ID_USER_TC1_EVU 12 /**< ID for TC1 event user EVU */
#define EVENT_ID_USER_TC2_EVU 13 /**< ID for TC2 event user EVU */
#define EVENT_ID_USER_ADC_START 14 /**< ID for ADC event user START */
#define EVENT_ID_USER_ADC_SYNC 15 /**< ID for ADC event user SYNC */
#define EVENT_ID_USER_AC_SOC_0 16 /**< ID for AC event user SOC_0 */
#define EVENT_ID_USER_AC_SOC_1 17 /**< ID for AC event user SOC_1 */
#define EVENT_ID_USER_DAC_START 18 /**< ID for DAC event user START */
#define EVENT_ID_USER_CCL_LUTIN_0 21 /**< ID for CCL event user LUTIN_0 */
#define EVENT_ID_USER_CCL_LUTIN_1 22 /**< ID for CCL event user LUTIN_1 */
#ifdef __cplusplus
}
#endif
/** @} end of SAML10E14A definitions */
#endif /* _SAML10E14A_H_ */

View File

@ -0,0 +1,801 @@
/**
* \file
*
* \brief Header file for ATSAML10E15A
*
* Copyright (c) 2018 Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* 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
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
/* file generated from device description version 2018-08-31T13:51:50Z */
#ifndef _SAML10E15A_H_
#define _SAML10E15A_H_
/** \addtogroup SAML10E15A_definitions SAML10E15A definitions
This file defines all structures and symbols for SAML10E15A:
- registers and bitfields
- peripheral base address
- peripheral ID
- PIO definitions
* @{
*/
#ifdef __cplusplus
extern "C" {
#endif
/** \defgroup Atmel_glob_defs Atmel Global Defines
<strong>IO Type Qualifiers</strong> are used
\li to specify the access to peripheral variables.
\li for automatic generation of peripheral register debug information.
\remark
CMSIS core has a syntax that differs from this using i.e. __I, __O, or __IO followed by 'uint<size>_t' respective types.
Default the header files will follow the CMSIS core syntax.
* @{
*/
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
#include <stdint.h>
/* IO definitions (access restrictions to peripheral registers) */
#ifndef __cplusplus
typedef volatile const uint32_t RoReg; /**< Read only 32-bit register (volatile const unsigned int) */
typedef volatile const uint16_t RoReg16; /**< Read only 16-bit register (volatile const unsigned int) */
typedef volatile const uint8_t RoReg8; /**< Read only 8-bit register (volatile const unsigned int) */
#else
typedef volatile uint32_t RoReg; /**< Read only 32-bit register (volatile const unsigned int) */
typedef volatile uint16_t RoReg16; /**< Read only 16-bit register (volatile const unsigned int) */
typedef volatile uint8_t RoReg8; /**< Read only 8-bit register (volatile const unsigned int) */
#endif
typedef volatile uint32_t WoReg; /**< Write only 32-bit register (volatile unsigned int) */
typedef volatile uint16_t WoReg16; /**< Write only 16-bit register (volatile unsigned int) */
typedef volatile uint8_t WoReg8; /**< Write only 8-bit register (volatile unsigned int) */
typedef volatile uint32_t RwReg; /**< Read-Write 32-bit register (volatile unsigned int) */
typedef volatile uint16_t RwReg16; /**< Read-Write 16-bit register (volatile unsigned int) */
typedef volatile uint8_t RwReg8; /**< Read-Write 8-bit register (volatile unsigned int) */
#define CAST(type, value) ((type *)(value)) /**< Pointer Type Conversion Macro for C/C++ */
#define REG_ACCESS(type, address) (*(type*)(address)) /**< C code: Register value */
#else /* Assembler */
#define CAST(type, value) (value) /**< Pointer Type Conversion Macro for Assembler */
#define REG_ACCESS(type, address) (address) /**< Assembly code: Register address */
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#if !defined(SKIP_INTEGER_LITERALS)
#if defined(_U_) || defined(_L_) || defined(_UL_)
#error "Integer Literals macros already defined elsewhere"
#endif
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
/* Macros that deal with adding suffixes to integer literal constants for C/C++ */
#define _U_(x) x ## U /**< C code: Unsigned integer literal constant value */
#define _L_(x) x ## L /**< C code: Long integer literal constant value */
#define _UL_(x) x ## UL /**< C code: Unsigned Long integer literal constant value */
#else /* Assembler */
#define _U_(x) x /**< Assembler: Unsigned integer literal constant value */
#define _L_(x) x /**< Assembler: Long integer literal constant value */
#define _UL_(x) x /**< Assembler: Unsigned Long integer literal constant value */
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#endif /* SKIP_INTEGER_LITERALS */
/** @} end of Atmel Global Defines */
/** \addtogroup SAML10E15A_cmsis CMSIS Definitions
* @{
*/
/* ************************************************************************** */
/* CMSIS DEFINITIONS FOR SAML10E15A */
/* ************************************************************************** */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
/** Interrupt Number Definition */
typedef enum IRQn
{
/****** CORTEX-M23 Processor Exceptions Numbers ******************************/
Reset_IRQn = -15, /**< 1 Reset Vector, invoked on Power up and warm reset */
NonMaskableInt_IRQn = -14, /**< 2 Non maskable Interrupt, cannot be stopped or preempted */
HardFault_IRQn = -13, /**< 3 Hard Fault, all classes of Fault */
SVCall_IRQn = -5 , /**< 11 System Service Call via SVC instruction */
PendSV_IRQn = -2 , /**< 14 Pendable request for system service */
SysTick_IRQn = -1 , /**< 15 System Tick Timer */
/****** SAML10E15A specific Interrupt Numbers ***********************************/
SYSTEM_IRQn = 0 , /**< 0 SAML10E15A Main Clock (MCLK) */
WDT_IRQn = 1 , /**< 1 SAML10E15A Watchdog Timer (WDT) */
RTC_IRQn = 2 , /**< 2 SAML10E15A Real-Time Counter (RTC) */
EIC_0_IRQn = 3 , /**< 3 SAML10E15A External Interrupt Controller (EIC) */
EIC_1_IRQn = 4 , /**< 4 SAML10E15A External Interrupt Controller (EIC) */
EIC_2_IRQn = 5 , /**< 5 SAML10E15A External Interrupt Controller (EIC) */
EIC_3_IRQn = 6 , /**< 6 SAML10E15A External Interrupt Controller (EIC) */
EIC_OTHER_IRQn = 7 , /**< 7 SAML10E15A External Interrupt Controller (EIC) */
FREQM_IRQn = 8 , /**< 8 SAML10E15A Frequency Meter (FREQM) */
NVMCTRL_IRQn = 9 , /**< 9 SAML10E15A Non-Volatile Memory Controller (NVMCTRL) */
PORT_IRQn = 10 , /**< 10 SAML10E15A Port Module (PORT) */
DMAC_0_IRQn = 11 , /**< 11 SAML10E15A Direct Memory Access Controller (DMAC) */
DMAC_1_IRQn = 12 , /**< 12 SAML10E15A Direct Memory Access Controller (DMAC) */
DMAC_2_IRQn = 13 , /**< 13 SAML10E15A Direct Memory Access Controller (DMAC) */
DMAC_3_IRQn = 14 , /**< 14 SAML10E15A Direct Memory Access Controller (DMAC) */
DMAC_OTHER_IRQn = 15 , /**< 15 SAML10E15A Direct Memory Access Controller (DMAC) */
EVSYS_0_IRQn = 16 , /**< 16 SAML10E15A Event System Interface (EVSYS) */
EVSYS_1_IRQn = 17 , /**< 17 SAML10E15A Event System Interface (EVSYS) */
EVSYS_2_IRQn = 18 , /**< 18 SAML10E15A Event System Interface (EVSYS) */
EVSYS_3_IRQn = 19 , /**< 19 SAML10E15A Event System Interface (EVSYS) */
EVSYS_NSCHK_IRQn = 20 , /**< 20 SAML10E15A Event System Interface (EVSYS) */
PAC_IRQn = 21 , /**< 21 SAML10E15A Peripheral Access Controller (PAC) */
SERCOM0_0_IRQn = 22 , /**< 22 SAML10E15A Serial Communication Interface (SERCOM0) */
SERCOM0_1_IRQn = 23 , /**< 23 SAML10E15A Serial Communication Interface (SERCOM0) */
SERCOM0_2_IRQn = 24 , /**< 24 SAML10E15A Serial Communication Interface (SERCOM0) */
SERCOM0_OTHER_IRQn = 25 , /**< 25 SAML10E15A Serial Communication Interface (SERCOM0) */
SERCOM1_0_IRQn = 26 , /**< 26 SAML10E15A Serial Communication Interface (SERCOM1) */
SERCOM1_1_IRQn = 27 , /**< 27 SAML10E15A Serial Communication Interface (SERCOM1) */
SERCOM1_2_IRQn = 28 , /**< 28 SAML10E15A Serial Communication Interface (SERCOM1) */
SERCOM1_OTHER_IRQn = 29 , /**< 29 SAML10E15A Serial Communication Interface (SERCOM1) */
SERCOM2_0_IRQn = 30 , /**< 30 SAML10E15A Serial Communication Interface (SERCOM2) */
SERCOM2_1_IRQn = 31 , /**< 31 SAML10E15A Serial Communication Interface (SERCOM2) */
SERCOM2_2_IRQn = 32 , /**< 32 SAML10E15A Serial Communication Interface (SERCOM2) */
SERCOM2_OTHER_IRQn = 33 , /**< 33 SAML10E15A Serial Communication Interface (SERCOM2) */
TC0_IRQn = 34 , /**< 34 SAML10E15A Basic Timer Counter (TC0) */
TC1_IRQn = 35 , /**< 35 SAML10E15A Basic Timer Counter (TC1) */
TC2_IRQn = 36 , /**< 36 SAML10E15A Basic Timer Counter (TC2) */
ADC_OTHER_IRQn = 37 , /**< 37 SAML10E15A Analog Digital Converter (ADC) */
ADC_RESRDY_IRQn = 38 , /**< 38 SAML10E15A Analog Digital Converter (ADC) */
AC_IRQn = 39 , /**< 39 SAML10E15A Analog Comparators (AC) */
DAC_UNDERRUN_A_IRQn = 40 , /**< 40 SAML10E15A Digital Analog Converter (DAC) */
DAC_EMPTY_IRQn = 41 , /**< 41 SAML10E15A Digital Analog Converter (DAC) */
PTC_IRQn = 42 , /**< 42 SAML10E15A Peripheral Touch Controller (PTC) */
TRNG_IRQn = 43 , /**< 43 SAML10E15A True Random Generator (TRNG) */
TRAM_IRQn = 44 , /**< 44 SAML10E15A TrustRAM (TRAM) */
PERIPH_COUNT_IRQn = 45 /**< Number of peripheral IDs */
} IRQn_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef struct _DeviceVectors
{
/* Stack pointer */
void* pvStack;
/* Cortex-M handlers */
void* pfnReset_Handler; /* -15 Reset Vector, invoked on Power up and warm reset */
void* pfnNonMaskableInt_Handler; /* -14 Non maskable Interrupt, cannot be stopped or preempted */
void* pfnHardFault_Handler; /* -13 Hard Fault, all classes of Fault */
void* pvReservedC12;
void* pvReservedC11;
void* pvReservedC10;
void* pvReservedC9;
void* pvReservedC8;
void* pvReservedC7;
void* pvReservedC6;
void* pfnSVCall_Handler; /* -5 System Service Call via SVC instruction */
void* pvReservedC4;
void* pvReservedC3;
void* pfnPendSV_Handler; /* -2 Pendable request for system service */
void* pfnSysTick_Handler; /* -1 System Tick Timer */
/* Peripheral handlers */
void* pfnSYSTEM_Handler; /* 0 SAML10E15A Main Clock (MCLK) */
void* pfnWDT_Handler; /* 1 SAML10E15A Watchdog Timer (WDT) */
void* pfnRTC_Handler; /* 2 SAML10E15A Real-Time Counter (RTC) */
void* pfnEIC_0_Handler; /* 3 SAML10E15A External Interrupt Controller (EIC) */
void* pfnEIC_1_Handler; /* 4 SAML10E15A External Interrupt Controller (EIC) */
void* pfnEIC_2_Handler; /* 5 SAML10E15A External Interrupt Controller (EIC) */
void* pfnEIC_3_Handler; /* 6 SAML10E15A External Interrupt Controller (EIC) */
void* pfnEIC_OTHER_Handler; /* 7 SAML10E15A External Interrupt Controller (EIC) */
void* pfnFREQM_Handler; /* 8 SAML10E15A Frequency Meter (FREQM) */
void* pfnNVMCTRL_Handler; /* 9 SAML10E15A Non-Volatile Memory Controller (NVMCTRL) */
void* pfnPORT_Handler; /* 10 SAML10E15A Port Module (PORT) */
void* pfnDMAC_0_Handler; /* 11 SAML10E15A Direct Memory Access Controller (DMAC) */
void* pfnDMAC_1_Handler; /* 12 SAML10E15A Direct Memory Access Controller (DMAC) */
void* pfnDMAC_2_Handler; /* 13 SAML10E15A Direct Memory Access Controller (DMAC) */
void* pfnDMAC_3_Handler; /* 14 SAML10E15A Direct Memory Access Controller (DMAC) */
void* pfnDMAC_OTHER_Handler; /* 15 SAML10E15A Direct Memory Access Controller (DMAC) */
void* pfnEVSYS_0_Handler; /* 16 SAML10E15A Event System Interface (EVSYS) */
void* pfnEVSYS_1_Handler; /* 17 SAML10E15A Event System Interface (EVSYS) */
void* pfnEVSYS_2_Handler; /* 18 SAML10E15A Event System Interface (EVSYS) */
void* pfnEVSYS_3_Handler; /* 19 SAML10E15A Event System Interface (EVSYS) */
void* pfnEVSYS_NSCHK_Handler; /* 20 SAML10E15A Event System Interface (EVSYS) */
void* pfnPAC_Handler; /* 21 SAML10E15A Peripheral Access Controller (PAC) */
void* pfnSERCOM0_0_Handler; /* 22 SAML10E15A Serial Communication Interface (SERCOM0) */
void* pfnSERCOM0_1_Handler; /* 23 SAML10E15A Serial Communication Interface (SERCOM0) */
void* pfnSERCOM0_2_Handler; /* 24 SAML10E15A Serial Communication Interface (SERCOM0) */
void* pfnSERCOM0_OTHER_Handler; /* 25 SAML10E15A Serial Communication Interface (SERCOM0) */
void* pfnSERCOM1_0_Handler; /* 26 SAML10E15A Serial Communication Interface (SERCOM1) */
void* pfnSERCOM1_1_Handler; /* 27 SAML10E15A Serial Communication Interface (SERCOM1) */
void* pfnSERCOM1_2_Handler; /* 28 SAML10E15A Serial Communication Interface (SERCOM1) */
void* pfnSERCOM1_OTHER_Handler; /* 29 SAML10E15A Serial Communication Interface (SERCOM1) */
void* pfnSERCOM2_0_Handler; /* 30 SAML10E15A Serial Communication Interface (SERCOM2) */
void* pfnSERCOM2_1_Handler; /* 31 SAML10E15A Serial Communication Interface (SERCOM2) */
void* pfnSERCOM2_2_Handler; /* 32 SAML10E15A Serial Communication Interface (SERCOM2) */
void* pfnSERCOM2_OTHER_Handler; /* 33 SAML10E15A Serial Communication Interface (SERCOM2) */
void* pfnTC0_Handler; /* 34 SAML10E15A Basic Timer Counter (TC0) */
void* pfnTC1_Handler; /* 35 SAML10E15A Basic Timer Counter (TC1) */
void* pfnTC2_Handler; /* 36 SAML10E15A Basic Timer Counter (TC2) */
void* pfnADC_OTHER_Handler; /* 37 SAML10E15A Analog Digital Converter (ADC) */
void* pfnADC_RESRDY_Handler; /* 38 SAML10E15A Analog Digital Converter (ADC) */
void* pfnAC_Handler; /* 39 SAML10E15A Analog Comparators (AC) */
void* pfnDAC_UNDERRUN_A_Handler; /* 40 SAML10E15A Digital Analog Converter (DAC) */
void* pfnDAC_EMPTY_Handler; /* 41 SAML10E15A Digital Analog Converter (DAC) */
void* pfnPTC_Handler; /* 42 SAML10E15A Peripheral Touch Controller (PTC) */
void* pfnTRNG_Handler; /* 43 SAML10E15A True Random Generator (TRNG) */
void* pfnTRAM_Handler; /* 44 SAML10E15A TrustRAM (TRAM) */
} DeviceVectors;
/* Defines for Deprecated Interrupt and Exceptions handler names */
#define pfnMemManage_Handler pfnMemoryManagement_Handler /**< \deprecated Backward compatibility for ASF */
#define pfnDebugMon_Handler pfnDebugMonitor_Handler /**< \deprecated Backward compatibility for ASF */
#define pfnNMI_Handler pfnNonMaskableInt_Handler /**< \deprecated Backward compatibility for ASF */
#define pfnSVC_Handler pfnSVCall_Handler /**< \deprecated Backward compatibility for ASF */
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
#if !defined DONT_USE_PREDEFINED_CORE_HANDLERS
/* CORTEX-M23 core handlers */
void Reset_Handler ( void );
void NonMaskableInt_Handler ( void );
void HardFault_Handler ( void );
void SVCall_Handler ( void );
void PendSV_Handler ( void );
void SysTick_Handler ( void );
#endif /* DONT_USE_PREDEFINED_CORE_HANDLERS */
#if !defined DONT_USE_PREDEFINED_PERIPHERALS_HANDLERS
/* Peripherals handlers */
void AC_Handler ( void );
void ADC_OTHER_Handler ( void );
void ADC_RESRDY_Handler ( void );
void DAC_EMPTY_Handler ( void );
void DAC_UNDERRUN_A_Handler ( void );
void DMAC_0_Handler ( void );
void DMAC_1_Handler ( void );
void DMAC_2_Handler ( void );
void DMAC_3_Handler ( void );
void DMAC_OTHER_Handler ( void );
void EIC_0_Handler ( void );
void EIC_1_Handler ( void );
void EIC_2_Handler ( void );
void EIC_3_Handler ( void );
void EIC_OTHER_Handler ( void );
void EVSYS_0_Handler ( void );
void EVSYS_1_Handler ( void );
void EVSYS_2_Handler ( void );
void EVSYS_3_Handler ( void );
void EVSYS_NSCHK_Handler ( void );
void FREQM_Handler ( void );
void NVMCTRL_Handler ( void );
void PAC_Handler ( void );
void PORT_Handler ( void );
void PTC_Handler ( void );
void RTC_Handler ( void );
void SERCOM0_0_Handler ( void );
void SERCOM0_1_Handler ( void );
void SERCOM0_2_Handler ( void );
void SERCOM0_OTHER_Handler ( void );
void SERCOM1_0_Handler ( void );
void SERCOM1_1_Handler ( void );
void SERCOM1_2_Handler ( void );
void SERCOM1_OTHER_Handler ( void );
void SERCOM2_0_Handler ( void );
void SERCOM2_1_Handler ( void );
void SERCOM2_2_Handler ( void );
void SERCOM2_OTHER_Handler ( void );
void SYSTEM_Handler ( void );
void TC0_Handler ( void );
void TC1_Handler ( void );
void TC2_Handler ( void );
void TRAM_Handler ( void );
void TRNG_Handler ( void );
void WDT_Handler ( void );
#endif /* DONT_USE_PREDEFINED_PERIPHERALS_HANDLERS */
/* Defines for Deprecated Interrupt and Exceptions handler names */
#define MemManage_Handler MemoryManagement_Handler /**< \deprecated Backward compatibility for ASF */
#define DebugMon_Handler DebugMonitor_Handler /**< \deprecated Backward compatibility for ASF */
#define NMI_Handler NonMaskableInt_Handler /**< \deprecated Backward compatibility for ASF */
#define SVC_Handler SVCall_Handler /**< \deprecated Backward compatibility for ASF */
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/*
* \brief Configuration of the CORTEX-M23 Processor and Core Peripherals
*/
#define NUM_IRQ 45 /**< Number of interrupt request lines */
#define __ARMv8MBL_REV 0x0000 /**< Cortex-M23 Core Revision */
#define __ETM_PRESENT 0 /**< ETM present or not */
#define __FPU_PRESENT 0 /**< FPU present or not */
#define __MPU_PRESENT 1 /**< MPU present or not */
#define __MTB_PRESENT 0 /**< MTB present or not */
#define __NVIC_PRIO_BITS 2 /**< Number of Bits used for Priority Levels */
#define __SAU_PRESENT 0 /**< SAU present or not */
#define __SEC_ENABLED 0 /**< TrustZone-M enabled or not */
#define __VTOR_PRESENT 1 /**< Vector Table Offset Register present or not */
#define __Vendor_SysTickConfig 0 /**< Set to 1 if different SysTick Config is used */
#define __ARCH_ARM 1
#define __ARCH_ARM_CORTEX_M 1
#define __DEVICE_IS_SAM 1
/*
* \brief CMSIS includes
*/
#include <core_cm23.h>
#if !defined DONT_USE_CMSIS_INIT
#include "system_saml10.h"
#endif /* DONT_USE_CMSIS_INIT */
/** @} end of SAML10E15A_cmsis CMSIS Definitions */
/** \defgroup SAML10E15A_api Peripheral Software API
* @{
*/
/* ************************************************************************** */
/** SOFTWARE PERIPHERAL API DEFINITION FOR SAML10E15A */
/* ************************************************************************** */
#include "component/ac.h"
#include "component/adc.h"
#include "component/ccl.h"
#include "component/dac.h"
#include "component/dmac.h"
#include "component/dsu.h"
#include "component/eic.h"
#include "component/evsys.h"
#include "component/freqm.h"
#include "component/gclk.h"
#include "component/idau.h"
#include "component/mclk.h"
#include "component/nvmctrl.h"
#include "component/opamp.h"
#include "component/oscctrl.h"
#include "component/osc32kctrl.h"
#include "component/pac.h"
#include "component/pm.h"
#include "component/port.h"
#include "component/ptc.h"
#include "component/rstc.h"
#include "component/rtc.h"
#include "component/sercom.h"
#include "component/supc.h"
#include "component/tc.h"
#include "component/tram.h"
#include "component/trng.h"
#include "component/wdt.h"
/** @} end of Peripheral Software API */
/** \defgroup SAML10E15A_reg Registers Access Definitions
* @{
*/
/* ************************************************************************** */
/* REGISTER ACCESS DEFINITIONS FOR SAML10E15A */
/* ************************************************************************** */
#include "instance/ac.h"
#include "instance/adc.h"
#include "instance/ccl.h"
#include "instance/dac.h"
#include "instance/dmac.h"
#include "instance/dsu.h"
#include "instance/eic.h"
#include "instance/evsys.h"
#include "instance/freqm.h"
#include "instance/gclk.h"
#include "instance/idau.h"
#include "instance/mclk.h"
#include "instance/nvmctrl.h"
#include "instance/opamp.h"
#include "instance/oscctrl.h"
#include "instance/osc32kctrl.h"
#include "instance/pac.h"
#include "instance/pm.h"
#include "instance/port.h"
#include "instance/ptc.h"
#include "instance/rstc.h"
#include "instance/rtc.h"
#include "instance/sercom0.h"
#include "instance/sercom1.h"
#include "instance/sercom2.h"
#include "instance/supc.h"
#include "instance/tc0.h"
#include "instance/tc1.h"
#include "instance/tc2.h"
#include "instance/tram.h"
#include "instance/trng.h"
#include "instance/wdt.h"
/** @} end of Registers Access Definitions */
/** \addtogroup SAML10E15A_id Peripheral Ids Definitions
* @{
*/
/* ************************************************************************** */
/* PERIPHERAL ID DEFINITIONS FOR SAML10E15A */
/* ************************************************************************** */
#define ID_PAC ( 0) /**< \brief Peripheral Access Controller (PAC) */
#define ID_PM ( 1) /**< \brief Power Manager (PM) */
#define ID_MCLK ( 2) /**< \brief Main Clock (MCLK) */
#define ID_RSTC ( 3) /**< \brief Reset Controller (RSTC) */
#define ID_OSCCTRL ( 4) /**< \brief Oscillators Control (OSCCTRL) */
#define ID_OSC32KCTRL ( 5) /**< \brief 32k Oscillators Control (OSC32KCTRL) */
#define ID_SUPC ( 6) /**< \brief Supply Controller (SUPC) */
#define ID_GCLK ( 7) /**< \brief Generic Clock Generator (GCLK) */
#define ID_WDT ( 8) /**< \brief Watchdog Timer (WDT) */
#define ID_RTC ( 9) /**< \brief Real-Time Counter (RTC) */
#define ID_EIC ( 10) /**< \brief External Interrupt Controller (EIC) */
#define ID_FREQM ( 11) /**< \brief Frequency Meter (FREQM) */
#define ID_PORT ( 12) /**< \brief Port Module (PORT) */
#define ID_AC ( 13) /**< \brief Analog Comparators (AC) */
#define ID_IDAU ( 32) /**< \brief Implementation Defined Attribution Unit (IDAU) */
#define ID_DSU ( 33) /**< \brief Device Service Unit (DSU) */
#define ID_NVMCTRL ( 34) /**< \brief Non-Volatile Memory Controller (NVMCTRL) */
#define ID_DMAC ( 35) /**< \brief Direct Memory Access Controller (DMAC) */
#define ID_EVSYS ( 64) /**< \brief Event System Interface (EVSYS) */
#define ID_SERCOM0 ( 65) /**< \brief Serial Communication Interface (SERCOM0) */
#define ID_SERCOM1 ( 66) /**< \brief Serial Communication Interface (SERCOM1) */
#define ID_SERCOM2 ( 67) /**< \brief Serial Communication Interface (SERCOM2) */
#define ID_TC0 ( 68) /**< \brief Basic Timer Counter (TC0) */
#define ID_TC1 ( 69) /**< \brief Basic Timer Counter (TC1) */
#define ID_TC2 ( 70) /**< \brief Basic Timer Counter (TC2) */
#define ID_ADC ( 71) /**< \brief Analog Digital Converter (ADC) */
#define ID_DAC ( 72) /**< \brief Digital Analog Converter (DAC) */
#define ID_PTC ( 73) /**< \brief Peripheral Touch Controller (PTC) */
#define ID_TRNG ( 74) /**< \brief True Random Generator (TRNG) */
#define ID_CCL ( 75) /**< \brief Configurable Custom Logic (CCL) */
#define ID_OPAMP ( 76) /**< \brief Operational Amplifier (OPAMP) */
#define ID_TRAM ( 77) /**< \brief TrustRAM (TRAM) */
#define ID_PERIPH_COUNT ( 78) /**< \brief Number of peripheral IDs */
/** @} end of Peripheral Ids Definitions */
/** \addtogroup SAML10E15A_base Peripheral Base Address Definitions
* @{
*/
/* ************************************************************************** */
/* BASE ADDRESS DEFINITIONS FOR SAML10E15A */
/* ************************************************************************** */
#if (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
#define AC (0x40003400) /**< \brief (AC ) Base Address */
#define ADC (0x42001C00) /**< \brief (ADC ) Base Address */
#define CCL (0x42002C00) /**< \brief (CCL ) Base Address */
#define DAC (0x42002000) /**< \brief (DAC ) Base Address */
#define DMAC (0x41006000) /**< \brief (DMAC ) Base Address */
#define DSU (0x41002000) /**< \brief (DSU ) Base Address */
#define DSU_EXT (0x41002100) /**< \brief (DSU ) Base Address */
#define EIC (0x40002800) /**< \brief (EIC ) Base Address */
#define EVSYS (0x42000000) /**< \brief (EVSYS ) Base Address */
#define FREQM (0x40002C00) /**< \brief (FREQM ) Base Address */
#define GCLK (0x40001C00) /**< \brief (GCLK ) Base Address */
#define IDAU (0x41000000) /**< \brief (IDAU ) Base Address */
#define MCLK (0x40000800) /**< \brief (MCLK ) Base Address */
#define NVMCTRL (0x41004000) /**< \brief (NVMCTRL ) Base Address */
#define OPAMP (0x42003000) /**< \brief (OPAMP ) Base Address */
#define OSCCTRL (0x40001000) /**< \brief (OSCCTRL ) Base Address */
#define OSC32KCTRL (0x40001400) /**< \brief (OSC32KCTRL) Base Address */
#define PAC (0x40000000) /**< \brief (PAC ) Base Address */
#define PM (0x40000400) /**< \brief (PM ) Base Address */
#define PORT (0x40003000) /**< \brief (PORT ) Base Address */
#define PORT_IOBUS (0x60000000) /**< \brief (PORT ) Base Address */
#define PTC (0x42002400) /**< \brief (PTC ) Base Address */
#define RSTC (0x40000C00) /**< \brief (RSTC ) Base Address */
#define RTC (0x40002400) /**< \brief (RTC ) Base Address */
#define SERCOM0 (0x42000400) /**< \brief (SERCOM0 ) Base Address */
#define SERCOM1 (0x42000800) /**< \brief (SERCOM1 ) Base Address */
#define SERCOM2 (0x42000C00) /**< \brief (SERCOM2 ) Base Address */
#define SUPC (0x40001800) /**< \brief (SUPC ) Base Address */
#define TC0 (0x42001000) /**< \brief (TC0 ) Base Address */
#define TC1 (0x42001400) /**< \brief (TC1 ) Base Address */
#define TC2 (0x42001800) /**< \brief (TC2 ) Base Address */
#define TRAM (0x42003400) /**< \brief (TRAM ) Base Address */
#define TRNG (0x42002800) /**< \brief (TRNG ) Base Address */
#define WDT (0x40002000) /**< \brief (WDT ) Base Address */
#else /* For C/C++ compiler */
#define AC ((Ac *)0x40003400U) /**< \brief (AC ) Base Address */
#define AC_INST_NUM 1 /**< \brief (AC ) Number of instances */
#define AC_INSTS { AC } /**< \brief (AC ) Instances List */
#define ADC ((Adc *)0x42001C00U) /**< \brief (ADC ) Base Address */
#define ADC_INST_NUM 1 /**< \brief (ADC ) Number of instances */
#define ADC_INSTS { ADC } /**< \brief (ADC ) Instances List */
#define CCL ((Ccl *)0x42002C00U) /**< \brief (CCL ) Base Address */
#define CCL_INST_NUM 1 /**< \brief (CCL ) Number of instances */
#define CCL_INSTS { CCL } /**< \brief (CCL ) Instances List */
#define DAC ((Dac *)0x42002000U) /**< \brief (DAC ) Base Address */
#define DAC_INST_NUM 1 /**< \brief (DAC ) Number of instances */
#define DAC_INSTS { DAC } /**< \brief (DAC ) Instances List */
#define DMAC ((Dmac *)0x41006000U) /**< \brief (DMAC ) Base Address */
#define DMAC_INST_NUM 1 /**< \brief (DMAC ) Number of instances */
#define DMAC_INSTS { DMAC } /**< \brief (DMAC ) Instances List */
#define DSU ((Dsu *)0x41002000U) /**< \brief (DSU ) Base Address */
#define DSU_EXT ((Dsu *)0x41002100U) /**< \brief (DSU ) Base Address */
#define DSU_INST_NUM 1 /**< \brief (DSU ) Number of instances */
#define DSU_INSTS { DSU } /**< \brief (DSU ) Instances List */
#define EIC ((Eic *)0x40002800U) /**< \brief (EIC ) Base Address */
#define EIC_INST_NUM 1 /**< \brief (EIC ) Number of instances */
#define EIC_INSTS { EIC } /**< \brief (EIC ) Instances List */
#define EVSYS ((Evsys *)0x42000000U) /**< \brief (EVSYS ) Base Address */
#define EVSYS_INST_NUM 1 /**< \brief (EVSYS ) Number of instances */
#define EVSYS_INSTS { EVSYS } /**< \brief (EVSYS ) Instances List */
#define FREQM ((Freqm *)0x40002C00U) /**< \brief (FREQM ) Base Address */
#define FREQM_INST_NUM 1 /**< \brief (FREQM ) Number of instances */
#define FREQM_INSTS { FREQM } /**< \brief (FREQM ) Instances List */
#define GCLK ((Gclk *)0x40001C00U) /**< \brief (GCLK ) Base Address */
#define GCLK_INST_NUM 1 /**< \brief (GCLK ) Number of instances */
#define GCLK_INSTS { GCLK } /**< \brief (GCLK ) Instances List */
#define IDAU ((Idau *)0x41000000U) /**< \brief (IDAU ) Base Address */
#define IDAU_INST_NUM 1 /**< \brief (IDAU ) Number of instances */
#define IDAU_INSTS { IDAU } /**< \brief (IDAU ) Instances List */
#define MCLK ((Mclk *)0x40000800U) /**< \brief (MCLK ) Base Address */
#define MCLK_INST_NUM 1 /**< \brief (MCLK ) Number of instances */
#define MCLK_INSTS { MCLK } /**< \brief (MCLK ) Instances List */
#define NVMCTRL ((Nvmctrl *)0x41004000U) /**< \brief (NVMCTRL ) Base Address */
#define NVMCTRL_INST_NUM 1 /**< \brief (NVMCTRL ) Number of instances */
#define NVMCTRL_INSTS { NVMCTRL } /**< \brief (NVMCTRL ) Instances List */
#define OPAMP ((Opamp *)0x42003000U) /**< \brief (OPAMP ) Base Address */
#define OPAMP_INST_NUM 1 /**< \brief (OPAMP ) Number of instances */
#define OPAMP_INSTS { OPAMP } /**< \brief (OPAMP ) Instances List */
#define OSCCTRL ((Oscctrl *)0x40001000U) /**< \brief (OSCCTRL ) Base Address */
#define OSCCTRL_INST_NUM 1 /**< \brief (OSCCTRL ) Number of instances */
#define OSCCTRL_INSTS { OSCCTRL } /**< \brief (OSCCTRL ) Instances List */
#define OSC32KCTRL ((Osc32kctrl *)0x40001400U) /**< \brief (OSC32KCTRL) Base Address */
#define OSC32KCTRL_INST_NUM 1 /**< \brief (OSC32KCTRL) Number of instances */
#define OSC32KCTRL_INSTS { OSC32KCTRL } /**< \brief (OSC32KCTRL) Instances List */
#define PAC ((Pac *)0x40000000U) /**< \brief (PAC ) Base Address */
#define PAC_INST_NUM 1 /**< \brief (PAC ) Number of instances */
#define PAC_INSTS { PAC } /**< \brief (PAC ) Instances List */
#define PM ((Pm *)0x40000400U) /**< \brief (PM ) Base Address */
#define PM_INST_NUM 1 /**< \brief (PM ) Number of instances */
#define PM_INSTS { PM } /**< \brief (PM ) Instances List */
#define PORT ((Port *)0x40003000U) /**< \brief (PORT ) Base Address */
#define PORT_IOBUS ((Port *)0x60000000U) /**< \brief (PORT ) Base Address */
#define PORT_INST_NUM 1 /**< \brief (PORT ) Number of instances */
#define PORT_INSTS { PORT } /**< \brief (PORT ) Instances List */
#define PTC ((Ptc *)0x42002400U) /**< \brief (PTC ) Base Address */
#define PTC_INST_NUM 1 /**< \brief (PTC ) Number of instances */
#define PTC_INSTS { PTC } /**< \brief (PTC ) Instances List */
#define RSTC ((Rstc *)0x40000C00U) /**< \brief (RSTC ) Base Address */
#define RSTC_INST_NUM 1 /**< \brief (RSTC ) Number of instances */
#define RSTC_INSTS { RSTC } /**< \brief (RSTC ) Instances List */
#define RTC ((Rtc *)0x40002400U) /**< \brief (RTC ) Base Address */
#define RTC_INST_NUM 1 /**< \brief (RTC ) Number of instances */
#define RTC_INSTS { RTC } /**< \brief (RTC ) Instances List */
#define SERCOM0 ((Sercom *)0x42000400U) /**< \brief (SERCOM0 ) Base Address */
#define SERCOM1 ((Sercom *)0x42000800U) /**< \brief (SERCOM1 ) Base Address */
#define SERCOM2 ((Sercom *)0x42000C00U) /**< \brief (SERCOM2 ) Base Address */
#define SERCOM_INST_NUM 3 /**< \brief (SERCOM ) Number of instances */
#define SERCOM_INSTS { SERCOM0, SERCOM1, SERCOM2 } /**< \brief (SERCOM ) Instances List */
#define SUPC ((Supc *)0x40001800U) /**< \brief (SUPC ) Base Address */
#define SUPC_INST_NUM 1 /**< \brief (SUPC ) Number of instances */
#define SUPC_INSTS { SUPC } /**< \brief (SUPC ) Instances List */
#define TC0 ((Tc *)0x42001000U) /**< \brief (TC0 ) Base Address */
#define TC1 ((Tc *)0x42001400U) /**< \brief (TC1 ) Base Address */
#define TC2 ((Tc *)0x42001800U) /**< \brief (TC2 ) Base Address */
#define TC_INST_NUM 3 /**< \brief (TC ) Number of instances */
#define TC_INSTS { TC0, TC1, TC2 } /**< \brief (TC ) Instances List */
#define TRAM ((Tram *)0x42003400U) /**< \brief (TRAM ) Base Address */
#define TRAM_INST_NUM 1 /**< \brief (TRAM ) Number of instances */
#define TRAM_INSTS { TRAM } /**< \brief (TRAM ) Instances List */
#define TRNG ((Trng *)0x42002800U) /**< \brief (TRNG ) Base Address */
#define TRNG_INST_NUM 1 /**< \brief (TRNG ) Number of instances */
#define TRNG_INSTS { TRNG } /**< \brief (TRNG ) Instances List */
#define WDT ((Wdt *)0x40002000U) /**< \brief (WDT ) Base Address */
#define WDT_INST_NUM 1 /**< \brief (WDT ) Number of instances */
#define WDT_INSTS { WDT } /**< \brief (WDT ) Instances List */
#endif /* (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/** @} end of Peripheral Base Address Definitions */
/** \addtogroup SAML10E15A_pio Peripheral Pio Definitions
* @{
*/
/* ************************************************************************** */
/* PIO DEFINITIONS FOR SAML10E15A*/
/* ************************************************************************** */
#include "pio/saml10e15a.h"
/** @} end of Peripheral Pio Definitions */
/* ************************************************************************** */
/* MEMORY MAPPING DEFINITIONS FOR SAML10E15A*/
/* ************************************************************************** */
#define FLASH_SIZE _U_(0x00008000) /* 32kB Memory segment type: flash */
#define FLASH_PAGE_SIZE _U_( 64)
#define FLASH_NB_OF_PAGES _U_( 512)
#define AUX_SIZE _U_(0x00000100) /* 0kB Memory segment type: fuses */
#define AUX_PAGE_SIZE _U_( 64)
#define AUX_NB_OF_PAGES _U_( 4)
#define BOCOR_SIZE _U_(0x00000100) /* 0kB Memory segment type: fuses */
#define BOCOR_PAGE_SIZE _U_( 64)
#define BOCOR_NB_OF_PAGES _U_( 4)
#define DATAFLASH_SIZE _U_(0x00000800) /* 2kB Memory segment type: flash */
#define DATAFLASH_PAGE_SIZE _U_( 64)
#define DATAFLASH_NB_OF_PAGES _U_( 32)
#define SW_CALIB_SIZE _U_(0x00000008) /* 0kB Memory segment type: fuses */
#define TEMP_LOG_SIZE _U_(0x00000008) /* 0kB Memory segment type: fuses */
#define USER_PAGE_SIZE _U_(0x00000100) /* 0kB Memory segment type: user_page */
#define USER_PAGE_PAGE_SIZE _U_( 64)
#define USER_PAGE_NB_OF_PAGES _U_( 4)
#define HSRAM_SIZE _U_(0x00002000) /* 8kB Memory segment type: ram */
#define HPB0_SIZE _U_(0x00008000) /* 32kB Memory segment type: io */
#define HPB1_SIZE _U_(0x00010000) /* 64kB Memory segment type: io */
#define HPB2_SIZE _U_(0x00004000) /* 16kB Memory segment type: io */
#define PPB_SIZE _U_(0x00100000) /* 1024kB Memory segment type: io */
#define SCS_SIZE _U_(0x00001000) /* 4kB Memory segment type: io */
#define PERIPHERALS_SIZE _U_(0x20000000) /* 524288kB Memory segment type: io */
#define FLASH_ADDR _U_(0x00000000) /**< FLASH base address (type: flash)*/
#define AUX_ADDR _U_(0x00806000) /**< AUX base address (type: fuses)*/
#define BOCOR_ADDR _U_(0x0080c000) /**< BOCOR base address (type: fuses)*/
#define DATAFLASH_ADDR _U_(0x00400000) /**< DATAFLASH base address (type: flash)*/
#define SW_CALIB_ADDR _U_(0x00806020) /**< SW_CALIB base address (type: fuses)*/
#define TEMP_LOG_ADDR _U_(0x00806038) /**< TEMP_LOG base address (type: fuses)*/
#define USER_PAGE_ADDR _U_(0x00804000) /**< USER_PAGE base address (type: user_page)*/
#define HSRAM_ADDR _U_(0x20000000) /**< HSRAM base address (type: ram)*/
#define HPB0_ADDR _U_(0x40000000) /**< HPB0 base address (type: io)*/
#define HPB1_ADDR _U_(0x41000000) /**< HPB1 base address (type: io)*/
#define HPB2_ADDR _U_(0x42000000) /**< HPB2 base address (type: io)*/
#define PPB_ADDR _U_(0xe0000000) /**< PPB base address (type: io)*/
#define SCS_ADDR _U_(0xe000e000) /**< SCS base address (type: io)*/
#define PERIPHERALS_ADDR _U_(0x40000000) /**< PERIPHERALS base address (type: io)*/
#define NVMCTRL_AUX AUX_ADDR /**< \brief \deprecated Old style definition. Use AUX_ADDR instead */
#define NVMCTRL_BOCOR BOCOR_ADDR /**< \brief \deprecated Old style definition. Use BOCOR_ADDR instead */
#define NVMCTRL_DATAFLASH DATAFLASH_ADDR /**< \brief \deprecated Old style definition. Use DATAFLASH_ADDR instead */
#define NVMCTRL_SW_CALIB SW_CALIB_ADDR /**< \brief \deprecated Old style definition. Use SW_CALIB_ADDR instead */
#define NVMCTRL_TEMP_LOG TEMP_LOG_ADDR /**< \brief \deprecated Old style definition. Use TEMP_LOG_ADDR instead */
#define NVMCTRL_USER USER_PAGE_ADDR /**< \brief \deprecated Old style definition. Use USER_PAGE_ADDR instead */
/* ************************************************************************** */
/** DEVICE SIGNATURES FOR SAML10E15A */
/* ************************************************************************** */
#define DSU_DID _UL_(0X20840001)
/* ************************************************************************** */
/** ELECTRICAL DEFINITIONS FOR SAML10E15A */
/* ************************************************************************** */
/* ************************************************************************** */
/** Event Generator IDs for SAML10E15A */
/* ************************************************************************** */
#define EVENT_ID_GEN_OSCCTRL_XOSC_FAIL 1 /**< ID for OSCCTRL event generator XOSC_FAIL */
#define EVENT_ID_GEN_OSC32KCTRL_XOSC32K_FAIL 2 /**< ID for OSC32KCTRL event generator XOSC32K_FAIL */
#define EVENT_ID_GEN_SUPC_BOD33DET 3 /**< ID for SUPC event generator BOD33DET */
#define EVENT_ID_GEN_RTC_PER_0 4 /**< ID for RTC event generator PER_0 */
#define EVENT_ID_GEN_RTC_PER_1 5 /**< ID for RTC event generator PER_1 */
#define EVENT_ID_GEN_RTC_PER_2 6 /**< ID for RTC event generator PER_2 */
#define EVENT_ID_GEN_RTC_PER_3 7 /**< ID for RTC event generator PER_3 */
#define EVENT_ID_GEN_RTC_PER_4 8 /**< ID for RTC event generator PER_4 */
#define EVENT_ID_GEN_RTC_PER_5 9 /**< ID for RTC event generator PER_5 */
#define EVENT_ID_GEN_RTC_PER_6 10 /**< ID for RTC event generator PER_6 */
#define EVENT_ID_GEN_RTC_PER_7 11 /**< ID for RTC event generator PER_7 */
#define EVENT_ID_GEN_RTC_CMP_0 12 /**< ID for RTC event generator CMP_0 */
#define EVENT_ID_GEN_RTC_CMP_1 13 /**< ID for RTC event generator CMP_1 */
#define EVENT_ID_GEN_RTC_TAMPER 14 /**< ID for RTC event generator TAMPER */
#define EVENT_ID_GEN_RTC_OVF 15 /**< ID for RTC event generator OVF */
#define EVENT_ID_GEN_RTC_PERD 16 /**< ID for RTC event generator PERD */
#define EVENT_ID_GEN_EIC_EXTINT_0 17 /**< ID for EIC event generator EXTINT_0 */
#define EVENT_ID_GEN_EIC_EXTINT_1 18 /**< ID for EIC event generator EXTINT_1 */
#define EVENT_ID_GEN_EIC_EXTINT_2 19 /**< ID for EIC event generator EXTINT_2 */
#define EVENT_ID_GEN_EIC_EXTINT_3 20 /**< ID for EIC event generator EXTINT_3 */
#define EVENT_ID_GEN_EIC_EXTINT_4 21 /**< ID for EIC event generator EXTINT_4 */
#define EVENT_ID_GEN_EIC_EXTINT_5 22 /**< ID for EIC event generator EXTINT_5 */
#define EVENT_ID_GEN_EIC_EXTINT_6 23 /**< ID for EIC event generator EXTINT_6 */
#define EVENT_ID_GEN_EIC_EXTINT_7 24 /**< ID for EIC event generator EXTINT_7 */
#define EVENT_ID_GEN_DMAC_CH_0 25 /**< ID for DMAC event generator CH_0 */
#define EVENT_ID_GEN_DMAC_CH_1 26 /**< ID for DMAC event generator CH_1 */
#define EVENT_ID_GEN_DMAC_CH_2 27 /**< ID for DMAC event generator CH_2 */
#define EVENT_ID_GEN_DMAC_CH_3 28 /**< ID for DMAC event generator CH_3 */
#define EVENT_ID_GEN_TC0_OVF 29 /**< ID for TC0 event generator OVF */
#define EVENT_ID_GEN_TC0_MCX_0 30 /**< ID for TC0 event generator MCX_0 */
#define EVENT_ID_GEN_TC0_MCX_1 31 /**< ID for TC0 event generator MCX_1 */
#define EVENT_ID_GEN_TC1_OVF 32 /**< ID for TC1 event generator OVF */
#define EVENT_ID_GEN_TC1_MCX_0 33 /**< ID for TC1 event generator MCX_0 */
#define EVENT_ID_GEN_TC1_MCX_1 34 /**< ID for TC1 event generator MCX_1 */
#define EVENT_ID_GEN_TC2_OVF 35 /**< ID for TC2 event generator OVF */
#define EVENT_ID_GEN_TC2_MCX_0 36 /**< ID for TC2 event generator MCX_0 */
#define EVENT_ID_GEN_TC2_MCX_1 37 /**< ID for TC2 event generator MCX_1 */
#define EVENT_ID_GEN_ADC_RESRDY 38 /**< ID for ADC event generator RESRDY */
#define EVENT_ID_GEN_ADC_WINMON 39 /**< ID for ADC event generator WINMON */
#define EVENT_ID_GEN_AC_COMP_0 40 /**< ID for AC event generator COMP_0 */
#define EVENT_ID_GEN_AC_COMP_1 41 /**< ID for AC event generator COMP_1 */
#define EVENT_ID_GEN_AC_WIN_0 42 /**< ID for AC event generator WIN_0 */
#define EVENT_ID_GEN_DAC_EMPTY 43 /**< ID for DAC event generator EMPTY */
#define EVENT_ID_GEN_TRNG_READY 46 /**< ID for TRNG event generator READY */
#define EVENT_ID_GEN_CCL_LUTOUT_0 47 /**< ID for CCL event generator LUTOUT_0 */
#define EVENT_ID_GEN_CCL_LUTOUT_1 48 /**< ID for CCL event generator LUTOUT_1 */
#define EVENT_ID_GEN_PAC_ERR 49 /**< ID for PAC event generator ERR */
/* ************************************************************************** */
/** Event User IDs for SAML10E15A */
/* ************************************************************************** */
#define EVENT_ID_USER_OSCCTRL_TUNE 0 /**< ID for OSCCTRL event user TUNE */
#define EVENT_ID_USER_RTC_TAMPER 1 /**< ID for RTC event user TAMPER */
#define EVENT_ID_USER_NVMCTRL_PAGEW 2 /**< ID for NVMCTRL event user PAGEW */
#define EVENT_ID_USER_PORT_EV_0 3 /**< ID for PORT event user EV_0 */
#define EVENT_ID_USER_PORT_EV_1 4 /**< ID for PORT event user EV_1 */
#define EVENT_ID_USER_PORT_EV_2 5 /**< ID for PORT event user EV_2 */
#define EVENT_ID_USER_PORT_EV_3 6 /**< ID for PORT event user EV_3 */
#define EVENT_ID_USER_DMAC_CH_0 7 /**< ID for DMAC event user CH_0 */
#define EVENT_ID_USER_DMAC_CH_1 8 /**< ID for DMAC event user CH_1 */
#define EVENT_ID_USER_DMAC_CH_2 9 /**< ID for DMAC event user CH_2 */
#define EVENT_ID_USER_DMAC_CH_3 10 /**< ID for DMAC event user CH_3 */
#define EVENT_ID_USER_TC0_EVU 11 /**< ID for TC0 event user EVU */
#define EVENT_ID_USER_TC1_EVU 12 /**< ID for TC1 event user EVU */
#define EVENT_ID_USER_TC2_EVU 13 /**< ID for TC2 event user EVU */
#define EVENT_ID_USER_ADC_START 14 /**< ID for ADC event user START */
#define EVENT_ID_USER_ADC_SYNC 15 /**< ID for ADC event user SYNC */
#define EVENT_ID_USER_AC_SOC_0 16 /**< ID for AC event user SOC_0 */
#define EVENT_ID_USER_AC_SOC_1 17 /**< ID for AC event user SOC_1 */
#define EVENT_ID_USER_DAC_START 18 /**< ID for DAC event user START */
#define EVENT_ID_USER_CCL_LUTIN_0 21 /**< ID for CCL event user LUTIN_0 */
#define EVENT_ID_USER_CCL_LUTIN_1 22 /**< ID for CCL event user LUTIN_1 */
#ifdef __cplusplus
}
#endif
/** @} end of SAML10E15A definitions */
#endif /* _SAML10E15A_H_ */

View File

@ -0,0 +1,801 @@
/**
* \file
*
* \brief Header file for ATSAML10E16A
*
* Copyright (c) 2018 Microchip Technology Inc.
*
* \license_start
*
* \page License
*
* 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
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* \license_stop
*
*/
/* file generated from device description version 2018-08-31T13:51:50Z */
#ifndef _SAML10E16A_H_
#define _SAML10E16A_H_
/** \addtogroup SAML10E16A_definitions SAML10E16A definitions
This file defines all structures and symbols for SAML10E16A:
- registers and bitfields
- peripheral base address
- peripheral ID
- PIO definitions
* @{
*/
#ifdef __cplusplus
extern "C" {
#endif
/** \defgroup Atmel_glob_defs Atmel Global Defines
<strong>IO Type Qualifiers</strong> are used
\li to specify the access to peripheral variables.
\li for automatic generation of peripheral register debug information.
\remark
CMSIS core has a syntax that differs from this using i.e. __I, __O, or __IO followed by 'uint<size>_t' respective types.
Default the header files will follow the CMSIS core syntax.
* @{
*/
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
#include <stdint.h>
/* IO definitions (access restrictions to peripheral registers) */
#ifndef __cplusplus
typedef volatile const uint32_t RoReg; /**< Read only 32-bit register (volatile const unsigned int) */
typedef volatile const uint16_t RoReg16; /**< Read only 16-bit register (volatile const unsigned int) */
typedef volatile const uint8_t RoReg8; /**< Read only 8-bit register (volatile const unsigned int) */
#else
typedef volatile uint32_t RoReg; /**< Read only 32-bit register (volatile const unsigned int) */
typedef volatile uint16_t RoReg16; /**< Read only 16-bit register (volatile const unsigned int) */
typedef volatile uint8_t RoReg8; /**< Read only 8-bit register (volatile const unsigned int) */
#endif
typedef volatile uint32_t WoReg; /**< Write only 32-bit register (volatile unsigned int) */
typedef volatile uint16_t WoReg16; /**< Write only 16-bit register (volatile unsigned int) */
typedef volatile uint8_t WoReg8; /**< Write only 8-bit register (volatile unsigned int) */
typedef volatile uint32_t RwReg; /**< Read-Write 32-bit register (volatile unsigned int) */
typedef volatile uint16_t RwReg16; /**< Read-Write 16-bit register (volatile unsigned int) */
typedef volatile uint8_t RwReg8; /**< Read-Write 8-bit register (volatile unsigned int) */
#define CAST(type, value) ((type *)(value)) /**< Pointer Type Conversion Macro for C/C++ */
#define REG_ACCESS(type, address) (*(type*)(address)) /**< C code: Register value */
#else /* Assembler */
#define CAST(type, value) (value) /**< Pointer Type Conversion Macro for Assembler */
#define REG_ACCESS(type, address) (address) /**< Assembly code: Register address */
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#if !defined(SKIP_INTEGER_LITERALS)
#if defined(_U_) || defined(_L_) || defined(_UL_)
#error "Integer Literals macros already defined elsewhere"
#endif
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
/* Macros that deal with adding suffixes to integer literal constants for C/C++ */
#define _U_(x) x ## U /**< C code: Unsigned integer literal constant value */
#define _L_(x) x ## L /**< C code: Long integer literal constant value */
#define _UL_(x) x ## UL /**< C code: Unsigned Long integer literal constant value */
#else /* Assembler */
#define _U_(x) x /**< Assembler: Unsigned integer literal constant value */
#define _L_(x) x /**< Assembler: Long integer literal constant value */
#define _UL_(x) x /**< Assembler: Unsigned Long integer literal constant value */
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#endif /* SKIP_INTEGER_LITERALS */
/** @} end of Atmel Global Defines */
/** \addtogroup SAML10E16A_cmsis CMSIS Definitions
* @{
*/
/* ************************************************************************** */
/* CMSIS DEFINITIONS FOR SAML10E16A */
/* ************************************************************************** */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
/** Interrupt Number Definition */
typedef enum IRQn
{
/****** CORTEX-M23 Processor Exceptions Numbers ******************************/
Reset_IRQn = -15, /**< 1 Reset Vector, invoked on Power up and warm reset */
NonMaskableInt_IRQn = -14, /**< 2 Non maskable Interrupt, cannot be stopped or preempted */
HardFault_IRQn = -13, /**< 3 Hard Fault, all classes of Fault */
SVCall_IRQn = -5 , /**< 11 System Service Call via SVC instruction */
PendSV_IRQn = -2 , /**< 14 Pendable request for system service */
SysTick_IRQn = -1 , /**< 15 System Tick Timer */
/****** SAML10E16A specific Interrupt Numbers ***********************************/
SYSTEM_IRQn = 0 , /**< 0 SAML10E16A Main Clock (MCLK) */
WDT_IRQn = 1 , /**< 1 SAML10E16A Watchdog Timer (WDT) */
RTC_IRQn = 2 , /**< 2 SAML10E16A Real-Time Counter (RTC) */
EIC_0_IRQn = 3 , /**< 3 SAML10E16A External Interrupt Controller (EIC) */
EIC_1_IRQn = 4 , /**< 4 SAML10E16A External Interrupt Controller (EIC) */
EIC_2_IRQn = 5 , /**< 5 SAML10E16A External Interrupt Controller (EIC) */
EIC_3_IRQn = 6 , /**< 6 SAML10E16A External Interrupt Controller (EIC) */
EIC_OTHER_IRQn = 7 , /**< 7 SAML10E16A External Interrupt Controller (EIC) */
FREQM_IRQn = 8 , /**< 8 SAML10E16A Frequency Meter (FREQM) */
NVMCTRL_IRQn = 9 , /**< 9 SAML10E16A Non-Volatile Memory Controller (NVMCTRL) */
PORT_IRQn = 10 , /**< 10 SAML10E16A Port Module (PORT) */
DMAC_0_IRQn = 11 , /**< 11 SAML10E16A Direct Memory Access Controller (DMAC) */
DMAC_1_IRQn = 12 , /**< 12 SAML10E16A Direct Memory Access Controller (DMAC) */
DMAC_2_IRQn = 13 , /**< 13 SAML10E16A Direct Memory Access Controller (DMAC) */
DMAC_3_IRQn = 14 , /**< 14 SAML10E16A Direct Memory Access Controller (DMAC) */
DMAC_OTHER_IRQn = 15 , /**< 15 SAML10E16A Direct Memory Access Controller (DMAC) */
EVSYS_0_IRQn = 16 , /**< 16 SAML10E16A Event System Interface (EVSYS) */
EVSYS_1_IRQn = 17 , /**< 17 SAML10E16A Event System Interface (EVSYS) */
EVSYS_2_IRQn = 18 , /**< 18 SAML10E16A Event System Interface (EVSYS) */
EVSYS_3_IRQn = 19 , /**< 19 SAML10E16A Event System Interface (EVSYS) */
EVSYS_NSCHK_IRQn = 20 , /**< 20 SAML10E16A Event System Interface (EVSYS) */
PAC_IRQn = 21 , /**< 21 SAML10E16A Peripheral Access Controller (PAC) */
SERCOM0_0_IRQn = 22 , /**< 22 SAML10E16A Serial Communication Interface (SERCOM0) */
SERCOM0_1_IRQn = 23 , /**< 23 SAML10E16A Serial Communication Interface (SERCOM0) */
SERCOM0_2_IRQn = 24 , /**< 24 SAML10E16A Serial Communication Interface (SERCOM0) */
SERCOM0_OTHER_IRQn = 25 , /**< 25 SAML10E16A Serial Communication Interface (SERCOM0) */
SERCOM1_0_IRQn = 26 , /**< 26 SAML10E16A Serial Communication Interface (SERCOM1) */
SERCOM1_1_IRQn = 27 , /**< 27 SAML10E16A Serial Communication Interface (SERCOM1) */
SERCOM1_2_IRQn = 28 , /**< 28 SAML10E16A Serial Communication Interface (SERCOM1) */
SERCOM1_OTHER_IRQn = 29 , /**< 29 SAML10E16A Serial Communication Interface (SERCOM1) */
SERCOM2_0_IRQn = 30 , /**< 30 SAML10E16A Serial Communication Interface (SERCOM2) */
SERCOM2_1_IRQn = 31 , /**< 31 SAML10E16A Serial Communication Interface (SERCOM2) */
SERCOM2_2_IRQn = 32 , /**< 32 SAML10E16A Serial Communication Interface (SERCOM2) */
SERCOM2_OTHER_IRQn = 33 , /**< 33 SAML10E16A Serial Communication Interface (SERCOM2) */
TC0_IRQn = 34 , /**< 34 SAML10E16A Basic Timer Counter (TC0) */
TC1_IRQn = 35 , /**< 35 SAML10E16A Basic Timer Counter (TC1) */
TC2_IRQn = 36 , /**< 36 SAML10E16A Basic Timer Counter (TC2) */
ADC_OTHER_IRQn = 37 , /**< 37 SAML10E16A Analog Digital Converter (ADC) */
ADC_RESRDY_IRQn = 38 , /**< 38 SAML10E16A Analog Digital Converter (ADC) */
AC_IRQn = 39 , /**< 39 SAML10E16A Analog Comparators (AC) */
DAC_UNDERRUN_A_IRQn = 40 , /**< 40 SAML10E16A Digital Analog Converter (DAC) */
DAC_EMPTY_IRQn = 41 , /**< 41 SAML10E16A Digital Analog Converter (DAC) */
PTC_IRQn = 42 , /**< 42 SAML10E16A Peripheral Touch Controller (PTC) */
TRNG_IRQn = 43 , /**< 43 SAML10E16A True Random Generator (TRNG) */
TRAM_IRQn = 44 , /**< 44 SAML10E16A TrustRAM (TRAM) */
PERIPH_COUNT_IRQn = 45 /**< Number of peripheral IDs */
} IRQn_Type;
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
typedef struct _DeviceVectors
{
/* Stack pointer */
void* pvStack;
/* Cortex-M handlers */
void* pfnReset_Handler; /* -15 Reset Vector, invoked on Power up and warm reset */
void* pfnNonMaskableInt_Handler; /* -14 Non maskable Interrupt, cannot be stopped or preempted */
void* pfnHardFault_Handler; /* -13 Hard Fault, all classes of Fault */
void* pvReservedC12;
void* pvReservedC11;
void* pvReservedC10;
void* pvReservedC9;
void* pvReservedC8;
void* pvReservedC7;
void* pvReservedC6;
void* pfnSVCall_Handler; /* -5 System Service Call via SVC instruction */
void* pvReservedC4;
void* pvReservedC3;
void* pfnPendSV_Handler; /* -2 Pendable request for system service */
void* pfnSysTick_Handler; /* -1 System Tick Timer */
/* Peripheral handlers */
void* pfnSYSTEM_Handler; /* 0 SAML10E16A Main Clock (MCLK) */
void* pfnWDT_Handler; /* 1 SAML10E16A Watchdog Timer (WDT) */
void* pfnRTC_Handler; /* 2 SAML10E16A Real-Time Counter (RTC) */
void* pfnEIC_0_Handler; /* 3 SAML10E16A External Interrupt Controller (EIC) */
void* pfnEIC_1_Handler; /* 4 SAML10E16A External Interrupt Controller (EIC) */
void* pfnEIC_2_Handler; /* 5 SAML10E16A External Interrupt Controller (EIC) */
void* pfnEIC_3_Handler; /* 6 SAML10E16A External Interrupt Controller (EIC) */
void* pfnEIC_OTHER_Handler; /* 7 SAML10E16A External Interrupt Controller (EIC) */
void* pfnFREQM_Handler; /* 8 SAML10E16A Frequency Meter (FREQM) */
void* pfnNVMCTRL_Handler; /* 9 SAML10E16A Non-Volatile Memory Controller (NVMCTRL) */
void* pfnPORT_Handler; /* 10 SAML10E16A Port Module (PORT) */
void* pfnDMAC_0_Handler; /* 11 SAML10E16A Direct Memory Access Controller (DMAC) */
void* pfnDMAC_1_Handler; /* 12 SAML10E16A Direct Memory Access Controller (DMAC) */
void* pfnDMAC_2_Handler; /* 13 SAML10E16A Direct Memory Access Controller (DMAC) */
void* pfnDMAC_3_Handler; /* 14 SAML10E16A Direct Memory Access Controller (DMAC) */
void* pfnDMAC_OTHER_Handler; /* 15 SAML10E16A Direct Memory Access Controller (DMAC) */
void* pfnEVSYS_0_Handler; /* 16 SAML10E16A Event System Interface (EVSYS) */
void* pfnEVSYS_1_Handler; /* 17 SAML10E16A Event System Interface (EVSYS) */
void* pfnEVSYS_2_Handler; /* 18 SAML10E16A Event System Interface (EVSYS) */
void* pfnEVSYS_3_Handler; /* 19 SAML10E16A Event System Interface (EVSYS) */
void* pfnEVSYS_NSCHK_Handler; /* 20 SAML10E16A Event System Interface (EVSYS) */
void* pfnPAC_Handler; /* 21 SAML10E16A Peripheral Access Controller (PAC) */
void* pfnSERCOM0_0_Handler; /* 22 SAML10E16A Serial Communication Interface (SERCOM0) */
void* pfnSERCOM0_1_Handler; /* 23 SAML10E16A Serial Communication Interface (SERCOM0) */
void* pfnSERCOM0_2_Handler; /* 24 SAML10E16A Serial Communication Interface (SERCOM0) */
void* pfnSERCOM0_OTHER_Handler; /* 25 SAML10E16A Serial Communication Interface (SERCOM0) */
void* pfnSERCOM1_0_Handler; /* 26 SAML10E16A Serial Communication Interface (SERCOM1) */
void* pfnSERCOM1_1_Handler; /* 27 SAML10E16A Serial Communication Interface (SERCOM1) */
void* pfnSERCOM1_2_Handler; /* 28 SAML10E16A Serial Communication Interface (SERCOM1) */
void* pfnSERCOM1_OTHER_Handler; /* 29 SAML10E16A Serial Communication Interface (SERCOM1) */
void* pfnSERCOM2_0_Handler; /* 30 SAML10E16A Serial Communication Interface (SERCOM2) */
void* pfnSERCOM2_1_Handler; /* 31 SAML10E16A Serial Communication Interface (SERCOM2) */
void* pfnSERCOM2_2_Handler; /* 32 SAML10E16A Serial Communication Interface (SERCOM2) */
void* pfnSERCOM2_OTHER_Handler; /* 33 SAML10E16A Serial Communication Interface (SERCOM2) */
void* pfnTC0_Handler; /* 34 SAML10E16A Basic Timer Counter (TC0) */
void* pfnTC1_Handler; /* 35 SAML10E16A Basic Timer Counter (TC1) */
void* pfnTC2_Handler; /* 36 SAML10E16A Basic Timer Counter (TC2) */
void* pfnADC_OTHER_Handler; /* 37 SAML10E16A Analog Digital Converter (ADC) */
void* pfnADC_RESRDY_Handler; /* 38 SAML10E16A Analog Digital Converter (ADC) */
void* pfnAC_Handler; /* 39 SAML10E16A Analog Comparators (AC) */
void* pfnDAC_UNDERRUN_A_Handler; /* 40 SAML10E16A Digital Analog Converter (DAC) */
void* pfnDAC_EMPTY_Handler; /* 41 SAML10E16A Digital Analog Converter (DAC) */
void* pfnPTC_Handler; /* 42 SAML10E16A Peripheral Touch Controller (PTC) */
void* pfnTRNG_Handler; /* 43 SAML10E16A True Random Generator (TRNG) */
void* pfnTRAM_Handler; /* 44 SAML10E16A TrustRAM (TRAM) */
} DeviceVectors;
/* Defines for Deprecated Interrupt and Exceptions handler names */
#define pfnMemManage_Handler pfnMemoryManagement_Handler /**< \deprecated Backward compatibility for ASF */
#define pfnDebugMon_Handler pfnDebugMonitor_Handler /**< \deprecated Backward compatibility for ASF */
#define pfnNMI_Handler pfnNonMaskableInt_Handler /**< \deprecated Backward compatibility for ASF */
#define pfnSVC_Handler pfnSVCall_Handler /**< \deprecated Backward compatibility for ASF */
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
#if !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
#if !defined DONT_USE_PREDEFINED_CORE_HANDLERS
/* CORTEX-M23 core handlers */
void Reset_Handler ( void );
void NonMaskableInt_Handler ( void );
void HardFault_Handler ( void );
void SVCall_Handler ( void );
void PendSV_Handler ( void );
void SysTick_Handler ( void );
#endif /* DONT_USE_PREDEFINED_CORE_HANDLERS */
#if !defined DONT_USE_PREDEFINED_PERIPHERALS_HANDLERS
/* Peripherals handlers */
void AC_Handler ( void );
void ADC_OTHER_Handler ( void );
void ADC_RESRDY_Handler ( void );
void DAC_EMPTY_Handler ( void );
void DAC_UNDERRUN_A_Handler ( void );
void DMAC_0_Handler ( void );
void DMAC_1_Handler ( void );
void DMAC_2_Handler ( void );
void DMAC_3_Handler ( void );
void DMAC_OTHER_Handler ( void );
void EIC_0_Handler ( void );
void EIC_1_Handler ( void );
void EIC_2_Handler ( void );
void EIC_3_Handler ( void );
void EIC_OTHER_Handler ( void );
void EVSYS_0_Handler ( void );
void EVSYS_1_Handler ( void );
void EVSYS_2_Handler ( void );
void EVSYS_3_Handler ( void );
void EVSYS_NSCHK_Handler ( void );
void FREQM_Handler ( void );
void NVMCTRL_Handler ( void );
void PAC_Handler ( void );
void PORT_Handler ( void );
void PTC_Handler ( void );
void RTC_Handler ( void );
void SERCOM0_0_Handler ( void );
void SERCOM0_1_Handler ( void );
void SERCOM0_2_Handler ( void );
void SERCOM0_OTHER_Handler ( void );
void SERCOM1_0_Handler ( void );
void SERCOM1_1_Handler ( void );
void SERCOM1_2_Handler ( void );
void SERCOM1_OTHER_Handler ( void );
void SERCOM2_0_Handler ( void );
void SERCOM2_1_Handler ( void );
void SERCOM2_2_Handler ( void );
void SERCOM2_OTHER_Handler ( void );
void SYSTEM_Handler ( void );
void TC0_Handler ( void );
void TC1_Handler ( void );
void TC2_Handler ( void );
void TRAM_Handler ( void );
void TRNG_Handler ( void );
void WDT_Handler ( void );
#endif /* DONT_USE_PREDEFINED_PERIPHERALS_HANDLERS */
/* Defines for Deprecated Interrupt and Exceptions handler names */
#define MemManage_Handler MemoryManagement_Handler /**< \deprecated Backward compatibility for ASF */
#define DebugMon_Handler DebugMonitor_Handler /**< \deprecated Backward compatibility for ASF */
#define NMI_Handler NonMaskableInt_Handler /**< \deprecated Backward compatibility for ASF */
#define SVC_Handler SVCall_Handler /**< \deprecated Backward compatibility for ASF */
#endif /* !(defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/*
* \brief Configuration of the CORTEX-M23 Processor and Core Peripherals
*/
#define NUM_IRQ 45 /**< Number of interrupt request lines */
#define __ARMv8MBL_REV 0x0000 /**< Cortex-M23 Core Revision */
#define __ETM_PRESENT 0 /**< ETM present or not */
#define __FPU_PRESENT 0 /**< FPU present or not */
#define __MPU_PRESENT 1 /**< MPU present or not */
#define __MTB_PRESENT 0 /**< MTB present or not */
#define __NVIC_PRIO_BITS 2 /**< Number of Bits used for Priority Levels */
#define __SAU_PRESENT 0 /**< SAU present or not */
#define __SEC_ENABLED 0 /**< TrustZone-M enabled or not */
#define __VTOR_PRESENT 1 /**< Vector Table Offset Register present or not */
#define __Vendor_SysTickConfig 0 /**< Set to 1 if different SysTick Config is used */
#define __ARCH_ARM 1
#define __ARCH_ARM_CORTEX_M 1
#define __DEVICE_IS_SAM 1
/*
* \brief CMSIS includes
*/
#include <core_cm23.h>
#if !defined DONT_USE_CMSIS_INIT
#include "system_saml10.h"
#endif /* DONT_USE_CMSIS_INIT */
/** @} end of SAML10E16A_cmsis CMSIS Definitions */
/** \defgroup SAML10E16A_api Peripheral Software API
* @{
*/
/* ************************************************************************** */
/** SOFTWARE PERIPHERAL API DEFINITION FOR SAML10E16A */
/* ************************************************************************** */
#include "component/ac.h"
#include "component/adc.h"
#include "component/ccl.h"
#include "component/dac.h"
#include "component/dmac.h"
#include "component/dsu.h"
#include "component/eic.h"
#include "component/evsys.h"
#include "component/freqm.h"
#include "component/gclk.h"
#include "component/idau.h"
#include "component/mclk.h"
#include "component/nvmctrl.h"
#include "component/opamp.h"
#include "component/oscctrl.h"
#include "component/osc32kctrl.h"
#include "component/pac.h"
#include "component/pm.h"
#include "component/port.h"
#include "component/ptc.h"
#include "component/rstc.h"
#include "component/rtc.h"
#include "component/sercom.h"
#include "component/supc.h"
#include "component/tc.h"
#include "component/tram.h"
#include "component/trng.h"
#include "component/wdt.h"
/** @} end of Peripheral Software API */
/** \defgroup SAML10E16A_reg Registers Access Definitions
* @{
*/
/* ************************************************************************** */
/* REGISTER ACCESS DEFINITIONS FOR SAML10E16A */
/* ************************************************************************** */
#include "instance/ac.h"
#include "instance/adc.h"
#include "instance/ccl.h"
#include "instance/dac.h"
#include "instance/dmac.h"
#include "instance/dsu.h"
#include "instance/eic.h"
#include "instance/evsys.h"
#include "instance/freqm.h"
#include "instance/gclk.h"
#include "instance/idau.h"
#include "instance/mclk.h"
#include "instance/nvmctrl.h"
#include "instance/opamp.h"
#include "instance/oscctrl.h"
#include "instance/osc32kctrl.h"
#include "instance/pac.h"
#include "instance/pm.h"
#include "instance/port.h"
#include "instance/ptc.h"
#include "instance/rstc.h"
#include "instance/rtc.h"
#include "instance/sercom0.h"
#include "instance/sercom1.h"
#include "instance/sercom2.h"
#include "instance/supc.h"
#include "instance/tc0.h"
#include "instance/tc1.h"
#include "instance/tc2.h"
#include "instance/tram.h"
#include "instance/trng.h"
#include "instance/wdt.h"
/** @} end of Registers Access Definitions */
/** \addtogroup SAML10E16A_id Peripheral Ids Definitions
* @{
*/
/* ************************************************************************** */
/* PERIPHERAL ID DEFINITIONS FOR SAML10E16A */
/* ************************************************************************** */
#define ID_PAC ( 0) /**< \brief Peripheral Access Controller (PAC) */
#define ID_PM ( 1) /**< \brief Power Manager (PM) */
#define ID_MCLK ( 2) /**< \brief Main Clock (MCLK) */
#define ID_RSTC ( 3) /**< \brief Reset Controller (RSTC) */
#define ID_OSCCTRL ( 4) /**< \brief Oscillators Control (OSCCTRL) */
#define ID_OSC32KCTRL ( 5) /**< \brief 32k Oscillators Control (OSC32KCTRL) */
#define ID_SUPC ( 6) /**< \brief Supply Controller (SUPC) */
#define ID_GCLK ( 7) /**< \brief Generic Clock Generator (GCLK) */
#define ID_WDT ( 8) /**< \brief Watchdog Timer (WDT) */
#define ID_RTC ( 9) /**< \brief Real-Time Counter (RTC) */
#define ID_EIC ( 10) /**< \brief External Interrupt Controller (EIC) */
#define ID_FREQM ( 11) /**< \brief Frequency Meter (FREQM) */
#define ID_PORT ( 12) /**< \brief Port Module (PORT) */
#define ID_AC ( 13) /**< \brief Analog Comparators (AC) */
#define ID_IDAU ( 32) /**< \brief Implementation Defined Attribution Unit (IDAU) */
#define ID_DSU ( 33) /**< \brief Device Service Unit (DSU) */
#define ID_NVMCTRL ( 34) /**< \brief Non-Volatile Memory Controller (NVMCTRL) */
#define ID_DMAC ( 35) /**< \brief Direct Memory Access Controller (DMAC) */
#define ID_EVSYS ( 64) /**< \brief Event System Interface (EVSYS) */
#define ID_SERCOM0 ( 65) /**< \brief Serial Communication Interface (SERCOM0) */
#define ID_SERCOM1 ( 66) /**< \brief Serial Communication Interface (SERCOM1) */
#define ID_SERCOM2 ( 67) /**< \brief Serial Communication Interface (SERCOM2) */
#define ID_TC0 ( 68) /**< \brief Basic Timer Counter (TC0) */
#define ID_TC1 ( 69) /**< \brief Basic Timer Counter (TC1) */
#define ID_TC2 ( 70) /**< \brief Basic Timer Counter (TC2) */
#define ID_ADC ( 71) /**< \brief Analog Digital Converter (ADC) */
#define ID_DAC ( 72) /**< \brief Digital Analog Converter (DAC) */
#define ID_PTC ( 73) /**< \brief Peripheral Touch Controller (PTC) */
#define ID_TRNG ( 74) /**< \brief True Random Generator (TRNG) */
#define ID_CCL ( 75) /**< \brief Configurable Custom Logic (CCL) */
#define ID_OPAMP ( 76) /**< \brief Operational Amplifier (OPAMP) */
#define ID_TRAM ( 77) /**< \brief TrustRAM (TRAM) */
#define ID_PERIPH_COUNT ( 78) /**< \brief Number of peripheral IDs */
/** @} end of Peripheral Ids Definitions */
/** \addtogroup SAML10E16A_base Peripheral Base Address Definitions
* @{
*/
/* ************************************************************************** */
/* BASE ADDRESS DEFINITIONS FOR SAML10E16A */
/* ************************************************************************** */
#if (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__))
#define AC (0x40003400) /**< \brief (AC ) Base Address */
#define ADC (0x42001C00) /**< \brief (ADC ) Base Address */
#define CCL (0x42002C00) /**< \brief (CCL ) Base Address */
#define DAC (0x42002000) /**< \brief (DAC ) Base Address */
#define DMAC (0x41006000) /**< \brief (DMAC ) Base Address */
#define DSU (0x41002000) /**< \brief (DSU ) Base Address */
#define DSU_EXT (0x41002100) /**< \brief (DSU ) Base Address */
#define EIC (0x40002800) /**< \brief (EIC ) Base Address */
#define EVSYS (0x42000000) /**< \brief (EVSYS ) Base Address */
#define FREQM (0x40002C00) /**< \brief (FREQM ) Base Address */
#define GCLK (0x40001C00) /**< \brief (GCLK ) Base Address */
#define IDAU (0x41000000) /**< \brief (IDAU ) Base Address */
#define MCLK (0x40000800) /**< \brief (MCLK ) Base Address */
#define NVMCTRL (0x41004000) /**< \brief (NVMCTRL ) Base Address */
#define OPAMP (0x42003000) /**< \brief (OPAMP ) Base Address */
#define OSCCTRL (0x40001000) /**< \brief (OSCCTRL ) Base Address */
#define OSC32KCTRL (0x40001400) /**< \brief (OSC32KCTRL) Base Address */
#define PAC (0x40000000) /**< \brief (PAC ) Base Address */
#define PM (0x40000400) /**< \brief (PM ) Base Address */
#define PORT (0x40003000) /**< \brief (PORT ) Base Address */
#define PORT_IOBUS (0x60000000) /**< \brief (PORT ) Base Address */
#define PTC (0x42002400) /**< \brief (PTC ) Base Address */
#define RSTC (0x40000C00) /**< \brief (RSTC ) Base Address */
#define RTC (0x40002400) /**< \brief (RTC ) Base Address */
#define SERCOM0 (0x42000400) /**< \brief (SERCOM0 ) Base Address */
#define SERCOM1 (0x42000800) /**< \brief (SERCOM1 ) Base Address */
#define SERCOM2 (0x42000C00) /**< \brief (SERCOM2 ) Base Address */
#define SUPC (0x40001800) /**< \brief (SUPC ) Base Address */
#define TC0 (0x42001000) /**< \brief (TC0 ) Base Address */
#define TC1 (0x42001400) /**< \brief (TC1 ) Base Address */
#define TC2 (0x42001800) /**< \brief (TC2 ) Base Address */
#define TRAM (0x42003400) /**< \brief (TRAM ) Base Address */
#define TRNG (0x42002800) /**< \brief (TRNG ) Base Address */
#define WDT (0x40002000) /**< \brief (WDT ) Base Address */
#else /* For C/C++ compiler */
#define AC ((Ac *)0x40003400U) /**< \brief (AC ) Base Address */
#define AC_INST_NUM 1 /**< \brief (AC ) Number of instances */
#define AC_INSTS { AC } /**< \brief (AC ) Instances List */
#define ADC ((Adc *)0x42001C00U) /**< \brief (ADC ) Base Address */
#define ADC_INST_NUM 1 /**< \brief (ADC ) Number of instances */
#define ADC_INSTS { ADC } /**< \brief (ADC ) Instances List */
#define CCL ((Ccl *)0x42002C00U) /**< \brief (CCL ) Base Address */
#define CCL_INST_NUM 1 /**< \brief (CCL ) Number of instances */
#define CCL_INSTS { CCL } /**< \brief (CCL ) Instances List */
#define DAC ((Dac *)0x42002000U) /**< \brief (DAC ) Base Address */
#define DAC_INST_NUM 1 /**< \brief (DAC ) Number of instances */
#define DAC_INSTS { DAC } /**< \brief (DAC ) Instances List */
#define DMAC ((Dmac *)0x41006000U) /**< \brief (DMAC ) Base Address */
#define DMAC_INST_NUM 1 /**< \brief (DMAC ) Number of instances */
#define DMAC_INSTS { DMAC } /**< \brief (DMAC ) Instances List */
#define DSU ((Dsu *)0x41002000U) /**< \brief (DSU ) Base Address */
#define DSU_EXT ((Dsu *)0x41002100U) /**< \brief (DSU ) Base Address */
#define DSU_INST_NUM 1 /**< \brief (DSU ) Number of instances */
#define DSU_INSTS { DSU } /**< \brief (DSU ) Instances List */
#define EIC ((Eic *)0x40002800U) /**< \brief (EIC ) Base Address */
#define EIC_INST_NUM 1 /**< \brief (EIC ) Number of instances */
#define EIC_INSTS { EIC } /**< \brief (EIC ) Instances List */
#define EVSYS ((Evsys *)0x42000000U) /**< \brief (EVSYS ) Base Address */
#define EVSYS_INST_NUM 1 /**< \brief (EVSYS ) Number of instances */
#define EVSYS_INSTS { EVSYS } /**< \brief (EVSYS ) Instances List */
#define FREQM ((Freqm *)0x40002C00U) /**< \brief (FREQM ) Base Address */
#define FREQM_INST_NUM 1 /**< \brief (FREQM ) Number of instances */
#define FREQM_INSTS { FREQM } /**< \brief (FREQM ) Instances List */
#define GCLK ((Gclk *)0x40001C00U) /**< \brief (GCLK ) Base Address */
#define GCLK_INST_NUM 1 /**< \brief (GCLK ) Number of instances */
#define GCLK_INSTS { GCLK } /**< \brief (GCLK ) Instances List */
#define IDAU ((Idau *)0x41000000U) /**< \brief (IDAU ) Base Address */
#define IDAU_INST_NUM 1 /**< \brief (IDAU ) Number of instances */
#define IDAU_INSTS { IDAU } /**< \brief (IDAU ) Instances List */
#define MCLK ((Mclk *)0x40000800U) /**< \brief (MCLK ) Base Address */
#define MCLK_INST_NUM 1 /**< \brief (MCLK ) Number of instances */
#define MCLK_INSTS { MCLK } /**< \brief (MCLK ) Instances List */
#define NVMCTRL ((Nvmctrl *)0x41004000U) /**< \brief (NVMCTRL ) Base Address */
#define NVMCTRL_INST_NUM 1 /**< \brief (NVMCTRL ) Number of instances */
#define NVMCTRL_INSTS { NVMCTRL } /**< \brief (NVMCTRL ) Instances List */
#define OPAMP ((Opamp *)0x42003000U) /**< \brief (OPAMP ) Base Address */
#define OPAMP_INST_NUM 1 /**< \brief (OPAMP ) Number of instances */
#define OPAMP_INSTS { OPAMP } /**< \brief (OPAMP ) Instances List */
#define OSCCTRL ((Oscctrl *)0x40001000U) /**< \brief (OSCCTRL ) Base Address */
#define OSCCTRL_INST_NUM 1 /**< \brief (OSCCTRL ) Number of instances */
#define OSCCTRL_INSTS { OSCCTRL } /**< \brief (OSCCTRL ) Instances List */
#define OSC32KCTRL ((Osc32kctrl *)0x40001400U) /**< \brief (OSC32KCTRL) Base Address */
#define OSC32KCTRL_INST_NUM 1 /**< \brief (OSC32KCTRL) Number of instances */
#define OSC32KCTRL_INSTS { OSC32KCTRL } /**< \brief (OSC32KCTRL) Instances List */
#define PAC ((Pac *)0x40000000U) /**< \brief (PAC ) Base Address */
#define PAC_INST_NUM 1 /**< \brief (PAC ) Number of instances */
#define PAC_INSTS { PAC } /**< \brief (PAC ) Instances List */
#define PM ((Pm *)0x40000400U) /**< \brief (PM ) Base Address */
#define PM_INST_NUM 1 /**< \brief (PM ) Number of instances */
#define PM_INSTS { PM } /**< \brief (PM ) Instances List */
#define PORT ((Port *)0x40003000U) /**< \brief (PORT ) Base Address */
#define PORT_IOBUS ((Port *)0x60000000U) /**< \brief (PORT ) Base Address */
#define PORT_INST_NUM 1 /**< \brief (PORT ) Number of instances */
#define PORT_INSTS { PORT } /**< \brief (PORT ) Instances List */
#define PTC ((Ptc *)0x42002400U) /**< \brief (PTC ) Base Address */
#define PTC_INST_NUM 1 /**< \brief (PTC ) Number of instances */
#define PTC_INSTS { PTC } /**< \brief (PTC ) Instances List */
#define RSTC ((Rstc *)0x40000C00U) /**< \brief (RSTC ) Base Address */
#define RSTC_INST_NUM 1 /**< \brief (RSTC ) Number of instances */
#define RSTC_INSTS { RSTC } /**< \brief (RSTC ) Instances List */
#define RTC ((Rtc *)0x40002400U) /**< \brief (RTC ) Base Address */
#define RTC_INST_NUM 1 /**< \brief (RTC ) Number of instances */
#define RTC_INSTS { RTC } /**< \brief (RTC ) Instances List */
#define SERCOM0 ((Sercom *)0x42000400U) /**< \brief (SERCOM0 ) Base Address */
#define SERCOM1 ((Sercom *)0x42000800U) /**< \brief (SERCOM1 ) Base Address */
#define SERCOM2 ((Sercom *)0x42000C00U) /**< \brief (SERCOM2 ) Base Address */
#define SERCOM_INST_NUM 3 /**< \brief (SERCOM ) Number of instances */
#define SERCOM_INSTS { SERCOM0, SERCOM1, SERCOM2 } /**< \brief (SERCOM ) Instances List */
#define SUPC ((Supc *)0x40001800U) /**< \brief (SUPC ) Base Address */
#define SUPC_INST_NUM 1 /**< \brief (SUPC ) Number of instances */
#define SUPC_INSTS { SUPC } /**< \brief (SUPC ) Instances List */
#define TC0 ((Tc *)0x42001000U) /**< \brief (TC0 ) Base Address */
#define TC1 ((Tc *)0x42001400U) /**< \brief (TC1 ) Base Address */
#define TC2 ((Tc *)0x42001800U) /**< \brief (TC2 ) Base Address */
#define TC_INST_NUM 3 /**< \brief (TC ) Number of instances */
#define TC_INSTS { TC0, TC1, TC2 } /**< \brief (TC ) Instances List */
#define TRAM ((Tram *)0x42003400U) /**< \brief (TRAM ) Base Address */
#define TRAM_INST_NUM 1 /**< \brief (TRAM ) Number of instances */
#define TRAM_INSTS { TRAM } /**< \brief (TRAM ) Instances List */
#define TRNG ((Trng *)0x42002800U) /**< \brief (TRNG ) Base Address */
#define TRNG_INST_NUM 1 /**< \brief (TRNG ) Number of instances */
#define TRNG_INSTS { TRNG } /**< \brief (TRNG ) Instances List */
#define WDT ((Wdt *)0x40002000U) /**< \brief (WDT ) Base Address */
#define WDT_INST_NUM 1 /**< \brief (WDT ) Number of instances */
#define WDT_INSTS { WDT } /**< \brief (WDT ) Instances List */
#endif /* (defined(__ASSEMBLER__) || defined(__IAR_SYSTEMS_ASM__)) */
/** @} end of Peripheral Base Address Definitions */
/** \addtogroup SAML10E16A_pio Peripheral Pio Definitions
* @{
*/
/* ************************************************************************** */
/* PIO DEFINITIONS FOR SAML10E16A*/
/* ************************************************************************** */
#include "pio/saml10e16a.h"
/** @} end of Peripheral Pio Definitions */
/* ************************************************************************** */
/* MEMORY MAPPING DEFINITIONS FOR SAML10E16A*/
/* ************************************************************************** */
#define FLASH_SIZE _U_(0x00010000) /* 64kB Memory segment type: flash */
#define FLASH_PAGE_SIZE _U_( 64)
#define FLASH_NB_OF_PAGES _U_( 1024)
#define AUX_SIZE _U_(0x00000100) /* 0kB Memory segment type: fuses */
#define AUX_PAGE_SIZE _U_( 64)
#define AUX_NB_OF_PAGES _U_( 4)
#define BOCOR_SIZE _U_(0x00000100) /* 0kB Memory segment type: fuses */
#define BOCOR_PAGE_SIZE _U_( 64)
#define BOCOR_NB_OF_PAGES _U_( 4)
#define DATAFLASH_SIZE _U_(0x00000800) /* 2kB Memory segment type: flash */
#define DATAFLASH_PAGE_SIZE _U_( 64)
#define DATAFLASH_NB_OF_PAGES _U_( 32)
#define SW_CALIB_SIZE _U_(0x00000008) /* 0kB Memory segment type: fuses */
#define TEMP_LOG_SIZE _U_(0x00000008) /* 0kB Memory segment type: fuses */
#define USER_PAGE_SIZE _U_(0x00000100) /* 0kB Memory segment type: user_page */
#define USER_PAGE_PAGE_SIZE _U_( 64)
#define USER_PAGE_NB_OF_PAGES _U_( 4)
#define HSRAM_SIZE _U_(0x00004000) /* 16kB Memory segment type: ram */
#define HPB0_SIZE _U_(0x00008000) /* 32kB Memory segment type: io */
#define HPB1_SIZE _U_(0x00010000) /* 64kB Memory segment type: io */
#define HPB2_SIZE _U_(0x00004000) /* 16kB Memory segment type: io */
#define PPB_SIZE _U_(0x00100000) /* 1024kB Memory segment type: io */
#define SCS_SIZE _U_(0x00001000) /* 4kB Memory segment type: io */
#define PERIPHERALS_SIZE _U_(0x20000000) /* 524288kB Memory segment type: io */
#define FLASH_ADDR _U_(0x00000000) /**< FLASH base address (type: flash)*/
#define AUX_ADDR _U_(0x00806000) /**< AUX base address (type: fuses)*/
#define BOCOR_ADDR _U_(0x0080c000) /**< BOCOR base address (type: fuses)*/
#define DATAFLASH_ADDR _U_(0x00400000) /**< DATAFLASH base address (type: flash)*/
#define SW_CALIB_ADDR _U_(0x00806020) /**< SW_CALIB base address (type: fuses)*/
#define TEMP_LOG_ADDR _U_(0x00806038) /**< TEMP_LOG base address (type: fuses)*/
#define USER_PAGE_ADDR _U_(0x00804000) /**< USER_PAGE base address (type: user_page)*/
#define HSRAM_ADDR _U_(0x20000000) /**< HSRAM base address (type: ram)*/
#define HPB0_ADDR _U_(0x40000000) /**< HPB0 base address (type: io)*/
#define HPB1_ADDR _U_(0x41000000) /**< HPB1 base address (type: io)*/
#define HPB2_ADDR _U_(0x42000000) /**< HPB2 base address (type: io)*/
#define PPB_ADDR _U_(0xe0000000) /**< PPB base address (type: io)*/
#define SCS_ADDR _U_(0xe000e000) /**< SCS base address (type: io)*/
#define PERIPHERALS_ADDR _U_(0x40000000) /**< PERIPHERALS base address (type: io)*/
#define NVMCTRL_AUX AUX_ADDR /**< \brief \deprecated Old style definition. Use AUX_ADDR instead */
#define NVMCTRL_BOCOR BOCOR_ADDR /**< \brief \deprecated Old style definition. Use BOCOR_ADDR instead */
#define NVMCTRL_DATAFLASH DATAFLASH_ADDR /**< \brief \deprecated Old style definition. Use DATAFLASH_ADDR instead */
#define NVMCTRL_SW_CALIB SW_CALIB_ADDR /**< \brief \deprecated Old style definition. Use SW_CALIB_ADDR instead */
#define NVMCTRL_TEMP_LOG TEMP_LOG_ADDR /**< \brief \deprecated Old style definition. Use TEMP_LOG_ADDR instead */
#define NVMCTRL_USER USER_PAGE_ADDR /**< \brief \deprecated Old style definition. Use USER_PAGE_ADDR instead */
/* ************************************************************************** */
/** DEVICE SIGNATURES FOR SAML10E16A */
/* ************************************************************************** */
#define DSU_DID _UL_(0X20840000)
/* ************************************************************************** */
/** ELECTRICAL DEFINITIONS FOR SAML10E16A */
/* ************************************************************************** */
/* ************************************************************************** */
/** Event Generator IDs for SAML10E16A */
/* ************************************************************************** */
#define EVENT_ID_GEN_OSCCTRL_XOSC_FAIL 1 /**< ID for OSCCTRL event generator XOSC_FAIL */
#define EVENT_ID_GEN_OSC32KCTRL_XOSC32K_FAIL 2 /**< ID for OSC32KCTRL event generator XOSC32K_FAIL */
#define EVENT_ID_GEN_SUPC_BOD33DET 3 /**< ID for SUPC event generator BOD33DET */
#define EVENT_ID_GEN_RTC_PER_0 4 /**< ID for RTC event generator PER_0 */
#define EVENT_ID_GEN_RTC_PER_1 5 /**< ID for RTC event generator PER_1 */
#define EVENT_ID_GEN_RTC_PER_2 6 /**< ID for RTC event generator PER_2 */
#define EVENT_ID_GEN_RTC_PER_3 7 /**< ID for RTC event generator PER_3 */
#define EVENT_ID_GEN_RTC_PER_4 8 /**< ID for RTC event generator PER_4 */
#define EVENT_ID_GEN_RTC_PER_5 9 /**< ID for RTC event generator PER_5 */
#define EVENT_ID_GEN_RTC_PER_6 10 /**< ID for RTC event generator PER_6 */
#define EVENT_ID_GEN_RTC_PER_7 11 /**< ID for RTC event generator PER_7 */
#define EVENT_ID_GEN_RTC_CMP_0 12 /**< ID for RTC event generator CMP_0 */
#define EVENT_ID_GEN_RTC_CMP_1 13 /**< ID for RTC event generator CMP_1 */
#define EVENT_ID_GEN_RTC_TAMPER 14 /**< ID for RTC event generator TAMPER */
#define EVENT_ID_GEN_RTC_OVF 15 /**< ID for RTC event generator OVF */
#define EVENT_ID_GEN_RTC_PERD 16 /**< ID for RTC event generator PERD */
#define EVENT_ID_GEN_EIC_EXTINT_0 17 /**< ID for EIC event generator EXTINT_0 */
#define EVENT_ID_GEN_EIC_EXTINT_1 18 /**< ID for EIC event generator EXTINT_1 */
#define EVENT_ID_GEN_EIC_EXTINT_2 19 /**< ID for EIC event generator EXTINT_2 */
#define EVENT_ID_GEN_EIC_EXTINT_3 20 /**< ID for EIC event generator EXTINT_3 */
#define EVENT_ID_GEN_EIC_EXTINT_4 21 /**< ID for EIC event generator EXTINT_4 */
#define EVENT_ID_GEN_EIC_EXTINT_5 22 /**< ID for EIC event generator EXTINT_5 */
#define EVENT_ID_GEN_EIC_EXTINT_6 23 /**< ID for EIC event generator EXTINT_6 */
#define EVENT_ID_GEN_EIC_EXTINT_7 24 /**< ID for EIC event generator EXTINT_7 */
#define EVENT_ID_GEN_DMAC_CH_0 25 /**< ID for DMAC event generator CH_0 */
#define EVENT_ID_GEN_DMAC_CH_1 26 /**< ID for DMAC event generator CH_1 */
#define EVENT_ID_GEN_DMAC_CH_2 27 /**< ID for DMAC event generator CH_2 */
#define EVENT_ID_GEN_DMAC_CH_3 28 /**< ID for DMAC event generator CH_3 */
#define EVENT_ID_GEN_TC0_OVF 29 /**< ID for TC0 event generator OVF */
#define EVENT_ID_GEN_TC0_MCX_0 30 /**< ID for TC0 event generator MCX_0 */
#define EVENT_ID_GEN_TC0_MCX_1 31 /**< ID for TC0 event generator MCX_1 */
#define EVENT_ID_GEN_TC1_OVF 32 /**< ID for TC1 event generator OVF */
#define EVENT_ID_GEN_TC1_MCX_0 33 /**< ID for TC1 event generator MCX_0 */
#define EVENT_ID_GEN_TC1_MCX_1 34 /**< ID for TC1 event generator MCX_1 */
#define EVENT_ID_GEN_TC2_OVF 35 /**< ID for TC2 event generator OVF */
#define EVENT_ID_GEN_TC2_MCX_0 36 /**< ID for TC2 event generator MCX_0 */
#define EVENT_ID_GEN_TC2_MCX_1 37 /**< ID for TC2 event generator MCX_1 */
#define EVENT_ID_GEN_ADC_RESRDY 38 /**< ID for ADC event generator RESRDY */
#define EVENT_ID_GEN_ADC_WINMON 39 /**< ID for ADC event generator WINMON */
#define EVENT_ID_GEN_AC_COMP_0 40 /**< ID for AC event generator COMP_0 */
#define EVENT_ID_GEN_AC_COMP_1 41 /**< ID for AC event generator COMP_1 */
#define EVENT_ID_GEN_AC_WIN_0 42 /**< ID for AC event generator WIN_0 */
#define EVENT_ID_GEN_DAC_EMPTY 43 /**< ID for DAC event generator EMPTY */
#define EVENT_ID_GEN_TRNG_READY 46 /**< ID for TRNG event generator READY */
#define EVENT_ID_GEN_CCL_LUTOUT_0 47 /**< ID for CCL event generator LUTOUT_0 */
#define EVENT_ID_GEN_CCL_LUTOUT_1 48 /**< ID for CCL event generator LUTOUT_1 */
#define EVENT_ID_GEN_PAC_ERR 49 /**< ID for PAC event generator ERR */
/* ************************************************************************** */
/** Event User IDs for SAML10E16A */
/* ************************************************************************** */
#define EVENT_ID_USER_OSCCTRL_TUNE 0 /**< ID for OSCCTRL event user TUNE */
#define EVENT_ID_USER_RTC_TAMPER 1 /**< ID for RTC event user TAMPER */
#define EVENT_ID_USER_NVMCTRL_PAGEW 2 /**< ID for NVMCTRL event user PAGEW */
#define EVENT_ID_USER_PORT_EV_0 3 /**< ID for PORT event user EV_0 */
#define EVENT_ID_USER_PORT_EV_1 4 /**< ID for PORT event user EV_1 */
#define EVENT_ID_USER_PORT_EV_2 5 /**< ID for PORT event user EV_2 */
#define EVENT_ID_USER_PORT_EV_3 6 /**< ID for PORT event user EV_3 */
#define EVENT_ID_USER_DMAC_CH_0 7 /**< ID for DMAC event user CH_0 */
#define EVENT_ID_USER_DMAC_CH_1 8 /**< ID for DMAC event user CH_1 */
#define EVENT_ID_USER_DMAC_CH_2 9 /**< ID for DMAC event user CH_2 */
#define EVENT_ID_USER_DMAC_CH_3 10 /**< ID for DMAC event user CH_3 */
#define EVENT_ID_USER_TC0_EVU 11 /**< ID for TC0 event user EVU */
#define EVENT_ID_USER_TC1_EVU 12 /**< ID for TC1 event user EVU */
#define EVENT_ID_USER_TC2_EVU 13 /**< ID for TC2 event user EVU */
#define EVENT_ID_USER_ADC_START 14 /**< ID for ADC event user START */
#define EVENT_ID_USER_ADC_SYNC 15 /**< ID for ADC event user SYNC */
#define EVENT_ID_USER_AC_SOC_0 16 /**< ID for AC event user SOC_0 */
#define EVENT_ID_USER_AC_SOC_1 17 /**< ID for AC event user SOC_1 */
#define EVENT_ID_USER_DAC_START 18 /**< ID for DAC event user START */
#define EVENT_ID_USER_CCL_LUTIN_0 21 /**< ID for CCL event user LUTIN_0 */
#define EVENT_ID_USER_CCL_LUTIN_1 22 /**< ID for CCL event user LUTIN_1 */
#ifdef __cplusplus
}
#endif
/** @} end of SAML10E16A definitions */
#endif /* _SAML10E16A_H_ */

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